commit c932efe7ff96a7725d5ae55401dc515af769debd Author: yikestone Date: Sun Feb 18 14:02:33 2018 +0530 initial diff --git a/AHRS/MPU6050_HMC5883L_AHRS_Kalman/Kalman.h b/AHRS/MPU6050_HMC5883L_AHRS_Kalman/Kalman.h new file mode 100644 index 0000000..fdddcb0 --- /dev/null +++ b/AHRS/MPU6050_HMC5883L_AHRS_Kalman/Kalman.h @@ -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 diff --git a/AHRS/MPU6050_HMC5883L_AHRS_Kalman/MPU6050_HMC5883L_AHRS_Kalman.ino b/AHRS/MPU6050_HMC5883L_AHRS_Kalman/MPU6050_HMC5883L_AHRS_Kalman.ino new file mode 100644 index 0000000..7658e59 --- /dev/null +++ b/AHRS/MPU6050_HMC5883L_AHRS_Kalman/MPU6050_HMC5883L_AHRS_Kalman.ino @@ -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 +#include "Kalman.h" // Source: https://github.com/TKJElectronics/KalmanFilter +#include +#include + +#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 +} diff --git a/AHRS/MPU6050_HMC5883L_AHRS_Kalman/my HMC5883L_GY-87_Offset.txt b/AHRS/MPU6050_HMC5883L_AHRS_Kalman/my HMC5883L_GY-87_Offset.txt new file mode 100644 index 0000000..b22ae56 --- /dev/null +++ b/AHRS/MPU6050_HMC5883L_AHRS_Kalman/my HMC5883L_GY-87_Offset.txt @@ -0,0 +1,6 @@ +#define magX 312 +#define magY 837 +#define magZ 588 +#define magx -1039 +#define magy -640 +#define magz -672 \ No newline at end of file diff --git a/AHRS/MPU6050_calibration2/MPU6050_calibration2.ino b/AHRS/MPU6050_calibration2/MPU6050_calibration2.ino new file mode 100644 index 0000000..775b0b9 --- /dev/null +++ b/AHRS/MPU6050_calibration2/MPU6050_calibration2.ino @@ -0,0 +1,215 @@ +// Arduino sketch that returns calibration offsets for MPU6050 // Version 1.1 (31th January 2014) +// Done by Luis Ródenas +// Based on the I2Cdev library and previous work by Jeff Rowberg +// 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; + } +} diff --git a/AHRS/MPU9150_AHRS_Kalman/Kalman.h b/AHRS/MPU9150_AHRS_Kalman/Kalman.h new file mode 100644 index 0000000..fdddcb0 --- /dev/null +++ b/AHRS/MPU9150_AHRS_Kalman/Kalman.h @@ -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 diff --git a/AHRS/MPU9150_AHRS_Kalman/MPU9150_AHRS_Kalman.ino b/AHRS/MPU9150_AHRS_Kalman/MPU9150_AHRS_Kalman.ino new file mode 100644 index 0000000..c39ad01 --- /dev/null +++ b/AHRS/MPU9150_AHRS_Kalman/MPU9150_AHRS_Kalman.ino @@ -0,0 +1,287 @@ +#include +#include "Kalman.h" // Source: https://github.com/TKJElectronics/KalmanFilter +#include +#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; +} diff --git a/AHRS/Readme.md b/AHRS/Readme.md new file mode 100644 index 0000000..a4ee366 --- /dev/null +++ b/AHRS/Readme.md @@ -0,0 +1 @@ +These are a collection for estimating AHRS algorithms and callibration routines. \ No newline at end of file diff --git a/AHRS/madgwick_AHRS/madgwick_AHRS.ino b/AHRS/madgwick_AHRS/madgwick_AHRS.ino new file mode 100644 index 0000000..90b0121 --- /dev/null +++ b/AHRS/madgwick_AHRS/madgwick_AHRS.ino @@ -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; +} diff --git a/HC_05_Programmer/HC_05_Programmer.ino b/HC_05_Programmer/HC_05_Programmer.ino new file mode 100644 index 0000000..4c53a8b --- /dev/null +++ b/HC_05_Programmer/HC_05_Programmer.ino @@ -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 +/*-----( 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 )*********** + diff --git a/Motor_Encoder_Control/Motor_Encoder_Control.ino b/Motor_Encoder_Control/Motor_Encoder_Control.ino new file mode 100644 index 0000000..5167189 --- /dev/null +++ b/Motor_Encoder_Control/Motor_Encoder_Control.ino @@ -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 +} \ No newline at end of file diff --git a/Motor_Encoder_Control/README.md b/Motor_Encoder_Control/README.md new file mode 100644 index 0000000..13d5d76 --- /dev/null +++ b/Motor_Encoder_Control/README.md @@ -0,0 +1,2 @@ +PID tuner for encoder motors. +Alpha version. \ No newline at end of file diff --git a/Self_balancing_robot/model 1/Fuzzy/Fuzzy.ino b/Self_balancing_robot/model 1/Fuzzy/Fuzzy.ino new file mode 100644 index 0000000..a5bbc9c --- /dev/null +++ b/Self_balancing_robot/model 1/Fuzzy/Fuzzy.ino @@ -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]); +} diff --git a/Self_balancing_robot/model 1/Fuzzy/Kalman.h b/Self_balancing_robot/model 1/Fuzzy/Kalman.h new file mode 100644 index 0000000..fdddcb0 --- /dev/null +++ b/Self_balancing_robot/model 1/Fuzzy/Kalman.h @@ -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 diff --git a/Self_balancing_robot/model 1/README.md b/Self_balancing_robot/model 1/README.md new file mode 100644 index 0000000..dce0b0c --- /dev/null +++ b/Self_balancing_robot/model 1/README.md @@ -0,0 +1 @@ +These are various algorithms tested for two wheeled self balancing robot. \ No newline at end of file diff --git a/Self_balancing_robot/model 1/sbr4/sbr4.ino b/Self_balancing_robot/model 1/sbr4/sbr4.ino new file mode 100644 index 0000000..6b838ec --- /dev/null +++ b/Self_balancing_robot/model 1/sbr4/sbr4.ino @@ -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(); + } diff --git a/Self_balancing_robot/model 1/sbr5/sbr5.ino b/Self_balancing_robot/model 1/sbr5/sbr5.ino new file mode 100644 index 0000000..1c2c3ba --- /dev/null +++ b/Self_balancing_robot/model 1/sbr5/sbr5.ino @@ -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(); + } + } diff --git a/Self_balancing_robot/model 1/sbr6/sbr6.ino b/Self_balancing_robot/model 1/sbr6/sbr6.ino new file mode 100644 index 0000000..4af118f --- /dev/null +++ b/Self_balancing_robot/model 1/sbr6/sbr6.ino @@ -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); +} diff --git a/Self_balancing_robot/model 1/sbr7/Kalman.h b/Self_balancing_robot/model 1/sbr7/Kalman.h new file mode 100644 index 0000000..fdddcb0 --- /dev/null +++ b/Self_balancing_robot/model 1/sbr7/Kalman.h @@ -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 diff --git a/Self_balancing_robot/model 1/sbr7/SBR_final.pde b/Self_balancing_robot/model 1/sbr7/SBR_final.pde new file mode 100644 index 0000000..b064528 --- /dev/null +++ b/Self_balancing_robot/model 1/sbr7/SBR_final.pde @@ -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)); + */ + + +} \ No newline at end of file diff --git a/Self_balancing_robot/model 1/sbr_exp/sbr_exp.ino b/Self_balancing_robot/model 1/sbr_exp/sbr_exp.ino new file mode 100644 index 0000000..74543fd --- /dev/null +++ b/Self_balancing_robot/model 1/sbr_exp/sbr_exp.ino @@ -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))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); + } +} diff --git a/Self_balancing_robot/model 1/sbrlqr/sbblqr.ino b/Self_balancing_robot/model 1/sbrlqr/sbblqr.ino new file mode 100644 index 0000000..58fab2f --- /dev/null +++ b/Self_balancing_robot/model 1/sbrlqr/sbblqr.ino @@ -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(); + } + } diff --git a/Self_balancing_robot/model 1/teensy_sbr_lqr/teensy_sbr_lqr.ino b/Self_balancing_robot/model 1/teensy_sbr_lqr/teensy_sbr_lqr.ino new file mode 100644 index 0000000..afeb3b5 --- /dev/null +++ b/Self_balancing_robot/model 1/teensy_sbr_lqr/teensy_sbr_lqr.ino @@ -0,0 +1,262 @@ +#include "I2Cdev.h" +#include "MPU6050_6Axis_MotionApps20.h" +#include "Wire.h" +#include +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); +*/} diff --git a/Self_balancing_robot/with robotic arm/Arm motion/Pickup/Pickup.ino b/Self_balancing_robot/with robotic arm/Arm motion/Pickup/Pickup.ino new file mode 100644 index 0000000..cd2cf32 --- /dev/null +++ b/Self_balancing_robot/with robotic arm/Arm motion/Pickup/Pickup.ino @@ -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); +} + diff --git a/Self_balancing_robot/with robotic arm/Arm motion/Place/Place.ino b/Self_balancing_robot/with robotic arm/Arm motion/Place/Place.ino new file mode 100644 index 0000000..94d1e5c --- /dev/null +++ b/Self_balancing_robot/with robotic arm/Arm motion/Place/Place.ino @@ -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); +} + diff --git a/Self_balancing_robot/with robotic arm/Arm motion/README.md b/Self_balancing_robot/with robotic arm/Arm motion/README.md new file mode 100644 index 0000000..e8d5bc0 --- /dev/null +++ b/Self_balancing_robot/with robotic arm/Arm motion/README.md @@ -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 \ No newline at end of file diff --git a/Self_balancing_robot/with robotic arm/Localization/Localization.ino b/Self_balancing_robot/with robotic arm/Localization/Localization.ino new file mode 100644 index 0000000..e8b68ae --- /dev/null +++ b/Self_balancing_robot/with robotic arm/Localization/Localization.ino @@ -0,0 +1,90 @@ +#include +#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); + } +} \ No newline at end of file diff --git a/Self_balancing_robot/with robotic arm/Localization/README.md b/Self_balancing_robot/with robotic arm/Localization/README.md new file mode 100644 index 0000000..4570a7b --- /dev/null +++ b/Self_balancing_robot/with robotic arm/Localization/README.md @@ -0,0 +1 @@ +Localization using ultrasonic distance sensors. Still in development. \ No newline at end of file diff --git a/Self_balancing_robot/with robotic arm/README.md b/Self_balancing_robot/with robotic arm/README.md new file mode 100644 index 0000000..b22b29f --- /dev/null +++ b/Self_balancing_robot/with robotic arm/README.md @@ -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. \ No newline at end of file diff --git a/Self_balancing_robot/with robotic arm/SBR_teensy/Fuzzy_controller.h b/Self_balancing_robot/with robotic arm/SBR_teensy/Fuzzy_controller.h new file mode 100644 index 0000000..8da7ba2 --- /dev/null +++ b/Self_balancing_robot/with robotic arm/SBR_teensy/Fuzzy_controller.h @@ -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; +} + diff --git a/Self_balancing_robot/with robotic arm/SBR_teensy/Motor_driver.h b/Self_balancing_robot/with robotic arm/SBR_teensy/Motor_driver.h new file mode 100644 index 0000000..806e7bc --- /dev/null +++ b/Self_balancing_robot/with robotic arm/SBR_teensy/Motor_driver.h @@ -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 diff --git a/Self_balancing_robot/with robotic arm/SBR_teensy/SBR_final_teensy.h b/Self_balancing_robot/with robotic arm/SBR_teensy/SBR_final_teensy.h new file mode 100644 index 0000000..31fdfa8 --- /dev/null +++ b/Self_balancing_robot/with robotic arm/SBR_teensy/SBR_final_teensy.h @@ -0,0 +1,209 @@ +#include "Fuzzy_controller.h" +#include "Motor_driver.h" +#include +#include +#include + +//#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]; +} \ No newline at end of file diff --git a/Self_balancing_robot/with robotic arm/SBR_teensy/SBR_final_teensy.ino b/Self_balancing_robot/with robotic arm/SBR_teensy/SBR_final_teensy.ino new file mode 100644 index 0000000..7dc2afe --- /dev/null +++ b/Self_balancing_robot/with robotic arm/SBR_teensy/SBR_final_teensy.ino @@ -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(); + +} diff --git a/Stepper_Pul_Dir_drive/README.md b/Stepper_Pul_Dir_drive/README.md new file mode 100644 index 0000000..35663b6 --- /dev/null +++ b/Stepper_Pul_Dir_drive/README.md @@ -0,0 +1 @@ +Code for driving motor using Stepper drive with Pulse and Direction pins. \ No newline at end of file diff --git a/Stepper_Pul_Dir_drive/Stepper_Pul_Dir_drive.ino b/Stepper_Pul_Dir_drive/Stepper_Pul_Dir_drive.ino new file mode 100644 index 0000000..feab07d --- /dev/null +++ b/Stepper_Pul_Dir_drive/Stepper_Pul_Dir_drive.ino @@ -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"); +*/ +//} diff --git a/custom_ir_communication/cust1/cust1.ino b/custom_ir_communication/cust1/cust1.ino new file mode 100644 index 0000000..b3c0b9d --- /dev/null +++ b/custom_ir_communication/cust1/cust1.ino @@ -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)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) + + +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 +} diff --git a/ir_maze_solver/Readme.md b/ir_maze_solver/Readme.md new file mode 100644 index 0000000..697c31a --- /dev/null +++ b/ir_maze_solver/Readme.md @@ -0,0 +1 @@ +IR based Maze Solver using PID and Flood fill algorithms. Done in my freshman year. \ No newline at end of file diff --git a/ir_maze_solver/maze_solver_final/maze_solver_final.ino b/ir_maze_solver/maze_solver_final/maze_solver_final.ino new file mode 100644 index 0000000..1b50e9d --- /dev/null +++ b/ir_maze_solver/maze_solver_final/maze_solver_final.ino @@ -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]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)||(dD)||(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;k100&&((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]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)||(dD)||(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;k100)&&((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]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)||(dD)||(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;kpwmm)?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]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)||(dD)||(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 +// +// 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); +} diff --git a/libraries/AD7746/AD7746.h b/libraries/AD7746/AD7746.h new file mode 100644 index 0000000..0e77a6c --- /dev/null +++ b/libraries/AD7746/AD7746.h @@ -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 +// +// 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_ */ diff --git a/libraries/AD7746/library.json b/libraries/AD7746/library.json new file mode 100644 index 0000000..70940ff --- /dev/null +++ b/libraries/AD7746/library.json @@ -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" +} diff --git a/libraries/ADS1115/ADS1115.cpp b/libraries/ADS1115/ADS1115.cpp new file mode 100644 index 0000000..c3d7e87 --- /dev/null +++ b/libraries/ADS1115/ADS1115.cpp @@ -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 +// 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 +}; + diff --git a/libraries/ADS1115/ADS1115.h b/libraries/ADS1115/ADS1115.h new file mode 100644 index 0000000..2ac68ee --- /dev/null +++ b/libraries/ADS1115/ADS1115.h @@ -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 +// 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_ */ diff --git a/libraries/ADS1115/examples/ADS1115_differential/ADS1115_differential.ino b/libraries/ADS1115/examples/ADS1115_differential/ADS1115_differential.ino new file mode 100644 index 0000000..a67b77b --- /dev/null +++ b/libraries/ADS1115/examples/ADS1115_differential/ADS1115_differential.ino @@ -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); +} + diff --git a/libraries/ADS1115/examples/ADS1115_single/ADS1115_single.ino b/libraries/ADS1115/examples/ADS1115_single/ADS1115_single.ino new file mode 100644 index 0000000..015b56f --- /dev/null +++ b/libraries/ADS1115/examples/ADS1115_single/ADS1115_single.ino @@ -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); +} + + + + + diff --git a/libraries/ADS1115/library.json b/libraries/ADS1115/library.json new file mode 100644 index 0000000..e3e6553 --- /dev/null +++ b/libraries/ADS1115/library.json @@ -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" +} diff --git a/libraries/ADXL345/ADXL345.cpp b/libraries/ADXL345/ADXL345.cpp new file mode 100644 index 0000000..7890d4c --- /dev/null +++ b/libraries/ADXL345/ADXL345.cpp @@ -0,0 +1,1668 @@ +// I2Cdev library collection - ADXL345 I2C device class +// Based on Analog Devices ADXL345 datasheet rev. C, 5/2011 +// 7/31/2011 by Jeff Rowberg +// 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. +=============================================== +*/ + +#include "ADXL345.h" + +/** Default constructor, uses default I2C address. + * @see ADXL345_DEFAULT_ADDRESS + */ +ADXL345::ADXL345() { + devAddr = ADXL345_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see ADXL345_DEFAULT_ADDRESS + * @see ADXL345_ADDRESS_ALT_LOW + * @see ADXL345_ADDRESS_ALT_HIGH + */ +ADXL345::ADXL345(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * This will activate the accelerometer, so be sure to adjust the power settings + * after you call this method if you want it to enter standby mode, or another + * less demanding mode of operation. + */ +void ADXL345::initialize() { + I2Cdev::writeByte(devAddr, ADXL345_RA_POWER_CTL, 0); // reset all power settings + setAutoSleepEnabled(true); + setMeasureEnabled(true); +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool ADXL345::testConnection() { + return getDeviceID() == 0xE5; +} + +// DEVID register + +/** Get Device ID. + * The DEVID register holds a fixed device ID code of 0xE5 (345 octal). + * @return Device ID (should be 0xE5, 229 dec, 345 oct) + * @see ADXL345_RA_DEVID + */ +uint8_t ADXL345::getDeviceID() { + I2Cdev::readByte(devAddr, ADXL345_RA_DEVID, buffer); + return buffer[0]; +} + +// THRESH_TAP register + +/** Get tap threshold. + * The THRESH_TAP register is eight bits and holds the threshold value for tap + * interrupts. The data format is unsigned, therefore, the magnitude of the tap + * event is compared with the value in THRESH_TAP for normal tap detection. The + * scale factor is 62.5 mg/LSB (that is, 0xFF = 16 g). A value of 0 may result + * in undesirable behavior if single tap/double tap interrupts are enabled. + * @return Tap threshold (scaled at 62.5 mg/LSB) + * @see ADXL345_RA_THRESH_TAP + */ +uint8_t ADXL345::getTapThreshold() { + I2Cdev::readByte(devAddr, ADXL345_RA_THRESH_TAP, buffer); + return buffer[0]; +} +/** Set tap threshold. + * @param threshold Tap magnitude threshold (scaled at 62.5 mg/LSB) + * @see ADXL345_RA_THRESH_TAP + * @see getTapThreshold() + */ +void ADXL345::setTapThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, ADXL345_RA_THRESH_TAP, threshold); +} + +// OFS* registers + +/** Get axis offsets. + * The OFSX, OFSY, and OFSZ registers are each eight bits and offer user-set + * offset adjustments in twos complement format with a scale factor of 15.6 + * mg/LSB (that is, 0x7F = 2 g). The value stored in the offset registers is + * automatically added to the acceleration data, and the resulting value is + * stored in the output data registers. For additional information regarding + * offset calibration and the use of the offset registers, refer to the Offset + * Calibration section of the datasheet. + * @param x X axis offset container + * @param y Y axis offset container + * @param z Z axis offset container + * @see ADXL345_RA_OFSX + * @see ADXL345_RA_OFSY + * @see ADXL345_RA_OFSZ + */ +void ADXL345::getOffset(int8_t* x, int8_t* y, int8_t* z) { + I2Cdev::readBytes(devAddr, ADXL345_RA_OFSX, 3, buffer); + *x = buffer[0]; + *y = buffer[1]; + *z = buffer[2]; +} +/** Set axis offsets. + * @param x X axis offset value + * @param y Y axis offset value + * @param z Z axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSX + * @see ADXL345_RA_OFSY + * @see ADXL345_RA_OFSZ + */ +void ADXL345::setOffset(int8_t x, int8_t y, int8_t z) { + I2Cdev::writeByte(devAddr, ADXL345_RA_OFSX, x); + I2Cdev::writeByte(devAddr, ADXL345_RA_OFSY, y); + I2Cdev::writeByte(devAddr, ADXL345_RA_OFSZ, z); +} +/** Get X axis offset. + * @return X axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSX + */ +int8_t ADXL345::getOffsetX() { + I2Cdev::readByte(devAddr, ADXL345_RA_OFSX, buffer); + return buffer[0]; +} +/** Set X axis offset. + * @param x X axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSX + */ +void ADXL345::setOffsetX(int8_t x) { + I2Cdev::writeByte(devAddr, ADXL345_RA_OFSX, x); +} +/** Get Y axis offset. + * @return Y axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSY + */ +int8_t ADXL345::getOffsetY() { + I2Cdev::readByte(devAddr, ADXL345_RA_OFSY, buffer); + return buffer[0]; +} +/** Set Y axis offset. + * @param y Y axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSY + */ +void ADXL345::setOffsetY(int8_t y) { + I2Cdev::writeByte(devAddr, ADXL345_RA_OFSY, y); +} +/** Get Z axis offset. + * @return Z axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSZ + */ +int8_t ADXL345::getOffsetZ() { + I2Cdev::readByte(devAddr, ADXL345_RA_OFSZ, buffer); + return buffer[0]; +} +/** Set Z axis offset. + * @param z Z axis offset value + * @see getOffset() + * @see ADXL345_RA_OFSZ + */ +void ADXL345::setOffsetZ(int8_t z) { + I2Cdev::writeByte(devAddr, ADXL345_RA_OFSZ, z); +} + +// DUR register + +/** Get tap duration. + * The DUR register is eight bits and contains an unsigned time value + * representing the maximum time that an event must be above the THRESH_TAP + * threshold to qualify as a tap event. The scale factor is 625 us/LSB. A value + * of 0 disables the single tap/ double tap functions. + * @return Tap duration (scaled at 625 us/LSB) + * @see ADXL345_RA_DUR + */ +uint8_t ADXL345::getTapDuration() { + I2Cdev::readByte(devAddr, ADXL345_RA_DUR, buffer); + return buffer[0]; +} +/** Set tap duration. + * @param duration Tap duration (scaled at 625 us/LSB) + * @see getTapDuration() + * @see ADXL345_RA_DUR + */ +void ADXL345::setTapDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, ADXL345_RA_DUR, duration); +} + +// LATENT register + +/** Get tap duration. + * The latent register is eight bits and contains an unsigned time value + * representing the wait time from the detection of a tap event to the start of + * the time window (defined by the window register) during which a possible + * second tap event can be detected. The scale factor is 1.25 ms/LSB. A value of + * 0 disables the double tap function. + * @return Tap latency (scaled at 1.25 ms/LSB) + * @see ADXL345_RA_LATENT + */ +uint8_t ADXL345::getDoubleTapLatency() { + I2Cdev::readByte(devAddr, ADXL345_RA_LATENT, buffer); + return buffer[0]; +} +/** Set tap duration. + * @param latency Tap latency (scaled at 1.25 ms/LSB) + * @see getDoubleTapLatency() + * @see ADXL345_RA_LATENT + */ +void ADXL345::setDoubleTapLatency(uint8_t latency) { + I2Cdev::writeByte(devAddr, ADXL345_RA_LATENT, latency); +} + +// WINDOW register + +/** Get double tap window. + * The window register is eight bits and contains an unsigned time value + * representing the amount of time after the expiration of the latency time + * (determined by the latent register) during which a second valid tap can + * begin. The scale factor is 1.25 ms/LSB. A value of 0 disables the double tap + * function. + * @return Double tap window (scaled at 1.25 ms/LSB) + * @see ADXL345_RA_WINDOW + */ +uint8_t ADXL345::getDoubleTapWindow() { + I2Cdev::readByte(devAddr, ADXL345_RA_WINDOW, buffer); + return buffer[0]; +} +/** Set double tap window. + * @param window Double tap window (scaled at 1.25 ms/LSB) + * @see getDoubleTapWindow() + * @see ADXL345_RA_WINDOW + */ +void ADXL345::setDoubleTapWindow(uint8_t window) { + I2Cdev::writeByte(devAddr, ADXL345_RA_WINDOW, window); +} + +// THRESH_ACT register + +/** Get activity threshold. + * The THRESH_ACT register is eight bits and holds the threshold value for + * detecting activity. The data format is unsigned, so the magnitude of the + * activity event is compared with the value in the THRESH_ACT register. The + * scale factor is 62.5 mg/LSB. A value of 0 may result in undesirable behavior + * if the activity interrupt is enabled. + * @return Activity threshold (scaled at 62.5 mg/LSB) + * @see ADXL345_RA_THRESH_ACT + */ +uint8_t ADXL345::getActivityThreshold() { + I2Cdev::readByte(devAddr, ADXL345_RA_THRESH_ACT, buffer); + return buffer[0]; +} +/** Set activity threshold. + * @param threshold Activity threshold (scaled at 62.5 mg/LSB) + * @see getActivityThreshold() + * @see ADXL345_RA_THRESH_ACT + */ +void ADXL345::setActivityThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, ADXL345_RA_THRESH_ACT, threshold); +} + +// THRESH_INACT register + +/** Get inactivity threshold. + * The THRESH_INACT register is eight bits and holds the threshold value for + * detecting inactivity. The data format is unsigned, so the magnitude of the + * inactivity event is compared with the value in the THRESH_INACT register. The + * scale factor is 62.5 mg/LSB. A value of 0 may result in undesirable behavior + * if the inactivity interrupt is enabled. + * @return Inactivity threshold (scaled at 62.5 mg/LSB) + * @see ADXL345_RA_THRESH_INACT + */ +uint8_t ADXL345::getInactivityThreshold() { + I2Cdev::readByte(devAddr, ADXL345_RA_THRESH_INACT, buffer); + return buffer[0]; +} +/** Set inactivity threshold. + * @param threshold Inctivity threshold (scaled at 62.5 mg/LSB) + * @see getInctivityThreshold() + * @see ADXL345_RA_THRESH_INACT + */ +void ADXL345::setInactivityThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, ADXL345_RA_THRESH_INACT, threshold); +} + +// TIME_INACT register + +/** Set inactivity time. + * The TIME_INACT register is eight bits and contains an unsigned time value + * representing the amount of time that acceleration must be less than the value + * in the THRESH_INACT register for inactivity to be declared. The scale factor + * is 1 sec/LSB. Unlike the other interrupt functions, which use unfiltered data + * (see the Threshold sectionof the datasheet), the inactivity function uses + * filtered output data. At least one output sample must be generated for the + * inactivity interrupt to be triggered. This results in the function appearing + * unresponsive if the TIME_INACT register is set to a value less than the time + * constant of the output data rate. A value of 0 results in an interrupt when + * the output data is less than the value in the THRESH_INACT register. + * @return Inactivity time (scaled at 1 sec/LSB) + * @see ADXL345_RA_TIME_INACT + */ +uint8_t ADXL345::getInactivityTime() { + I2Cdev::readByte(devAddr, ADXL345_RA_TIME_INACT, buffer); + return buffer[0]; +} +/** Set inactivity time. + * @param time Inactivity time (scaled at 1 sec/LSB) + * @see getInctivityTime() + * @see ADXL345_RA_TIME_INACT + */ +void ADXL345::setInactivityTime(uint8_t time) { + I2Cdev::writeByte(devAddr, ADXL345_RA_TIME_INACT, time); +} + +// ACT_INACT_CTL register + +/** Get activity AC/DC coupling. + * A setting of 0 selects dc-coupled operation, and a setting of 1 enables + * ac-coupled operation. In dc-coupled operation, the current acceleration + * magnitude is compared directly with THRESH_ACT and THRESH_INACT to determine + * whether activity or inactivity is detected. + * + * In ac-coupled operation for activity detection, the acceleration value at the + * start of activity detection is taken as a reference value. New samples of + * acceleration are then compared to this reference value, and if the magnitude + * of the difference exceeds the THRESH_ACT value, the device triggers an + * activity interrupt. + * + * Similarly, in ac-coupled operation for inactivity detection, a reference + * value is used for comparison and is updated whenever the device exceeds the + * inactivity threshold. After the reference value is selected, the device + * compares the magnitude of the difference between the reference value and the + * current acceleration with THRESH_INACT. If the difference is less than the + * value in THRESH_INACT for the time in TIME_INACT, the device is considered + * inactive and the inactivity interrupt is triggered. + * + * @return Activity coupling (0 = DC, 1 = AC) + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_AC_BIT + */ +bool ADXL345::getActivityAC() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_AC_BIT, buffer); + return buffer[0]; +} +/** Set activity AC/DC coupling. + * @param enabled Activity AC/DC coupling (TRUE for AC, FALSE for DC) + * @see getActivityAC() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_AC_BIT + */ +void ADXL345::setActivityAC(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_AC_BIT, enabled); +} +/** Get X axis activity monitoring inclusion. + * For all "get[In]Activity*Enabled()" methods: a setting of 1 enables x-, y-, + * or z-axis participation in detecting activity or inactivity. A setting of 0 + * excludes the selected axis from participation. If all axes are excluded, the + * function is disabled. For activity detection, all participating axes are + * logically OR�ed, causing the activity function to trigger when any of the + * participating axes exceeds the threshold. For inactivity detection, all + * participating axes are logically AND�ed, causing the inactivity function to + * trigger only if all participating axes are below the threshold for the + * specified time. + * @return X axis activity monitoring enabled value + * @see getActivityAC() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_X_BIT + */ +bool ADXL345::getActivityXEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_X_BIT, buffer); + return buffer[0]; +} +/** Set X axis activity monitoring inclusion. + * @param enabled X axis activity monitoring inclusion value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_X_BIT + */ +void ADXL345::setActivityXEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_X_BIT, enabled); +} +/** Get Y axis activity monitoring. + * @return Y axis activity monitoring enabled value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_Y_BIT + */ +bool ADXL345::getActivityYEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_Y_BIT, buffer); + return buffer[0]; +} +/** Set Y axis activity monitoring inclusion. + * @param enabled Y axis activity monitoring inclusion value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_Y_BIT + */ +void ADXL345::setActivityYEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_Y_BIT, enabled); +} +/** Get Z axis activity monitoring. + * @return Z axis activity monitoring enabled value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_Z_BIT + */ +bool ADXL345::getActivityZEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_Z_BIT, buffer); + return buffer[0]; +} +/** Set Z axis activity monitoring inclusion. + * @param enabled Z axis activity monitoring inclusion value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_ACT_Z_BIT + */ +void ADXL345::setActivityZEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_ACT_Z_BIT, enabled); +} +/** Get inactivity AC/DC coupling. + * @return Inctivity coupling (0 = DC, 1 = AC) + * @see getActivityAC() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_AC_BIT + */ +bool ADXL345::getInactivityAC() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_AC_BIT, buffer); + return buffer[0]; +} +/** Set inctivity AC/DC coupling. + * @param enabled Inactivity AC/DC coupling (TRUE for AC, FALSE for DC) + * @see getActivityAC() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_AC_BIT + */ +void ADXL345::setInactivityAC(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_AC_BIT, enabled); +} +/** Get X axis inactivity monitoring. + * @return Y axis inactivity monitoring enabled value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_X_BIT + */ +bool ADXL345::getInactivityXEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_X_BIT, buffer); + return buffer[0]; +} +/** Set X axis activity monitoring inclusion. + * @param enabled X axis inactivity monitoring inclusion value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_X_BIT + */ +void ADXL345::setInactivityXEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_X_BIT, enabled); +} +/** Get Y axis inactivity monitoring. + * @return Y axis inactivity monitoring enabled value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_Y_BIT + */ +bool ADXL345::getInactivityYEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_Y_BIT, buffer); + return buffer[0]; +} +/** Set Y axis inactivity monitoring inclusion. + * @param enabled Y axis inactivity monitoring inclusion value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_Y_BIT + */ +void ADXL345::setInactivityYEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_Y_BIT, enabled); +} +/** Get Z axis inactivity monitoring. + * @return Z axis inactivity monitoring enabled value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_Z_BIT + */ +bool ADXL345::getInactivityZEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_Z_BIT, buffer); + return buffer[0]; +} +/** Set Z axis inactivity monitoring inclusion. + * @param enabled Z axis activity monitoring inclusion value + * @see getActivityAC() + * @see getActivityXEnabled() + * @see ADXL345_RA_ACT_INACT_CTL + * @see ADXL345_AIC_INACT_Z_BIT + */ +void ADXL345::setInactivityZEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_ACT_INACT_CTL, ADXL345_AIC_INACT_Z_BIT, enabled); +} + +// THRESH_FF register + +/** Get freefall threshold value. + * The THRESH_FF register is eight bits and holds the threshold value, in + * unsigned format, for free-fall detection. The acceleration on all axes is + * compared with the value in THRESH_FF to determine if a free-fall event + * occurred. The scale factor is 62.5 mg/LSB. Note that a value of 0 mg may + * result in undesirable behavior if the free-fall interrupt is enabled. Values + * between 300 mg and 600 mg (0x05 to 0x09) are recommended. + * @return Freefall threshold value (scaled at 62.5 mg/LSB) + * @see ADXL345_RA_THRESH_FF + */ +uint8_t ADXL345::getFreefallThreshold() { + I2Cdev::readByte(devAddr, ADXL345_RA_THRESH_FF, buffer); + return buffer[0]; +} +/** Set freefall threshold value. + * @param threshold Freefall threshold value (scaled at 62.5 mg/LSB) + * @see getFreefallThreshold() + * @see ADXL345_RA_THRESH_FF + */ +void ADXL345::setFreefallThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, ADXL345_RA_THRESH_FF, threshold); +} + +// TIME_FF register + +/** Get freefall time value. + * The TIME_FF register is eight bits and stores an unsigned time value + * representing the minimum time that the value of all axes must be less than + * THRESH_FF to generate a free-fall interrupt. The scale factor is 5 ms/LSB. A + * value of 0 may result in undesirable behavior if the free-fall interrupt is + * enabled. Values between 100 ms and 350 ms (0x14 to 0x46) are recommended. + * @return Freefall time value (scaled at 5 ms/LSB) + * @see getFreefallThreshold() + * @see ADXL345_RA_TIME_FF + */ +uint8_t ADXL345::getFreefallTime() { + I2Cdev::readByte(devAddr, ADXL345_RA_TIME_FF, buffer); + return buffer[0]; +} +/** Set freefall time value. + * @param threshold Freefall time value (scaled at 5 ms/LSB) + * @see getFreefallTime() + * @see ADXL345_RA_TIME_FF + */ +void ADXL345::setFreefallTime(uint8_t time) { + I2Cdev::writeByte(devAddr, ADXL345_RA_TIME_FF, time); +} + +// TAP_AXES register + +/** Get double-tap fast-movement suppression. + * Setting the suppress bit suppresses double tap detection if acceleration + * greater than the value in THRESH_TAP is present between taps. See the Tap + * Detection section in the datasheet for more details. + * @return Double-tap fast-movement suppression value + * @see getTapThreshold() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_SUP_BIT + */ +bool ADXL345::getTapAxisSuppress() { + I2Cdev::readBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_SUP_BIT, buffer); + return buffer[0]; +} +/** Set double-tap fast-movement suppression. + * @param enabled Double-tap fast-movement suppression value + * @see getTapAxisSuppress() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_SUP_BIT + */ +void ADXL345::setTapAxisSuppress(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_SUP_BIT, enabled); +} +/** Get double-tap fast-movement suppression. + * A setting of 1 in the TAP_X enable bit enables x-axis participation in tap + * detection. A setting of 0 excludes the selected axis from participation in + * tap detection. + * @return Double-tap fast-movement suppression value + * @see getTapThreshold() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_X_BIT + */ +bool ADXL345::getTapAxisXEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_X_BIT, buffer); + return buffer[0]; +} +/** Set tap detection X axis inclusion. + * @param enabled X axis tap detection enabled value + * @see getTapAxisXEnabled() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_X_BIT + */ +void ADXL345::setTapAxisXEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_X_BIT, enabled); +} +/** Get tap detection Y axis inclusion. + * A setting of 1 in the TAP_Y enable bit enables y-axis participation in tap + * detection. A setting of 0 excludes the selected axis from participation in + * tap detection. + * @return Double-tap fast-movement suppression value + * @see getTapThreshold() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_Y_BIT + */ +bool ADXL345::getTapAxisYEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_Y_BIT, buffer); + return buffer[0]; +} +/** Set tap detection Y axis inclusion. + * @param enabled Y axis tap detection enabled value + * @see getTapAxisYEnabled() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_Y_BIT + */ +void ADXL345::setTapAxisYEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_Y_BIT, enabled); +} +/** Get tap detection Z axis inclusion. + * A setting of 1 in the TAP_Z enable bit enables z-axis participation in tap + * detection. A setting of 0 excludes the selected axis from participation in + * tap detection. + * @return Double-tap fast-movement suppression value + * @see getTapThreshold() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_Z_BIT + */ +bool ADXL345::getTapAxisZEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_Z_BIT, buffer); + return buffer[0]; +} +/** Set tap detection Z axis inclusion. + * @param enabled Z axis tap detection enabled value + * @see getTapAxisZEnabled() + * @see ADXL345_RA_TAP_AXES + * @see ADXL345_TAPAXIS_Z_BIT + */ +void ADXL345::setTapAxisZEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_TAP_AXES, ADXL345_TAPAXIS_Z_BIT, enabled); +} + +// ACT_TAP_STATUS register + +/** Get X axis activity source flag. + * These bits indicate the first axis involved in a tap or activity event. A + * setting of 1 corresponds to involvement in the event, and a setting of 0 + * corresponds to no involvement. When new data is available, these bits are not + * cleared but are overwritten by the new data. The ACT_TAP_STATUS register + * should be read before clearing the interrupt. Disabling an axis from + * participation clears the corresponding source bit when the next activity or + * single tap/double tap event occurs. + * @return X axis activity source flag + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_ACTX_BIT + */ +bool ADXL345::getActivitySourceX() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_ACTX_BIT, buffer); + return buffer[0]; +} +/** Get Y axis activity source flag. + * @return Y axis activity source flag + * @see getActivitySourceX() + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_ACTY_BIT + */ +bool ADXL345::getActivitySourceY() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_ACTY_BIT, buffer); + return buffer[0]; +} +/** Get Z axis activity source flag. + * @return Z axis activity source flag + * @see getActivitySourceX() + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_ACTZ_BIT + */ +bool ADXL345::getActivitySourceZ() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_ACTZ_BIT, buffer); + return buffer[0]; +} +/** Get sleep mode flag. + * A setting of 1 in the asleep bit indicates that the part is asleep, and a + * setting of 0 indicates that the part is not asleep. This bit toggles only if + * the device is configured for auto sleep. See the AUTO_SLEEP Bit section of + * the datasheet for more information on autosleep mode. + * @return Sleep mode enabled flag + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_ASLEEP_BIT + */ +bool ADXL345::getAsleep() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_ASLEEP_BIT, buffer); + return buffer[0]; +} +/** Get X axis tap source flag. + * @return X axis tap source flag + * @see getActivitySourceX() + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_TAPX_BIT + */ +bool ADXL345::getTapSourceX() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_TAPX_BIT, buffer); + return buffer[0]; +} +/** Get Y axis tap source flag. + * @return Y axis tap source flag + * @see getActivitySourceX() + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_TAPY_BIT + */ +bool ADXL345::getTapSourceY() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_TAPY_BIT, buffer); + return buffer[0]; +} +/** Get Z axis tap source flag. + * @return Z axis tap source flag + * @see getActivitySourceX() + * @see ADXL345_RA_ACT_TAP_STATUS + * @see ADXL345_TAPSTAT_TAPZ_BIT + */ +bool ADXL345::getTapSourceZ() { + I2Cdev::readBit(devAddr, ADXL345_RA_ACT_TAP_STATUS, ADXL345_TAPSTAT_TAPZ_BIT, buffer); + return buffer[0]; +} + +// BW_RATE register + +/** Get low power enabled status. + * A setting of 0 in the LOW_POWER bit selects normal operation, and a setting + * of 1 selects reduced power operation, which has somewhat higher noise (see + * the Power Modes section of the datasheet for details). + * @return Low power enabled status + * @see ADXL345_RA_BW_RATE + * @see ADXL345_BW_LOWPOWER_BIT + */ +bool ADXL345::getLowPowerEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_BW_RATE, ADXL345_BW_LOWPOWER_BIT, buffer); + return buffer[0]; +} +/** Set low power enabled status. + * @see getLowPowerEnabled() + * @param enabled Low power enable setting + * @see ADXL345_RA_BW_RATE + * @see ADXL345_BW_LOWPOWER_BIT + */ +void ADXL345::setLowPowerEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_BW_RATE, ADXL345_BW_LOWPOWER_BIT, enabled); +} +/** Get measurement data rate. + * These bits select the device bandwidth and output data rate (see Table 7 and + * Table 8 in the datasheet for details). The default value is 0x0A, which + * translates to a 100 Hz output data rate. An output data rate should be + * selected that is appropriate for the communication protocol and frequency + * selected. Selecting too high of an output data rate with a low communication + * speed results in samples being discarded. + * @return Data rate (0x0 - 0xF) + * @see ADXL345_RA_BW_RATE + * @see ADXL345_BW_RATE_BIT + * @see ADXL345_BW_RATE_LENGTH + */ +uint8_t ADXL345::getRate() { + I2Cdev::readBits(devAddr, ADXL345_RA_BW_RATE, ADXL345_BW_RATE_BIT, ADXL345_BW_RATE_LENGTH, buffer); + return buffer[0]; +} +/** Set measurement data rate. + * 0x7 = 12.5Hz + * 0x8 = 25Hz, increasing or decreasing by factors of 2, so: + * 0x9 = 50Hz + * 0xA = 100Hz + * @param rate New data rate (0x0 - 0xF) + * @see ADXL345_RATE_100 + * @see ADXL345_RA_BW_RATE + * @see ADXL345_BW_RATE_BIT + * @see ADXL345_BW_RATE_LENGTH + */ +void ADXL345::setRate(uint8_t rate) { + I2Cdev::writeBits(devAddr, ADXL345_RA_BW_RATE, ADXL345_BW_RATE_BIT, ADXL345_BW_RATE_LENGTH, rate); +} + +// POWER_CTL register + +/** Get activity/inactivity serial linkage status. + * A setting of 1 in the link bit with both the activity and inactivity + * functions enabled delays the start of the activity function until + * inactivity is detected. After activity is detected, inactivity detection + * begins, preventing the detection of activity. This bit serially links the + * activity and inactivity functions. When this bit is set to 0, the inactivity + * and activity functions are concurrent. Additional information can be found + * in the Link Mode section of the datasheet. + * + * When clearing the link bit, it is recommended that the part be placed into + * standby mode and then set back to measurement mode with a subsequent write. + * This is done to ensure that the device is properly biased if sleep mode is + * manually disabled; otherwise, the first few samples of data after the link + * bit is cleared may have additional noise, especially if the device was asleep + * when the bit was cleared. + * + * @return Link status + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_LINK_BIT + */ +bool ADXL345::getLinkEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_LINK_BIT, buffer); + return buffer[0]; +} +/** Set activity/inactivity serial linkage status. + * @param enabled New link status + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_LINK_BIT + */ +void ADXL345::setLinkEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_LINK_BIT, enabled); +} +/** Get auto-sleep enabled status. + * If the link bit is set, a setting of 1 in the AUTO_SLEEP bit enables the + * auto-sleep functionality. In this mode, the ADXL345 auto-matically switches + * to sleep mode if the inactivity function is enabled and inactivity is + * detected (that is, when acceleration is below the THRESH_INACT value for at + * least the time indicated by TIME_INACT). If activity is also enabled, the + * ADXL345 automatically wakes up from sleep after detecting activity and + * returns to operation at the output data rate set in the BW_RATE register. A + * setting of 0 in the AUTO_SLEEP bit disables automatic switching to sleep + * mode. See the description of the Sleep Bit in this section of the datasheet + * for more information on sleep mode. + * + * If the link bit is not set, the AUTO_SLEEP feature is disabled and setting + * the AUTO_SLEEP bit does not have an impact on device operation. Refer to the + * Link Bit section or the Link Mode section for more information on utilization + * of the link feature. + * + * When clearing the AUTO_SLEEP bit, it is recommended that the part be placed + * into standby mode and then set back to measure-ment mode with a subsequent + * write. This is done to ensure that the device is properly biased if sleep + * mode is manually disabled; otherwise, the first few samples of data after the + * AUTO_SLEEP bit is cleared may have additional noise, especially if the device + * was asleep when the bit was cleared. + * + * @return Auto-sleep enabled status + * @see getActivityThreshold() + * @see getInactivityThreshold() + * @see getInactivityTime() + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_AUTOSLEEP_BIT + */ +bool ADXL345::getAutoSleepEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_AUTOSLEEP_BIT, buffer); + return buffer[0]; +} +/** Set auto-sleep enabled status. + * @param enabled New auto-sleep status + * @see getAutoSleepEnabled() + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_AUTOSLEEP_BIT + */ +void ADXL345::setAutoSleepEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_AUTOSLEEP_BIT, enabled); +} +/** Get measurement enabled status. + * A setting of 0 in the measure bit places the part into standby mode, and a + * setting of 1 places the part into measurement mode. The ADXL345 powers up in + * standby mode with minimum power consumption. + * @return Measurement enabled status + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_MEASURE_BIT + */ +bool ADXL345::getMeasureEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_MEASURE_BIT, buffer); + return buffer[0]; +} +/** Set measurement enabled status. + * @param enabled Measurement enabled status + * @see getMeasureEnabled() + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_MEASURE_BIT + */ +void ADXL345::setMeasureEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_MEASURE_BIT, enabled); +} +/** Get sleep mode enabled status. + * A setting of 0 in the sleep bit puts the part into the normal mode of + * operation, and a setting of 1 places the part into sleep mode. Sleep mode + * suppresses DATA_READY, stops transmission of data to FIFO, and switches the + * sampling rate to one specified by the wakeup bits. In sleep mode, only the + * activity function can be used. When the DATA_READY interrupt is suppressed, + * the output data registers (Register 0x32 to Register 0x37) are still updated + * at the sampling rate set by the wakeup bits (D1:D0). + * + * When clearing the sleep bit, it is recommended that the part be placed into + * standby mode and then set back to measurement mode with a subsequent write. + * This is done to ensure that the device is properly biased if sleep mode is + * manually disabled; otherwise, the first few samples of data after the sleep + * bit is cleared may have additional noise, especially if the device was asleep + * when the bit was cleared. + * + * @return Sleep enabled status + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_SLEEP_BIT + */ +bool ADXL345::getSleepEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_SLEEP_BIT, buffer); + return buffer[0]; +} +/** Set sleep mode enabled status. + * @param Sleep mode enabled status + * @see getSleepEnabled() + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_SLEEP_BIT + */ +void ADXL345::setSleepEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_SLEEP_BIT, enabled); +} +/** Get wakeup frequency. + * These bits control the frequency of readings in sleep mode as described in + * Table 20 in the datasheet. (That is, 0 = 8Hz, 1 = 4Hz, 2 = 2Hz, 3 = 1Hz) + * @return Wakeup frequency (0x0 - 0x3, indicating 8/4/2/1Hz respectively) + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_SLEEP_BIT + */ +uint8_t ADXL345::getWakeupFrequency() { + I2Cdev::readBits(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_WAKEUP_BIT, ADXL345_PCTL_WAKEUP_LENGTH, buffer); + return buffer[0]; +} +/** Set wakeup frequency. + * @param frequency Wakeup frequency (0x0 - 0x3, indicating 8/4/2/1Hz respectively) + * @see getWakeupFrequency() + * @see ADXL345_RA_POWER_CTL + * @see ADXL345_PCTL_SLEEP_BIT + */ +void ADXL345::setWakeupFrequency(uint8_t frequency) { + I2Cdev::writeBits(devAddr, ADXL345_RA_POWER_CTL, ADXL345_PCTL_WAKEUP_BIT, ADXL345_PCTL_WAKEUP_LENGTH, frequency); +} + +// INT_ENABLE register + +/** Get DATA_READY interrupt enabled status. + * Setting bits in this register to a value of 1 enables their respective + * functions to generate interrupts, whereas a value of 0 prevents the functions + * from generating interrupts. The DATA_READY, watermark, and overrun bits + * enable only the interrupt output; the functions are always enabled. It is + * recommended that interrupts be configured before enabling their outputs. + * @return DATA_READY interrupt enabled status. + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_DATA_READY_BIT + */ +bool ADXL345::getIntDataReadyEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_DATA_READY_BIT, buffer); + return buffer[0]; +} +/** Set DATA_READY interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_DATA_READY_BIT + */ +void ADXL345::setIntDataReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_DATA_READY_BIT, enabled); +} +/** Set SINGLE_TAP interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_SINGLE_TAP_BIT + */ +bool ADXL345::getIntSingleTapEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_SINGLE_TAP_BIT, buffer); + return buffer[0]; +} +/** Set SINGLE_TAP interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_SINGLE_TAP_BIT + */ +void ADXL345::setIntSingleTapEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_SINGLE_TAP_BIT, enabled); +} +/** Get DOUBLE_TAP interrupt enabled status. + * @return Interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_DOUBLE_TAP_BIT + */ +bool ADXL345::getIntDoubleTapEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_DOUBLE_TAP_BIT, buffer); + return buffer[0]; +} +/** Set DOUBLE_TAP interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_DOUBLE_TAP_BIT + */ +void ADXL345::setIntDoubleTapEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_DOUBLE_TAP_BIT, enabled); +} +/** Set ACTIVITY interrupt enabled status. + * @return Interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_ACTIVITY_BIT + */ +bool ADXL345::getIntActivityEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_ACTIVITY_BIT, buffer); + return buffer[0]; +} +/** Set ACTIVITY interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_ACTIVITY_BIT + */ +void ADXL345::setIntActivityEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_ACTIVITY_BIT, enabled); +} +/** Get INACTIVITY interrupt enabled status. + * @return Interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_INACTIVITY_BIT + */ +bool ADXL345::getIntInactivityEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_INACTIVITY_BIT, buffer); + return buffer[0]; +} +/** Set INACTIVITY interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_INACTIVITY_BIT + */ +void ADXL345::setIntInactivityEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_INACTIVITY_BIT, enabled); +} +/** Get FREE_FALL interrupt enabled status. + * @return Interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_FREE_FALL_BIT + */ +bool ADXL345::getIntFreefallEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_FREE_FALL_BIT, buffer); + return buffer[0]; +} +/** Set FREE_FALL interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_FREE_FALL_BIT + */ +void ADXL345::setIntFreefallEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_FREE_FALL_BIT, enabled); +} +/** Get WATERMARK interrupt enabled status. + * @return Interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_WATERMARK_BIT + */ +bool ADXL345::getIntWatermarkEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_WATERMARK_BIT, buffer); + return buffer[0]; +} +/** Set WATERMARK interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_WATERMARK_BIT + */ +void ADXL345::setIntWatermarkEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_WATERMARK_BIT, enabled); +} +/** Get OVERRUN interrupt enabled status. + * @return Interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_OVERRUN_BIT + */ +bool ADXL345::getIntOverrunEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_OVERRUN_BIT, buffer); + return buffer[0]; +} +/** Set OVERRUN interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see ADXL345_RA_INT_ENABLE + * @see ADXL345_INT_OVERRUN_BIT + */ +void ADXL345::setIntOverrunEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_ENABLE, ADXL345_INT_OVERRUN_BIT, enabled); +} + +// INT_MAP register + +/** Get DATA_READY interrupt pin. + * Any bits set to 0 in this register send their respective interrupts to the + * INT1 pin, whereas bits set to 1 send their respective interrupts to the INT2 + * pin. All selected interrupts for a given pin are OR'ed. + * @return Interrupt pin setting + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_DATA_READY_BIT + */ +uint8_t ADXL345::getIntDataReadyPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_DATA_READY_BIT, buffer); + return buffer[0]; +} +/** Set DATA_READY interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_DATA_READY_BIT + */ +void ADXL345::setIntDataReadyPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_DATA_READY_BIT, pin); +} +/** Get SINGLE_TAP interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_SINGLE_TAP_BIT + */ +uint8_t ADXL345::getIntSingleTapPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_SINGLE_TAP_BIT, buffer); + return buffer[0]; +} +/** Set SINGLE_TAP interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_SINGLE_TAP_BIT + */ +void ADXL345::setIntSingleTapPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_SINGLE_TAP_BIT, pin); +} +/** Get DOUBLE_TAP interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_DOUBLE_TAP_BIT + */ +uint8_t ADXL345::getIntDoubleTapPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_DOUBLE_TAP_BIT, buffer); + return buffer[0]; +} +/** Set DOUBLE_TAP interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_DOUBLE_TAP_BIT + */ +void ADXL345::setIntDoubleTapPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_DOUBLE_TAP_BIT, pin); +} +/** Get ACTIVITY interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_ACTIVITY_BIT + */ +uint8_t ADXL345::getIntActivityPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_ACTIVITY_BIT, buffer); + return buffer[0]; +} +/** Set ACTIVITY interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_ACTIVITY_BIT + */ +void ADXL345::setIntActivityPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_ACTIVITY_BIT, pin); +} +/** Get INACTIVITY interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_INACTIVITY_BIT + */ +uint8_t ADXL345::getIntInactivityPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_INACTIVITY_BIT, buffer); + return buffer[0]; +} +/** Set INACTIVITY interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_INACTIVITY_BIT + */ +void ADXL345::setIntInactivityPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_INACTIVITY_BIT, pin); +} +/** Get FREE_FALL interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_FREE_FALL_BIT + */ +uint8_t ADXL345::getIntFreefallPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_FREE_FALL_BIT, buffer); + return buffer[0]; +} +/** Set FREE_FALL interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_FREE_FALL_BIT + */ +void ADXL345::setIntFreefallPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_FREE_FALL_BIT, pin); +} +/** Get WATERMARK interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_WATERMARK_BIT + */ +uint8_t ADXL345::getIntWatermarkPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_WATERMARK_BIT, buffer); + return buffer[0]; +} +/** Set WATERMARK interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_WATERMARK_BIT + */ +void ADXL345::setIntWatermarkPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_WATERMARK_BIT, pin); +} +/** Get OVERRUN interrupt pin. + * @return Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_OVERRUN_BIT + */ +uint8_t ADXL345::getIntOverrunPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_OVERRUN_BIT, buffer); + return buffer[0]; +} +/** Set OVERRUN interrupt pin. + * @param pin Interrupt pin setting + * @see getIntDataReadyPin() + * @see ADXL345_RA_INT_MAP + * @see ADXL345_INT_OVERRUN_BIT + */ +void ADXL345::setIntOverrunPin(uint8_t pin) { + I2Cdev::writeBit(devAddr, ADXL345_RA_INT_MAP, ADXL345_INT_OVERRUN_BIT, pin); +} + +// INT_SOURCE register + +/** Get DATA_READY interrupt source flag. + * Bits set to 1 in this register indicate that their respective functions have + * triggered an event, whereas a value of 0 indicates that the corresponding + * event has not occurred. The DATA_READY, watermark, and overrun bits are + * always set if the corresponding events occur, regardless of the INT_ENABLE + * register settings, and are cleared by reading data from the DATAX, DATAY, and + * DATAZ registers. The DATA_READY and watermark bits may require multiple + * reads, as indicated in the FIFO mode descriptions in the FIFO section. Other + * bits, and the corresponding interrupts, are cleared by reading the INT_SOURCE + * register. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_DATA_READY_BIT + */ +uint8_t ADXL345::getIntDataReadySource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_DATA_READY_BIT, buffer); + return buffer[0]; +} +/** Get SINGLE_TAP interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_SINGLE_TAP_BIT + */ +uint8_t ADXL345::getIntSingleTapSource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_SINGLE_TAP_BIT, buffer); + return buffer[0]; +} +/** Get DOUBLE_TAP interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_DOUBLE_TAP_BIT + */ +uint8_t ADXL345::getIntDoubleTapSource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_DOUBLE_TAP_BIT, buffer); + return buffer[0]; +} +/** Get ACTIVITY interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_ACTIVITY_BIT + */ +uint8_t ADXL345::getIntActivitySource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_ACTIVITY_BIT, buffer); + return buffer[0]; +} +/** Get INACTIVITY interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_INACTIVITY_BIT + */ +uint8_t ADXL345::getIntInactivitySource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_INACTIVITY_BIT, buffer); + return buffer[0]; +} +/** Get FREE_FALL interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_FREE_FALL_BIT + */ +uint8_t ADXL345::getIntFreefallSource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_FREE_FALL_BIT, buffer); + return buffer[0]; +} +/** Get WATERMARK interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_WATERMARK_BIT + */ +uint8_t ADXL345::getIntWatermarkSource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_WATERMARK_BIT, buffer); + return buffer[0]; +} +/** Get OVERRUN interrupt source flag. + * @return Interrupt source flag + * @see ADXL345_RA_INT_SOURCE + * @see ADXL345_INT_OVERRUN_BIT + */ +uint8_t ADXL345::getIntOverrunSource() { + I2Cdev::readBit(devAddr, ADXL345_RA_INT_SOURCE, ADXL345_INT_OVERRUN_BIT, buffer); + return buffer[0]; +} + +// DATA_FORMAT register + +/** Get self-test force enabled. + * A setting of 1 in the SELF_TEST bit applies a self-test force to the sensor, + * causing a shift in the output data. A value of 0 disables the self-test + * force. + * @return Self-test force enabled setting + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_SELFTEST_BIT + */ +uint8_t ADXL345::getSelfTestEnabled() { + I2Cdev::readBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_SELFTEST_BIT, buffer); + return buffer[0]; +} +/** Set self-test force enabled. + * @param enabled New self-test force enabled setting + * @see getSelfTestEnabled() + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_SELFTEST_BIT + */ +void ADXL345::setSelfTestEnabled(uint8_t enabled) { + I2Cdev::writeBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_SELFTEST_BIT, enabled); +} +/** Get SPI mode setting. + * A value of 1 in the SPI bit sets the device to 3-wire SPI mode, and a value + * of 0 sets the device to 4-wire SPI mode. + * @return SPI mode setting + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_SELFTEST_BIT + */ +uint8_t ADXL345::getSPIMode() { + I2Cdev::readBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_SPIMODE_BIT, buffer); + return buffer[0]; +} +/** Set SPI mode setting. + * @param mode New SPI mode setting + * @see getSPIMode() + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_SELFTEST_BIT + */ +void ADXL345::setSPIMode(uint8_t mode) { + I2Cdev::writeBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_SPIMODE_BIT, mode); +} +/** Get interrupt mode setting. + * A value of 0 in the INT_INVERT bit sets the interrupts to active high, and a + * value of 1 sets the interrupts to active low. + * @return Interrupt mode setting + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_INTMODE_BIT + */ +uint8_t ADXL345::getInterruptMode() { + I2Cdev::readBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_INTMODE_BIT, buffer); + return buffer[0]; +} +/** Set interrupt mode setting. + * @param mode New interrupt mode setting + * @see getInterruptMode() + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_INTMODE_BIT + */ +void ADXL345::setInterruptMode(uint8_t mode) { + I2Cdev::writeBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_INTMODE_BIT, mode); +} +/** Get full resolution mode setting. + * When this bit is set to a value of 1, the device is in full resolution mode, + * where the output resolution increases with the g range set by the range bits + * to maintain a 4 mg/LSB scale factor. When the FULL_RES bit is set to 0, the + * device is in 10-bit mode, and the range bits determine the maximum g range + * and scale factor. + * @return Full resolution enabled setting + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_FULL_RES_BIT + */ +uint8_t ADXL345::getFullResolution() { + I2Cdev::readBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_FULL_RES_BIT, buffer); + return buffer[0]; +} +/** Set full resolution mode setting. + * @param resolution New full resolution enabled setting + * @see getFullResolution() + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_FULL_RES_BIT + */ +void ADXL345::setFullResolution(uint8_t resolution) { + I2Cdev::writeBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_FULL_RES_BIT, resolution); +} +/** Get data justification mode setting. + * A setting of 1 in the justify bit selects left-justified (MSB) mode, and a + * setting of 0 selects right-justified mode with sign extension. + * @return Data justification mode + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_JUSTIFY_BIT + */ +uint8_t ADXL345::getDataJustification() { + I2Cdev::readBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_JUSTIFY_BIT, buffer); + return buffer[0]; +} +/** Set data justification mode setting. + * @param justification New data justification mode + * @see getDataJustification() + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_JUSTIFY_BIT + */ +void ADXL345::setDataJustification(uint8_t justification) { + I2Cdev::writeBit(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_JUSTIFY_BIT, justification); +} +/** Get data range setting. + * These bits set the g range as described in Table 21. (That is, 0x0 - 0x3 to + * indicate 2g/4g/8g/16g respectively) + * @return Range value (0x0 - 0x3 for 2g/4g/8g/16g) + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_RANGE_BIT + * @see ADXL345_FORMAT_RANGE_LENGTH + */ +uint8_t ADXL345::getRange() { + I2Cdev::readBits(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_RANGE_BIT, ADXL345_FORMAT_RANGE_LENGTH, buffer); + return buffer[0]; +} +/** Set data range setting. + * @param range Range value (0x0 - 0x3 for 2g/4g/8g/16g) + * @see getRange() + * @see ADXL345_RA_DATA_FORMAT + * @see ADXL345_FORMAT_RANGE_BIT + * @see ADXL345_FORMAT_RANGE_LENGTH + */ +void ADXL345::setRange(uint8_t range) { + I2Cdev::writeBits(devAddr, ADXL345_RA_DATA_FORMAT, ADXL345_FORMAT_RANGE_BIT, ADXL345_FORMAT_RANGE_LENGTH, range); +} + +// DATA* registers + +/** Get 3-axis accleration measurements. + * These six bytes (Register 0x32 to Register 0x37) are eight bits each and hold + * the output data for each axis. Register 0x32 and Register 0x33 hold the + * output data for the x-axis, Register 0x34 and Register 0x35 hold the output + * data for the y-axis, and Register 0x36 and Register 0x37 hold the output data + * for the z-axis. The output data is twos complement, with DATAx0 as the least + * significant byte and DATAx1 as the most significant byte, where x represent + * X, Y, or Z. The DATA_FORMAT register (Address 0x31) controls the format of + * the data. It is recommended that a multiple-byte read of all registers be + * performed to prevent a change in data between reads of sequential registers. + * + * The DATA_FORMAT register controls the presentation of data to Register 0x32 + * through Register 0x37. All data, except that for the +/-16 g range, must be + * clipped to avoid rollover. + * + * @param x 16-bit signed integer container for X-axis acceleration + * @param y 16-bit signed integer container for Y-axis acceleration + * @param z 16-bit signed integer container for Z-axis acceleration + * @see ADXL345_RA_DATAX0 + */ +void ADXL345::getAcceleration(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, ADXL345_RA_DATAX0, 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]; +} +/** Get X-axis accleration measurement. + * @return 16-bit signed X-axis acceleration value + * @see ADXL345_RA_DATAX0 + */ +int16_t ADXL345::getAccelerationX() { + I2Cdev::readBytes(devAddr, ADXL345_RA_DATAX0, 2, buffer); + return (((int16_t)buffer[1]) << 8) | buffer[0]; +} +/** Get Y-axis accleration measurement. + * @return 16-bit signed Y-axis acceleration value + * @see ADXL345_RA_DATAY0 + */ +int16_t ADXL345::getAccelerationY() { + I2Cdev::readBytes(devAddr, ADXL345_RA_DATAY0, 2, buffer); + return (((int16_t)buffer[1]) << 8) | buffer[0]; +} +/** Get Z-axis accleration measurement. + * @return 16-bit signed Z-axis acceleration value + * @see ADXL345_RA_DATAZ0 + */ +int16_t ADXL345::getAccelerationZ() { + I2Cdev::readBytes(devAddr, ADXL345_RA_DATAZ0, 2, buffer); + return (((int16_t)buffer[1]) << 8) | buffer[0]; +} + +// FIFO_CTL register + +/** Get FIFO mode. + * These bits set the FIFO mode, as described in Table 22. That is: + * + * 0x0 = Bypass (FIFO is bypassed.) + * + * 0x1 = FIFO (FIFO collects up to 32 values and then stops collecting data, + * collecting new data only when FIFO is not full.) + * + * 0x2 = Stream (FIFO holds the last 32 data values. When FIFO is full, the + * oldest data is overwritten with newer data.) + * + * 0x3 = Trigger (When triggered by the trigger bit, FIFO holds the last data + * samples before the trigger event and then continues to collect data + * until full. New data is collected only when FIFO is not full.) + * + * @return Curent FIFO mode + * @see ADXL345_RA_FIFO_CTL + * @see ADXL345_FIFO_MODE_BIT + * @see ADXL345_FIFO_MODE_LENGTH + */ +uint8_t ADXL345::getFIFOMode() { + I2Cdev::readBits(devAddr, ADXL345_RA_FIFO_CTL, ADXL345_FIFO_MODE_BIT, ADXL345_FIFO_MODE_LENGTH, buffer); + return buffer[0]; +} +/** Set FIFO mode. + * @param mode New FIFO mode + * @see getFIFOMode() + * @see ADXL345_RA_FIFO_CTL + * @see ADXL345_FIFO_MODE_BIT + * @see ADXL345_FIFO_MODE_LENGTH + */ +void ADXL345::setFIFOMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, ADXL345_RA_FIFO_CTL, ADXL345_FIFO_MODE_BIT, ADXL345_FIFO_MODE_LENGTH, mode); +} +/** Get FIFO trigger interrupt setting. + * A value of 0 in the trigger bit links the trigger event of trigger mode to + * INT1, and a value of 1 links the trigger event to INT2. + * @return Current FIFO trigger interrupt setting + * @see ADXL345_RA_FIFO_CTL + * @see ADXL345_FIFO_TRIGGER_BIT + */ +uint8_t ADXL345::getFIFOTriggerInterruptPin() { + I2Cdev::readBit(devAddr, ADXL345_RA_FIFO_CTL, ADXL345_FIFO_TRIGGER_BIT, buffer); + return buffer[0]; +} +/** Set FIFO trigger interrupt pin setting. + * @param interrupt New FIFO trigger interrupt pin setting + * @see ADXL345_RA_FIFO_CTL + * @see ADXL345_FIFO_TRIGGER_BIT + */ +void ADXL345::setFIFOTriggerInterruptPin(uint8_t interrupt) { + I2Cdev::writeBit(devAddr, ADXL345_RA_FIFO_CTL, ADXL345_FIFO_TRIGGER_BIT, interrupt); +} +/** Get FIFO samples setting. + * The function of these bits depends on the FIFO mode selected (see Table 23). + * Entering a value of 0 in the samples bits immediately sets the watermark + * status bit in the INT_SOURCE register, regardless of which FIFO mode is + * selected. Undesirable operation may occur if a value of 0 is used for the + * samples bits when trigger mode is used. + * + * MODE | EFFECT + * --------+------------------------------------------------------------------- + * Bypass | None. + * FIFO | FIFO entries needed to trigger a watermark interrupt. + * Stream | FIFO entries needed to trigger a watermark interrupt. + * Trigger | Samples are retained in the FIFO buffer before a trigger event. + * + * @return Current FIFO samples setting + * @see ADXL345_RA_FIFO_CTL + * @see ADXL345_FIFO_SAMPLES_BIT + * @see ADXL345_FIFO_SAMPLES_LENGTH + */ +uint8_t ADXL345::getFIFOSamples() { + I2Cdev::readBits(devAddr, ADXL345_RA_FIFO_CTL, ADXL345_FIFO_SAMPLES_BIT, ADXL345_FIFO_SAMPLES_LENGTH, buffer); + return buffer[0]; +} +/** Set FIFO samples setting. + * @param size New FIFO samples setting (impact depends on FIFO mode setting) + * @see getFIFOSamples() + * @see getFIFOMode() + * @see ADXL345_RA_FIFO_CTL + * @see ADXL345_FIFO_SAMPLES_BIT + * @see ADXL345_FIFO_SAMPLES_LENGTH + */ +void ADXL345::setFIFOSamples(uint8_t size) { + I2Cdev::writeBits(devAddr, ADXL345_RA_FIFO_CTL, ADXL345_FIFO_SAMPLES_BIT, ADXL345_FIFO_SAMPLES_LENGTH, size); +} + +// FIFO_STATUS register + +/** Get FIFO trigger occurred status. + * A 1 in the FIFO_TRIG bit corresponds to a trigger event occurring, and a 0 + * means that a FIFO trigger event has not occurred. + * @return FIFO trigger occurred status + * @see ADXL345_RA_FIFO_STATUS + * @see ADXL345_FIFOSTAT_TRIGGER_BIT + */ +bool ADXL345::getFIFOTriggerOccurred() { + I2Cdev::readBit(devAddr, ADXL345_RA_FIFO_STATUS, ADXL345_FIFOSTAT_TRIGGER_BIT, buffer); + return buffer[0]; +} +/** Get FIFO length. + * These bits report how many data values are stored in FIFO. Access to collect + * the data from FIFO is provided through the DATAX, DATAY, and DATAZ registers. + * FIFO reads must be done in burst or multiple-byte mode because each FIFO + * level is cleared after any read (single- or multiple-byte) of FIFO. FIFO + * stores a maximum of 32 entries, which equates to a maximum of 33 entries + * available at any given time because an additional entry is available at the + * output filter of the I2Cdev:: + * @return Current FIFO length + * @see ADXL345_RA_FIFO_STATUS + * @see ADXL345_FIFOSTAT_LENGTH_BIT + * @see ADXL345_FIFOSTAT_LENGTH_LENGTH + */ +uint8_t ADXL345::getFIFOLength() { + I2Cdev::readBits(devAddr, ADXL345_RA_FIFO_STATUS, ADXL345_FIFOSTAT_LENGTH_BIT, ADXL345_FIFOSTAT_LENGTH_LENGTH, buffer); + return buffer[0]; +} diff --git a/libraries/ADXL345/ADXL345.h b/libraries/ADXL345/ADXL345.h new file mode 100644 index 0000000..b610caf --- /dev/null +++ b/libraries/ADXL345/ADXL345.h @@ -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 +// 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_ */ diff --git a/libraries/ADXL345/examples/ADXL345_raw/ADXL345_raw.ino b/libraries/ADXL345/examples/ADXL345_raw/ADXL345_raw.ino new file mode 100644 index 0000000..2039df0 --- /dev/null +++ b/libraries/ADXL345/examples/ADXL345_raw/ADXL345_raw.ino @@ -0,0 +1,86 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for ADXL345 class +// 10/7/2011 by Jeff Rowberg +// 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); +} diff --git a/libraries/ADXL345/library.json b/libraries/ADXL345/library.json new file mode 100644 index 0000000..bb71418 --- /dev/null +++ b/libraries/ADXL345/library.json @@ -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" +} diff --git a/libraries/AK8963/AK8963.cpp b/libraries/AK8963/AK8963.cpp new file mode 100644 index 0000000..7643d76 --- /dev/null +++ b/libraries/AK8963/AK8963.cpp @@ -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 +// 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); +} diff --git a/libraries/AK8963/AK8963.h b/libraries/AK8963/AK8963.h new file mode 100644 index 0000000..c19f13b --- /dev/null +++ b/libraries/AK8963/AK8963.h @@ -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 +// 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_ */ diff --git a/libraries/AK8963/library.json b/libraries/AK8963/library.json new file mode 100644 index 0000000..69da4f2 --- /dev/null +++ b/libraries/AK8963/library.json @@ -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" +} diff --git a/libraries/AK8975/.AK8975.cpp.un~ b/libraries/AK8975/.AK8975.cpp.un~ new file mode 100644 index 0000000..a00b569 Binary files /dev/null and b/libraries/AK8975/.AK8975.cpp.un~ differ diff --git a/libraries/AK8975/AK8975.cpp b/libraries/AK8975/AK8975.cpp new file mode 100644 index 0000000..b0368b8 --- /dev/null +++ b/libraries/AK8975/AK8975.cpp @@ -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 +// 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); +} diff --git a/libraries/AK8975/AK8975.cpp~ b/libraries/AK8975/AK8975.cpp~ new file mode 100644 index 0000000..c946d0b --- /dev/null +++ b/libraries/AK8975/AK8975.cpp~ @@ -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 +// 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); +} diff --git a/libraries/AK8975/AK8975.h b/libraries/AK8975/AK8975.h new file mode 100644 index 0000000..cbaba84 --- /dev/null +++ b/libraries/AK8975/AK8975.h @@ -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 +// 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_ */ \ No newline at end of file diff --git a/libraries/AK8975/examples/AK8975_MPUEVB_heading/AK8975_MPUEVB_heading.ino b/libraries/AK8975/examples/AK8975_MPUEVB_heading/AK8975_MPUEVB_heading.ino new file mode 100644 index 0000000..aef0e80 --- /dev/null +++ b/libraries/AK8975/examples/AK8975_MPUEVB_heading/AK8975_MPUEVB_heading.ino @@ -0,0 +1,118 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for AK8975 class +// 6/11/2012 by Jeff Rowberg +// 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 +} diff --git a/libraries/AK8975/examples/AK8975_MPUEVB_raw/AK8975_MPUEVB_raw.ino b/libraries/AK8975/examples/AK8975_MPUEVB_raw/AK8975_MPUEVB_raw.ino new file mode 100644 index 0000000..630833e --- /dev/null +++ b/libraries/AK8975/examples/AK8975_MPUEVB_raw/AK8975_MPUEVB_raw.ino @@ -0,0 +1,109 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for AK8975 class +// 10/7/2011 by Jeff Rowberg +// 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); +} diff --git a/libraries/AK8975/examples/AK8975_raw/AK8975_raw.ino b/libraries/AK8975/examples/AK8975_raw/AK8975_raw.ino new file mode 100644 index 0000000..49a56af --- /dev/null +++ b/libraries/AK8975/examples/AK8975_raw/AK8975_raw.ino @@ -0,0 +1,88 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for AK8975 class +// 10/7/2011 by Jeff Rowberg +// 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); +} diff --git a/libraries/AK8975/library.json b/libraries/AK8975/library.json new file mode 100644 index 0000000..0010d1e --- /dev/null +++ b/libraries/AK8975/library.json @@ -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" +} diff --git a/libraries/AccelStepper-master/.github/ISSUE_TEMPLATE.md b/libraries/AccelStepper-master/.github/ISSUE_TEMPLATE.md new file mode 100644 index 0000000..f0e2614 --- /dev/null +++ b/libraries/AccelStepper-master/.github/ISSUE_TEMPLATE.md @@ -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** diff --git a/libraries/AccelStepper-master/.github/PULL_REQUEST_TEMPLATE.md b/libraries/AccelStepper-master/.github/PULL_REQUEST_TEMPLATE.md new file mode 100644 index 0000000..7b641eb --- /dev/null +++ b/libraries/AccelStepper-master/.github/PULL_REQUEST_TEMPLATE.md @@ -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. diff --git a/libraries/AccelStepper-master/AccelStepper.cpp b/libraries/AccelStepper-master/AccelStepper.cpp new file mode 100644 index 0000000..da5b3b2 --- /dev/null +++ b/libraries/AccelStepper-master/AccelStepper.cpp @@ -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(); +} + diff --git a/libraries/AccelStepper-master/AccelStepper.h b/libraries/AccelStepper-master/AccelStepper.h new file mode 100644 index 0000000..a7906e8 --- /dev/null +++ b/libraries/AccelStepper-master/AccelStepper.h @@ -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 +/// \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 diff --git a/libraries/AccelStepper-master/LICENSE b/libraries/AccelStepper-master/LICENSE new file mode 100644 index 0000000..da124e1 --- /dev/null +++ b/libraries/AccelStepper-master/LICENSE @@ -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. diff --git a/libraries/AccelStepper-master/MANIFEST b/libraries/AccelStepper-master/MANIFEST new file mode 100644 index 0000000..8835e18 --- /dev/null +++ b/libraries/AccelStepper-master/MANIFEST @@ -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 diff --git a/libraries/AccelStepper-master/Makefile b/libraries/AccelStepper-master/Makefile new file mode 100644 index 0000000..cb3f65d --- /dev/null +++ b/libraries/AccelStepper-master/Makefile @@ -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) diff --git a/libraries/AccelStepper-master/README.txt b/libraries/AccelStepper-master/README.txt new file mode 100644 index 0000000..0e5b45f --- /dev/null +++ b/libraries/AccelStepper-master/README.txt @@ -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) \ No newline at end of file diff --git a/libraries/AccelStepper-master/doc/AccelStepper_8h-source.html b/libraries/AccelStepper-master/doc/AccelStepper_8h-source.html new file mode 100644 index 0000000..2c0c25d --- /dev/null +++ b/libraries/AccelStepper-master/doc/AccelStepper_8h-source.html @@ -0,0 +1,336 @@ + + +AccelStepper: AccelStepper.h Source File + + + + + +
Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by  + +doxygen 1.5.6
+ + diff --git a/libraries/AccelStepper-master/doc/annotated.html b/libraries/AccelStepper-master/doc/annotated.html new file mode 100644 index 0000000..18e809b --- /dev/null +++ b/libraries/AccelStepper-master/doc/annotated.html @@ -0,0 +1,32 @@ + + +AccelStepper: Class List + + + + + +
+

Class List

Here are the classes, structs, unions and interfaces with brief descriptions: + +
AccelStepperSupport for stepper motors with acceleration etc
+
+
Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by  + +doxygen 1.5.6
+ + diff --git a/libraries/AccelStepper-master/doc/classAccelStepper-members.html b/libraries/AccelStepper-master/doc/classAccelStepper-members.html new file mode 100644 index 0000000..471ce2f --- /dev/null +++ b/libraries/AccelStepper-master/doc/classAccelStepper-members.html @@ -0,0 +1,54 @@ + + +AccelStepper: Member List + + + + + +
+

AccelStepper Member List

This is the complete list of members for AccelStepper, including all inherited members.

+ + + + + + + + + + + + + + + + + + + + + + + + +
AccelStepper(uint8_t pins=4, uint8_t pin1=2, uint8_t pin2=3, uint8_t pin3=4, uint8_t pin4=5)AccelStepper
computeNewSpeed()AccelStepper [protected]
currentPosition()AccelStepper
desiredSpeed()AccelStepper [protected, virtual]
disableOutputs()AccelStepper
distanceToGo()AccelStepper
enableOutputs()AccelStepper
move(long relative)AccelStepper
moveTo(long absolute)AccelStepper
run()AccelStepper
runSpeed()AccelStepper
runSpeedToPosition()AccelStepper
runToNewPosition(long position)AccelStepper
runToPosition()AccelStepper
setAcceleration(float acceleration)AccelStepper
setCurrentPosition(long position)AccelStepper
setMaxSpeed(float speed)AccelStepper
setSpeed(float speed)AccelStepper
speed()AccelStepper
step(uint8_t step)AccelStepper [protected, virtual]
step1(uint8_t step)AccelStepper [protected, virtual]
step2(uint8_t step)AccelStepper [protected, virtual]
step4(uint8_t step)AccelStepper [protected, virtual]
targetPosition()AccelStepper

+
Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by  + +doxygen 1.5.6
+ + diff --git a/libraries/AccelStepper-master/doc/classAccelStepper.html b/libraries/AccelStepper-master/doc/classAccelStepper.html new file mode 100644 index 0000000..fb17ffc --- /dev/null +++ b/libraries/AccelStepper-master/doc/classAccelStepper.html @@ -0,0 +1,723 @@ + + +AccelStepper: AccelStepper Class Reference + + + + + +
+

AccelStepper Class Reference

Support for stepper motors with acceleration etc. +More... +

+#include <AccelStepper.h> +

+ +

+List of all members. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

Public Member Functions

 AccelStepper (uint8_t pins=4, uint8_t pin1=2, uint8_t pin2=3, uint8_t pin3=4, uint8_t pin4=5)
void moveTo (long absolute)
void move (long relative)
boolean run ()
boolean runSpeed ()
void setMaxSpeed (float speed)
void setAcceleration (float acceleration)
void setSpeed (float speed)
float speed ()
long distanceToGo ()
long targetPosition ()
long currentPosition ()
void setCurrentPosition (long position)
void runToPosition ()
boolean runSpeedToPosition ()
void runToNewPosition (long position)
void disableOutputs ()
void enableOutputs ()

Protected Member Functions

void computeNewSpeed ()
virtual void step (uint8_t step)
virtual void step1 (uint8_t step)
virtual void step2 (uint8_t step)
virtual void step4 (uint8_t step)
virtual float desiredSpeed ()
+


Detailed Description

+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.

+

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.
+
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.
+
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.

Constructor & Destructor Documentation

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
AccelStepper::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. The motor pins will be initialised to OUTPUT mode during the constructor by a call to enableOutputs().

Parameters:
+ + + + + + +
[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.
[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)
[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.
[in] pin3 Arduino digital pin number for motor pin 3. Defaults to pin 4.
[in] pin4 Arduino digital pin number for motor pin 4. Defaults to pin 5.
+
+ +

References enableOutputs().

+ +
+

+


Member Function Documentation

+ +
+
+ + + + + + + + + +
void AccelStepper::moveTo (long  absolute  ) 
+
+
+ +

+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.

Parameters:
+ + +
[in] absolute The desired absolute position. Negative is anticlockwise from the 0 position.
+
+ +

References computeNewSpeed().

+ +

Referenced by move(), and runToNewPosition().

+ +
+

+ +

+
+ + + + + + + + + +
void AccelStepper::move (long  relative  ) 
+
+
+ +

+Set the target position relative to the current position

Parameters:
+ + +
[in] relative The desired position relative to the current position. Negative is anticlockwise from the current position.
+
+ +

References moveTo().

+ +
+

+ +

+
+ + + + + + + + +
boolean AccelStepper::run (  ) 
+
+
+ +

+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.

Returns:
true if the motor is at the target position.
+ +

References computeNewSpeed(), and runSpeed().

+ +

Referenced by runToPosition().

+ +
+

+ +

+
+ + + + + + + + +
boolean AccelStepper::runSpeed (  ) 
+
+
+ +

+Poll the motor and step it if a step is due, implmenting a constant speed as set by the most recent call to setSpeed().

Returns:
true if the motor was stepped.
+ +

References step().

+ +

Referenced by run(), and runSpeedToPosition().

+ +
+

+ +

+
+ + + + + + + + + +
void AccelStepper::setMaxSpeed (float  speed  ) 
+
+
+ +

+Sets the maximum permitted speed. the run() function will accelerate up to the speed set by this function.

Parameters:
+ + +
[in] speed The desired maximum speed in steps per second. Must be > 0. Speeds of more than 1000 steps per second are unreliable.
+
+ +

References computeNewSpeed().

+ +
+

+ +

+
+ + + + + + + + + +
void AccelStepper::setAcceleration (float  acceleration  ) 
+
+
+ +

+Sets the acceleration and deceleration parameter.

Parameters:
+ + +
[in] acceleration The desired acceleration in steps per second per second. Must be > 0.
+
+ +

References computeNewSpeed().

+ +
+

+ +

+
+ + + + + + + + + +
void AccelStepper::setSpeed (float  speed  ) 
+
+
+ +

+Sets the desired constant speed for use with runSpeed().

Parameters:
+ + +
[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.
+
+ +

Referenced by computeNewSpeed().

+ +
+

+ +

+
+ + + + + + + + +
float AccelStepper::speed (  ) 
+
+
+ +

+The most recently set speed

Returns:
the most recent speed in steps per second
+ +
+

+ +

+
+ + + + + + + + +
long AccelStepper::distanceToGo (  ) 
+
+
+ +

+The distance from the current position to the target position.

Returns:
the distance from the current position to the target position in steps. Positive is clockwise from the current position.
+ +

Referenced by desiredSpeed().

+ +
+

+ +

+
+ + + + + + + + +
long AccelStepper::targetPosition (  ) 
+
+
+ +

+The most recently set target position.

Returns:
the target position in steps. Positive is clockwise from the 0 position.
+ +
+

+ +

+
+ + + + + + + + +
long AccelStepper::currentPosition (  ) 
+
+
+ +

+The currently motor position.

Returns:
the current motor position in steps. Positive is clockwise from the 0 position.
+ +
+

+ +

+
+ + + + + + + + + +
void AccelStepper::setCurrentPosition (long  position  ) 
+
+
+ +

+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.

Parameters:
+ + +
[in] position The position in steps of wherever the motor happens to be right now.
+
+ +
+

+ +

+
+ + + + + + + + +
void AccelStepper::runToPosition (  ) 
+
+
+ +

+Moves the motor to the target position and blocks until it is at position. Dont use this in event loops, since it blocks. +

References run().

+ +

Referenced by runToNewPosition().

+ +
+

+ +

+
+ + + + + + + + +
boolean AccelStepper::runSpeedToPosition (  ) 
+
+
+ +

+Runs at the currently selected speed until the target position is reached Does not implement accelerations. +

References runSpeed().

+ +
+

+ +

+
+ + + + + + + + + +
void AccelStepper::runToNewPosition (long  position  ) 
+
+
+ +

+Moves the motor to the new target position and blocks until it is at position. Dont use this in event loops, since it blocks.

Parameters:
+ + +
[in] position The new target position.
+
+ +

References moveTo(), and runToPosition().

+ +
+

+ +

+
+ + + + + + + + +
void AccelStepper::disableOutputs (  ) 
+
+
+ +

+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 AccelStepper::enableOutputs (  ) 
+
+
+ +

+Enable motor pin outputs by setting the motor pins to OUTPUT mode. Called automatically by the constructor. +

Referenced by AccelStepper().

+ +
+

+ +

+
+ + + + + + + + +
void AccelStepper::computeNewSpeed (  )  [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:

+ +

References desiredSpeed(), and setSpeed().

+ +

Referenced by moveTo(), run(), setAcceleration(), and setMaxSpeed().

+ +
+

+ +

+
+ + + + + + + + + +
void AccelStepper::step (uint8_t  step  )  [protected, virtual]
+
+
+ +

+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.

Parameters:
+ + +
[in] step The current step phase number (0 to 3)
+
+ +

References step1(), step2(), and step4().

+ +

Referenced by runSpeed().

+ +
+

+ +

+
+ + + + + + + + + +
void AccelStepper::step1 (uint8_t  step  )  [protected, virtual]
+
+
+ +

+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.

Parameters:
+ + +
[in] step The current step phase number (0 to 3)
+
+ +

Referenced by step().

+ +
+

+ +

+
+ + + + + + + + + +
void AccelStepper::step2 (uint8_t  step  )  [protected, virtual]
+
+
+ +

+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

Parameters:
+ + +
[in] step The current step phase number (0 to 3)
+
+ +

Referenced by step().

+ +
+

+ +

+
+ + + + + + + + + +
void AccelStepper::step4 (uint8_t  step  )  [protected, virtual]
+
+
+ +

+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.

Parameters:
+ + +
[in] step The current step phase number (0 to 3)
+
+ +

Referenced by step().

+ +
+

+ +

+
+ + + + + + + + +
float AccelStepper::desiredSpeed (  )  [protected, virtual]
+
+
+ +

+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. +

References distanceToGo().

+ +

Referenced by computeNewSpeed().

+ +
+

+


The documentation for this class was generated from the following files: +
+
Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by  + +doxygen 1.5.6
+ + diff --git a/libraries/AccelStepper-master/doc/doxygen.css b/libraries/AccelStepper-master/doc/doxygen.css new file mode 100644 index 0000000..22c4843 --- /dev/null +++ b/libraries/AccelStepper-master/doc/doxygen.css @@ -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%; +} + diff --git a/libraries/AccelStepper-master/doc/doxygen.png b/libraries/AccelStepper-master/doc/doxygen.png new file mode 100644 index 0000000..f0a274b Binary files /dev/null and b/libraries/AccelStepper-master/doc/doxygen.png differ diff --git a/libraries/AccelStepper-master/doc/files.html b/libraries/AccelStepper-master/doc/files.html new file mode 100644 index 0000000..87d95dd --- /dev/null +++ b/libraries/AccelStepper-master/doc/files.html @@ -0,0 +1,26 @@ + + +AccelStepper: File Index + + + + + +
+

File List

Here is a list of all documented files with brief descriptions: + +
AccelStepper.h [code]
+
+
Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by  + +doxygen 1.5.6
+ + diff --git a/libraries/AccelStepper-master/doc/functions.html b/libraries/AccelStepper-master/doc/functions.html new file mode 100644 index 0000000..cffefb7 --- /dev/null +++ b/libraries/AccelStepper-master/doc/functions.html @@ -0,0 +1,87 @@ + + +AccelStepper: Class Members + + + + + +
+Here is a list of all documented class members with links to the class documentation for each member: +

+

+
+
Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by  + +doxygen 1.5.6
+ + diff --git a/libraries/AccelStepper-master/doc/functions_func.html b/libraries/AccelStepper-master/doc/functions_func.html new file mode 100644 index 0000000..6e4d3fd --- /dev/null +++ b/libraries/AccelStepper-master/doc/functions_func.html @@ -0,0 +1,87 @@ + + +AccelStepper: Class Members - Functions + + + + + +
+  +

+

+
+
Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by  + +doxygen 1.5.6
+ + diff --git a/libraries/AccelStepper-master/doc/index.html b/libraries/AccelStepper-master/doc/index.html new file mode 100644 index 0000000..6391457 --- /dev/null +++ b/libraries/AccelStepper-master/doc/index.html @@ -0,0 +1,51 @@ + + +AccelStepper: AccelStepper library for Arduino + + + + + +
+

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:

    +
  • Supports acceleration and deceleration
  • +
  • Supports multiple simultaneous steppers, with independent concurrent stepping on each stepper
  • +
  • API functions never delay() or block
  • +
  • Supports 2 and 4 wire steppers
  • +
  • Supports stepper drivers such as the Sparkfun EasyDriver (based on 3967 driver chip)
  • +
  • Very slow speeds are supported
  • +
  • Extensive API
  • +
  • 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.

+

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:

+

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.
+
Revision History
+
Version:
1.0 Initial release

+1.1 Added speed() function to get the current speed.

+1.2 Added runSpeedToPosition() submitted by Gunnar Arndt.

+1.3 Added support for stepper drivers (ie with Step and Direction inputs) with _pins == 1

+
Author:
Mike McCauley (mikem@open.com.au)
+
+
Generated on Sun Oct 24 18:22:50 2010 for AccelStepper by  + +doxygen 1.5.6
+ + diff --git a/libraries/AccelStepper-master/doc/tab_b.gif b/libraries/AccelStepper-master/doc/tab_b.gif new file mode 100644 index 0000000..0d62348 Binary files /dev/null and b/libraries/AccelStepper-master/doc/tab_b.gif differ diff --git a/libraries/AccelStepper-master/doc/tab_l.gif b/libraries/AccelStepper-master/doc/tab_l.gif new file mode 100644 index 0000000..9b1e633 Binary files /dev/null and b/libraries/AccelStepper-master/doc/tab_l.gif differ diff --git a/libraries/AccelStepper-master/doc/tab_r.gif b/libraries/AccelStepper-master/doc/tab_r.gif new file mode 100644 index 0000000..ce9dd9f Binary files /dev/null and b/libraries/AccelStepper-master/doc/tab_r.gif differ diff --git a/libraries/AccelStepper-master/doc/tabs.css b/libraries/AccelStepper-master/doc/tabs.css new file mode 100644 index 0000000..95f00a9 --- /dev/null +++ b/libraries/AccelStepper-master/doc/tabs.css @@ -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; +} diff --git a/libraries/AccelStepper-master/examples/AFMotor_ConstantSpeed/AFMotor_ConstantSpeed.pde b/libraries/AccelStepper-master/examples/AFMotor_ConstantSpeed/AFMotor_ConstantSpeed.pde new file mode 100644 index 0000000..523150f --- /dev/null +++ b/libraries/AccelStepper-master/examples/AFMotor_ConstantSpeed/AFMotor_ConstantSpeed.pde @@ -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 +#include + +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(); +} diff --git a/libraries/AccelStepper-master/examples/AFMotor_MultiStepper/AFMotor_MultiStepper.pde b/libraries/AccelStepper-master/examples/AFMotor_MultiStepper/AFMotor_MultiStepper.pde new file mode 100644 index 0000000..d6db8b1 --- /dev/null +++ b/libraries/AccelStepper-master/examples/AFMotor_MultiStepper/AFMotor_MultiStepper.pde @@ -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 +#include + +// 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(); +} diff --git a/libraries/AccelStepper-master/examples/Blocking/Blocking.pde b/libraries/AccelStepper-master/examples/Blocking/Blocking.pde new file mode 100644 index 0000000..33534a6 --- /dev/null +++ b/libraries/AccelStepper-master/examples/Blocking/Blocking.pde @@ -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 + +// 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); +} diff --git a/libraries/AccelStepper-master/examples/ConstantSpeed/ConstantSpeed.pde b/libraries/AccelStepper-master/examples/ConstantSpeed/ConstantSpeed.pde new file mode 100644 index 0000000..52a8044 --- /dev/null +++ b/libraries/AccelStepper-master/examples/ConstantSpeed/ConstantSpeed.pde @@ -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 stepper; // Defaults to 4 pins on 2, 3, 4, 5 + +void setup() +{ + stepper.setSpeed(50); +} + +void loop() +{ + stepper.runSpeed(); +} diff --git a/libraries/AccelStepper-master/examples/MultiStepper/MultiStepper.pde b/libraries/AccelStepper-master/examples/MultiStepper/MultiStepper.pde new file mode 100644 index 0000000..e5d6fb9 --- /dev/null +++ b/libraries/AccelStepper-master/examples/MultiStepper/MultiStepper.pde @@ -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 + +// 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(); +} diff --git a/libraries/AccelStepper-master/examples/Overshoot/Overshoot.pde b/libraries/AccelStepper-master/examples/Overshoot/Overshoot.pde new file mode 100644 index 0000000..e7eb42c --- /dev/null +++ b/libraries/AccelStepper-master/examples/Overshoot/Overshoot.pde @@ -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 + +// 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); +} diff --git a/libraries/AccelStepper-master/examples/Random/Random.pde b/libraries/AccelStepper-master/examples/Random/Random.pde new file mode 100644 index 0000000..a30cb33 --- /dev/null +++ b/libraries/AccelStepper-master/examples/Random/Random.pde @@ -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 + +// 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(); +} diff --git a/libraries/AccelStepper-master/project.cfg b/libraries/AccelStepper-master/project.cfg new file mode 100644 index 0000000..c38326c --- /dev/null +++ b/libraries/AccelStepper-master/project.cfg @@ -0,0 +1,1294 @@ +# Doxyfile 1.5.3 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project +# +# All text after a hash (#) is considered a comment and will be ignored +# The format is: +# TAG = value [value, ...] +# For lists items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (" ") + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the config file that +# follow. The default is UTF-8 which is also the encoding used for all text before +# the first occurrence of this tag. Doxygen uses libiconv (or the iconv built into +# libc) for the transcoding. See http://www.gnu.org/software/libiconv for the list of +# possible encodings. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or a sequence of words surrounded +# by quotes) that should identify the project. + +PROJECT_NAME = AccelStepper + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. +# This could be handy for archiving the generated documentation or +# if some version control system is used. + +PROJECT_NUMBER = + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) +# base path where the generated documentation will be put. +# If a relative path is entered, it will be relative to the location +# where doxygen was started. If left blank the current directory will be used. + +OUTPUT_DIRECTORY = + +# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create +# 4096 sub-directories (in 2 levels) under the output directory of each output +# format and will distribute the generated files over these directories. +# Enabling this option can be useful when feeding doxygen a huge amount of +# source files, where putting all generated files in the same directory would +# otherwise cause performance problems for the file system. + +CREATE_SUBDIRS = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# The default language is English, other supported languages are: +# Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional, +# Croatian, Czech, Danish, Dutch, Finnish, French, German, Greek, Hungarian, +# Italian, Japanese, Japanese-en (Japanese with English messages), Korean, +# Korean-en, Lithuanian, Norwegian, Polish, Portuguese, Romanian, Russian, +# Serbian, Slovak, Slovene, Spanish, Swedish, and Ukrainian. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will +# include brief member descriptions after the members that are listed in +# the file and class documentation (similar to JavaDoc). +# Set to NO to disable this. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend +# the brief description of a member or function before the detailed description. +# Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator +# that is used to form the text in various listings. Each string +# in this list, if found as the leading text of the brief description, will be +# stripped from the text and the result after processing the whole list, is +# used as the annotated text. Otherwise, the brief description is used as-is. +# If left blank, the following values are used ("$name" is automatically +# replaced with the name of the entity): "The $name class" "The $name widget" +# "The $name file" "is" "provides" "specifies" "contains" +# "represents" "a" "an" "the" + +ABBREVIATE_BRIEF = + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# Doxygen will generate a detailed section even if there is only a brief +# description. + +ALWAYS_DETAILED_SEC = NO + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full +# path before files name in the file list and in the header files. If set +# to NO the shortest path that makes the file name unique will be used. + +FULL_PATH_NAMES = YES + +# If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag +# can be used to strip a user-defined part of the path. Stripping is +# only done if one of the specified strings matches the left-hand part of +# the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the +# path to strip. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of +# the path mentioned in the documentation of a class, which tells +# the reader which header file to include in order to use a class. +# If left blank only the name of the header file containing the class +# definition is used. Otherwise one should specify the include paths that +# are normally passed to the compiler using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter +# (but less readable) file names. This can be useful is your file systems +# doesn't support long names like on DOS, Mac, or CD-ROM. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen +# will interpret the first line (until the first dot) of a JavaDoc-style +# comment as the brief description. If set to NO, the JavaDoc +# comments will behave just like regular Qt-style comments +# (thus requiring an explicit @brief command for a brief description.) + +JAVADOC_AUTOBRIEF = NO + +# If the QT_AUTOBRIEF tag is set to YES then Doxygen will +# interpret the first line (until the first dot) of a Qt-style +# comment as the brief description. If set to NO, the comments +# will behave just like regular Qt-style comments (thus requiring +# an explicit \brief command for a brief description.) + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen +# treat a multi-line C++ special comment block (i.e. a block of //! or /// +# comments) as a brief description. This used to be the default behaviour. +# The new default is to treat a multi-line C++ comment block as a detailed +# description. Set this tag to YES if you prefer the old behaviour instead. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the DETAILS_AT_TOP tag is set to YES then Doxygen +# will output the detailed description near the top, like JavaDoc. +# If set to NO, the detailed description appears after the member +# documentation. + +DETAILS_AT_TOP = NO + +# If the INHERIT_DOCS tag is set to YES (the default) then an undocumented +# member inherits the documentation from any documented member that it +# re-implements. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce +# a new page for each member. If set to NO, the documentation of a member will +# be part of the file/class/namespace that contains it. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. +# Doxygen uses this value to replace tabs by spaces in code fragments. + +TAB_SIZE = 8 + +# This tag can be used to specify a number of aliases that acts +# as commands in the documentation. An alias has the form "name=value". +# For example adding "sideeffect=\par Side Effects:\n" will allow you to +# put the command \sideeffect (or @sideeffect) in the documentation, which +# will result in a user-defined paragraph with heading "Side Effects:". +# You can put \n's in the value part of an alias to insert newlines. + +ALIASES = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C +# sources only. Doxygen will then generate output that is more tailored for C. +# For instance, some of the names that are used will be different. The list +# of all members will be omitted, etc. + +OPTIMIZE_OUTPUT_FOR_C = NO + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java +# sources only. Doxygen will then generate output that is more tailored for Java. +# For instance, namespaces will be presented as packages, qualified scopes +# will look different, etc. + +OPTIMIZE_OUTPUT_JAVA = NO + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want to +# include (a tag file for) the STL sources as input, then you should +# set this tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); v.s. +# func(std::string) {}). This also make the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. + +CPP_CLI_SUPPORT = NO + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES, then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. + +DISTRIBUTE_GROUP_DOC = NO + +# Set the SUBGROUPING tag to YES (the default) to allow class member groups of +# the same type (for instance a group of public functions) to be put as a +# subgroup of that type (e.g. under the Public Functions section). Set it to +# NO to prevent subgrouping. Alternatively, this can be done per class using +# the \nosubgrouping command. + +SUBGROUPING = YES + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in +# documentation are documented, even if no documentation was available. +# Private class members and static file members will be hidden unless +# the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES + +EXTRACT_ALL = NO + +# If the EXTRACT_PRIVATE tag is set to YES all private members of a class +# will be included in the documentation. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_STATIC tag is set to YES all static members of a file +# will be included in the documentation. + +EXTRACT_STATIC = NO + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) +# defined locally in source files will be included in the documentation. +# If set to NO only classes defined in header files are included. + +EXTRACT_LOCAL_CLASSES = YES + +# This flag is only useful for Objective-C code. When set to YES local +# methods, which are defined in the implementation section but not in +# the interface are included in the documentation. +# If set to NO (the default) only methods in the interface are included. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be extracted +# and appear in the documentation as a namespace called 'anonymous_namespace{file}', +# where file will be replaced with the base name of the file that contains the anonymous +# namespace. By default anonymous namespace are hidden. + +EXTRACT_ANON_NSPACES = NO + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all +# undocumented members of documented classes, files or namespaces. +# If set to NO (the default) these members will be included in the +# various overviews, but no documentation section is generated. +# This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. +# If set to NO (the default) these classes will be included in the various +# overviews. This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all +# friend (class|struct|union) declarations. +# If set to NO (the default) these declarations will be included in the +# documentation. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any +# documentation blocks found inside the body of a function. +# If set to NO (the default) these blocks will be appended to the +# function's detailed documentation block. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation +# that is typed after a \internal command is included. If the tag is set +# to NO (the default) then the documentation will be excluded. +# Set it to YES to include the internal documentation. + +INTERNAL_DOCS = NO + +# If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate +# file names in lower-case letters. If set to YES upper-case letters are also +# allowed. This is useful if you have classes or files whose names only differ +# in case and if your file system supports case sensitive file names. Windows +# and Mac users are advised to set this option to NO. + +CASE_SENSE_NAMES = YES + +# If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen +# will show members with their full class and namespace scopes in the +# documentation. If set to YES the scope will be hidden. + +HIDE_SCOPE_NAMES = NO + +# If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen +# will put a list of the files that are included by a file in the documentation +# of that file. + +SHOW_INCLUDE_FILES = YES + +# If the INLINE_INFO tag is set to YES (the default) then a tag [inline] +# is inserted in the documentation for inline members. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen +# will sort the (detailed) documentation of file and class members +# alphabetically by member name. If set to NO the members will appear in +# declaration order. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the +# brief documentation of file, namespace and class members alphabetically +# by member name. If set to NO (the default) the members will appear in +# declaration order. + +SORT_BRIEF_DOCS = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be +# sorted by fully-qualified names, including namespaces. If set to +# NO (the default), the class list will be sorted only by class name, +# not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the +# alphabetical list. + +SORT_BY_SCOPE_NAME = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or +# disable (NO) the todo list. This list is created by putting \todo +# commands in the documentation. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or +# disable (NO) the test list. This list is created by putting \test +# commands in the documentation. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or +# disable (NO) the bug list. This list is created by putting \bug +# commands in the documentation. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or +# disable (NO) the deprecated list. This list is created by putting +# \deprecated commands in the documentation. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional +# documentation sections, marked by \if sectionname ... \endif. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines +# the initial value of a variable or define consists of for it to appear in +# the documentation. If the initializer consists of more lines than specified +# here it will be hidden. Use a value of 0 to hide initializers completely. +# The appearance of the initializer of individual variables and defines in the +# documentation can be controlled using \showinitializer or \hideinitializer +# command in the documentation regardless of this setting. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated +# at the bottom of the documentation of classes and structs. If set to YES the +# list will mention the files that were used to generate the documentation. + +SHOW_USED_FILES = YES + +# If the sources in your project are distributed over multiple directories +# then setting the SHOW_DIRECTORIES tag to YES will show the directory hierarchy +# in the documentation. The default is NO. + +SHOW_DIRECTORIES = NO + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from the +# version control system). Doxygen will invoke the program by executing (via +# popen()) the command , where is the value of +# the FILE_VERSION_FILTER tag, and is the name of an input file +# provided by doxygen. Whatever the program writes to standard output +# is used as the file version. See the manual for examples. + +FILE_VERSION_FILTER = + +#--------------------------------------------------------------------------- +# configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated +# by doxygen. Possible values are YES and NO. If left blank NO is used. + +QUIET = NO + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated by doxygen. Possible values are YES and NO. If left blank +# NO is used. + +WARNINGS = YES + +# If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings +# for undocumented members. If EXTRACT_ALL is set to YES then this flag will +# automatically be disabled. + +WARN_IF_UNDOCUMENTED = YES + +# If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some +# parameters in a documented function, or documenting parameters that +# don't exist or using markup commands wrongly. + +WARN_IF_DOC_ERROR = YES + +# This WARN_NO_PARAMDOC option can be abled to get warnings for +# functions that are documented, but have no documentation for their parameters +# or return value. If set to NO (the default) doxygen will only warn about +# wrong or incomplete parameter documentation, but not about the absence of +# documentation. + +WARN_NO_PARAMDOC = NO + +# The WARN_FORMAT tag determines the format of the warning messages that +# doxygen can produce. The string should contain the $file, $line, and $text +# tags, which will be replaced by the file and line number from which the +# warning originated and the warning text. Optionally the format may contain +# $version, which will be replaced by the version of the file (if it could +# be obtained via FILE_VERSION_FILTER) + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning +# and error messages should be written. If left blank the output is written +# to stderr. + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag can be used to specify the files and/or directories that contain +# documented source files. You may enter file names like "myfile.cpp" or +# directories like "/usr/src/myproject". Separate the files or directories +# with spaces. + +INPUT = + +# This tag can be used to specify the character encoding of the source files that +# doxygen parses. Internally doxygen uses the UTF-8 encoding, which is also the default +# input encoding. Doxygen uses libiconv (or the iconv built into libc) for the transcoding. +# See http://www.gnu.org/software/libiconv for the list of possible encodings. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank the following patterns are tested: +# *.c *.cc *.cxx *.cpp *.c++ *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh *.hxx +# *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.py + +FILE_PATTERNS = + +# The RECURSIVE tag can be used to turn specify whether or not subdirectories +# should be searched for input files as well. Possible values are YES and NO. +# If left blank NO is used. + +RECURSIVE = NO + +# The EXCLUDE tag can be used to specify files and/or directories that should +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. + +EXCLUDE = + +# The EXCLUDE_SYMLINKS tag can be used select whether or not files or +# directories that are symbolic links (a Unix filesystem feature) are excluded +# from the input. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. Note that the wildcards are matched +# against the file with absolute path, so to exclude all test directories +# for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the output. +# The symbol name can be a fully qualified name, a word, or if the wildcard * is used, +# a substring. Examples: ANamespace, AClass, AClass::ANamespace, ANamespace::*Test + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or +# directories that contain example code fragments that are included (see +# the \include command). + +EXAMPLE_PATH = + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank all files are included. + +EXAMPLE_PATTERNS = + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude +# commands irrespective of the value of the RECURSIVE tag. +# Possible values are YES and NO. If left blank NO is used. + +EXAMPLE_RECURSIVE = NO + +# The IMAGE_PATH tag can be used to specify one or more files or +# directories that contain image that are included in the documentation (see +# the \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command , where +# is the value of the INPUT_FILTER tag, and is the name of an +# input file. Doxygen will then use the output that the filter program writes +# to standard output. If FILTER_PATTERNS is specified, this tag will be +# ignored. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. The filters are a list of the form: +# pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further +# info on how filters are used. If FILTER_PATTERNS is empty, INPUT_FILTER +# is applied to all files. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will be used to filter the input files when producing source +# files to browse (i.e. when SOURCE_BROWSER is set to YES). + +FILTER_SOURCE_FILES = NO + +#--------------------------------------------------------------------------- +# configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will +# be generated. Documented entities will be cross-referenced with these sources. +# Note: To get rid of all source code in the generated output, make sure also +# VERBATIM_HEADERS is set to NO. If you have enabled CALL_GRAPH or CALLER_GRAPH +# then you must also enable this option. If you don't then doxygen will produce +# a warning and turn it on anyway + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body +# of functions and classes directly in the documentation. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct +# doxygen to hide any special comment blocks from generated source code +# fragments. Normal C and C++ comments will always remain visible. + +STRIP_CODE_COMMENTS = NO + +# If the REFERENCED_BY_RELATION tag is set to YES (the default) +# then for each documented function all documented +# functions referencing it will be listed. + +REFERENCED_BY_RELATION = YES + +# If the REFERENCES_RELATION tag is set to YES (the default) +# then for each documented function all documented entities +# called/used by that function will be listed. + +REFERENCES_RELATION = YES + +# If the REFERENCES_LINK_SOURCE tag is set to YES (the default) +# and SOURCE_BROWSER tag is set to YES, then the hyperlinks from +# functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will +# link to the source code. Otherwise they will link to the documentstion. + +REFERENCES_LINK_SOURCE = YES + +# If the USE_HTAGS tag is set to YES then the references to source code +# will point to the HTML generated by the htags(1) tool instead of doxygen +# built-in source browser. The htags tool is part of GNU's global source +# tagging system (see http://www.gnu.org/software/global/global.html). You +# will need version 4.8.6 or higher. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen +# will generate a verbatim copy of the header file for each class for +# which an include is specified. Set to NO to disable this. + +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index +# of all compounds will be generated. Enable this if the project +# contains a lot of classes, structs, unions or interfaces. + +ALPHABETICAL_INDEX = NO + +# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then +# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns +# in which this list will be split (can be a number in the range [1..20]) + +COLS_IN_ALPHA_INDEX = 5 + +# In case all classes in a project start with a common prefix, all +# classes will be put under the same header in the alphabetical index. +# The IGNORE_PREFIX tag can be used to specify one or more prefixes that +# should be ignored while generating the index headers. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES (the default) Doxygen will +# generate HTML output. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `html' will be used as the default path. + +HTML_OUTPUT = doc + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for +# each generated HTML page (for example: .htm,.php,.asp). If it is left blank +# doxygen will generate files with .html extension. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a personal HTML header for +# each generated HTML page. If it is left blank doxygen will generate a +# standard header. + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a personal HTML footer for +# each generated HTML page. If it is left blank doxygen will generate a +# standard footer. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading +# style sheet that is used by each HTML page. It can be used to +# fine-tune the look of the HTML output. If the tag is left blank doxygen +# will generate a default style sheet. Note that doxygen will try to copy +# the style sheet file to the HTML output directory, so don't put your own +# stylesheet in the HTML output directory as well, or it will be erased! + +HTML_STYLESHEET = + +# If the HTML_ALIGN_MEMBERS tag is set to YES, the members of classes, +# files or namespaces will be aligned in HTML using tables. If set to +# NO a bullet list will be used. + +HTML_ALIGN_MEMBERS = YES + +# If the GENERATE_HTMLHELP tag is set to YES, additional index files +# will be generated that can be used as input for tools like the +# Microsoft HTML help workshop to generate a compressed HTML help file (.chm) +# of the generated HTML documentation. + +GENERATE_HTMLHELP = NO + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. For this to work a browser that supports +# JavaScript and DHTML is required (for instance Mozilla 1.0+, Firefox +# Netscape 6.0+, Internet explorer 5.0+, Konqueror, or Safari). + +HTML_DYNAMIC_SECTIONS = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can +# be used to specify the file name of the resulting .chm file. You +# can add a path in front of the file if the result should not be +# written to the html output directory. + +CHM_FILE = + +# If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can +# be used to specify the location (absolute path including file name) of +# the HTML help compiler (hhc.exe). If non-empty doxygen will try to run +# the HTML help compiler on the generated index.hhp. + +HHC_LOCATION = + +# If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag +# controls if a separate .chi index file is generated (YES) or that +# it should be included in the master .chm file (NO). + +GENERATE_CHI = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag +# controls whether a binary table of contents is generated (YES) or a +# normal table of contents (NO) in the .chm file. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members +# to the contents of the HTML help documentation and to the tree view. + +TOC_EXPAND = NO + +# The DISABLE_INDEX tag can be used to turn on/off the condensed index at +# top of each HTML page. The value NO (the default) enables the index and +# the value YES disables it. + +DISABLE_INDEX = NO + +# This tag can be used to set the number of enum values (range [1..20]) +# that doxygen will group on one line in the generated HTML documentation. + +ENUM_VALUES_PER_LINE = 4 + +# If the GENERATE_TREEVIEW tag is set to YES, a side panel will be +# generated containing a tree-like index structure (just like the one that +# is generated for HTML Help). For this to work a browser that supports +# JavaScript, DHTML, CSS and frames is required (for instance Mozilla 1.0+, +# Netscape 6.0+, Internet explorer 5.0+, or Konqueror). Windows users are +# probably better off using the HTML help feature. + +GENERATE_TREEVIEW = NO + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be +# used to set the initial width (in pixels) of the frame in which the tree +# is shown. + +TREEVIEW_WIDTH = 250 + +#--------------------------------------------------------------------------- +# configuration options related to the LaTeX output +#--------------------------------------------------------------------------- + +# If the GENERATE_LATEX tag is set to YES (the default) Doxygen will +# generate Latex output. + +GENERATE_LATEX = NO + +# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `latex' will be used as the default path. + +LATEX_OUTPUT = latex + +# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be +# invoked. If left blank `latex' will be used as the default command name. + +LATEX_CMD_NAME = latex + +# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to +# generate index for LaTeX. If left blank `makeindex' will be used as the +# default command name. + +MAKEINDEX_CMD_NAME = makeindex + +# If the COMPACT_LATEX tag is set to YES Doxygen generates more compact +# LaTeX documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_LATEX = NO + +# The PAPER_TYPE tag can be used to set the paper type that is used +# by the printer. Possible values are: a4, a4wide, letter, legal and +# executive. If left blank a4wide will be used. + +PAPER_TYPE = a4wide + +# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX +# packages that should be included in the LaTeX output. + +EXTRA_PACKAGES = + +# The LATEX_HEADER tag can be used to specify a personal LaTeX header for +# the generated latex document. The header should contain everything until +# the first chapter. If it is left blank doxygen will generate a +# standard header. Notice: only use this tag if you know what you are doing! + +LATEX_HEADER = + +# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated +# is prepared for conversion to pdf (using ps2pdf). The pdf file will +# contain links (just like the HTML output) instead of page references +# This makes the output suitable for online browsing using a pdf viewer. + +PDF_HYPERLINKS = NO + +# If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of +# plain latex in the generated Makefile. Set this option to YES to get a +# higher quality PDF documentation. + +USE_PDFLATEX = NO + +# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. +# command to the generated LaTeX files. This will instruct LaTeX to keep +# running if errors occur, instead of asking the user for help. +# This option is also used when generating formulas in HTML. + +LATEX_BATCHMODE = NO + +# If LATEX_HIDE_INDICES is set to YES then doxygen will not +# include the index chapters (such as File Index, Compound Index, etc.) +# in the output. + +LATEX_HIDE_INDICES = NO + +#--------------------------------------------------------------------------- +# configuration options related to the RTF output +#--------------------------------------------------------------------------- + +# If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output +# The RTF output is optimized for Word 97 and may not look very pretty with +# other RTF readers or editors. + +GENERATE_RTF = NO + +# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `rtf' will be used as the default path. + +RTF_OUTPUT = rtf + +# If the COMPACT_RTF tag is set to YES Doxygen generates more compact +# RTF documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_RTF = NO + +# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated +# will contain hyperlink fields. The RTF file will +# contain links (just like the HTML output) instead of page references. +# This makes the output suitable for online browsing using WORD or other +# programs which support those fields. +# Note: wordpad (write) and others do not support links. + +RTF_HYPERLINKS = NO + +# Load stylesheet definitions from file. Syntax is similar to doxygen's +# config file, i.e. a series of assignments. You only have to provide +# replacements, missing definitions are set to their default value. + +RTF_STYLESHEET_FILE = + +# Set optional variables used in the generation of an rtf document. +# Syntax is similar to doxygen's config file. + +RTF_EXTENSIONS_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to the man page output +#--------------------------------------------------------------------------- + +# If the GENERATE_MAN tag is set to YES (the default) Doxygen will +# generate man pages + +GENERATE_MAN = NO + +# The MAN_OUTPUT tag is used to specify where the man pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `man' will be used as the default path. + +MAN_OUTPUT = man + +# The MAN_EXTENSION tag determines the extension that is added to +# the generated man pages (default is the subroutine's section .3) + +MAN_EXTENSION = .3 + +# If the MAN_LINKS tag is set to YES and Doxygen generates man output, +# then it will generate one additional man file for each entity +# documented in the real man page(s). These additional files +# only source the real man page, but without them the man command +# would be unable to find the correct page. The default is NO. + +MAN_LINKS = NO + +#--------------------------------------------------------------------------- +# configuration options related to the XML output +#--------------------------------------------------------------------------- + +# If the GENERATE_XML tag is set to YES Doxygen will +# generate an XML file that captures the structure of +# the code including all documentation. + +GENERATE_XML = NO + +# The XML_OUTPUT tag is used to specify where the XML pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `xml' will be used as the default path. + +XML_OUTPUT = xml + +# The XML_SCHEMA tag can be used to specify an XML schema, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_SCHEMA = + +# The XML_DTD tag can be used to specify an XML DTD, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_DTD = + +# If the XML_PROGRAMLISTING tag is set to YES Doxygen will +# dump the program listings (including syntax highlighting +# and cross-referencing information) to the XML output. Note that +# enabling this will significantly increase the size of the XML output. + +XML_PROGRAMLISTING = YES + +#--------------------------------------------------------------------------- +# configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- + +# If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will +# generate an AutoGen Definitions (see autogen.sf.net) file +# that captures the structure of the code including all +# documentation. Note that this feature is still experimental +# and incomplete at the moment. + +GENERATE_AUTOGEN_DEF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the Perl module output +#--------------------------------------------------------------------------- + +# If the GENERATE_PERLMOD tag is set to YES Doxygen will +# generate a Perl module file that captures the structure of +# the code including all documentation. Note that this +# feature is still experimental and incomplete at the +# moment. + +GENERATE_PERLMOD = NO + +# If the PERLMOD_LATEX tag is set to YES Doxygen will generate +# the necessary Makefile rules, Perl scripts and LaTeX code to be able +# to generate PDF and DVI output from the Perl module output. + +PERLMOD_LATEX = NO + +# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be +# nicely formatted so it can be parsed by a human reader. This is useful +# if you want to understand what is going on. On the other hand, if this +# tag is set to NO the size of the Perl module output will be much smaller +# and Perl will parse it just the same. + +PERLMOD_PRETTY = YES + +# The names of the make variables in the generated doxyrules.make file +# are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. +# This is useful so different doxyrules.make files included by the same +# Makefile don't overwrite each other's variables. + +PERLMOD_MAKEVAR_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- + +# If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will +# evaluate all C-preprocessor directives found in the sources and include +# files. + +ENABLE_PREPROCESSING = YES + +# If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro +# names in the source code. If set to NO (the default) only conditional +# compilation will be performed. Macro expansion can be done in a controlled +# way by setting EXPAND_ONLY_PREDEF to YES. + +MACRO_EXPANSION = NO + +# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES +# then the macro expansion is limited to the macros specified with the +# PREDEFINED and EXPAND_AS_DEFINED tags. + +EXPAND_ONLY_PREDEF = NO + +# If the SEARCH_INCLUDES tag is set to YES (the default) the includes files +# in the INCLUDE_PATH (see below) will be search if a #include is found. + +SEARCH_INCLUDES = YES + +# The INCLUDE_PATH tag can be used to specify one or more directories that +# contain include files that are not input files but should be processed by +# the preprocessor. + +INCLUDE_PATH = + +# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard +# patterns (like *.h and *.hpp) to filter out the header-files in the +# directories. If left blank, the patterns specified with FILE_PATTERNS will +# be used. + +INCLUDE_FILE_PATTERNS = + +# The PREDEFINED tag can be used to specify one or more macro names that +# are defined before the preprocessor is started (similar to the -D option of +# gcc). The argument of the tag is a list of macros of the form: name +# or name=definition (no spaces). If the definition and the = are +# omitted =1 is assumed. To prevent a macro definition from being +# undefined via #undef or recursively expanded use the := operator +# instead of the = operator. + +PREDEFINED = + +# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then +# this tag can be used to specify a list of macro names that should be expanded. +# The macro definition that is found in the sources will be used. +# Use the PREDEFINED tag if you want to use a different macro definition. + +EXPAND_AS_DEFINED = + +# If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then +# doxygen's preprocessor will remove all function-like macros that are alone +# on a line, have an all uppercase name, and do not end with a semicolon. Such +# function macros are typically used for boiler-plate code, and will confuse +# the parser if not removed. + +SKIP_FUNCTION_MACROS = YES + +#--------------------------------------------------------------------------- +# Configuration::additions related to external references +#--------------------------------------------------------------------------- + +# The TAGFILES option can be used to specify one or more tagfiles. +# Optionally an initial location of the external documentation +# can be added for each tagfile. The format of a tag file without +# this location is as follows: +# TAGFILES = file1 file2 ... +# Adding location for the tag files is done as follows: +# TAGFILES = file1=loc1 "file2 = loc2" ... +# where "loc1" and "loc2" can be relative or absolute paths or +# URLs. If a location is present for each tag, the installdox tool +# does not have to be run to correct the links. +# Note that each tag file must have a unique name +# (where the name does NOT include the path) +# If a tag file is not located in the directory in which doxygen +# is run, you must also specify the path to the tagfile here. + +TAGFILES = + +# When a file name is specified after GENERATE_TAGFILE, doxygen will create +# a tag file that is based on the input files it reads. + +GENERATE_TAGFILE = + +# If the ALLEXTERNALS tag is set to YES all external classes will be listed +# in the class index. If set to NO only the inherited external classes +# will be listed. + +ALLEXTERNALS = NO + +# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed +# in the modules index. If set to NO, only the current project's groups will +# be listed. + +EXTERNAL_GROUPS = YES + +# The PERL_PATH should be the absolute path and name of the perl script +# interpreter (i.e. the result of `which perl'). + +PERL_PATH = /usr/bin/perl + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- + +# If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will +# generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base +# or super classes. Setting the tag to NO turns the diagrams off. Note that +# this option is superseded by the HAVE_DOT option below. This is only a +# fallback. It is recommended to install and use dot, since it yields more +# powerful graphs. + +CLASS_DIAGRAMS = YES + +# You can define message sequence charts within doxygen comments using the \msc +# command. Doxygen will then run the mscgen tool (see http://www.mcternan.me.uk/mscgen/) to +# produce the chart and insert it in the documentation. The MSCGEN_PATH tag allows you to +# specify the directory where the mscgen tool resides. If left empty the tool is assumed to +# be found in the default search path. + +MSCGEN_PATH = + +# If set to YES, the inheritance and collaboration graphs will hide +# inheritance and usage relations if the target is undocumented +# or is not a class. + +HIDE_UNDOC_RELATIONS = YES + +# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is +# available from the path. This tool is part of Graphviz, a graph visualization +# toolkit from AT&T and Lucent Bell Labs. The other options in this section +# have no effect if this option is set to NO (the default) + +HAVE_DOT = NO + +# If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect inheritance relations. Setting this tag to YES will force the +# the CLASS_DIAGRAMS tag to NO. + +CLASS_GRAPH = YES + +# If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect implementation dependencies (inheritance, containment, and +# class references variables) of the class with other documented classes. + +COLLABORATION_GRAPH = YES + +# If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for groups, showing the direct groups dependencies + +GROUP_GRAPHS = YES + +# If the UML_LOOK tag is set to YES doxygen will generate inheritance and +# collaboration diagrams in a style similar to the OMG's Unified Modeling +# Language. + +UML_LOOK = NO + +# If set to YES, the inheritance and collaboration graphs will show the +# relations between templates and their instances. + +TEMPLATE_RELATIONS = NO + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT +# tags are set to YES then doxygen will generate a graph for each documented +# file showing the direct and indirect include dependencies of the file with +# other documented files. + +INCLUDE_GRAPH = YES + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and +# HAVE_DOT tags are set to YES then doxygen will generate a graph for each +# documented header file showing the documented files that directly or +# indirectly include this file. + +INCLUDED_BY_GRAPH = YES + +# If the CALL_GRAPH, SOURCE_BROWSER and HAVE_DOT tags are set to YES then doxygen will +# generate a call dependency graph for every global function or class method. +# Note that enabling this option will significantly increase the time of a run. +# So in most cases it will be better to enable call graphs for selected +# functions only using the \callgraph command. + +CALL_GRAPH = NO + +# If the CALLER_GRAPH, SOURCE_BROWSER and HAVE_DOT tags are set to YES then doxygen will +# generate a caller dependency graph for every global function or class method. +# Note that enabling this option will significantly increase the time of a run. +# So in most cases it will be better to enable caller graphs for selected +# functions only using the \callergraph command. + +CALLER_GRAPH = NO + +# If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen +# will graphical hierarchy of all classes instead of a textual one. + +GRAPHICAL_HIERARCHY = YES + +# If the DIRECTORY_GRAPH, SHOW_DIRECTORIES and HAVE_DOT tags are set to YES +# then doxygen will show the dependencies a directory has on other directories +# in a graphical way. The dependency relations are determined by the #include +# relations between the files in the directories. + +DIRECTORY_GRAPH = YES + +# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images +# generated by dot. Possible values are png, jpg, or gif +# If left blank png will be used. + +DOT_IMAGE_FORMAT = png + +# The tag DOT_PATH can be used to specify the path where the dot tool can be +# found. If left blank, it is assumed the dot tool can be found in the path. + +DOT_PATH = + +# The DOTFILE_DIRS tag can be used to specify one or more directories that +# contain dot files that are included in the documentation (see the +# \dotfile command). + +DOTFILE_DIRS = + +# The MAX_DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of +# nodes that will be shown in the graph. If the number of nodes in a graph +# becomes larger than this value, doxygen will truncate the graph, which is +# visualized by representing a node as a red box. Note that doxygen if the number +# of direct children of the root node in a graph is already larger than +# MAX_DOT_GRAPH_NOTES then the graph will not be shown at all. Also note +# that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH. + +DOT_GRAPH_MAX_NODES = 50 + +# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the +# graphs generated by dot. A depth value of 3 means that only nodes reachable +# from the root by following a path via at most 3 edges will be shown. Nodes +# that lay further from the root node will be omitted. Note that setting this +# option to 1 or 2 may greatly reduce the computation time needed for large +# code bases. Also note that the size of a graph can be further restricted by +# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction. + +MAX_DOT_GRAPH_DEPTH = 0 + +# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent +# background. This is disabled by default, which results in a white background. +# Warning: Depending on the platform used, enabling this option may lead to +# badly anti-aliased labels on the edges of a graph (i.e. they become hard to +# read). + +DOT_TRANSPARENT = NO + +# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output +# files in one run (i.e. multiple -o and -T options on the command line). This +# makes dot run faster, but since only newer versions of dot (>1.8.10) +# support this, this feature is disabled by default. + +DOT_MULTI_TARGETS = NO + +# If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will +# generate a legend page explaining the meaning of the various boxes and +# arrows in the dot generated graphs. + +GENERATE_LEGEND = YES + +# If the DOT_CLEANUP tag is set to YES (the default) Doxygen will +# remove the intermediate dot files that are used to generate +# the various graphs. + +DOT_CLEANUP = YES + +#--------------------------------------------------------------------------- +# Configuration::additions related to the search engine +#--------------------------------------------------------------------------- + +# The SEARCHENGINE tag specifies whether or not a search engine should be +# used. If set to NO the values of all tags below this one will be ignored. + +SEARCHENGINE = NO diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Adafruit_GFX.cpp b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Adafruit_GFX.cpp new file mode 100644 index 0000000..46d4d54 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Adafruit_GFX.cpp @@ -0,0 +1,1071 @@ +/* +This is the core graphics library for all our displays, providing a common +set of graphics primitives (points, lines, circles, etc.). It needs to be +paired with a hardware-specific library for each display device we carry +(to handle the lower-level functions). + +Adafruit invests time and resources providing this open source code, please +support Adafruit & open-source hardware by purchasing products from Adafruit! + +Copyright (c) 2013 Adafruit Industries. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +- Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. +- Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifdef __AVR__ + #include +#elif defined(ESP8266) + #include +#endif +#include "Adafruit_GFX.h" +#include "glcdfont.c" + +// Many (but maybe not all) non-AVR board installs define macros +// for compatibility with existing PROGMEM-reading AVR code. +// Do our own checks and defines here for good measure... + +#ifndef pgm_read_byte + #define pgm_read_byte(addr) (*(const unsigned char *)(addr)) +#endif +#ifndef pgm_read_word + #define pgm_read_word(addr) (*(const unsigned short *)(addr)) +#endif +#ifndef pgm_read_dword + #define pgm_read_dword(addr) (*(const unsigned long *)(addr)) +#endif + +// Pointers are a peculiar case...typically 16-bit on AVR boards, +// 32 bits elsewhere. Try to accommodate both... + +#if !defined(__INT_MAX__) || (__INT_MAX__ > 0xFFFF) + #define pgm_read_pointer(addr) ((void *)pgm_read_dword(addr)) +#else + #define pgm_read_pointer(addr) ((void *)pgm_read_word(addr)) +#endif + +#ifndef min +#define min(a,b) (((a) < (b)) ? (a) : (b)) +#endif + +#ifndef _swap_int16_t +#define _swap_int16_t(a, b) { int16_t t = a; a = b; b = t; } +#endif + +Adafruit_GFX::Adafruit_GFX(int16_t w, int16_t h): + WIDTH(w), HEIGHT(h) +{ + _width = WIDTH; + _height = HEIGHT; + rotation = 0; + cursor_y = cursor_x = 0; + textsize = 1; + textcolor = textbgcolor = 0xFFFF; + wrap = true; + _cp437 = false; + gfxFont = NULL; +} + +// Draw a circle outline +void Adafruit_GFX::drawCircle(int16_t x0, int16_t y0, int16_t r, + uint16_t color) { + int16_t f = 1 - r; + int16_t ddF_x = 1; + int16_t ddF_y = -2 * r; + int16_t x = 0; + int16_t y = r; + + drawPixel(x0 , y0+r, color); + drawPixel(x0 , y0-r, color); + drawPixel(x0+r, y0 , color); + drawPixel(x0-r, y0 , color); + + while (x= 0) { + y--; + ddF_y += 2; + f += ddF_y; + } + x++; + ddF_x += 2; + f += ddF_x; + + drawPixel(x0 + x, y0 + y, color); + drawPixel(x0 - x, y0 + y, color); + drawPixel(x0 + x, y0 - y, color); + drawPixel(x0 - x, y0 - y, color); + drawPixel(x0 + y, y0 + x, color); + drawPixel(x0 - y, y0 + x, color); + drawPixel(x0 + y, y0 - x, color); + drawPixel(x0 - y, y0 - x, color); + } +} + +void Adafruit_GFX::drawCircleHelper( int16_t x0, int16_t y0, + int16_t r, uint8_t cornername, uint16_t color) { + int16_t f = 1 - r; + int16_t ddF_x = 1; + int16_t ddF_y = -2 * r; + int16_t x = 0; + int16_t y = r; + + while (x= 0) { + y--; + ddF_y += 2; + f += ddF_y; + } + x++; + ddF_x += 2; + f += ddF_x; + if (cornername & 0x4) { + drawPixel(x0 + x, y0 + y, color); + drawPixel(x0 + y, y0 + x, color); + } + if (cornername & 0x2) { + drawPixel(x0 + x, y0 - y, color); + drawPixel(x0 + y, y0 - x, color); + } + if (cornername & 0x8) { + drawPixel(x0 - y, y0 + x, color); + drawPixel(x0 - x, y0 + y, color); + } + if (cornername & 0x1) { + drawPixel(x0 - y, y0 - x, color); + drawPixel(x0 - x, y0 - y, color); + } + } +} + +void Adafruit_GFX::fillCircle(int16_t x0, int16_t y0, int16_t r, + uint16_t color) { + drawFastVLine(x0, y0-r, 2*r+1, color); + fillCircleHelper(x0, y0, r, 3, 0, color); +} + +// Used to do circles and roundrects +void Adafruit_GFX::fillCircleHelper(int16_t x0, int16_t y0, int16_t r, + uint8_t cornername, int16_t delta, uint16_t color) { + + int16_t f = 1 - r; + int16_t ddF_x = 1; + int16_t ddF_y = -2 * r; + int16_t x = 0; + int16_t y = r; + + while (x= 0) { + y--; + ddF_y += 2; + f += ddF_y; + } + x++; + ddF_x += 2; + f += ddF_x; + + if (cornername & 0x1) { + drawFastVLine(x0+x, y0-y, 2*y+1+delta, color); + drawFastVLine(x0+y, y0-x, 2*x+1+delta, color); + } + if (cornername & 0x2) { + drawFastVLine(x0-x, y0-y, 2*y+1+delta, color); + drawFastVLine(x0-y, y0-x, 2*x+1+delta, color); + } + } +} + +// Bresenham's algorithm - thx wikpedia +void Adafruit_GFX::drawLine(int16_t x0, int16_t y0, int16_t x1, int16_t y1, + uint16_t color) { + int16_t steep = abs(y1 - y0) > abs(x1 - x0); + if (steep) { + _swap_int16_t(x0, y0); + _swap_int16_t(x1, y1); + } + + if (x0 > x1) { + _swap_int16_t(x0, x1); + _swap_int16_t(y0, y1); + } + + int16_t dx, dy; + dx = x1 - x0; + dy = abs(y1 - y0); + + int16_t err = dx / 2; + int16_t ystep; + + if (y0 < y1) { + ystep = 1; + } else { + ystep = -1; + } + + for (; x0<=x1; x0++) { + if (steep) { + drawPixel(y0, x0, color); + } else { + drawPixel(x0, y0, color); + } + err -= dy; + if (err < 0) { + y0 += ystep; + err += dx; + } + } +} + +// Draw a rectangle +void Adafruit_GFX::drawRect(int16_t x, int16_t y, int16_t w, int16_t h, + uint16_t color) { + drawFastHLine(x, y, w, color); + drawFastHLine(x, y+h-1, w, color); + drawFastVLine(x, y, h, color); + drawFastVLine(x+w-1, y, h, color); +} + +void Adafruit_GFX::drawFastVLine(int16_t x, int16_t y, + int16_t h, uint16_t color) { + // Update in subclasses if desired! + drawLine(x, y, x, y+h-1, color); +} + +void Adafruit_GFX::drawFastHLine(int16_t x, int16_t y, + int16_t w, uint16_t color) { + // Update in subclasses if desired! + drawLine(x, y, x+w-1, y, color); +} + +void Adafruit_GFX::fillRect(int16_t x, int16_t y, int16_t w, int16_t h, + uint16_t color) { + // Update in subclasses if desired! + for (int16_t i=x; i= y1 >= y0) + if (y0 > y1) { + _swap_int16_t(y0, y1); _swap_int16_t(x0, x1); + } + if (y1 > y2) { + _swap_int16_t(y2, y1); _swap_int16_t(x2, x1); + } + if (y0 > y1) { + _swap_int16_t(y0, y1); _swap_int16_t(x0, x1); + } + + if(y0 == y2) { // Handle awkward all-on-same-line case as its own thing + a = b = x0; + if(x1 < a) a = x1; + else if(x1 > b) b = x1; + if(x2 < a) a = x2; + else if(x2 > b) b = x2; + drawFastHLine(a, y0, b-a+1, color); + return; + } + + int16_t + dx01 = x1 - x0, + dy01 = y1 - y0, + dx02 = x2 - x0, + dy02 = y2 - y0, + dx12 = x2 - x1, + dy12 = y2 - y1; + int32_t + sa = 0, + sb = 0; + + // For upper part of triangle, find scanline crossings for segments + // 0-1 and 0-2. If y1=y2 (flat-bottomed triangle), the scanline y1 + // is included here (and second loop will be skipped, avoiding a /0 + // error there), otherwise scanline y1 is skipped here and handled + // in the second loop...which also avoids a /0 error here if y0=y1 + // (flat-topped triangle). + if(y1 == y2) last = y1; // Include y1 scanline + else last = y1-1; // Skip it + + for(y=y0; y<=last; y++) { + a = x0 + sa / dy01; + b = x0 + sb / dy02; + sa += dx01; + sb += dx02; + /* longhand: + a = x0 + (x1 - x0) * (y - y0) / (y1 - y0); + b = x0 + (x2 - x0) * (y - y0) / (y2 - y0); + */ + if(a > b) _swap_int16_t(a,b); + drawFastHLine(a, y, b-a+1, color); + } + + // For lower part of triangle, find scanline crossings for segments + // 0-2 and 1-2. This loop is skipped if y1=y2. + sa = dx12 * (y - y1); + sb = dx02 * (y - y0); + for(; y<=y2; y++) { + a = x1 + sa / dy12; + b = x0 + sb / dy02; + sa += dx12; + sb += dx02; + /* longhand: + a = x1 + (x2 - x1) * (y - y1) / (y2 - y1); + b = x0 + (x2 - x0) * (y - y0) / (y2 - y0); + */ + if(a > b) _swap_int16_t(a,b); + drawFastHLine(a, y, b-a+1, color); + } +} + +// Draw a 1-bit image (bitmap) at the specified (x,y) position from the +// provided bitmap buffer (must be PROGMEM memory) using the specified +// foreground color (unset bits are transparent). +void Adafruit_GFX::drawBitmap(int16_t x, int16_t y, + const uint8_t *bitmap, int16_t w, int16_t h, uint16_t color) { + + int16_t i, j, byteWidth = (w + 7) / 8; + uint8_t byte; + + for(j=0; j>= 1; + else byte = pgm_read_byte(bitmap + j * byteWidth + i / 8); + if(byte & 0x01) drawPixel(x+i, y+j, color); + } + } +} + +#if ARDUINO >= 100 +size_t Adafruit_GFX::write(uint8_t c) { +#else +void Adafruit_GFX::write(uint8_t c) { +#endif + + if(!gfxFont) { // 'Classic' built-in font + + if(c == '\n') { + cursor_y += textsize*8; + cursor_x = 0; + } else if(c == '\r') { + // skip em + } else { + if(wrap && ((cursor_x + textsize * 6) >= _width)) { // Heading off edge? + cursor_x = 0; // Reset x to zero + cursor_y += textsize * 8; // Advance y one line + } + drawChar(cursor_x, cursor_y, c, textcolor, textbgcolor, textsize); + cursor_x += textsize * 6; + } + + } else { // Custom font + + if(c == '\n') { + cursor_x = 0; + cursor_y += (int16_t)textsize * + (uint8_t)pgm_read_byte(&gfxFont->yAdvance); + } else if(c != '\r') { + uint8_t first = pgm_read_byte(&gfxFont->first); + if((c >= first) && (c <= (uint8_t)pgm_read_byte(&gfxFont->last))) { + uint8_t c2 = c - pgm_read_byte(&gfxFont->first); + GFXglyph *glyph = &(((GFXglyph *)pgm_read_pointer(&gfxFont->glyph))[c2]); + uint8_t w = pgm_read_byte(&glyph->width), + h = pgm_read_byte(&glyph->height); + if((w > 0) && (h > 0)) { // Is there an associated bitmap? + int16_t xo = (int8_t)pgm_read_byte(&glyph->xOffset); // sic + if(wrap && ((cursor_x + textsize * (xo + w)) >= _width)) { + // Drawing character would go off right edge; wrap to new line + cursor_x = 0; + cursor_y += (int16_t)textsize * + (uint8_t)pgm_read_byte(&gfxFont->yAdvance); + } + drawChar(cursor_x, cursor_y, c, textcolor, textbgcolor, textsize); + } + cursor_x += pgm_read_byte(&glyph->xAdvance) * (int16_t)textsize; + } + } + + } +#if ARDUINO >= 100 + return 1; +#endif +} + +// Draw a character +void Adafruit_GFX::drawChar(int16_t x, int16_t y, unsigned char c, + uint16_t color, uint16_t bg, uint8_t size) { + + if(!gfxFont) { // 'Classic' built-in font + + if((x >= _width) || // Clip right + (y >= _height) || // Clip bottom + ((x + 6 * size - 1) < 0) || // Clip left + ((y + 8 * size - 1) < 0)) // Clip top + return; + + if(!_cp437 && (c >= 176)) c++; // Handle 'classic' charset behavior + + for(int8_t i=0; i<6; i++ ) { + uint8_t line; + if(i < 5) line = pgm_read_byte(font+(c*5)+i); + else line = 0x0; + for(int8_t j=0; j<8; j++, line >>= 1) { + if(line & 0x1) { + if(size == 1) drawPixel(x+i, y+j, color); + else fillRect(x+(i*size), y+(j*size), size, size, color); + } else if(bg != color) { + if(size == 1) drawPixel(x+i, y+j, bg); + else fillRect(x+i*size, y+j*size, size, size, bg); + } + } + } + + } else { // Custom font + + // Character is assumed previously filtered by write() to eliminate + // newlines, returns, non-printable characters, etc. Calling drawChar() + // directly with 'bad' characters of font may cause mayhem! + + c -= pgm_read_byte(&gfxFont->first); + GFXglyph *glyph = &(((GFXglyph *)pgm_read_pointer(&gfxFont->glyph))[c]); + uint8_t *bitmap = (uint8_t *)pgm_read_pointer(&gfxFont->bitmap); + + uint16_t bo = pgm_read_word(&glyph->bitmapOffset); + uint8_t w = pgm_read_byte(&glyph->width), + h = pgm_read_byte(&glyph->height), + xa = pgm_read_byte(&glyph->xAdvance); + int8_t xo = pgm_read_byte(&glyph->xOffset), + yo = pgm_read_byte(&glyph->yOffset); + uint8_t xx, yy, bits, bit = 0; + int16_t xo16, yo16; + + if(size > 1) { + xo16 = xo; + yo16 = yo; + } + + // Todo: Add character clipping here + + // NOTE: THERE IS NO 'BACKGROUND' COLOR OPTION ON CUSTOM FONTS. + // THIS IS ON PURPOSE AND BY DESIGN. The background color feature + // has typically been used with the 'classic' font to overwrite old + // screen contents with new data. This ONLY works because the + // characters are a uniform size; it's not a sensible thing to do with + // proportionally-spaced fonts with glyphs of varying sizes (and that + // may overlap). To replace previously-drawn text when using a custom + // font, use the getTextBounds() function to determine the smallest + // rectangle encompassing a string, erase the area with fillRect(), + // then draw new text. This WILL infortunately 'blink' the text, but + // is unavoidable. Drawing 'background' pixels will NOT fix this, + // only creates a new set of problems. Have an idea to work around + // this (a canvas object type for MCUs that can afford the RAM and + // displays supporting setAddrWindow() and pushColors()), but haven't + // implemented this yet. + + for(yy=0; yy 0) ? s : 1; +} + +void Adafruit_GFX::setTextColor(uint16_t c) { + // For 'transparent' background, we'll set the bg + // to the same as fg instead of using a flag + textcolor = textbgcolor = c; +} + +void Adafruit_GFX::setTextColor(uint16_t c, uint16_t b) { + textcolor = c; + textbgcolor = b; +} + +void Adafruit_GFX::setTextWrap(boolean w) { + wrap = w; +} + +uint8_t Adafruit_GFX::getRotation(void) const { + return rotation; +} + +void Adafruit_GFX::setRotation(uint8_t x) { + rotation = (x & 3); + switch(rotation) { + case 0: + case 2: + _width = WIDTH; + _height = HEIGHT; + break; + case 1: + case 3: + _width = HEIGHT; + _height = WIDTH; + break; + } +} + +// Enable (or disable) Code Page 437-compatible charset. +// There was an error in glcdfont.c for the longest time -- one character +// (#176, the 'light shade' block) was missing -- this threw off the index +// of every character that followed it. But a TON of code has been written +// with the erroneous character indices. By default, the library uses the +// original 'wrong' behavior and old sketches will still work. Pass 'true' +// to this function to use correct CP437 character values in your code. +void Adafruit_GFX::cp437(boolean x) { + _cp437 = x; +} + +void Adafruit_GFX::setFont(const GFXfont *f) { + if(f) { // Font struct pointer passed in? + if(!gfxFont) { // And no current font struct? + // Switching from classic to new font behavior. + // Move cursor pos down 6 pixels so it's on baseline. + cursor_y += 6; + } + } else if(gfxFont) { // NULL passed. Current font struct defined? + // Switching from new to classic font behavior. + // Move cursor pos up 6 pixels so it's at top-left of char. + cursor_y -= 6; + } + gfxFont = (GFXfont *)f; +} + +// Pass string and a cursor position, returns UL corner and W,H. +void Adafruit_GFX::getTextBounds(char *str, int16_t x, int16_t y, + int16_t *x1, int16_t *y1, uint16_t *w, uint16_t *h) { + uint8_t c; // Current character + + *x1 = x; + *y1 = y; + *w = *h = 0; + + if(gfxFont) { + + GFXglyph *glyph; + uint8_t first = pgm_read_byte(&gfxFont->first), + last = pgm_read_byte(&gfxFont->last), + gw, gh, xa; + int8_t xo, yo; + int16_t minx = _width, miny = _height, maxx = -1, maxy = -1, + gx1, gy1, gx2, gy2, ts = (int16_t)textsize, + ya = ts * (uint8_t)pgm_read_byte(&gfxFont->yAdvance); + + while((c = *str++)) { + if(c != '\n') { // Not a newline + if(c != '\r') { // Not a carriage return, is normal char + if((c >= first) && (c <= last)) { // Char present in current font + c -= first; + glyph = &(((GFXglyph *)pgm_read_pointer(&gfxFont->glyph))[c]); + gw = pgm_read_byte(&glyph->width); + gh = pgm_read_byte(&glyph->height); + xa = pgm_read_byte(&glyph->xAdvance); + xo = pgm_read_byte(&glyph->xOffset); + yo = pgm_read_byte(&glyph->yOffset); + if(wrap && ((x + (((int16_t)xo + gw) * ts)) >= _width)) { + // Line wrap + x = 0; // Reset x to 0 + y += ya; // Advance y by 1 line + } + gx1 = x + xo * ts; + gy1 = y + yo * ts; + gx2 = gx1 + gw * ts - 1; + gy2 = gy1 + gh * ts - 1; + if(gx1 < minx) minx = gx1; + if(gy1 < miny) miny = gy1; + if(gx2 > maxx) maxx = gx2; + if(gy2 > maxy) maxy = gy2; + x += xa * ts; + } + } // Carriage return = do nothing + } else { // Newline + x = 0; // Reset x + y += ya; // Advance y by 1 line + } + } + // End of string + *x1 = minx; + *y1 = miny; + if(maxx >= minx) *w = maxx - minx + 1; + if(maxy >= miny) *h = maxy - miny + 1; + + } else { // Default font + + uint16_t lineWidth = 0, maxWidth = 0; // Width of current, all lines + + while((c = *str++)) { + if(c != '\n') { // Not a newline + if(c != '\r') { // Not a carriage return, is normal char + if(wrap && ((x + textsize * 6) >= _width)) { + x = 0; // Reset x to 0 + y += textsize * 8; // Advance y by 1 line + if(lineWidth > maxWidth) maxWidth = lineWidth; // Save widest line + lineWidth = textsize * 6; // First char on new line + } else { // No line wrap, just keep incrementing X + lineWidth += textsize * 6; // Includes interchar x gap + } + } // Carriage return = do nothing + } else { // Newline + x = 0; // Reset x to 0 + y += textsize * 8; // Advance y by 1 line + if(lineWidth > maxWidth) maxWidth = lineWidth; // Save widest line + lineWidth = 0; // Reset lineWidth for new line + } + } + // End of string + if(lineWidth) y += textsize * 8; // Add height of last (or only) line + if(lineWidth > maxWidth) maxWidth = lineWidth; // Is the last or only line the widest? + *w = maxWidth - 1; // Don't include last interchar x gap + *h = y - *y1; + + } // End classic vs custom font +} + +// Same as above, but for PROGMEM strings +void Adafruit_GFX::getTextBounds(const __FlashStringHelper *str, + int16_t x, int16_t y, int16_t *x1, int16_t *y1, uint16_t *w, uint16_t *h) { + uint8_t *s = (uint8_t *)str, c; + + *x1 = x; + *y1 = y; + *w = *h = 0; + + if(gfxFont) { + + GFXglyph *glyph; + uint8_t first = pgm_read_byte(&gfxFont->first), + last = pgm_read_byte(&gfxFont->last), + gw, gh, xa; + int8_t xo, yo; + int16_t minx = _width, miny = _height, maxx = -1, maxy = -1, + gx1, gy1, gx2, gy2, ts = (int16_t)textsize, + ya = ts * (uint8_t)pgm_read_byte(&gfxFont->yAdvance); + + while((c = pgm_read_byte(s++))) { + if(c != '\n') { // Not a newline + if(c != '\r') { // Not a carriage return, is normal char + if((c >= first) && (c <= last)) { // Char present in current font + c -= first; + glyph = &(((GFXglyph *)pgm_read_pointer(&gfxFont->glyph))[c]); + gw = pgm_read_byte(&glyph->width); + gh = pgm_read_byte(&glyph->height); + xa = pgm_read_byte(&glyph->xAdvance); + xo = pgm_read_byte(&glyph->xOffset); + yo = pgm_read_byte(&glyph->yOffset); + if(wrap && ((x + (((int16_t)xo + gw) * ts)) >= _width)) { + // Line wrap + x = 0; // Reset x to 0 + y += ya; // Advance y by 1 line + } + gx1 = x + xo * ts; + gy1 = y + yo * ts; + gx2 = gx1 + gw * ts - 1; + gy2 = gy1 + gh * ts - 1; + if(gx1 < minx) minx = gx1; + if(gy1 < miny) miny = gy1; + if(gx2 > maxx) maxx = gx2; + if(gy2 > maxy) maxy = gy2; + x += xa * ts; + } + } // Carriage return = do nothing + } else { // Newline + x = 0; // Reset x + y += ya; // Advance y by 1 line + } + } + // End of string + *x1 = minx; + *y1 = miny; + if(maxx >= minx) *w = maxx - minx + 1; + if(maxy >= miny) *h = maxy - miny + 1; + + } else { // Default font + + uint16_t lineWidth = 0, maxWidth = 0; // Width of current, all lines + + while((c = pgm_read_byte(s++))) { + if(c != '\n') { // Not a newline + if(c != '\r') { // Not a carriage return, is normal char + if(wrap && ((x + textsize * 6) >= _width)) { + x = 0; // Reset x to 0 + y += textsize * 8; // Advance y by 1 line + if(lineWidth > maxWidth) maxWidth = lineWidth; // Save widest line + lineWidth = textsize * 6; // First char on new line + } else { // No line wrap, just keep incrementing X + lineWidth += textsize * 6; // Includes interchar x gap + } + } // Carriage return = do nothing + } else { // Newline + x = 0; // Reset x to 0 + y += textsize * 8; // Advance y by 1 line + if(lineWidth > maxWidth) maxWidth = lineWidth; // Save widest line + lineWidth = 0; // Reset lineWidth for new line + } + } + // End of string + if(lineWidth) y += textsize * 8; // Add height of last (or only) line + if(lineWidth > maxWidth) maxWidth = lineWidth; // Is the last or only line the widest? + *w = maxWidth - 1; // Don't include last interchar x gap + *h = y - *y1; + + } // End classic vs custom font +} + +// Return the size of the display (per current rotation) +int16_t Adafruit_GFX::width(void) const { + return _width; +} + +int16_t Adafruit_GFX::height(void) const { + return _height; +} + +void Adafruit_GFX::invertDisplay(boolean i) { + // Do nothing, must be subclassed if supported by hardware +} + +/***************************************************************************/ +// code for the GFX button UI element + +Adafruit_GFX_Button::Adafruit_GFX_Button(void) { + _gfx = 0; +} + +void Adafruit_GFX_Button::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) +{ + _x = x; + _y = y; + _w = w; + _h = h; + _outlinecolor = outline; + _fillcolor = fill; + _textcolor = textcolor; + _textsize = textsize; + _gfx = gfx; + strncpy(_label, label, 9); + _label[9] = 0; +} + +void Adafruit_GFX_Button::drawButton(boolean inverted) { + uint16_t fill, outline, text; + + if(!inverted) { + fill = _fillcolor; + outline = _outlinecolor; + text = _textcolor; + } else { + fill = _textcolor; + outline = _outlinecolor; + text = _fillcolor; + } + + _gfx->fillRoundRect(_x - (_w/2), _y - (_h/2), _w, _h, min(_w,_h)/4, fill); + _gfx->drawRoundRect(_x - (_w/2), _y - (_h/2), _w, _h, min(_w,_h)/4, outline); + + _gfx->setCursor(_x - strlen(_label)*3*_textsize, _y-4*_textsize); + _gfx->setTextColor(text); + _gfx->setTextSize(_textsize); + _gfx->print(_label); +} + +boolean Adafruit_GFX_Button::contains(int16_t x, int16_t y) { + if ((x < (_x - _w/2)) || (x > (_x + _w/2))) return false; + if ((y < (_y - _h/2)) || (y > (_y + _h/2))) return false; + return true; +} + +void Adafruit_GFX_Button::press(boolean p) { + laststate = currstate; + currstate = p; +} + +boolean Adafruit_GFX_Button::isPressed() { return currstate; } +boolean Adafruit_GFX_Button::justPressed() { return (currstate && !laststate); } +boolean Adafruit_GFX_Button::justReleased() { return (!currstate && laststate); } + +// ------------------------------------------------------------------------- + +// GFXcanvas1 and GFXcanvas16 (currently a WIP, don't get too comfy with the +// implementation) provide 1- and 16-bit offscreen canvases, the address of +// which can be passed to drawBitmap() or pushColors() (the latter appears +// to only be in Adafruit_TFTLCD at this time). This is here mostly to +// help with the recently-added proportionally-spaced fonts; adds a way to +// refresh a section of the screen without a massive flickering clear-and- +// redraw...but maybe you'll find other uses too. VERY RAM-intensive, since +// the buffer is in MCU memory and not the display driver...GXFcanvas1 might +// be minimally useful on an Uno-class board, but this and GFXcanvas16 are +// much more likely to require at least a Mega or various recent ARM-type +// boards (recomment, as the text+bitmap draw can be pokey). GFXcanvas1 +// requires 1 bit per pixel (rounded up to nearest byte per scanline), +// GFXcanvas16 requires 2 bytes per pixel (no scanline pad). +// NOT EXTENSIVELY TESTED YET. MAY CONTAIN WORST BUGS KNOWN TO HUMANKIND. + +GFXcanvas1::GFXcanvas1(uint16_t w, uint16_t h) : Adafruit_GFX(w, h) { + uint16_t bytes = ((w + 7) / 8) * h; + if((buffer = (uint8_t *)malloc(bytes))) { + memset(buffer, 0, bytes); + } +} + +GFXcanvas1::~GFXcanvas1(void) { + if(buffer) free(buffer); +} + +uint8_t* GFXcanvas1::getBuffer(void) { + return buffer; +} + +void GFXcanvas1::drawPixel(int16_t x, int16_t y, uint16_t color) { + // Bitmask tables of 0x80>>X and ~(0x80>>X), because X>>Y is slow on AVR + static const uint8_t PROGMEM + GFXsetBit[] = { 0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01 }, + GFXclrBit[] = { 0x7F, 0xBF, 0xDF, 0xEF, 0xF7, 0xFB, 0xFD, 0xFE }; + + if(buffer) { + if((x < 0) || (y < 0) || (x >= _width) || (y >= _height)) return; + + int16_t t; + switch(rotation) { + case 1: + t = x; + x = WIDTH - 1 - y; + y = t; + break; + case 2: + x = WIDTH - 1 - x; + y = HEIGHT - 1 - y; + break; + case 3: + t = x; + x = y; + y = HEIGHT - 1 - t; + break; + } + + uint8_t *ptr = &buffer[(x / 8) + y * ((WIDTH + 7) / 8)]; + if(color) *ptr |= pgm_read_byte(&GFXsetBit[x & 7]); + else *ptr &= pgm_read_byte(&GFXclrBit[x & 7]); + } +} + +void GFXcanvas1::fillScreen(uint16_t color) { + if(buffer) { + uint16_t bytes = ((WIDTH + 7) / 8) * HEIGHT; + memset(buffer, color ? 0xFF : 0x00, bytes); + } +} + +GFXcanvas16::GFXcanvas16(uint16_t w, uint16_t h) : Adafruit_GFX(w, h) { + uint16_t bytes = w * h * 2; + if((buffer = (uint16_t *)malloc(bytes))) { + memset(buffer, 0, bytes); + } +} + +GFXcanvas16::~GFXcanvas16(void) { + if(buffer) free(buffer); +} + +uint16_t* GFXcanvas16::getBuffer(void) { + return buffer; +} + +void GFXcanvas16::drawPixel(int16_t x, int16_t y, uint16_t color) { + if(buffer) { + if((x < 0) || (y < 0) || (x >= _width) || (y >= _height)) return; + + int16_t t; + switch(rotation) { + case 1: + t = x; + x = WIDTH - 1 - y; + y = t; + break; + case 2: + x = WIDTH - 1 - x; + y = HEIGHT - 1 - y; + break; + case 3: + t = x; + x = y; + y = HEIGHT - 1 - t; + break; + } + + buffer[x + y * WIDTH] = color; + } +} + +void GFXcanvas16::fillScreen(uint16_t color) { + if(buffer) { + uint8_t hi = color >> 8, lo = color & 0xFF; + if(hi == lo) { + memset(buffer, lo, WIDTH * HEIGHT * 2); + } else { + uint16_t i, pixels = WIDTH * HEIGHT; + for(i=0; i= 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 diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMono12pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMono12pt7b.h new file mode 100644 index 0000000..94ecb88 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMono12pt7b.h @@ -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 diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMono18pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMono18pt7b.h new file mode 100644 index 0000000..c605d29 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMono18pt7b.h @@ -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 diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMono24pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMono24pt7b.h new file mode 100644 index 0000000..4c8bd15 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMono24pt7b.h @@ -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 diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMono9pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMono9pt7b.h new file mode 100644 index 0000000..c82d786 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMono9pt7b.h @@ -0,0 +1,176 @@ +const uint8_t FreeMono9pt7bBitmaps[] PROGMEM = { + 0xAA, 0xA8, 0x0C, 0xED, 0x24, 0x92, 0x48, 0x24, 0x48, 0x91, 0x2F, 0xE4, + 0x89, 0x7F, 0x28, 0x51, 0x22, 0x40, 0x08, 0x3E, 0x62, 0x40, 0x30, 0x0E, + 0x01, 0x81, 0xC3, 0xBE, 0x08, 0x08, 0x71, 0x12, 0x23, 0x80, 0x23, 0xB8, + 0x0E, 0x22, 0x44, 0x70, 0x38, 0x81, 0x02, 0x06, 0x1A, 0x65, 0x46, 0xC8, + 0xEC, 0xE9, 0x24, 0x5A, 0xAA, 0xA9, 0x40, 0xA9, 0x55, 0x5A, 0x80, 0x10, + 0x22, 0x4B, 0xE3, 0x05, 0x11, 0x00, 0x10, 0x20, 0x47, 0xF1, 0x02, 0x04, + 0x00, 0x6B, 0x48, 0xFF, 0x00, 0xF0, 0x02, 0x08, 0x10, 0x60, 0x81, 0x04, + 0x08, 0x20, 0x41, 0x02, 0x08, 0x00, 0x38, 0x8A, 0x0C, 0x18, 0x30, 0x60, + 0xC1, 0x82, 0x88, 0xE0, 0x27, 0x28, 0x42, 0x10, 0x84, 0x21, 0x3E, 0x38, + 0x8A, 0x08, 0x10, 0x20, 0x82, 0x08, 0x61, 0x03, 0xF8, 0x7C, 0x06, 0x02, + 0x02, 0x1C, 0x06, 0x01, 0x01, 0x01, 0x42, 0x3C, 0x18, 0xA2, 0x92, 0x8A, + 0x28, 0xBF, 0x08, 0x21, 0xC0, 0x7C, 0x81, 0x03, 0xE4, 0x40, 0x40, 0x81, + 0x03, 0x88, 0xE0, 0x1E, 0x41, 0x04, 0x0B, 0x98, 0xB0, 0xC1, 0xC2, 0x88, + 0xE0, 0xFE, 0x04, 0x08, 0x20, 0x40, 0x82, 0x04, 0x08, 0x20, 0x40, 0x38, + 0x8A, 0x0C, 0x14, 0x47, 0x11, 0x41, 0x83, 0x8C, 0xE0, 0x38, 0x8A, 0x1C, + 0x18, 0x68, 0xCE, 0x81, 0x04, 0x13, 0xC0, 0xF0, 0x0F, 0x6C, 0x00, 0xD2, + 0xD2, 0x00, 0x03, 0x04, 0x18, 0x60, 0x60, 0x18, 0x04, 0x03, 0xFF, 0x80, + 0x00, 0x1F, 0xF0, 0x40, 0x18, 0x03, 0x00, 0x60, 0x20, 0x60, 0xC0, 0x80, + 0x3D, 0x84, 0x08, 0x30, 0xC2, 0x00, 0x00, 0x00, 0x30, 0x3C, 0x46, 0x82, + 0x8E, 0xB2, 0xA2, 0xA2, 0x9F, 0x80, 0x80, 0x40, 0x3C, 0x3C, 0x01, 0x40, + 0x28, 0x09, 0x01, 0x10, 0x42, 0x0F, 0xC1, 0x04, 0x40, 0x9E, 0x3C, 0xFE, + 0x21, 0x90, 0x48, 0x67, 0xE2, 0x09, 0x02, 0x81, 0x41, 0xFF, 0x80, 0x3E, + 0xB0, 0xF0, 0x30, 0x08, 0x04, 0x02, 0x00, 0x80, 0x60, 0x8F, 0x80, 0xFE, + 0x21, 0x90, 0x68, 0x14, 0x0A, 0x05, 0x02, 0x83, 0x43, 0x7F, 0x00, 0xFF, + 0x20, 0x90, 0x08, 0x87, 0xC2, 0x21, 0x00, 0x81, 0x40, 0xFF, 0xC0, 0xFF, + 0xA0, 0x50, 0x08, 0x87, 0xC2, 0x21, 0x00, 0x80, 0x40, 0x78, 0x00, 0x1E, + 0x98, 0x6C, 0x0A, 0x00, 0x80, 0x20, 0xF8, 0x0B, 0x02, 0x60, 0x87, 0xC0, + 0xE3, 0xA0, 0x90, 0x48, 0x27, 0xF2, 0x09, 0x04, 0x82, 0x41, 0x71, 0xC0, + 0xF9, 0x08, 0x42, 0x10, 0x84, 0x27, 0xC0, 0x1F, 0x02, 0x02, 0x02, 0x02, + 0x02, 0x82, 0x82, 0xC6, 0x78, 0xE3, 0xA1, 0x11, 0x09, 0x05, 0x83, 0x21, + 0x08, 0x84, 0x41, 0x70, 0xC0, 0xE0, 0x40, 0x40, 0x40, 0x40, 0x40, 0x41, + 0x41, 0x41, 0xFF, 0xE0, 0xEC, 0x19, 0x45, 0x28, 0xA4, 0xA4, 0x94, 0x91, + 0x12, 0x02, 0x40, 0x5C, 0x1C, 0xC3, 0xB0, 0x94, 0x4A, 0x24, 0x92, 0x49, + 0x14, 0x8A, 0x43, 0x70, 0x80, 0x1E, 0x31, 0x90, 0x50, 0x18, 0x0C, 0x06, + 0x02, 0x82, 0x63, 0x0F, 0x00, 0xFE, 0x43, 0x41, 0x41, 0x42, 0x7C, 0x40, + 0x40, 0x40, 0xF0, 0x1C, 0x31, 0x90, 0x50, 0x18, 0x0C, 0x06, 0x02, 0x82, + 0x63, 0x1F, 0x04, 0x07, 0x92, 0x30, 0xFE, 0x21, 0x90, 0x48, 0x24, 0x23, + 0xE1, 0x10, 0x84, 0x41, 0x70, 0xC0, 0x3A, 0xCD, 0x0A, 0x03, 0x01, 0x80, + 0xC1, 0xC7, 0x78, 0xFF, 0xC4, 0x62, 0x21, 0x00, 0x80, 0x40, 0x20, 0x10, + 0x08, 0x1F, 0x00, 0xE3, 0xA0, 0x90, 0x48, 0x24, 0x12, 0x09, 0x04, 0x82, + 0x22, 0x0E, 0x00, 0xF1, 0xE8, 0x10, 0x82, 0x10, 0x42, 0x10, 0x22, 0x04, + 0x80, 0x50, 0x0C, 0x00, 0x80, 0xF1, 0xE8, 0x09, 0x11, 0x25, 0x44, 0xA8, + 0x55, 0x0C, 0xA1, 0x8C, 0x31, 0x84, 0x30, 0xE3, 0xA0, 0x88, 0x82, 0x80, + 0x80, 0xC0, 0x90, 0x44, 0x41, 0x71, 0xC0, 0xE3, 0xA0, 0x88, 0x82, 0x81, + 0x40, 0x40, 0x20, 0x10, 0x08, 0x1F, 0x00, 0xFD, 0x0A, 0x20, 0x81, 0x04, + 0x10, 0x21, 0x83, 0xFC, 0xEA, 0xAA, 0xAA, 0xC0, 0x80, 0x81, 0x03, 0x02, + 0x04, 0x04, 0x08, 0x08, 0x10, 0x10, 0x20, 0x20, 0xD5, 0x55, 0x55, 0xC0, + 0x10, 0x51, 0x22, 0x28, 0x20, 0xFF, 0xE0, 0x88, 0x80, 0x7E, 0x00, 0x80, + 0x47, 0xEC, 0x14, 0x0A, 0x0C, 0xFB, 0xC0, 0x20, 0x10, 0x0B, 0xC6, 0x12, + 0x05, 0x02, 0x81, 0x40, 0xB0, 0xB7, 0x80, 0x3A, 0x8E, 0x0C, 0x08, 0x10, + 0x10, 0x9E, 0x03, 0x00, 0x80, 0x47, 0xA4, 0x34, 0x0A, 0x05, 0x02, 0x81, + 0x21, 0x8F, 0x60, 0x3C, 0x43, 0x81, 0xFF, 0x80, 0x80, 0x61, 0x3E, 0x3D, + 0x04, 0x3E, 0x41, 0x04, 0x10, 0x41, 0x0F, 0x80, 0x3D, 0xA1, 0xA0, 0x50, + 0x28, 0x14, 0x09, 0x0C, 0x7A, 0x01, 0x01, 0x87, 0x80, 0xC0, 0x20, 0x10, + 0x0B, 0xC6, 0x32, 0x09, 0x04, 0x82, 0x41, 0x20, 0xB8, 0xE0, 0x10, 0x01, + 0xC0, 0x81, 0x02, 0x04, 0x08, 0x11, 0xFC, 0x10, 0x3E, 0x10, 0x84, 0x21, + 0x08, 0x42, 0x3F, 0x00, 0xC0, 0x40, 0x40, 0x4F, 0x44, 0x58, 0x70, 0x48, + 0x44, 0x42, 0xC7, 0x70, 0x20, 0x40, 0x81, 0x02, 0x04, 0x08, 0x10, 0x23, + 0xF8, 0xB7, 0x64, 0x62, 0x31, 0x18, 0x8C, 0x46, 0x23, 0x91, 0x5E, 0x31, + 0x90, 0x48, 0x24, 0x12, 0x09, 0x05, 0xC7, 0x3E, 0x31, 0xA0, 0x30, 0x18, + 0x0C, 0x05, 0x8C, 0x7C, 0xDE, 0x30, 0x90, 0x28, 0x14, 0x0A, 0x05, 0x84, + 0xBC, 0x40, 0x20, 0x38, 0x00, 0x3D, 0xA1, 0xA0, 0x50, 0x28, 0x14, 0x09, + 0x0C, 0x7A, 0x01, 0x00, 0x80, 0xE0, 0xCE, 0xA1, 0x82, 0x04, 0x08, 0x10, + 0x7C, 0x3A, 0x8D, 0x0B, 0x80, 0xF0, 0x70, 0xDE, 0x40, 0x40, 0xFC, 0x40, + 0x40, 0x40, 0x40, 0x40, 0x41, 0x3E, 0xC3, 0x41, 0x41, 0x41, 0x41, 0x41, + 0x43, 0x3D, 0xE3, 0xA0, 0x90, 0x84, 0x42, 0x20, 0xA0, 0x50, 0x10, 0xE3, + 0xC0, 0x92, 0x4B, 0x25, 0x92, 0xA9, 0x98, 0x44, 0xE3, 0x31, 0x05, 0x01, + 0x01, 0x41, 0x11, 0x05, 0xC7, 0xE3, 0xA0, 0x90, 0x84, 0x42, 0x40, 0xA0, + 0x60, 0x10, 0x10, 0x08, 0x3E, 0x00, 0xFD, 0x08, 0x20, 0x82, 0x08, 0x10, + 0xBF, 0x29, 0x24, 0xA2, 0x49, 0x26, 0xFF, 0xF8, 0x89, 0x24, 0x8A, 0x49, + 0x2C, 0x61, 0x24, 0x30 }; + +const GFXglyph FreeMono9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 11, 0, 1 }, // 0x20 ' ' + { 0, 2, 11, 11, 4, -10 }, // 0x21 '!' + { 3, 6, 5, 11, 2, -10 }, // 0x22 '"' + { 7, 7, 12, 11, 2, -10 }, // 0x23 '#' + { 18, 8, 12, 11, 1, -10 }, // 0x24 '$' + { 30, 7, 11, 11, 2, -10 }, // 0x25 '%' + { 40, 7, 10, 11, 2, -9 }, // 0x26 '&' + { 49, 3, 5, 11, 4, -10 }, // 0x27 ''' + { 51, 2, 13, 11, 5, -10 }, // 0x28 '(' + { 55, 2, 13, 11, 4, -10 }, // 0x29 ')' + { 59, 7, 7, 11, 2, -10 }, // 0x2A '*' + { 66, 7, 7, 11, 2, -8 }, // 0x2B '+' + { 73, 3, 5, 11, 2, -1 }, // 0x2C ',' + { 75, 9, 1, 11, 1, -5 }, // 0x2D '-' + { 77, 2, 2, 11, 4, -1 }, // 0x2E '.' + { 78, 7, 13, 11, 2, -11 }, // 0x2F '/' + { 90, 7, 11, 11, 2, -10 }, // 0x30 '0' + { 100, 5, 11, 11, 3, -10 }, // 0x31 '1' + { 107, 7, 11, 11, 2, -10 }, // 0x32 '2' + { 117, 8, 11, 11, 1, -10 }, // 0x33 '3' + { 128, 6, 11, 11, 3, -10 }, // 0x34 '4' + { 137, 7, 11, 11, 2, -10 }, // 0x35 '5' + { 147, 7, 11, 11, 2, -10 }, // 0x36 '6' + { 157, 7, 11, 11, 2, -10 }, // 0x37 '7' + { 167, 7, 11, 11, 2, -10 }, // 0x38 '8' + { 177, 7, 11, 11, 2, -10 }, // 0x39 '9' + { 187, 2, 8, 11, 4, -7 }, // 0x3A ':' + { 189, 3, 11, 11, 3, -7 }, // 0x3B ';' + { 194, 8, 8, 11, 1, -8 }, // 0x3C '<' + { 202, 9, 4, 11, 1, -6 }, // 0x3D '=' + { 207, 9, 8, 11, 1, -8 }, // 0x3E '>' + { 216, 7, 10, 11, 2, -9 }, // 0x3F '?' + { 225, 8, 12, 11, 2, -10 }, // 0x40 '@' + { 237, 11, 10, 11, 0, -9 }, // 0x41 'A' + { 251, 9, 10, 11, 1, -9 }, // 0x42 'B' + { 263, 9, 10, 11, 1, -9 }, // 0x43 'C' + { 275, 9, 10, 11, 1, -9 }, // 0x44 'D' + { 287, 9, 10, 11, 1, -9 }, // 0x45 'E' + { 299, 9, 10, 11, 1, -9 }, // 0x46 'F' + { 311, 10, 10, 11, 1, -9 }, // 0x47 'G' + { 324, 9, 10, 11, 1, -9 }, // 0x48 'H' + { 336, 5, 10, 11, 3, -9 }, // 0x49 'I' + { 343, 8, 10, 11, 2, -9 }, // 0x4A 'J' + { 353, 9, 10, 11, 1, -9 }, // 0x4B 'K' + { 365, 8, 10, 11, 2, -9 }, // 0x4C 'L' + { 375, 11, 10, 11, 0, -9 }, // 0x4D 'M' + { 389, 9, 10, 11, 1, -9 }, // 0x4E 'N' + { 401, 9, 10, 11, 1, -9 }, // 0x4F 'O' + { 413, 8, 10, 11, 1, -9 }, // 0x50 'P' + { 423, 9, 13, 11, 1, -9 }, // 0x51 'Q' + { 438, 9, 10, 11, 1, -9 }, // 0x52 'R' + { 450, 7, 10, 11, 2, -9 }, // 0x53 'S' + { 459, 9, 10, 11, 1, -9 }, // 0x54 'T' + { 471, 9, 10, 11, 1, -9 }, // 0x55 'U' + { 483, 11, 10, 11, 0, -9 }, // 0x56 'V' + { 497, 11, 10, 11, 0, -9 }, // 0x57 'W' + { 511, 9, 10, 11, 1, -9 }, // 0x58 'X' + { 523, 9, 10, 11, 1, -9 }, // 0x59 'Y' + { 535, 7, 10, 11, 2, -9 }, // 0x5A 'Z' + { 544, 2, 13, 11, 5, -10 }, // 0x5B '[' + { 548, 7, 13, 11, 2, -11 }, // 0x5C '\' + { 560, 2, 13, 11, 4, -10 }, // 0x5D ']' + { 564, 7, 5, 11, 2, -10 }, // 0x5E '^' + { 569, 11, 1, 11, 0, 2 }, // 0x5F '_' + { 571, 3, 3, 11, 3, -11 }, // 0x60 '`' + { 573, 9, 8, 11, 1, -7 }, // 0x61 'a' + { 582, 9, 11, 11, 1, -10 }, // 0x62 'b' + { 595, 7, 8, 11, 2, -7 }, // 0x63 'c' + { 602, 9, 11, 11, 1, -10 }, // 0x64 'd' + { 615, 8, 8, 11, 1, -7 }, // 0x65 'e' + { 623, 6, 11, 11, 3, -10 }, // 0x66 'f' + { 632, 9, 11, 11, 1, -7 }, // 0x67 'g' + { 645, 9, 11, 11, 1, -10 }, // 0x68 'h' + { 658, 7, 10, 11, 2, -9 }, // 0x69 'i' + { 667, 5, 13, 11, 3, -9 }, // 0x6A 'j' + { 676, 8, 11, 11, 2, -10 }, // 0x6B 'k' + { 687, 7, 11, 11, 2, -10 }, // 0x6C 'l' + { 697, 9, 8, 11, 1, -7 }, // 0x6D 'm' + { 706, 9, 8, 11, 1, -7 }, // 0x6E 'n' + { 715, 9, 8, 11, 1, -7 }, // 0x6F 'o' + { 724, 9, 11, 11, 1, -7 }, // 0x70 'p' + { 737, 9, 11, 11, 1, -7 }, // 0x71 'q' + { 750, 7, 8, 11, 3, -7 }, // 0x72 'r' + { 757, 7, 8, 11, 2, -7 }, // 0x73 's' + { 764, 8, 10, 11, 2, -9 }, // 0x74 't' + { 774, 8, 8, 11, 1, -7 }, // 0x75 'u' + { 782, 9, 8, 11, 1, -7 }, // 0x76 'v' + { 791, 9, 8, 11, 1, -7 }, // 0x77 'w' + { 800, 9, 8, 11, 1, -7 }, // 0x78 'x' + { 809, 9, 11, 11, 1, -7 }, // 0x79 'y' + { 822, 7, 8, 11, 2, -7 }, // 0x7A 'z' + { 829, 3, 13, 11, 4, -10 }, // 0x7B '{' + { 834, 1, 13, 11, 5, -10 }, // 0x7C '|' + { 836, 3, 13, 11, 4, -10 }, // 0x7D '}' + { 841, 7, 3, 11, 2, -6 } }; // 0x7E '~' + +const GFXfont FreeMono9pt7b PROGMEM = { + (uint8_t *)FreeMono9pt7bBitmaps, + (GFXglyph *)FreeMono9pt7bGlyphs, + 0x20, 0x7E, 18 }; + +// Approx. 1516 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBold12pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBold12pt7b.h new file mode 100644 index 0000000..4ad9d1a --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBold12pt7b.h @@ -0,0 +1,250 @@ +const uint8_t FreeMonoBold12pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xF6, 0x66, 0x60, 0x6F, 0x60, 0xE7, 0xE7, 0x62, 0x42, + 0x42, 0x42, 0x42, 0x11, 0x87, 0x30, 0xC6, 0x18, 0xC3, 0x31, 0xFF, 0xFF, + 0xF9, 0x98, 0x33, 0x06, 0x60, 0xCC, 0x7F, 0xEF, 0xFC, 0x66, 0x0C, 0xC3, + 0x98, 0x63, 0x04, 0x40, 0x0C, 0x03, 0x00, 0xC0, 0xFE, 0x7F, 0x9C, 0x66, + 0x09, 0x80, 0x78, 0x0F, 0xE0, 0x7F, 0x03, 0xE0, 0xF8, 0x7F, 0xFB, 0xFC, + 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x38, 0x1F, 0x0C, 0x42, 0x10, 0xC4, 0x1F, + 0x03, 0x9C, 0x3C, 0x7F, 0x33, 0xE0, 0x8C, 0x21, 0x08, 0xC3, 0xE0, 0x70, + 0x3E, 0x1F, 0xC6, 0x61, 0x80, 0x70, 0x0C, 0x07, 0x83, 0xEE, 0xDF, 0xB3, + 0xCC, 0x73, 0xFE, 0x7F, 0x80, 0xFD, 0x24, 0x90, 0x39, 0xDC, 0xE6, 0x73, + 0x18, 0xC6, 0x31, 0x8C, 0x31, 0x8E, 0x31, 0xC4, 0xE7, 0x1C, 0xE3, 0x1C, + 0x63, 0x18, 0xC6, 0x31, 0x98, 0xCE, 0x67, 0x10, 0x0C, 0x03, 0x00, 0xC3, + 0xB7, 0xFF, 0xDF, 0xE1, 0xE0, 0xFC, 0x33, 0x0C, 0xC0, 0x06, 0x00, 0x60, + 0x06, 0x00, 0x60, 0x06, 0x0F, 0xFF, 0xFF, 0xF0, 0x60, 0x06, 0x00, 0x60, + 0x06, 0x00, 0x60, 0x06, 0x00, 0x3B, 0x9C, 0xCE, 0x62, 0x00, 0xFF, 0xFF, + 0xFF, 0xFF, 0x80, 0x00, 0x40, 0x30, 0x1C, 0x07, 0x03, 0x80, 0xE0, 0x30, + 0x1C, 0x06, 0x03, 0x80, 0xC0, 0x70, 0x18, 0x0E, 0x03, 0x01, 0xC0, 0x60, + 0x38, 0x0E, 0x01, 0x00, 0x1E, 0x0F, 0xC6, 0x1B, 0x87, 0xC0, 0xF0, 0x3C, + 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x87, 0x61, 0x8F, 0xC1, 0xE0, 0x1C, + 0x0F, 0x0F, 0xC3, 0xB0, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x0C, 0x03, 0x00, + 0xC0, 0x30, 0x0C, 0x3F, 0xFF, 0xFC, 0x1F, 0x1F, 0xEE, 0x1F, 0x83, 0xC0, + 0xC0, 0x70, 0x38, 0x1E, 0x0F, 0x07, 0x83, 0xC1, 0xE3, 0xF0, 0xFF, 0xFF, + 0xFC, 0x3F, 0x0F, 0xF1, 0x87, 0x00, 0x60, 0x0C, 0x03, 0x83, 0xE0, 0x7C, + 0x01, 0xC0, 0x0C, 0x01, 0x80, 0x3C, 0x0F, 0xFF, 0x9F, 0xC0, 0x07, 0x07, + 0x83, 0xC3, 0xE1, 0xB1, 0xD8, 0xCC, 0xC6, 0xE3, 0x7F, 0xFF, 0xE0, 0x61, + 0xF8, 0xFC, 0x7F, 0x9F, 0xE6, 0x01, 0x80, 0x60, 0x1F, 0x87, 0xF9, 0x86, + 0x00, 0xC0, 0x30, 0x0C, 0x03, 0xC1, 0xBF, 0xE7, 0xE0, 0x07, 0xC7, 0xF3, + 0xC1, 0xC0, 0x60, 0x38, 0x0E, 0xF3, 0xFE, 0xF1, 0xF8, 0x3E, 0x0F, 0x83, + 0x71, 0xCF, 0xE1, 0xF0, 0xFF, 0xFF, 0xFC, 0x1F, 0x07, 0x01, 0x80, 0x60, + 0x38, 0x0C, 0x03, 0x01, 0xC0, 0x60, 0x18, 0x0E, 0x03, 0x00, 0xC0, 0x1E, + 0x1F, 0xEE, 0x1F, 0x03, 0xC0, 0xF0, 0x36, 0x19, 0xFE, 0x7F, 0xB8, 0x7C, + 0x0F, 0x03, 0xE1, 0xDF, 0xE3, 0xF0, 0x3E, 0x1F, 0xCE, 0x3B, 0x07, 0xC1, + 0xF0, 0x7E, 0x3D, 0xFF, 0x3D, 0xC0, 0x70, 0x18, 0x0E, 0x0F, 0x3F, 0x8F, + 0x80, 0xFF, 0x80, 0x00, 0xFF, 0x80, 0x77, 0x70, 0x00, 0x00, 0x76, 0x6C, + 0xC8, 0x80, 0x00, 0x30, 0x0F, 0x03, 0xE0, 0xF8, 0x3E, 0x0F, 0x80, 0x3E, + 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x00, 0x20, 0xFF, 0xFF, 0xFF, 0x00, 0x00, + 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xF0, 0x60, 0x0F, 0x80, 0x3E, 0x00, 0xF8, + 0x03, 0xE0, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x0F, 0x00, 0x40, 0x00, 0x7C, + 0x7F, 0xB0, 0xF8, 0x30, 0x18, 0x1C, 0x3C, 0x3C, 0x18, 0x08, 0x00, 0x07, + 0x03, 0x81, 0xC0, 0x1E, 0x07, 0xF1, 0xC7, 0x30, 0x6C, 0x0D, 0x87, 0xB3, + 0xF6, 0xE6, 0xD8, 0xDB, 0x1B, 0x73, 0x67, 0xFC, 0x7F, 0x80, 0x30, 0x03, + 0x00, 0x71, 0xC7, 0xF8, 0x7C, 0x00, 0x3F, 0x80, 0x7F, 0x80, 0x1F, 0x00, + 0x76, 0x00, 0xEE, 0x01, 0x8C, 0x07, 0x18, 0x0E, 0x38, 0x1F, 0xF0, 0x7F, + 0xF0, 0xC0, 0x61, 0x80, 0xCF, 0xC7, 0xFF, 0x8F, 0xC0, 0xFF, 0xC7, 0xFF, + 0x0C, 0x1C, 0x60, 0x63, 0x03, 0x18, 0x38, 0xFF, 0x87, 0xFE, 0x30, 0x39, + 0x80, 0xCC, 0x06, 0x60, 0x7F, 0xFF, 0x7F, 0xF0, 0x0F, 0xF3, 0xFF, 0x70, + 0x76, 0x03, 0xC0, 0x3C, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0x60, + 0x37, 0x07, 0x3F, 0xF0, 0xFC, 0xFF, 0x0F, 0xFC, 0x60, 0xE6, 0x06, 0x60, + 0x36, 0x03, 0x60, 0x36, 0x03, 0x60, 0x36, 0x03, 0x60, 0x76, 0x0E, 0xFF, + 0xCF, 0xF8, 0xFF, 0xF7, 0xFF, 0x8C, 0x0C, 0x60, 0x63, 0x1B, 0x18, 0xC0, + 0xFE, 0x07, 0xF0, 0x31, 0x81, 0x8C, 0xCC, 0x06, 0x60, 0x3F, 0xFF, 0xFF, + 0xFC, 0xFF, 0xFF, 0xFF, 0xCC, 0x06, 0x60, 0x33, 0x19, 0x98, 0xC0, 0xFE, + 0x07, 0xF0, 0x31, 0x81, 0x8C, 0x0C, 0x00, 0x60, 0x0F, 0xF0, 0x7F, 0x80, + 0x0F, 0xF1, 0xFF, 0x9C, 0x1C, 0xC0, 0x6C, 0x03, 0x60, 0x03, 0x00, 0x18, + 0x7F, 0xC3, 0xFE, 0x01, 0xB8, 0x0C, 0xE0, 0xE3, 0xFF, 0x07, 0xE0, 0x7C, + 0xF9, 0xF3, 0xE3, 0x03, 0x0C, 0x0C, 0x30, 0x30, 0xC0, 0xC3, 0xFF, 0x0F, + 0xFC, 0x30, 0x30, 0xC0, 0xC3, 0x03, 0x0C, 0x0C, 0xFC, 0xFF, 0xF3, 0xF0, + 0xFF, 0xFF, 0xF0, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x0C, 0x03, + 0x00, 0xC0, 0x30, 0xFF, 0xFF, 0xF0, 0x0F, 0xF8, 0x7F, 0xC0, 0x30, 0x01, + 0x80, 0x0C, 0x00, 0x60, 0x03, 0x18, 0x18, 0xC0, 0xC6, 0x06, 0x30, 0x31, + 0xC3, 0x0F, 0xF8, 0x1F, 0x00, 0xFC, 0xFB, 0xF3, 0xE3, 0x0E, 0x0C, 0x70, + 0x33, 0x80, 0xFC, 0x03, 0xF0, 0x0F, 0xE0, 0x39, 0xC0, 0xC3, 0x03, 0x0E, + 0x0C, 0x18, 0xFC, 0x7F, 0xF0, 0xF0, 0xFF, 0x0F, 0xF0, 0x18, 0x01, 0x80, + 0x18, 0x01, 0x80, 0x18, 0x01, 0x80, 0x18, 0x31, 0x83, 0x18, 0x31, 0x83, + 0xFF, 0xFF, 0xFF, 0xF0, 0x3F, 0xC0, 0xF7, 0x87, 0x9E, 0x1E, 0x7C, 0xF9, + 0xB3, 0xE6, 0xFD, 0x99, 0xF6, 0x67, 0x99, 0x8E, 0x66, 0x31, 0x98, 0x06, + 0xFC, 0xFF, 0xF3, 0xF0, 0xF1, 0xFF, 0xCF, 0xCF, 0x0C, 0x78, 0x63, 0xE3, + 0x1B, 0x18, 0xDC, 0xC6, 0x76, 0x31, 0xB1, 0x8F, 0x8C, 0x3C, 0x61, 0xE7, + 0xE7, 0x3F, 0x18, 0x0F, 0x03, 0xFC, 0x70, 0xE6, 0x06, 0xE0, 0x7C, 0x03, + 0xC0, 0x3C, 0x03, 0xC0, 0x3E, 0x07, 0x60, 0x67, 0x0E, 0x3F, 0xC0, 0xF0, + 0xFF, 0x8F, 0xFE, 0x30, 0x73, 0x03, 0x30, 0x33, 0x03, 0x30, 0x73, 0xFE, + 0x3F, 0x83, 0x00, 0x30, 0x03, 0x00, 0xFF, 0x0F, 0xF0, 0x0F, 0x03, 0xFC, + 0x70, 0xE6, 0x06, 0xE0, 0x7C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3E, 0x07, + 0x60, 0x67, 0x0E, 0x3F, 0xC1, 0xF0, 0x18, 0x33, 0xFF, 0x3F, 0xE0, 0xFF, + 0x83, 0xFF, 0x83, 0x07, 0x0C, 0x0C, 0x30, 0x30, 0xC1, 0xC3, 0xFE, 0x0F, + 0xF0, 0x31, 0xE0, 0xC3, 0x83, 0x07, 0x0C, 0x0C, 0xFE, 0x3F, 0xF8, 0x70, + 0x3F, 0xDF, 0xFE, 0x1F, 0x03, 0xC0, 0xF8, 0x07, 0xE0, 0x7E, 0x01, 0xF0, + 0x3C, 0x0F, 0x87, 0xFF, 0xBF, 0xC0, 0xFF, 0xFF, 0xFF, 0xC6, 0x3C, 0x63, + 0xC6, 0x3C, 0x63, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x3F, 0xC3, 0xFC, 0xFF, 0xFF, 0xFF, 0x60, 0x66, 0x06, 0x60, 0x66, 0x06, + 0x60, 0x66, 0x06, 0x60, 0x66, 0x06, 0x60, 0x63, 0x9C, 0x1F, 0xC0, 0xF0, + 0xFC, 0x3F, 0xFC, 0x3F, 0x30, 0x0C, 0x38, 0x1C, 0x18, 0x18, 0x1C, 0x38, + 0x1C, 0x38, 0x0E, 0x70, 0x0E, 0x70, 0x0F, 0x60, 0x07, 0xE0, 0x07, 0xE0, + 0x03, 0xC0, 0x03, 0xC0, 0xFC, 0xFF, 0xF3, 0xF6, 0x01, 0xDC, 0xC6, 0x77, + 0x99, 0xDE, 0x67, 0x79, 0x8D, 0xFE, 0x3F, 0xF8, 0xF3, 0xE3, 0xCF, 0x8F, + 0x3C, 0x38, 0x70, 0xE1, 0xC0, 0xF8, 0xFB, 0xE3, 0xE3, 0x86, 0x0F, 0x38, + 0x1F, 0xC0, 0x3E, 0x00, 0x70, 0x03, 0xE0, 0x0F, 0x80, 0x77, 0x03, 0x8E, + 0x1E, 0x1C, 0xFC, 0xFF, 0xF3, 0xF0, 0xF9, 0xFF, 0x9F, 0x30, 0xC3, 0x9C, + 0x19, 0x81, 0xF8, 0x0F, 0x00, 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x3F, 0xC3, 0xFC, 0xFF, 0xBF, 0xEC, 0x3B, 0x0C, 0xC6, 0x33, 0x80, 0xC0, + 0x60, 0x38, 0xCC, 0x36, 0x0F, 0x03, 0xFF, 0xFF, 0xF0, 0xFF, 0xF1, 0x8C, + 0x63, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0xC7, 0xFE, 0x40, 0x30, 0x0E, + 0x01, 0x80, 0x70, 0x0C, 0x03, 0x80, 0x60, 0x1C, 0x03, 0x00, 0xE0, 0x18, + 0x07, 0x00, 0xC0, 0x38, 0x0E, 0x01, 0xC0, 0x70, 0x0C, 0x01, 0xFF, 0xC6, + 0x31, 0x8C, 0x63, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x1F, 0xFE, 0x04, 0x03, + 0x01, 0xE0, 0xFC, 0x7B, 0x9C, 0x7E, 0x1F, 0x03, 0xFF, 0xFF, 0xFF, 0xF0, + 0xCE, 0x73, 0x3F, 0x07, 0xF8, 0x00, 0xC0, 0x0C, 0x1F, 0xC7, 0xFC, 0x60, + 0xCC, 0x0C, 0xC1, 0xCF, 0xFF, 0x3F, 0xF0, 0xF0, 0x07, 0x80, 0x0C, 0x00, + 0x60, 0x03, 0x7C, 0x1F, 0xF8, 0xF1, 0xC7, 0x07, 0x30, 0x19, 0x80, 0xCC, + 0x06, 0x60, 0x73, 0xC7, 0x7F, 0xFB, 0xDF, 0x00, 0x1F, 0xB3, 0xFF, 0x70, + 0xFE, 0x07, 0xC0, 0x3C, 0x00, 0xC0, 0x0C, 0x00, 0x70, 0x77, 0xFF, 0x1F, + 0xC0, 0x01, 0xE0, 0x0F, 0x00, 0x18, 0x00, 0xC1, 0xF6, 0x3F, 0xF1, 0xC7, + 0x9C, 0x1C, 0xC0, 0x66, 0x03, 0x30, 0x19, 0x81, 0xC7, 0x1E, 0x3F, 0xFC, + 0x7D, 0xE0, 0x1F, 0x83, 0xFC, 0x70, 0xEE, 0x07, 0xFF, 0xFF, 0xFF, 0xE0, + 0x0E, 0x00, 0x70, 0x73, 0xFF, 0x1F, 0xC0, 0x07, 0xC3, 0xFC, 0x60, 0x0C, + 0x0F, 0xFD, 0xFF, 0x86, 0x00, 0xC0, 0x18, 0x03, 0x00, 0x60, 0x0C, 0x01, + 0x81, 0xFF, 0xBF, 0xF0, 0x1F, 0x79, 0xFF, 0xDC, 0x79, 0x81, 0xCC, 0x06, + 0x60, 0x33, 0x01, 0x9C, 0x1C, 0x71, 0xE1, 0xFF, 0x07, 0xD8, 0x00, 0xC0, + 0x06, 0x00, 0x70, 0x7F, 0x03, 0xF0, 0xF0, 0x03, 0xC0, 0x03, 0x00, 0x0C, + 0x00, 0x37, 0xC0, 0xFF, 0x83, 0xC7, 0x0C, 0x0C, 0x30, 0x30, 0xC0, 0xC3, + 0x03, 0x0C, 0x0C, 0x30, 0x33, 0xF3, 0xFF, 0xCF, 0xC0, 0x06, 0x00, 0xC0, + 0x00, 0x3F, 0x07, 0xE0, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, 0x18, + 0x03, 0x0F, 0xFF, 0xFF, 0xC0, 0x06, 0x06, 0x00, 0xFF, 0xFF, 0x03, 0x03, + 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x07, 0xFE, 0xFC, + 0xF0, 0x07, 0x80, 0x0C, 0x00, 0x60, 0x03, 0x3F, 0x19, 0xF8, 0xDE, 0x07, + 0xE0, 0x3E, 0x01, 0xF0, 0x0F, 0xC0, 0x6F, 0x03, 0x1C, 0x78, 0xFF, 0xC7, + 0xE0, 0x7E, 0x0F, 0xC0, 0x18, 0x03, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x30, + 0x06, 0x00, 0xC0, 0x18, 0x03, 0x00, 0x61, 0xFF, 0xFF, 0xF8, 0xFE, 0xF1, + 0xFF, 0xF1, 0xCE, 0x63, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0xC6, 0x31, + 0x8C, 0x63, 0x19, 0xF7, 0xBF, 0xEF, 0x78, 0x77, 0xC1, 0xFF, 0x83, 0xC7, + 0x0C, 0x0C, 0x30, 0x30, 0xC0, 0xC3, 0x03, 0x0C, 0x0C, 0x30, 0x33, 0xF1, + 0xFF, 0xC7, 0xC0, 0x1F, 0x83, 0xFC, 0x70, 0xEE, 0x07, 0xC0, 0x3C, 0x03, + 0xC0, 0x3E, 0x07, 0x70, 0xE3, 0xFC, 0x1F, 0x80, 0xF7, 0xE3, 0xFF, 0xC3, + 0xC3, 0x8E, 0x07, 0x30, 0x0C, 0xC0, 0x33, 0x00, 0xCE, 0x07, 0x3C, 0x38, + 0xFF, 0xC3, 0x7E, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x0F, 0xE0, 0x3F, 0x80, + 0x1F, 0xBC, 0xFF, 0xF7, 0x0F, 0x38, 0x1C, 0xC0, 0x33, 0x00, 0xCC, 0x03, + 0x38, 0x1C, 0x70, 0xF0, 0xFF, 0xC1, 0xFB, 0x00, 0x0C, 0x00, 0x30, 0x00, + 0xC0, 0x1F, 0xC0, 0x7F, 0x79, 0xE7, 0xFF, 0x1F, 0x31, 0xC0, 0x18, 0x01, + 0x80, 0x18, 0x01, 0x80, 0x18, 0x0F, 0xFC, 0xFF, 0xC0, 0x3F, 0x9F, 0xFE, + 0x1F, 0x82, 0xFE, 0x1F, 0xE0, 0xFF, 0x03, 0xE0, 0xFF, 0xFF, 0xF0, 0x30, + 0x06, 0x00, 0xC0, 0x7F, 0xEF, 0xFC, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, + 0x00, 0xC0, 0x18, 0x71, 0xFE, 0x1F, 0x00, 0xF1, 0xF7, 0x8F, 0x8C, 0x0C, + 0x60, 0x63, 0x03, 0x18, 0x18, 0xC0, 0xC6, 0x06, 0x38, 0xF0, 0xFF, 0xC3, + 0xEE, 0xFC, 0xFF, 0xF3, 0xF3, 0x87, 0x0E, 0x1C, 0x1C, 0x60, 0x73, 0x80, + 0xEC, 0x03, 0xF0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x00, 0xF8, 0x7F, 0xE1, + 0xF7, 0x39, 0x8C, 0xE6, 0x37, 0xB0, 0xFF, 0xC3, 0xFF, 0x07, 0xBC, 0x1C, + 0xF0, 0x73, 0x81, 0x86, 0x00, 0x7C, 0xF9, 0xF3, 0xE3, 0xCF, 0x07, 0xF8, + 0x0F, 0xC0, 0x1E, 0x00, 0xFC, 0x07, 0x38, 0x38, 0x73, 0xF3, 0xFF, 0xCF, + 0xC0, 0xF9, 0xFF, 0x9F, 0x70, 0xE3, 0x0C, 0x39, 0xC1, 0x98, 0x19, 0x81, + 0xF8, 0x0F, 0x00, 0xF0, 0x06, 0x00, 0x60, 0x0E, 0x00, 0xC0, 0xFF, 0x0F, + 0xF0, 0x7F, 0xCF, 0xF9, 0x8E, 0x33, 0x80, 0x70, 0x1C, 0x07, 0x01, 0xC6, + 0x70, 0xFF, 0xFF, 0xFF, 0x80, 0x0E, 0x3C, 0x60, 0xC1, 0x83, 0x06, 0x0C, + 0x39, 0xE3, 0xC0, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x3C, 0x38, 0xFF, 0xFF, + 0xFF, 0xFF, 0xF0, 0xE1, 0xC0, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x30, 0x3C, + 0x79, 0x83, 0x06, 0x0C, 0x18, 0x31, 0xE3, 0x80, 0x3C, 0x37, 0xE7, 0x67, + 0xE6, 0x1C }; + +const GFXglyph FreeMonoBold12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 14, 0, 1 }, // 0x20 ' ' + { 0, 4, 15, 14, 5, -14 }, // 0x21 '!' + { 8, 8, 7, 14, 3, -13 }, // 0x22 '"' + { 15, 11, 18, 14, 2, -15 }, // 0x23 '#' + { 40, 10, 20, 14, 2, -16 }, // 0x24 '$' + { 65, 10, 15, 14, 2, -14 }, // 0x25 '%' + { 84, 10, 13, 14, 2, -12 }, // 0x26 '&' + { 101, 3, 7, 14, 5, -13 }, // 0x27 ''' + { 104, 5, 19, 14, 6, -14 }, // 0x28 '(' + { 116, 5, 19, 14, 3, -14 }, // 0x29 ')' + { 128, 10, 10, 14, 2, -14 }, // 0x2A '*' + { 141, 12, 13, 14, 1, -12 }, // 0x2B '+' + { 161, 5, 7, 14, 4, -2 }, // 0x2C ',' + { 166, 12, 2, 14, 1, -7 }, // 0x2D '-' + { 169, 3, 3, 14, 5, -2 }, // 0x2E '.' + { 171, 10, 20, 14, 2, -16 }, // 0x2F '/' + { 196, 10, 15, 14, 2, -14 }, // 0x30 '0' + { 215, 10, 15, 14, 2, -14 }, // 0x31 '1' + { 234, 10, 15, 14, 2, -14 }, // 0x32 '2' + { 253, 11, 15, 14, 1, -14 }, // 0x33 '3' + { 274, 9, 14, 14, 2, -13 }, // 0x34 '4' + { 290, 10, 15, 14, 2, -14 }, // 0x35 '5' + { 309, 10, 15, 14, 2, -14 }, // 0x36 '6' + { 328, 10, 15, 14, 2, -14 }, // 0x37 '7' + { 347, 10, 15, 14, 2, -14 }, // 0x38 '8' + { 366, 10, 15, 14, 3, -14 }, // 0x39 '9' + { 385, 3, 11, 14, 5, -10 }, // 0x3A ':' + { 390, 4, 15, 14, 4, -10 }, // 0x3B ';' + { 398, 12, 11, 14, 1, -11 }, // 0x3C '<' + { 415, 12, 7, 14, 1, -9 }, // 0x3D '=' + { 426, 12, 11, 14, 1, -11 }, // 0x3E '>' + { 443, 9, 14, 14, 3, -13 }, // 0x3F '?' + { 459, 11, 19, 14, 2, -14 }, // 0x40 '@' + { 486, 15, 14, 14, -1, -13 }, // 0x41 'A' + { 513, 13, 14, 14, 0, -13 }, // 0x42 'B' + { 536, 12, 14, 14, 1, -13 }, // 0x43 'C' + { 557, 12, 14, 14, 1, -13 }, // 0x44 'D' + { 578, 13, 14, 14, 0, -13 }, // 0x45 'E' + { 601, 13, 14, 14, 0, -13 }, // 0x46 'F' + { 624, 13, 14, 14, 1, -13 }, // 0x47 'G' + { 647, 14, 14, 14, 0, -13 }, // 0x48 'H' + { 672, 10, 14, 14, 2, -13 }, // 0x49 'I' + { 690, 13, 14, 14, 1, -13 }, // 0x4A 'J' + { 713, 14, 14, 14, 0, -13 }, // 0x4B 'K' + { 738, 12, 14, 14, 1, -13 }, // 0x4C 'L' + { 759, 14, 14, 14, 0, -13 }, // 0x4D 'M' + { 784, 13, 14, 14, 0, -13 }, // 0x4E 'N' + { 807, 12, 14, 14, 1, -13 }, // 0x4F 'O' + { 828, 12, 14, 14, 0, -13 }, // 0x50 'P' + { 849, 12, 17, 14, 1, -13 }, // 0x51 'Q' + { 875, 14, 14, 14, 0, -13 }, // 0x52 'R' + { 900, 10, 14, 14, 2, -13 }, // 0x53 'S' + { 918, 12, 14, 14, 1, -13 }, // 0x54 'T' + { 939, 12, 14, 14, 1, -13 }, // 0x55 'U' + { 960, 16, 14, 14, -1, -13 }, // 0x56 'V' + { 988, 14, 14, 14, 0, -13 }, // 0x57 'W' + { 1013, 14, 14, 14, 0, -13 }, // 0x58 'X' + { 1038, 12, 14, 14, 1, -13 }, // 0x59 'Y' + { 1059, 10, 14, 14, 2, -13 }, // 0x5A 'Z' + { 1077, 5, 19, 14, 6, -14 }, // 0x5B '[' + { 1089, 10, 20, 14, 2, -16 }, // 0x5C '\' + { 1114, 5, 19, 14, 3, -14 }, // 0x5D ']' + { 1126, 10, 8, 14, 2, -15 }, // 0x5E '^' + { 1136, 14, 2, 14, 0, 4 }, // 0x5F '_' + { 1140, 4, 4, 14, 4, -15 }, // 0x60 '`' + { 1142, 12, 11, 14, 1, -10 }, // 0x61 'a' + { 1159, 13, 15, 14, 0, -14 }, // 0x62 'b' + { 1184, 12, 11, 14, 1, -10 }, // 0x63 'c' + { 1201, 13, 15, 14, 1, -14 }, // 0x64 'd' + { 1226, 12, 11, 14, 1, -10 }, // 0x65 'e' + { 1243, 11, 15, 14, 2, -14 }, // 0x66 'f' + { 1264, 13, 16, 14, 1, -10 }, // 0x67 'g' + { 1290, 14, 15, 14, 0, -14 }, // 0x68 'h' + { 1317, 11, 14, 14, 1, -13 }, // 0x69 'i' + { 1337, 8, 19, 15, 3, -13 }, // 0x6A 'j' + { 1356, 13, 15, 14, 1, -14 }, // 0x6B 'k' + { 1381, 11, 15, 14, 1, -14 }, // 0x6C 'l' + { 1402, 15, 11, 14, 0, -10 }, // 0x6D 'm' + { 1423, 14, 11, 14, 0, -10 }, // 0x6E 'n' + { 1443, 12, 11, 14, 1, -10 }, // 0x6F 'o' + { 1460, 14, 16, 14, 0, -10 }, // 0x70 'p' + { 1488, 14, 16, 14, 0, -10 }, // 0x71 'q' + { 1516, 12, 11, 14, 1, -10 }, // 0x72 'r' + { 1533, 10, 11, 14, 2, -10 }, // 0x73 's' + { 1547, 11, 14, 14, 1, -13 }, // 0x74 't' + { 1567, 13, 11, 14, 0, -10 }, // 0x75 'u' + { 1585, 14, 11, 14, 0, -10 }, // 0x76 'v' + { 1605, 14, 11, 14, 0, -10 }, // 0x77 'w' + { 1625, 14, 11, 14, 0, -10 }, // 0x78 'x' + { 1645, 12, 16, 14, 1, -10 }, // 0x79 'y' + { 1669, 11, 11, 14, 1, -10 }, // 0x7A 'z' + { 1685, 7, 19, 14, 3, -14 }, // 0x7B '{' + { 1702, 2, 19, 14, 6, -14 }, // 0x7C '|' + { 1707, 7, 19, 14, 4, -14 }, // 0x7D '}' + { 1724, 12, 4, 14, 1, -7 } }; // 0x7E '~' + +const GFXfont FreeMonoBold12pt7b PROGMEM = { + (uint8_t *)FreeMonoBold12pt7bBitmaps, + (GFXglyph *)FreeMonoBold12pt7bGlyphs, + 0x20, 0x7E, 24 }; + +// Approx. 2402 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBold18pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBold18pt7b.h new file mode 100644 index 0000000..36e0be0 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBold18pt7b.h @@ -0,0 +1,423 @@ +const uint8_t FreeMonoBold18pt7bBitmaps[] PROGMEM = { + 0x77, 0xFF, 0xFF, 0xFF, 0xFF, 0xFB, 0x9C, 0xE7, 0x39, 0xC4, 0x03, 0xBF, + 0xFF, 0xB8, 0xF1, 0xFE, 0x3F, 0xC7, 0xF8, 0xFF, 0x1E, 0xC1, 0x98, 0x33, + 0x06, 0x60, 0xCC, 0x18, 0x0E, 0x1C, 0x0F, 0x3C, 0x1F, 0x3C, 0x1E, 0x3C, + 0x1E, 0x3C, 0x1E, 0x78, 0x1E, 0x78, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFE, 0x1E, 0x78, 0x1E, 0x78, 0x1E, 0x78, 0x7F, 0xFE, 0x7F, 0xFE, + 0x7F, 0xFE, 0x7F, 0xFE, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0xF0, + 0x3C, 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, 0x03, 0x00, 0x1E, 0x00, 0x78, 0x01, + 0xE0, 0x1F, 0xF1, 0xFF, 0xE7, 0xFF, 0xBE, 0x1E, 0xF0, 0x3B, 0xC0, 0xCF, + 0xE0, 0x3F, 0xF8, 0x7F, 0xF0, 0x7F, 0xE0, 0x1F, 0xF0, 0x0F, 0xE0, 0x3F, + 0x80, 0xFF, 0x87, 0xFF, 0xFE, 0xFF, 0xF3, 0x7F, 0x80, 0x78, 0x01, 0xE0, + 0x07, 0x80, 0x1E, 0x00, 0x78, 0x00, 0xC0, 0x1E, 0x00, 0xFF, 0x03, 0x86, + 0x06, 0x06, 0x0C, 0x0C, 0x18, 0x18, 0x38, 0x70, 0x3F, 0xC2, 0x1E, 0x3E, + 0x03, 0xF8, 0x3F, 0x83, 0xF8, 0x0F, 0x8F, 0x18, 0x7F, 0x01, 0xC7, 0x03, + 0x06, 0x06, 0x0C, 0x0C, 0x18, 0x1C, 0x70, 0x1F, 0xC0, 0x0F, 0x00, 0x03, + 0xD0, 0x1F, 0xF0, 0x7F, 0xE1, 0xFF, 0xC3, 0xE6, 0x07, 0x80, 0x0F, 0x00, + 0x0F, 0x00, 0x1F, 0x00, 0x3E, 0x00, 0xFE, 0x03, 0xFE, 0xFF, 0xBD, 0xFE, + 0x3F, 0xFC, 0x3F, 0x7C, 0x7C, 0xFF, 0xFE, 0xFF, 0xFC, 0xFF, 0xF8, 0x7E, + 0xF0, 0xFF, 0xFF, 0xF6, 0x66, 0x66, 0x07, 0x0F, 0x1F, 0x1E, 0x3E, 0x3C, + 0x78, 0x78, 0x78, 0x70, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0x78, 0x78, 0x78, 0x3C, 0x3C, 0x1E, 0x1F, 0x0F, 0x07, 0xE0, 0xF0, 0xF8, + 0x78, 0x7C, 0x3C, 0x3E, 0x1E, 0x1E, 0x1E, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0E, 0x1E, 0x1E, 0x1E, 0x3C, 0x3C, 0x78, 0xF8, 0xF0, 0xE0, + 0x01, 0x80, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0xFF, 0xFF, + 0xFF, 0xFF, 0x7F, 0xFE, 0x1F, 0xF8, 0x07, 0xE0, 0x0F, 0xF0, 0x1F, 0xF8, + 0x1E, 0x78, 0x1C, 0x38, 0x18, 0x18, 0x01, 0xC0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x01, 0x80, 0x3E, 0x78, 0xF3, 0xC7, + 0x8E, 0x1C, 0x70, 0xE1, 0x80, 0x7F, 0xFF, 0xDF, 0xFF, 0xF9, 0xFF, 0xFF, + 0x3F, 0xFF, 0xE0, 0x77, 0xFF, 0xF7, 0x00, 0x00, 0x0E, 0x00, 0x3C, 0x00, + 0x78, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x1E, 0x00, 0x38, 0x00, 0xF0, + 0x01, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x3C, 0x00, 0x78, 0x01, 0xE0, 0x03, + 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x78, 0x00, 0xF0, 0x03, 0xC0, 0x07, 0x80, + 0x1E, 0x00, 0x3C, 0x00, 0x70, 0x01, 0xE0, 0x03, 0x80, 0x03, 0x00, 0x00, + 0x07, 0xE0, 0x1F, 0xF8, 0x3F, 0xFC, 0x3F, 0xFC, 0x7C, 0x3E, 0x78, 0x1E, + 0xF8, 0x1F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, + 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF8, 0x1F, 0x78, 0x1E, + 0x7C, 0x3E, 0x3F, 0xFC, 0x3F, 0xFC, 0x1F, 0xF8, 0x07, 0xE0, 0x07, 0xC0, + 0x1F, 0x80, 0xFF, 0x03, 0xFE, 0x0F, 0xBC, 0x0C, 0x78, 0x00, 0xF0, 0x01, + 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, + 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x81, 0xFF, 0xFB, 0xFF, 0xF7, + 0xFF, 0xE7, 0xFF, 0x80, 0x0F, 0xC0, 0x7F, 0xE1, 0xFF, 0xE3, 0xFF, 0xEF, + 0x87, 0xDE, 0x07, 0xF8, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x7C, 0x01, + 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, + 0x78, 0x03, 0xE0, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, + 0x0F, 0xC0, 0x7F, 0xF0, 0xFF, 0xF8, 0xFF, 0xFC, 0x70, 0x3E, 0x00, 0x1E, + 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x3C, 0x03, 0xFC, 0x03, 0xF0, 0x03, 0xF0, + 0x03, 0xFC, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0F, + 0xE0, 0x3F, 0xFF, 0xFE, 0xFF, 0xFC, 0x7F, 0xF8, 0x1F, 0xE0, 0x00, 0xF8, + 0x03, 0xF0, 0x07, 0xE0, 0x1F, 0xC0, 0x77, 0x80, 0xEF, 0x03, 0x9E, 0x0F, + 0x3C, 0x1C, 0x78, 0x70, 0xF1, 0xE1, 0xE3, 0x83, 0xCF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x78, 0x07, 0xFC, 0x0F, 0xF8, 0x1F, 0xF0, + 0x1F, 0xC0, 0x3F, 0xFC, 0x1F, 0xFE, 0x0F, 0xFF, 0x07, 0xFF, 0x83, 0xC0, + 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x7B, 0xE0, 0x3F, 0xFC, 0x1F, 0xFF, 0x0F, + 0xFF, 0xC3, 0x83, 0xE0, 0x00, 0xF8, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x0F, + 0x00, 0x0F, 0xB8, 0x0F, 0xBF, 0xFF, 0xCF, 0xFF, 0xC3, 0xFF, 0xC0, 0x7F, + 0x80, 0x00, 0xFC, 0x07, 0xFC, 0x3F, 0xF8, 0xFF, 0xF1, 0xF8, 0x07, 0xC0, + 0x1F, 0x00, 0x3C, 0x00, 0xF0, 0x01, 0xE7, 0xC3, 0xDF, 0xC7, 0x7F, 0xCF, + 0xFF, 0xDF, 0x8F, 0xFC, 0x07, 0xF0, 0x0F, 0xF0, 0x1F, 0xE0, 0x3D, 0xE0, + 0xFB, 0xFF, 0xE3, 0xFF, 0xC3, 0xFF, 0x01, 0xF8, 0x00, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x01, 0xE0, 0x03, 0x80, 0x0F, 0x00, 0x1E, + 0x00, 0x38, 0x00, 0xF0, 0x01, 0xE0, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, + 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x38, + 0x00, 0x70, 0x00, 0x07, 0xC0, 0x3F, 0xE0, 0xFF, 0xE3, 0xFF, 0xEF, 0x83, + 0xFE, 0x03, 0xFC, 0x07, 0xF8, 0x0F, 0xF0, 0x1E, 0xF0, 0x78, 0xFF, 0xE0, + 0xFF, 0x81, 0xFF, 0x0F, 0xFF, 0x9E, 0x0F, 0x78, 0x0F, 0xF0, 0x1F, 0xE0, + 0x3F, 0xE0, 0xFB, 0xFF, 0xE7, 0xFF, 0xC7, 0xFF, 0x03, 0xF8, 0x00, 0x0F, + 0xC0, 0x3F, 0xE0, 0xFF, 0xE3, 0xFF, 0xEF, 0xC3, 0xDF, 0x03, 0xBC, 0x07, + 0xF8, 0x0F, 0xF0, 0x1F, 0xF0, 0x3D, 0xF1, 0xFB, 0xFF, 0xF3, 0xFE, 0xE3, + 0xFB, 0xC3, 0xE7, 0x80, 0x1E, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xE7, 0xFF, + 0x8F, 0xFE, 0x1F, 0xF0, 0x1F, 0x80, 0x00, 0x77, 0xFF, 0xF7, 0x00, 0x00, + 0x00, 0x00, 0xEF, 0xFF, 0xEE, 0x1C, 0x7C, 0xF9, 0xF1, 0xC0, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xF3, 0xC7, 0x8E, 0x3C, 0x70, 0xE1, 0x87, 0x0C, 0x00, + 0x00, 0x00, 0x00, 0x80, 0x00, 0xF0, 0x00, 0xFC, 0x00, 0xFE, 0x00, 0xFE, + 0x00, 0xFE, 0x00, 0xFE, 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x07, 0xF0, 0x00, + 0x7F, 0x00, 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xF0, 0x00, 0x7C, 0x00, + 0x07, 0x7F, 0xFF, 0xDF, 0xFF, 0xF9, 0xFF, 0xFF, 0x3F, 0xFF, 0xE0, 0x00, + 0x00, 0x00, 0x00, 0x1F, 0xFF, 0xF7, 0xFF, 0xFE, 0x7F, 0xFF, 0xCF, 0xFF, + 0xF8, 0x00, 0x00, 0x3C, 0x00, 0x0F, 0xC0, 0x01, 0xFC, 0x00, 0x1F, 0xC0, + 0x01, 0xFC, 0x00, 0x1F, 0xC0, 0x01, 0xFC, 0x00, 0x3F, 0x80, 0x3F, 0x80, + 0x3F, 0x80, 0x3F, 0x80, 0x3F, 0x80, 0x3F, 0x80, 0x0F, 0x80, 0x03, 0x80, + 0x00, 0x1F, 0xC0, 0xFF, 0xE3, 0xFF, 0xF7, 0xFF, 0xEF, 0x07, 0xFE, 0x03, + 0xDC, 0x07, 0x80, 0x0F, 0x00, 0x7C, 0x03, 0xF8, 0x1F, 0xC0, 0x1E, 0x00, + 0x30, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x1F, 0x00, 0x3E, + 0x00, 0x7C, 0x00, 0x70, 0x00, 0x07, 0xE0, 0x1F, 0xE0, 0x7F, 0xE1, 0xE1, + 0xC7, 0x83, 0xCE, 0x03, 0xBC, 0x07, 0x70, 0x0E, 0xE0, 0x7D, 0xC3, 0xFB, + 0x8F, 0xF7, 0x3C, 0xEE, 0x71, 0xDC, 0xE3, 0xB9, 0xC7, 0x73, 0xCE, 0xE3, + 0xFF, 0xC3, 0xFF, 0x83, 0xFF, 0x00, 0x07, 0x00, 0x0E, 0x00, 0x1E, 0x02, + 0x1E, 0x1E, 0x3F, 0xFC, 0x1F, 0xF0, 0x1F, 0x80, 0x0F, 0xF8, 0x00, 0x7F, + 0xF0, 0x01, 0xFF, 0xC0, 0x03, 0xFF, 0x00, 0x01, 0xFE, 0x00, 0x07, 0xF8, + 0x00, 0x1C, 0xF0, 0x00, 0xF3, 0xC0, 0x03, 0xCF, 0x00, 0x1E, 0x1E, 0x00, + 0x78, 0x78, 0x03, 0xC0, 0xF0, 0x0F, 0xFF, 0xC0, 0x3F, 0xFF, 0x01, 0xFF, + 0xFE, 0x07, 0xFF, 0xF8, 0x3C, 0x00, 0xF3, 0xFC, 0x1F, 0xEF, 0xF8, 0x7F, + 0xFF, 0xE1, 0xFF, 0x7F, 0x03, 0xF8, 0x7F, 0xFC, 0x0F, 0xFF, 0xF0, 0xFF, + 0xFF, 0x8F, 0xFF, 0xF8, 0x3C, 0x07, 0xC3, 0xC0, 0x3C, 0x3C, 0x03, 0xC3, + 0xC0, 0x7C, 0x3F, 0xFF, 0x83, 0xFF, 0xF0, 0x3F, 0xFF, 0x83, 0xFF, 0xFE, + 0x3C, 0x03, 0xE3, 0xC0, 0x1F, 0x3C, 0x00, 0xF3, 0xC0, 0x0F, 0x3C, 0x01, + 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xEF, 0xFF, 0xFC, 0x7F, 0xFF, 0x00, 0x01, + 0xF8, 0xC1, 0xFF, 0xFC, 0x7F, 0xFF, 0x9F, 0xFF, 0xF7, 0xE0, 0x7E, 0xF8, + 0x07, 0xFE, 0x00, 0x7F, 0x80, 0x0E, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, + 0x00, 0x78, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xE0, + 0x07, 0x7F, 0x03, 0xE7, 0xFF, 0xFC, 0x7F, 0xFF, 0x03, 0xFF, 0xC0, 0x1F, + 0xE0, 0xFF, 0xF0, 0x3F, 0xFF, 0x0F, 0xFF, 0xE3, 0xFF, 0xFC, 0x78, 0x1F, + 0x9E, 0x03, 0xE7, 0x80, 0x79, 0xE0, 0x0F, 0x78, 0x03, 0xDE, 0x00, 0xF7, + 0x80, 0x3D, 0xE0, 0x0F, 0x78, 0x03, 0xDE, 0x00, 0xF7, 0x80, 0x7D, 0xE0, + 0x1E, 0x78, 0x1F, 0xBF, 0xFF, 0xCF, 0xFF, 0xF3, 0xFF, 0xF0, 0x7F, 0xF0, + 0x00, 0x7F, 0xFF, 0xDF, 0xFF, 0xFB, 0xFF, 0xFF, 0x7F, 0xFF, 0xE3, 0xC0, + 0x3C, 0x78, 0x07, 0x8F, 0x1C, 0xF1, 0xE3, 0xCC, 0x3F, 0xF8, 0x07, 0xFF, + 0x00, 0xFF, 0xE0, 0x1F, 0xFC, 0x03, 0xC7, 0x80, 0x78, 0xF1, 0x8F, 0x0C, + 0x79, 0xE0, 0x0F, 0x3C, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF7, 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF3, 0xC0, 0x1E, 0x78, 0x63, 0xCF, 0x1E, 0x79, 0xE3, 0xC6, 0x3F, 0xF8, + 0x07, 0xFF, 0x00, 0xFF, 0xE0, 0x1F, 0xFC, 0x03, 0xC7, 0x80, 0x78, 0xE0, + 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x1F, 0xFC, 0x03, 0xFF, 0x80, + 0x7F, 0xF0, 0x07, 0xFC, 0x00, 0x01, 0xFC, 0xE0, 0x7F, 0xFE, 0x1F, 0xFF, + 0xE3, 0xFF, 0xFE, 0x7F, 0x03, 0xE7, 0xC0, 0x1E, 0xF8, 0x00, 0xEF, 0x00, + 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x03, 0xFE, 0xF0, + 0x3F, 0xFF, 0x03, 0xFF, 0xF8, 0x3F, 0xF7, 0x80, 0x1E, 0x7E, 0x01, 0xE3, + 0xFF, 0xFE, 0x1F, 0xFF, 0xE0, 0xFF, 0xF8, 0x01, 0xFE, 0x00, 0x7F, 0x0F, + 0xE3, 0xFC, 0x7F, 0x9F, 0xE3, 0xFC, 0x7F, 0x1F, 0xC1, 0xE0, 0x3C, 0x0F, + 0x01, 0xE0, 0x78, 0x0F, 0x03, 0xC0, 0x78, 0x1E, 0x03, 0xC0, 0xFF, 0xFE, + 0x07, 0xFF, 0xF0, 0x3F, 0xFF, 0x81, 0xFF, 0xFC, 0x0F, 0x01, 0xE0, 0x78, + 0x0F, 0x03, 0xC0, 0x78, 0x1E, 0x03, 0xC3, 0xFC, 0x7F, 0xBF, 0xE3, 0xFF, + 0xFF, 0x1F, 0xF7, 0xF0, 0x7F, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, + 0x78, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, 0xE0, 0x07, 0x83, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0xF8, 0x01, 0xFF, 0xE0, 0x3F, 0xFC, + 0x07, 0xFF, 0x80, 0xFF, 0xF0, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, + 0x00, 0x78, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x38, 0x07, 0x8F, + 0x00, 0xF1, 0xE0, 0x1E, 0x3C, 0x03, 0xC7, 0x80, 0xF8, 0xF8, 0x3F, 0x1F, + 0xFF, 0xC3, 0xFF, 0xF0, 0x1F, 0xFC, 0x00, 0x7E, 0x00, 0xFF, 0x0F, 0xCF, + 0xF9, 0xFE, 0xFF, 0x9F, 0xEF, 0xF8, 0xFC, 0x3C, 0x1F, 0x03, 0xC3, 0xE0, + 0x3C, 0x7C, 0x03, 0xCF, 0x80, 0x3D, 0xF0, 0x03, 0xFE, 0x00, 0x3F, 0xF8, + 0x03, 0xFF, 0x80, 0x3E, 0x7C, 0x03, 0xC3, 0xE0, 0x3C, 0x1E, 0x03, 0xC0, + 0xF0, 0x3C, 0x0F, 0x0F, 0xF8, 0x7E, 0xFF, 0x87, 0xFF, 0xF8, 0x7F, 0x7F, + 0x03, 0xE0, 0xFF, 0xC0, 0x3F, 0xF0, 0x0F, 0xFC, 0x03, 0xFF, 0x00, 0x1E, + 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, + 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x01, 0x87, 0x80, 0xF1, 0xE0, 0x3C, + 0x78, 0x0F, 0x1E, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, + 0xFF, 0xC0, 0x3E, 0x00, 0xF8, 0xFC, 0x01, 0xF9, 0xFC, 0x07, 0xF3, 0xF8, + 0x0F, 0xE3, 0xF8, 0x3F, 0x87, 0xF0, 0x7F, 0x0F, 0xF1, 0xFE, 0x1F, 0xE3, + 0xFC, 0x3D, 0xE7, 0x78, 0x7B, 0xDE, 0xF0, 0xF7, 0xBD, 0xE1, 0xE7, 0xF3, + 0xC3, 0xCF, 0xE7, 0x87, 0x8F, 0x8F, 0x0F, 0x1F, 0x1E, 0x1E, 0x1E, 0x3C, + 0x3C, 0x00, 0x79, 0xFF, 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xFC, 0x1F, 0xF7, + 0xF0, 0x1F, 0xC0, 0xFC, 0x1F, 0xEF, 0xE1, 0xFF, 0xFE, 0x1F, 0xFF, 0xF1, + 0xFF, 0x3F, 0x83, 0xC3, 0xF8, 0x3C, 0x3F, 0xC3, 0xC3, 0xFC, 0x3C, 0x3D, + 0xE3, 0xC3, 0xDE, 0x3C, 0x3C, 0xF3, 0xC3, 0xC7, 0xBC, 0x3C, 0x7B, 0xC3, + 0xC3, 0xFC, 0x3C, 0x3F, 0xC3, 0xC1, 0xFC, 0x3C, 0x1F, 0xCF, 0xF8, 0xFC, + 0xFF, 0x87, 0xCF, 0xF8, 0x7C, 0x7F, 0x03, 0xC0, 0x01, 0xF8, 0x00, 0x7F, + 0xE0, 0x0F, 0xFF, 0x81, 0xFF, 0xFC, 0x3F, 0x0F, 0xC7, 0xC0, 0x3E, 0x78, + 0x01, 0xEF, 0x80, 0x1F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, + 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x80, 0x1F, 0x78, 0x01, 0xE7, 0xC0, 0x3E, + 0x3F, 0x0F, 0xC1, 0xFF, 0xF8, 0x1F, 0xFF, 0x00, 0x7F, 0xE0, 0x01, 0xF8, + 0x00, 0x7F, 0xF8, 0x3F, 0xFF, 0x8F, 0xFF, 0xF3, 0xFF, 0xFE, 0x3C, 0x0F, + 0xCF, 0x00, 0xF3, 0xC0, 0x3C, 0xF0, 0x0F, 0x3C, 0x03, 0xCF, 0x03, 0xF3, + 0xFF, 0xF8, 0xFF, 0xFC, 0x3F, 0xFE, 0x0F, 0xFE, 0x03, 0xC0, 0x00, 0xF0, + 0x00, 0x3C, 0x00, 0x3F, 0xF8, 0x0F, 0xFE, 0x03, 0xFF, 0x80, 0x7F, 0xC0, + 0x00, 0x01, 0xF8, 0x00, 0x7F, 0xE0, 0x0F, 0xFF, 0x01, 0xFF, 0xF8, 0x3F, + 0x0F, 0xC7, 0xC0, 0x3E, 0x78, 0x01, 0xEF, 0x80, 0x1F, 0xF0, 0x00, 0xFF, + 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x80, 0x1F, + 0x78, 0x01, 0xE7, 0xC0, 0x3E, 0x3F, 0x0F, 0xC1, 0xFF, 0xF8, 0x0F, 0xFF, + 0x00, 0x7F, 0xE0, 0x03, 0xF8, 0x00, 0x3F, 0x8E, 0x07, 0xFF, 0xF0, 0xFF, + 0xFF, 0x0F, 0xFF, 0xE0, 0x60, 0x78, 0x7F, 0xF8, 0x07, 0xFF, 0xF0, 0x3F, + 0xFF, 0xE0, 0xFF, 0xFF, 0x01, 0xE0, 0x7C, 0x0F, 0x01, 0xE0, 0x78, 0x0F, + 0x03, 0xC0, 0x78, 0x1E, 0x0F, 0xC0, 0xFF, 0xFC, 0x07, 0xFF, 0xC0, 0x3F, + 0xF8, 0x01, 0xFF, 0xE0, 0x0F, 0x0F, 0x80, 0x78, 0x3C, 0x03, 0xC0, 0xF0, + 0x1E, 0x07, 0xC3, 0xFE, 0x1F, 0xBF, 0xF0, 0x7F, 0xFF, 0x83, 0xF7, 0xF8, + 0x0F, 0x00, 0x07, 0xE7, 0x07, 0xFF, 0x8F, 0xFF, 0xC7, 0xFF, 0xE7, 0xC1, + 0xF3, 0xC0, 0x79, 0xE0, 0x3C, 0xF8, 0x00, 0x7F, 0x80, 0x1F, 0xFC, 0x07, + 0xFF, 0x81, 0xFF, 0xE0, 0x0F, 0xFB, 0x00, 0x7F, 0xC0, 0x1F, 0xE0, 0x0F, + 0xFC, 0x1F, 0xFF, 0xFF, 0xBF, 0xFF, 0x8D, 0xFF, 0x80, 0x3F, 0x00, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x0F, 0x1F, 0xE1, + 0xE3, 0xFC, 0x3C, 0x7F, 0x87, 0x8F, 0x60, 0xF0, 0xC0, 0x1E, 0x00, 0x03, + 0xC0, 0x00, 0x78, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x07, + 0x80, 0x00, 0xF0, 0x01, 0xFF, 0xE0, 0x3F, 0xFC, 0x07, 0xFF, 0x80, 0x7F, + 0xE0, 0xFF, 0x0F, 0xF7, 0xFC, 0x7F, 0xFF, 0xE3, 0xFE, 0xFF, 0x1F, 0xF3, + 0xC0, 0x1E, 0x1E, 0x00, 0xF0, 0xF0, 0x07, 0x87, 0x80, 0x3C, 0x3C, 0x01, + 0xE1, 0xE0, 0x0F, 0x0F, 0x00, 0x78, 0x78, 0x03, 0xC3, 0xC0, 0x1E, 0x1E, + 0x00, 0xF0, 0xF0, 0x07, 0x87, 0xC0, 0x7C, 0x1F, 0x07, 0xC0, 0xFF, 0xFE, + 0x03, 0xFF, 0xE0, 0x0F, 0xFE, 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0x03, 0xFD, + 0xFF, 0x07, 0xFF, 0xFE, 0x0F, 0xFB, 0xF8, 0x1F, 0xE1, 0xC0, 0x07, 0x03, + 0xC0, 0x1E, 0x07, 0x80, 0x3C, 0x07, 0x80, 0xF0, 0x0F, 0x01, 0xE0, 0x0F, + 0x03, 0x80, 0x1E, 0x0F, 0x00, 0x3E, 0x1E, 0x00, 0x3C, 0x78, 0x00, 0x78, + 0xF0, 0x00, 0x7B, 0xC0, 0x00, 0xF7, 0x80, 0x01, 0xFF, 0x00, 0x01, 0xFC, + 0x00, 0x03, 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0xFF, 0x0F, + 0xF7, 0xFC, 0x7F, 0xFF, 0xE3, 0xFF, 0xFE, 0x0F, 0xF7, 0x80, 0x0F, 0x3C, + 0x38, 0x78, 0xE3, 0xE3, 0x87, 0x1F, 0x1C, 0x38, 0xF8, 0xE1, 0xEF, 0xE7, + 0x0F, 0x7F, 0x78, 0x7B, 0xBB, 0xC3, 0xFD, 0xFE, 0x0F, 0xEF, 0xF0, 0x7E, + 0x3F, 0x03, 0xF1, 0xF8, 0x1F, 0x8F, 0xC0, 0xFC, 0x3E, 0x07, 0xC1, 0xF0, + 0x3E, 0x0F, 0x81, 0xF0, 0x7C, 0x00, 0x7E, 0x0F, 0xDF, 0xE3, 0xFF, 0xFC, + 0x7F, 0xBF, 0x07, 0xE1, 0xE0, 0xF8, 0x3E, 0x3E, 0x03, 0xEF, 0x80, 0x3D, + 0xE0, 0x03, 0xF8, 0x00, 0x3E, 0x00, 0x03, 0xC0, 0x00, 0xF8, 0x00, 0x3F, + 0x80, 0x0F, 0x78, 0x03, 0xC7, 0x80, 0xF8, 0x78, 0x3E, 0x0F, 0x8F, 0xE3, + 0xFF, 0xFC, 0x7F, 0xFF, 0x8F, 0xF7, 0xE0, 0xFC, 0x7E, 0x07, 0xEF, 0xF0, + 0xFF, 0xFF, 0x0F, 0xF7, 0xE0, 0x7E, 0x1E, 0x07, 0x81, 0xF0, 0xF8, 0x0F, + 0x0F, 0x00, 0x79, 0xE0, 0x07, 0xFE, 0x00, 0x3F, 0xC0, 0x01, 0xF8, 0x00, + 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, + 0x00, 0xF0, 0x00, 0xFF, 0xE0, 0x0F, 0xFF, 0x00, 0xFF, 0xF0, 0x07, 0xFE, + 0x00, 0xFF, 0xFC, 0xFF, 0xFC, 0xFF, 0xFC, 0xFF, 0xFC, 0xF0, 0x3C, 0xF0, + 0x78, 0xF0, 0xF0, 0x70, 0xE0, 0x01, 0xE0, 0x03, 0xC0, 0x03, 0x80, 0x07, + 0x00, 0x0F, 0x00, 0x1E, 0x0E, 0x1C, 0x0F, 0x38, 0x0F, 0x78, 0x0F, 0x7F, + 0xFF, 0x7F, 0xFF, 0x7F, 0xFF, 0x7F, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xFE, 0xFF, 0xFF, 0xFE, 0xE0, 0x01, + 0xE0, 0x03, 0xC0, 0x03, 0xC0, 0x07, 0x80, 0x07, 0x00, 0x0F, 0x00, 0x0E, + 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x3C, 0x00, 0x78, 0x00, 0x78, 0x00, 0xF0, + 0x00, 0xF0, 0x01, 0xE0, 0x01, 0xE0, 0x03, 0xC0, 0x03, 0xC0, 0x07, 0x80, + 0x07, 0x80, 0x0F, 0x00, 0x0F, 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x3C, 0x00, + 0x38, 0x00, 0x70, 0x7F, 0xFF, 0xFF, 0xFF, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x7F, 0xFF, 0xFF, 0xFF, 0x01, 0x00, 0x07, 0x00, 0x1F, 0x00, + 0x7F, 0x00, 0xFE, 0x03, 0xDE, 0x0F, 0x1E, 0x3E, 0x3E, 0xF8, 0x3F, 0xE0, + 0x3F, 0x80, 0x38, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xF0, 0xC3, 0x87, 0x0E, 0x1C, 0x30, 0x01, 0xFC, 0x01, 0xFF, 0xC0, + 0x3F, 0xFC, 0x07, 0xFF, 0xC0, 0x00, 0x78, 0x0F, 0xFF, 0x07, 0xFF, 0xE1, + 0xFF, 0xFC, 0x7F, 0xFF, 0x9F, 0x80, 0xF3, 0xC0, 0x1E, 0x78, 0x0F, 0xCF, + 0xFF, 0xFE, 0xFF, 0xFF, 0xCF, 0xFF, 0xF8, 0x7F, 0x3E, 0x7C, 0x00, 0x1F, + 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x0F, + 0x3F, 0x01, 0xFF, 0xF8, 0x3F, 0xFF, 0x87, 0xFF, 0xF0, 0xFC, 0x1F, 0x1F, + 0x01, 0xF3, 0xC0, 0x1E, 0x78, 0x03, 0xCF, 0x00, 0x79, 0xE0, 0x0F, 0x3E, + 0x03, 0xE7, 0xE0, 0xFB, 0xFF, 0xFF, 0x7F, 0xFF, 0xCF, 0xFF, 0xF0, 0xF9, + 0xF8, 0x00, 0x03, 0xF3, 0x87, 0xFF, 0xCF, 0xFF, 0xEF, 0xFF, 0xF7, 0xE0, + 0xFF, 0xC0, 0x3F, 0xC0, 0x0F, 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3E, + 0x00, 0x4F, 0x80, 0xF7, 0xFF, 0xF9, 0xFF, 0xF8, 0x7F, 0xF8, 0x0F, 0xF0, + 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x03, + 0xC0, 0x00, 0x3C, 0x03, 0xF3, 0xC0, 0xFF, 0xBC, 0x1F, 0xFF, 0xC3, 0xFF, + 0xFC, 0x7E, 0x0F, 0xC7, 0x80, 0x7C, 0xF0, 0x03, 0xCF, 0x00, 0x3C, 0xF0, + 0x03, 0xCF, 0x00, 0x3C, 0xF8, 0x07, 0xC7, 0xE0, 0xFC, 0x7F, 0xFF, 0xF3, + 0xFF, 0xFF, 0x0F, 0xFF, 0xF0, 0x3F, 0x3E, 0x03, 0xF0, 0x03, 0xFF, 0x01, + 0xFF, 0xE0, 0xFF, 0xFC, 0x7E, 0x0F, 0x9E, 0x01, 0xEF, 0x00, 0x3F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFD, 0xE0, 0x00, 0x7F, 0xFF, + 0xCF, 0xFF, 0xF1, 0xFF, 0xF8, 0x0F, 0xF0, 0x03, 0xFC, 0x07, 0xFF, 0x0F, + 0xFF, 0x1F, 0xFF, 0x1E, 0x00, 0x1E, 0x00, 0xFF, 0xF8, 0xFF, 0xFC, 0xFF, + 0xFC, 0xFF, 0xF8, 0x1E, 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x1E, + 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x1E, 0x00, 0xFF, 0xF8, 0xFF, 0xF8, 0xFF, + 0xF8, 0xFF, 0xF8, 0x07, 0xE7, 0xC3, 0xFF, 0xFC, 0xFF, 0xFF, 0xBF, 0xFF, + 0xF7, 0xC1, 0xF9, 0xF0, 0x1F, 0x3C, 0x01, 0xE7, 0x80, 0x3C, 0xF0, 0x07, + 0x9E, 0x00, 0xF3, 0xE0, 0x3E, 0x3E, 0x0F, 0xC7, 0xFF, 0xF8, 0x7F, 0xFF, + 0x07, 0xFD, 0xE0, 0x3F, 0x3C, 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x3E, + 0x03, 0xFF, 0x80, 0x7F, 0xF0, 0x0F, 0xFC, 0x00, 0xFE, 0x00, 0x3E, 0x00, + 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x01, 0xE0, 0x00, 0x0F, + 0x00, 0x00, 0x78, 0xF8, 0x03, 0xDF, 0xE0, 0x1F, 0xFF, 0x80, 0xFF, 0xFE, + 0x07, 0xE1, 0xF0, 0x3E, 0x07, 0x81, 0xE0, 0x3C, 0x0F, 0x01, 0xE0, 0x78, + 0x0F, 0x03, 0xC0, 0x78, 0x1E, 0x03, 0xC0, 0xF0, 0x1E, 0x1F, 0xC1, 0xFD, + 0xFE, 0x0F, 0xFF, 0xF0, 0x7F, 0xBF, 0x01, 0xF8, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xC0, 0x3F, 0xC0, + 0x3F, 0xC0, 0x3F, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0xFF, 0xFE, 0xFF, 0xFF, + 0xFF, 0xFF, 0x7F, 0xFE, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x00, 0x00, + 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xF7, 0xFF, 0x00, 0xF0, 0x0F, 0x00, 0xF0, + 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, + 0x0F, 0x00, 0xF0, 0x0F, 0x01, 0xFF, 0xFE, 0xFF, 0xEF, 0xFC, 0x7F, 0x00, + 0x7C, 0x00, 0x3F, 0x00, 0x0F, 0xC0, 0x03, 0xF0, 0x00, 0x3C, 0x00, 0x0F, + 0x00, 0x03, 0xC7, 0xF0, 0xF3, 0xFC, 0x3C, 0xFF, 0x0F, 0x3F, 0x83, 0xDF, + 0x00, 0xFF, 0x80, 0x3F, 0xC0, 0x0F, 0xE0, 0x03, 0xFC, 0x00, 0xF7, 0x80, + 0x3C, 0xF0, 0x0F, 0x1F, 0x0F, 0xC3, 0xFB, 0xF1, 0xFF, 0xFC, 0x7F, 0xDF, + 0x0F, 0xE0, 0x3F, 0xC0, 0x3F, 0xC0, 0x3F, 0xC0, 0x3F, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0xFE, 0x3D, 0xE3, + 0xC1, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0x1F, 0xFF, 0xFE, 0x3E, 0x3C, 0x78, + 0xF0, 0xF1, 0xE3, 0xC3, 0xC7, 0x8F, 0x0F, 0x1E, 0x3C, 0x3C, 0x78, 0xF0, + 0xF1, 0xE3, 0xC3, 0xC7, 0x8F, 0x0F, 0x1E, 0xFE, 0x3E, 0x7F, 0xF8, 0xF9, + 0xFF, 0xE3, 0xE7, 0xDF, 0x0F, 0x1E, 0x1E, 0x7C, 0x03, 0xEF, 0xF0, 0x3F, + 0xFF, 0x83, 0xFF, 0xFC, 0x1F, 0x87, 0xC1, 0xE0, 0x3C, 0x1E, 0x03, 0xC1, + 0xE0, 0x3C, 0x1E, 0x03, 0xC1, 0xE0, 0x3C, 0x1E, 0x03, 0xC1, 0xE0, 0x3C, + 0x7F, 0x0F, 0xFF, 0xF0, 0xFF, 0xFF, 0x0F, 0xF7, 0xE0, 0x7E, 0x03, 0xF8, + 0x01, 0xFF, 0xC0, 0x7F, 0xFC, 0x1F, 0xFF, 0xC7, 0xE0, 0xFD, 0xF0, 0x07, + 0xFC, 0x00, 0x7F, 0x80, 0x0F, 0xF0, 0x01, 0xFE, 0x00, 0x3F, 0xE0, 0x0F, + 0xBF, 0x07, 0xE3, 0xFF, 0xF8, 0x3F, 0xFE, 0x03, 0xFF, 0x80, 0x1F, 0xC0, + 0x3E, 0x7E, 0x03, 0xF7, 0xFC, 0x1F, 0xFF, 0xF0, 0xFF, 0xFF, 0xC1, 0xF8, + 0x3F, 0x0F, 0x80, 0x7C, 0x78, 0x01, 0xE3, 0xC0, 0x0F, 0x1E, 0x00, 0x78, + 0xF0, 0x03, 0xC7, 0xC0, 0x3E, 0x3F, 0x07, 0xE1, 0xFF, 0xFE, 0x0F, 0xFF, + 0xE0, 0x7B, 0xFE, 0x03, 0xCF, 0xC0, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, + 0x80, 0x00, 0xFF, 0x80, 0x0F, 0xFC, 0x00, 0x7F, 0xE0, 0x01, 0xFE, 0x00, + 0x00, 0x03, 0xF3, 0xE0, 0x7F, 0xDF, 0x87, 0xFF, 0xFC, 0x7F, 0xFF, 0xE7, + 0xE0, 0xFC, 0x7C, 0x03, 0xE3, 0xC0, 0x0F, 0x1E, 0x00, 0x78, 0xF0, 0x03, + 0xC7, 0x80, 0x1E, 0x3E, 0x01, 0xF0, 0xFC, 0x1F, 0x83, 0xFF, 0xFC, 0x1F, + 0xFF, 0xE0, 0x3F, 0xEF, 0x00, 0x7E, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, + 0x00, 0x00, 0xF0, 0x00, 0x3F, 0xE0, 0x01, 0xFF, 0x80, 0x0F, 0xFC, 0x00, + 0x3F, 0xC0, 0x7E, 0x1E, 0x7F, 0x3F, 0xFF, 0xBF, 0xFF, 0xFF, 0xF1, 0xFE, + 0x00, 0xFC, 0x00, 0x7C, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x0F, 0x00, 0x07, + 0x80, 0x03, 0xC0, 0x0F, 0xFF, 0x87, 0xFF, 0xC3, 0xFF, 0xE1, 0xFF, 0xE0, + 0x07, 0xE6, 0x1F, 0xFE, 0x7F, 0xFE, 0x7F, 0xFE, 0x78, 0x1E, 0x78, 0x0E, + 0x7F, 0xE0, 0x3F, 0xFC, 0x03, 0xFE, 0x60, 0x1F, 0xE0, 0x0F, 0xF8, 0x1F, + 0xFF, 0xFF, 0xFF, 0xFE, 0x7F, 0xFC, 0x07, 0xE0, 0x0C, 0x00, 0x0F, 0x00, + 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x07, 0xFF, 0xF3, 0xFF, 0xF9, 0xFF, + 0xFC, 0xFF, 0xFC, 0x0F, 0x00, 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x00, + 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1E, 0x07, 0x8F, 0xFF, 0xC3, 0xFF, + 0xC1, 0xFF, 0xC0, 0x3F, 0x80, 0xFC, 0x1F, 0xBF, 0x0F, 0xEF, 0xC3, 0xFB, + 0xF0, 0xFE, 0x3C, 0x07, 0x8F, 0x01, 0xE3, 0xC0, 0x78, 0xF0, 0x1E, 0x3C, + 0x07, 0x8F, 0x01, 0xE3, 0xC0, 0x78, 0xF8, 0x7E, 0x3F, 0xFF, 0xC7, 0xFF, + 0xF0, 0xFF, 0x7C, 0x0F, 0x9E, 0x7F, 0x07, 0xF7, 0xFC, 0x7F, 0xFF, 0xE3, + 0xFE, 0xFE, 0x0F, 0xE1, 0xE0, 0x3C, 0x0F, 0x01, 0xE0, 0x3C, 0x1E, 0x01, + 0xE0, 0xF0, 0x07, 0x8F, 0x00, 0x3E, 0x78, 0x00, 0xF7, 0x80, 0x07, 0xFC, + 0x00, 0x1F, 0xC0, 0x00, 0xFE, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x7E, + 0x03, 0xF7, 0xF8, 0x3F, 0xFF, 0xC1, 0xFE, 0xFC, 0x07, 0xF3, 0xC7, 0x0F, + 0x1E, 0x7C, 0xF0, 0x73, 0xE7, 0x83, 0x9F, 0x7C, 0x1F, 0xFF, 0xC0, 0xFF, + 0xFE, 0x03, 0xF7, 0xF0, 0x1F, 0xBF, 0x80, 0xFC, 0xF8, 0x07, 0xC7, 0xC0, + 0x1E, 0x3E, 0x00, 0xE0, 0xE0, 0x7E, 0x0F, 0xDF, 0xE3, 0xFF, 0xFC, 0x7F, + 0xBF, 0x07, 0xE1, 0xF1, 0xF0, 0x1F, 0xFC, 0x01, 0xFF, 0x00, 0x1F, 0xC0, + 0x07, 0xF8, 0x01, 0xFF, 0xC0, 0x7E, 0xFC, 0x1F, 0x8F, 0xC7, 0xE0, 0xFD, + 0xFE, 0x3F, 0xFF, 0xC7, 0xFF, 0xF0, 0x7F, 0x7E, 0x0F, 0xDF, 0xE3, 0xFF, + 0xFC, 0x7F, 0xBF, 0x07, 0xE3, 0xC0, 0x78, 0x3C, 0x0E, 0x07, 0x83, 0xC0, + 0x78, 0x70, 0x0F, 0x1E, 0x00, 0xE3, 0x80, 0x1E, 0xF0, 0x01, 0xDC, 0x00, + 0x3F, 0x80, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0x00, 0x01, 0xE0, 0x00, + 0x38, 0x00, 0x0F, 0x00, 0x3F, 0xF0, 0x0F, 0xFF, 0x01, 0xFF, 0xE0, 0x1F, + 0xF8, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xF9, 0xC7, + 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x78, 0x03, 0xC0, 0x1E, 0x07, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0x81, 0xF0, 0xFC, 0x7E, 0x1F, + 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0xF8, 0xFC, 0x3E, 0x0F, + 0x83, 0xF0, 0x3E, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xF0, 0x7E, + 0x0F, 0xC3, 0xF0, 0x38, 0x6F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x70, 0x3E, 0x0F, 0xC1, 0xF8, 0x3E, + 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x7C, 0x0F, 0xC1, 0xF0, + 0x7C, 0x3F, 0x1F, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x83, 0xE1, 0xF8, + 0xFC, 0x3F, 0x07, 0x00, 0x1E, 0x00, 0x1F, 0xC0, 0x1F, 0xF0, 0xDF, 0xFC, + 0xFF, 0x3F, 0xFB, 0x0F, 0xF8, 0x03, 0xF8, 0x00, 0x78 }; + +const GFXglyph FreeMonoBold18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 21, 0, 1 }, // 0x20 ' ' + { 0, 5, 22, 21, 8, -21 }, // 0x21 '!' + { 14, 11, 10, 21, 5, -20 }, // 0x22 '"' + { 28, 16, 25, 21, 3, -22 }, // 0x23 '#' + { 78, 14, 28, 21, 4, -23 }, // 0x24 '$' + { 127, 15, 21, 21, 3, -20 }, // 0x25 '%' + { 167, 15, 20, 21, 3, -19 }, // 0x26 '&' + { 205, 4, 10, 21, 8, -20 }, // 0x27 ''' + { 210, 8, 27, 21, 9, -21 }, // 0x28 '(' + { 237, 8, 27, 21, 4, -21 }, // 0x29 ')' + { 264, 16, 15, 21, 3, -21 }, // 0x2A '*' + { 294, 16, 19, 21, 3, -18 }, // 0x2B '+' + { 332, 7, 10, 21, 5, -3 }, // 0x2C ',' + { 341, 19, 4, 21, 1, -11 }, // 0x2D '-' + { 351, 5, 5, 21, 8, -4 }, // 0x2E '.' + { 355, 15, 28, 21, 3, -23 }, // 0x2F '/' + { 408, 16, 23, 21, 3, -22 }, // 0x30 '0' + { 454, 15, 22, 21, 3, -21 }, // 0x31 '1' + { 496, 15, 23, 21, 3, -22 }, // 0x32 '2' + { 540, 16, 23, 21, 3, -22 }, // 0x33 '3' + { 586, 15, 21, 21, 3, -20 }, // 0x34 '4' + { 626, 17, 22, 21, 2, -21 }, // 0x35 '5' + { 673, 15, 23, 21, 4, -22 }, // 0x36 '6' + { 717, 15, 22, 21, 3, -21 }, // 0x37 '7' + { 759, 15, 23, 21, 3, -22 }, // 0x38 '8' + { 803, 15, 23, 21, 4, -22 }, // 0x39 '9' + { 847, 5, 16, 21, 8, -15 }, // 0x3A ':' + { 857, 7, 22, 21, 5, -15 }, // 0x3B ';' + { 877, 18, 16, 21, 1, -17 }, // 0x3C '<' + { 913, 19, 10, 21, 1, -14 }, // 0x3D '=' + { 937, 18, 16, 21, 2, -17 }, // 0x3E '>' + { 973, 15, 21, 21, 4, -20 }, // 0x3F '?' + { 1013, 15, 27, 21, 3, -21 }, // 0x40 '@' + { 1064, 22, 21, 21, -1, -20 }, // 0x41 'A' + { 1122, 20, 21, 21, 1, -20 }, // 0x42 'B' + { 1175, 19, 21, 21, 1, -20 }, // 0x43 'C' + { 1225, 18, 21, 21, 2, -20 }, // 0x44 'D' + { 1273, 19, 21, 21, 1, -20 }, // 0x45 'E' + { 1323, 19, 21, 21, 1, -20 }, // 0x46 'F' + { 1373, 20, 21, 21, 1, -20 }, // 0x47 'G' + { 1426, 21, 21, 21, 0, -20 }, // 0x48 'H' + { 1482, 14, 21, 21, 4, -20 }, // 0x49 'I' + { 1519, 19, 21, 21, 2, -20 }, // 0x4A 'J' + { 1569, 20, 21, 21, 1, -20 }, // 0x4B 'K' + { 1622, 18, 21, 21, 2, -20 }, // 0x4C 'L' + { 1670, 23, 21, 21, -1, -20 }, // 0x4D 'M' + { 1731, 20, 21, 21, 1, -20 }, // 0x4E 'N' + { 1784, 20, 21, 21, 1, -20 }, // 0x4F 'O' + { 1837, 18, 21, 21, 1, -20 }, // 0x50 'P' + { 1885, 20, 26, 21, 1, -20 }, // 0x51 'Q' + { 1950, 21, 21, 21, 0, -20 }, // 0x52 'R' + { 2006, 17, 21, 21, 2, -20 }, // 0x53 'S' + { 2051, 19, 21, 21, 1, -20 }, // 0x54 'T' + { 2101, 21, 21, 21, 0, -20 }, // 0x55 'U' + { 2157, 23, 21, 21, -1, -20 }, // 0x56 'V' + { 2218, 21, 21, 21, 0, -20 }, // 0x57 'W' + { 2274, 19, 21, 21, 1, -20 }, // 0x58 'X' + { 2324, 20, 21, 21, 1, -20 }, // 0x59 'Y' + { 2377, 16, 21, 21, 3, -20 }, // 0x5A 'Z' + { 2419, 8, 27, 21, 9, -21 }, // 0x5B '[' + { 2446, 15, 28, 21, 3, -23 }, // 0x5C '\' + { 2499, 8, 27, 21, 4, -21 }, // 0x5D ']' + { 2526, 15, 11, 21, 3, -21 }, // 0x5E '^' + { 2547, 21, 4, 21, 0, 4 }, // 0x5F '_' + { 2558, 6, 6, 21, 6, -22 }, // 0x60 '`' + { 2563, 19, 16, 21, 1, -15 }, // 0x61 'a' + { 2601, 19, 22, 21, 1, -21 }, // 0x62 'b' + { 2654, 17, 16, 21, 2, -15 }, // 0x63 'c' + { 2688, 20, 22, 21, 1, -21 }, // 0x64 'd' + { 2743, 18, 16, 21, 1, -15 }, // 0x65 'e' + { 2779, 16, 22, 21, 4, -21 }, // 0x66 'f' + { 2823, 19, 23, 21, 1, -15 }, // 0x67 'g' + { 2878, 21, 22, 21, 0, -21 }, // 0x68 'h' + { 2936, 16, 22, 21, 3, -21 }, // 0x69 'i' + { 2980, 12, 29, 21, 5, -21 }, // 0x6A 'j' + { 3024, 18, 22, 21, 2, -21 }, // 0x6B 'k' + { 3074, 16, 22, 21, 3, -21 }, // 0x6C 'l' + { 3118, 22, 16, 21, -1, -15 }, // 0x6D 'm' + { 3162, 20, 16, 21, 0, -15 }, // 0x6E 'n' + { 3202, 19, 16, 21, 1, -15 }, // 0x6F 'o' + { 3240, 21, 23, 21, 0, -15 }, // 0x70 'p' + { 3301, 21, 23, 22, 1, -15 }, // 0x71 'q' + { 3362, 17, 16, 21, 3, -15 }, // 0x72 'r' + { 3396, 16, 16, 21, 3, -15 }, // 0x73 's' + { 3428, 17, 21, 21, 1, -20 }, // 0x74 't' + { 3473, 18, 16, 21, 1, -15 }, // 0x75 'u' + { 3509, 21, 16, 21, 0, -15 }, // 0x76 'v' + { 3551, 21, 16, 21, 0, -15 }, // 0x77 'w' + { 3593, 19, 16, 21, 1, -15 }, // 0x78 'x' + { 3631, 19, 23, 21, 1, -15 }, // 0x79 'y' + { 3686, 14, 16, 21, 3, -15 }, // 0x7A 'z' + { 3714, 10, 27, 21, 6, -21 }, // 0x7B '{' + { 3748, 4, 27, 21, 9, -21 }, // 0x7C '|' + { 3762, 10, 27, 21, 6, -21 }, // 0x7D '}' + { 3796, 17, 8, 21, 2, -13 } }; // 0x7E '~' + +const GFXfont FreeMonoBold18pt7b PROGMEM = { + (uint8_t *)FreeMonoBold18pt7bBitmaps, + (GFXglyph *)FreeMonoBold18pt7bGlyphs, + 0x20, 0x7E, 35 }; + +// Approx. 4485 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBold24pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBold24pt7b.h new file mode 100644 index 0000000..aa0dcd0 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBold24pt7b.h @@ -0,0 +1,672 @@ +const uint8_t FreeMonoBold24pt7bBitmaps[] PROGMEM = { + 0x38, 0xFB, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFD, 0xF3, 0xE7, 0xCF, + 0x9F, 0x3E, 0x7C, 0xF9, 0xF3, 0xE3, 0x82, 0x00, 0x00, 0x00, 0x71, 0xF7, + 0xFF, 0xEF, 0x9E, 0x00, 0xFC, 0x7E, 0xF8, 0x7D, 0xF0, 0xFB, 0xE1, 0xF7, + 0xC3, 0xEF, 0x87, 0xDF, 0x0F, 0xBE, 0x1F, 0x38, 0x1C, 0x70, 0x38, 0xE0, + 0x71, 0xC0, 0xE3, 0x81, 0xC7, 0x03, 0x80, 0x01, 0xC1, 0xC0, 0x0F, 0x8F, + 0x80, 0x3E, 0x3E, 0x00, 0xF8, 0xF8, 0x03, 0xE3, 0xE0, 0x0F, 0x8F, 0x80, + 0x7E, 0x3E, 0x01, 0xF0, 0xF8, 0x07, 0xC7, 0xC0, 0x1F, 0x1F, 0x03, 0xFF, + 0xFF, 0x9F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFD, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, + 0x81, 0xF1, 0xF0, 0x07, 0xC7, 0xC0, 0x1F, 0x1F, 0x00, 0x7C, 0x7C, 0x1F, + 0xFF, 0xFC, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0x9F, 0xFF, + 0xFC, 0x0F, 0x8F, 0x80, 0x3E, 0x3E, 0x00, 0xF8, 0xF8, 0x03, 0xE3, 0xE0, + 0x0F, 0x8F, 0x80, 0x3E, 0x3E, 0x00, 0xF8, 0xF8, 0x03, 0xE3, 0xE0, 0x0F, + 0x8F, 0x80, 0x3C, 0x3C, 0x00, 0x00, 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x1F, 0xFF, 0x07, 0xFF, 0xF1, 0xFF, 0xFE, + 0x7F, 0xFF, 0xDF, 0xC1, 0xFB, 0xF0, 0x1F, 0x7C, 0x01, 0xEF, 0x80, 0x39, + 0xF8, 0x00, 0x3F, 0xF8, 0x03, 0xFF, 0xE0, 0x3F, 0xFF, 0x03, 0xFF, 0xF0, + 0x0F, 0xFF, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0xC0, 0x07, 0xF8, 0x00, 0xFF, + 0x80, 0x1F, 0xF8, 0x07, 0xFF, 0x81, 0xFB, 0xFF, 0xFF, 0x7F, 0xFF, 0xCF, + 0xFF, 0xF1, 0xDF, 0xFC, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, + 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x01, 0xC0, 0x00, + 0x0F, 0x80, 0x00, 0xFF, 0x00, 0x1F, 0xFC, 0x00, 0xF0, 0xE0, 0x0F, 0x07, + 0x80, 0x70, 0x1C, 0x03, 0x80, 0xE0, 0x1C, 0x07, 0x00, 0xF0, 0x78, 0x03, + 0xC3, 0x80, 0x1F, 0xFC, 0x00, 0x7F, 0xC1, 0xF0, 0xF8, 0x7F, 0x00, 0x3F, + 0xF0, 0x0F, 0xFC, 0x03, 0xFF, 0x00, 0xFF, 0xC0, 0x07, 0xE0, 0xF8, 0x38, + 0x1F, 0xE0, 0x01, 0xFF, 0x80, 0x0F, 0x1E, 0x00, 0xF0, 0x78, 0x07, 0x01, + 0xC0, 0x38, 0x0E, 0x01, 0xC0, 0x70, 0x0F, 0x07, 0x80, 0x38, 0x78, 0x01, + 0xFF, 0xC0, 0x07, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x1F, 0xFC, + 0x01, 0xFF, 0xE0, 0x1F, 0xFF, 0x00, 0xFF, 0xF8, 0x0F, 0xC7, 0x00, 0x7C, + 0x10, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xF0, 0x00, + 0x1F, 0x80, 0x00, 0xFE, 0x00, 0x0F, 0xF8, 0x00, 0xFF, 0xC7, 0xCF, 0xFF, + 0x3F, 0x7E, 0xFF, 0xFF, 0xE7, 0xFF, 0xBE, 0x1F, 0xF9, 0xF0, 0x7F, 0x8F, + 0x83, 0xFC, 0x7C, 0x0F, 0xE3, 0xF0, 0x7F, 0xCF, 0xFF, 0xFF, 0x7F, 0xFF, + 0xF9, 0xFF, 0xFF, 0xC7, 0xFF, 0xFC, 0x0F, 0xE0, 0x00, 0xFD, 0xF7, 0xDF, + 0x7D, 0xF7, 0xDF, 0x38, 0xE3, 0x8E, 0x38, 0xE0, 0x01, 0x80, 0xF0, 0x7C, + 0x3F, 0x0F, 0xC7, 0xE1, 0xF8, 0xFC, 0x3E, 0x0F, 0x87, 0xC1, 0xF0, 0x7C, + 0x1F, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, + 0x81, 0xF0, 0x7C, 0x1F, 0x07, 0xC0, 0xF8, 0x3E, 0x0F, 0xC1, 0xF0, 0x7E, + 0x0F, 0x83, 0xF0, 0x7C, 0x1F, 0x03, 0xC0, 0x60, 0x3C, 0x0F, 0x83, 0xF0, + 0xFC, 0x1F, 0x83, 0xE0, 0xFC, 0x1F, 0x07, 0xC1, 0xF8, 0x3E, 0x0F, 0x83, + 0xE0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, + 0x1E, 0x0F, 0x83, 0xE0, 0xF8, 0x7C, 0x1F, 0x0F, 0xC3, 0xE1, 0xF8, 0x7C, + 0x3F, 0x0F, 0x83, 0xE0, 0xF0, 0x00, 0x00, 0x70, 0x00, 0x07, 0xC0, 0x00, + 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x10, 0x7C, 0x11, 0xF3, 0xE7, + 0xDF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, 0x87, 0xFF, 0xF0, 0x07, + 0xFC, 0x00, 0x3F, 0xE0, 0x03, 0xFF, 0x80, 0x3F, 0x7E, 0x01, 0xFB, 0xF0, + 0x1F, 0x8F, 0xC0, 0xF8, 0x3E, 0x03, 0x80, 0xE0, 0x00, 0x38, 0x00, 0x00, + 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, + 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, + 0x01, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xDF, 0xFF, 0xFF, 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, + 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, + 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x70, 0x00, 0x1F, + 0x8F, 0x87, 0xC7, 0xC3, 0xE1, 0xE1, 0xF0, 0xF0, 0x78, 0x38, 0x3C, 0x1C, + 0x0E, 0x06, 0x00, 0x7F, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, 0xFE, 0x7D, 0xFF, 0xFF, 0xFF, 0xEF, 0x80, + 0x00, 0x00, 0x60, 0x00, 0x0F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, + 0xF0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, + 0xF8, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, + 0x3E, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x0F, 0xC0, 0x00, 0xF8, 0x00, + 0x1F, 0x80, 0x01, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, + 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x1F, 0x00, + 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0xC0, + 0x00, 0xFC, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x00, 0x00, 0x01, + 0xFC, 0x00, 0x3F, 0xF8, 0x03, 0xFF, 0xE0, 0x3F, 0xFF, 0x83, 0xFF, 0xFE, + 0x1F, 0x83, 0xF1, 0xF8, 0x0F, 0xCF, 0x80, 0x3E, 0x7C, 0x01, 0xF7, 0xC0, + 0x07, 0xFE, 0x00, 0x3F, 0xF0, 0x01, 0xFF, 0x80, 0x0F, 0xFC, 0x00, 0x7F, + 0xE0, 0x03, 0xFF, 0x00, 0x1F, 0xF8, 0x00, 0xFF, 0xC0, 0x07, 0xFE, 0x00, + 0x3F, 0xF0, 0x01, 0xFF, 0x80, 0x0F, 0xFC, 0x00, 0x7D, 0xF0, 0x07, 0xCF, + 0x80, 0x3E, 0x7E, 0x03, 0xF1, 0xF8, 0x3F, 0x0F, 0xFF, 0xF8, 0x3F, 0xFF, + 0x80, 0xFF, 0xF8, 0x03, 0xFF, 0x80, 0x07, 0xF0, 0x00, 0x01, 0xF8, 0x00, + 0x3F, 0x80, 0x0F, 0xF8, 0x01, 0xFF, 0x80, 0x7F, 0xF8, 0x0F, 0xEF, 0x80, + 0xFC, 0xF8, 0x07, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, + 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, + 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, + 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x3F, 0xFF, 0xE7, + 0xFF, 0xFF, 0x7F, 0xFF, 0xF7, 0xFF, 0xFF, 0x3F, 0xFF, 0xE0, 0x01, 0xFC, + 0x00, 0x3F, 0xF8, 0x07, 0xFF, 0xF0, 0x7F, 0xFF, 0xC7, 0xFF, 0xFF, 0x3F, + 0x03, 0xFB, 0xF0, 0x07, 0xFF, 0x00, 0x1F, 0xF8, 0x00, 0xFB, 0x80, 0x07, + 0xC0, 0x00, 0x3E, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xF8, 0x00, + 0x3F, 0x80, 0x03, 0xF8, 0x00, 0x3F, 0x80, 0x03, 0xF8, 0x00, 0x3F, 0x00, + 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xE0, + 0x0E, 0xFE, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x03, 0xF8, 0x00, 0xFF, 0xF8, 0x0F, 0xFF, + 0xE0, 0xFF, 0xFF, 0x8F, 0xFF, 0xFE, 0x7E, 0x03, 0xF1, 0xC0, 0x0F, 0xC0, + 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, 0x0F, + 0xC0, 0x0F, 0xFC, 0x00, 0xFF, 0xC0, 0x07, 0xFC, 0x00, 0x3F, 0xF0, 0x00, + 0xFF, 0xC0, 0x00, 0x7F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xF0, 0x00, 0x0F, + 0x80, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x01, 0xFF, 0xC0, + 0x3F, 0xBF, 0xFF, 0xFD, 0xFF, 0xFF, 0xC7, 0xFF, 0xFC, 0x1F, 0xFF, 0xC0, + 0x1F, 0xF0, 0x00, 0x00, 0x3F, 0x80, 0x03, 0xF8, 0x00, 0x7F, 0x80, 0x07, + 0xF8, 0x00, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xEF, 0x80, 0x3E, 0xF8, 0x03, + 0xCF, 0x80, 0x7C, 0xF8, 0x0F, 0x8F, 0x80, 0xF0, 0xF8, 0x1F, 0x0F, 0x81, + 0xE0, 0xF8, 0x3E, 0x0F, 0x87, 0xC0, 0xF8, 0x78, 0x0F, 0x8F, 0xFF, 0xFE, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x0F, + 0x80, 0x07, 0xFE, 0x00, 0xFF, 0xF0, 0x0F, 0xFF, 0x00, 0xFF, 0xF0, 0x07, + 0xFE, 0x3F, 0xFF, 0xC1, 0xFF, 0xFF, 0x0F, 0xFF, 0xF8, 0x7F, 0xFF, 0xC3, + 0xFF, 0xFC, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, + 0x01, 0xF0, 0x00, 0x0F, 0xBF, 0x00, 0x7F, 0xFF, 0x03, 0xFF, 0xFC, 0x1F, + 0xFF, 0xF0, 0xFF, 0xFF, 0x83, 0xC0, 0xFE, 0x00, 0x01, 0xF0, 0x00, 0x0F, + 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, + 0x03, 0xE0, 0x00, 0x3F, 0xF0, 0x03, 0xF7, 0xE0, 0x3F, 0xBF, 0xFF, 0xF9, + 0xFF, 0xFF, 0xC7, 0xFF, 0xFC, 0x1F, 0xFF, 0x80, 0x1F, 0xF0, 0x00, 0x00, + 0x1F, 0xC0, 0x0F, 0xFF, 0x01, 0xFF, 0xF0, 0x7F, 0xFF, 0x0F, 0xFF, 0xE1, + 0xFF, 0x00, 0x1F, 0xC0, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x07, 0xE0, 0x00, + 0x7C, 0x00, 0x0F, 0x8F, 0xC0, 0xF9, 0xFF, 0x0F, 0xFF, 0xF8, 0xFF, 0xFF, + 0xCF, 0xFF, 0xFC, 0xFF, 0x0F, 0xEF, 0xE0, 0x3E, 0xFC, 0x03, 0xFF, 0x80, + 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xF7, 0xC0, 0x3F, 0x7E, + 0x03, 0xF3, 0xF0, 0x7E, 0x3F, 0xFF, 0xE1, 0xFF, 0xFC, 0x0F, 0xFF, 0x80, + 0x7F, 0xF0, 0x01, 0xFC, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x1F, 0xF0, 0x03, 0xE0, 0x00, + 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, + 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x1F, 0x00, + 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, + 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x06, 0x00, 0x01, 0xF8, 0x00, 0xFF, + 0xF0, 0x1F, 0xFF, 0x83, 0xFF, 0xFC, 0x7F, 0xFF, 0xE7, 0xE0, 0x7E, 0xFC, + 0x03, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xF7, + 0xC0, 0x3E, 0x7E, 0x07, 0xE3, 0xFF, 0xFC, 0x0F, 0xFF, 0x00, 0xFF, 0xF0, + 0x1F, 0xFF, 0x83, 0xFF, 0xFC, 0x7F, 0x0F, 0xE7, 0xC0, 0x3E, 0xF8, 0x01, + 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xFC, 0x03, 0xF7, 0xE0, + 0x7E, 0x7F, 0xFF, 0xE3, 0xFF, 0xFC, 0x1F, 0xFF, 0x80, 0xFF, 0xF0, 0x03, + 0xFC, 0x00, 0x03, 0xF8, 0x00, 0xFF, 0xE0, 0x1F, 0xFF, 0x83, 0xFF, 0xF8, + 0x7F, 0xFF, 0xC7, 0xE0, 0xFE, 0xFC, 0x03, 0xEF, 0x80, 0x3E, 0xF8, 0x01, + 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x3F, 0xFC, 0x07, 0xF7, 0xE0, + 0xFF, 0x7F, 0xFF, 0xF3, 0xFF, 0xFF, 0x1F, 0xFF, 0xF0, 0xFF, 0x9F, 0x03, + 0xF1, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xE0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, + 0x01, 0xFC, 0x00, 0x3F, 0x80, 0x0F, 0xF0, 0x7F, 0xFE, 0x0F, 0xFF, 0xC0, + 0xFF, 0xF8, 0x0F, 0xFF, 0x00, 0x3F, 0x80, 0x00, 0x7D, 0xFF, 0xFF, 0xFF, + 0xEF, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7D, 0xFF, + 0xFF, 0xFF, 0xEF, 0x80, 0x0F, 0x87, 0xF1, 0xFC, 0x7F, 0x1F, 0xC3, 0xE0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, + 0x1F, 0x87, 0xE1, 0xF0, 0xFC, 0x3E, 0x0F, 0x03, 0xC1, 0xE0, 0x78, 0x1C, + 0x07, 0x01, 0x80, 0x00, 0x00, 0x04, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x7F, + 0x00, 0x01, 0xFE, 0x00, 0x07, 0xFC, 0x00, 0x1F, 0xF0, 0x00, 0x7F, 0xC0, + 0x01, 0xFF, 0x00, 0x07, 0xFE, 0x00, 0x1F, 0xF8, 0x00, 0x7F, 0xE0, 0x00, + 0xFF, 0xE0, 0x00, 0x1F, 0xF8, 0x00, 0x07, 0xFE, 0x00, 0x01, 0xFF, 0x80, + 0x00, 0x7F, 0xE0, 0x00, 0x1F, 0xF8, 0x00, 0x07, 0xFC, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x7F, 0x00, 0x00, 0x1E, 0x7F, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, 0xFE, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xFE, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, 0xFE, + 0x00, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x07, + 0xFC, 0x00, 0x03, 0xFE, 0x00, 0x01, 0xFF, 0x00, 0x00, 0xFF, 0x80, 0x00, + 0x7F, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0xF0, 0x00, 0x3F, 0xF0, 0x01, + 0xFF, 0x00, 0x0F, 0xF8, 0x00, 0x7F, 0xC0, 0x03, 0xFE, 0x00, 0x1F, 0xF0, + 0x00, 0xFF, 0x80, 0x03, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x0F, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x03, 0xF8, 0x01, 0xFF, 0xF0, 0xFF, 0xFF, 0x8F, + 0xFF, 0xFC, 0xFF, 0xFF, 0xEF, 0xC0, 0x7E, 0xF8, 0x03, 0xFF, 0x80, 0x1F, + 0x70, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x3F, + 0xE0, 0x0F, 0xFC, 0x01, 0xFF, 0x00, 0x0F, 0xC0, 0x00, 0xF0, 0x00, 0x0F, + 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x1F, 0x00, 0x03, 0xF8, 0x00, 0x3F, 0x80, 0x03, 0xF8, 0x00, + 0x3F, 0x80, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0xFF, 0x80, 0x3F, 0xF8, + 0x0F, 0xFF, 0x83, 0xE0, 0xF8, 0x78, 0x07, 0x1E, 0x00, 0xF3, 0x80, 0x0E, + 0x70, 0x01, 0xDE, 0x00, 0x3B, 0x80, 0x3F, 0x70, 0x1F, 0xEE, 0x07, 0xFD, + 0xC1, 0xFF, 0xB8, 0x7E, 0x77, 0x0F, 0x0E, 0xE3, 0xC1, 0xDC, 0x70, 0x3B, + 0x8E, 0x07, 0x71, 0xC0, 0xEE, 0x3C, 0x1D, 0xC3, 0xC3, 0xB8, 0x7F, 0xF7, + 0x07, 0xFF, 0xE0, 0x7F, 0xFC, 0x03, 0xFB, 0xC0, 0x00, 0x38, 0x00, 0x07, + 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x61, 0xF0, 0x3E, 0x1F, 0xFF, 0xC3, + 0xFF, 0xF0, 0x1F, 0xFC, 0x01, 0xFC, 0x00, 0x07, 0xFF, 0x80, 0x00, 0x7F, + 0xFE, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x7F, 0xFE, + 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x01, 0xF7, 0xC0, 0x00, 0x0F, 0xBE, 0x00, + 0x00, 0x7D, 0xF8, 0x00, 0x07, 0xC7, 0xC0, 0x00, 0x3E, 0x3E, 0x00, 0x03, + 0xE0, 0xF8, 0x00, 0x1F, 0x07, 0xC0, 0x00, 0xF0, 0x3F, 0x00, 0x0F, 0x80, + 0xF8, 0x00, 0x7F, 0xFF, 0xC0, 0x07, 0xFF, 0xFF, 0x00, 0x3F, 0xFF, 0xF8, + 0x03, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0x00, 0xF8, 0x00, 0xF8, 0x0F, + 0x80, 0x03, 0xE1, 0xFF, 0x80, 0xFF, 0xDF, 0xFE, 0x0F, 0xFF, 0xFF, 0xF0, + 0x7F, 0xFF, 0xFF, 0x83, 0xFF, 0xDF, 0xF8, 0x0F, 0xFC, 0x7F, 0xFF, 0xC0, + 0x3F, 0xFF, 0xFC, 0x0F, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, + 0xFE, 0x07, 0xC0, 0x1F, 0xC1, 0xF0, 0x01, 0xF0, 0x7C, 0x00, 0x7C, 0x1F, + 0x00, 0x1F, 0x07, 0xC0, 0x0F, 0xC1, 0xF0, 0x07, 0xE0, 0x7F, 0xFF, 0xF0, + 0x1F, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, + 0xFC, 0x1F, 0x00, 0x3F, 0x87, 0xC0, 0x03, 0xF1, 0xF0, 0x00, 0x7C, 0x7C, + 0x00, 0x1F, 0x1F, 0x00, 0x07, 0xC7, 0xC0, 0x03, 0xF7, 0xFF, 0xFF, 0xFB, + 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, + 0x00, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0xE7, 0x01, 0xFF, 0xFF, 0xC1, 0xFF, + 0xFF, 0xE1, 0xFF, 0xFF, 0xF1, 0xFE, 0x07, 0xF8, 0xFC, 0x01, 0xFC, 0xFC, + 0x00, 0x7E, 0x7C, 0x00, 0x1F, 0x7E, 0x00, 0x0F, 0xBE, 0x00, 0x03, 0x9F, + 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, + 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0x1F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xF0, 0x00, 0x39, 0xFC, 0x00, + 0x7C, 0x7F, 0x80, 0xFF, 0x1F, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0x81, 0xFF, + 0xFF, 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x7F, + 0xFF, 0xF0, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xC1, + 0xF0, 0x0F, 0xF0, 0xF8, 0x01, 0xF8, 0x7C, 0x00, 0x7E, 0x3E, 0x00, 0x1F, + 0x1F, 0x00, 0x0F, 0xCF, 0x80, 0x03, 0xE7, 0xC0, 0x01, 0xF3, 0xE0, 0x00, + 0xF9, 0xF0, 0x00, 0x7C, 0xF8, 0x00, 0x3E, 0x7C, 0x00, 0x1F, 0x3E, 0x00, + 0x0F, 0x9F, 0x00, 0x07, 0xCF, 0x80, 0x07, 0xE7, 0xC0, 0x03, 0xE3, 0xE0, + 0x03, 0xF1, 0xF0, 0x07, 0xF1, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, 0xF8, 0xFF, + 0xFF, 0xF8, 0x7F, 0xFF, 0xF0, 0x1F, 0xFF, 0xE0, 0x00, 0x7F, 0xFF, 0xFF, + 0x7F, 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, + 0xF0, 0xF8, 0x00, 0xF8, 0x7C, 0x00, 0x7C, 0x3E, 0x0E, 0x3E, 0x1F, 0x0F, + 0x9F, 0x0F, 0x87, 0xC7, 0x07, 0xC3, 0xE0, 0x03, 0xFF, 0xF0, 0x01, 0xFF, + 0xF8, 0x00, 0xFF, 0xFC, 0x00, 0x7F, 0xFE, 0x00, 0x3F, 0xFF, 0x00, 0x1F, + 0x0F, 0x80, 0x0F, 0x87, 0xC3, 0x87, 0xC1, 0xC3, 0xE3, 0xE0, 0x01, 0xF1, + 0xF0, 0x00, 0xF8, 0xF8, 0x00, 0x7D, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF7, 0xFF, + 0xFF, 0xF8, 0xF8, 0x00, 0x7C, 0x7C, 0x00, 0x3E, 0x3E, 0x00, 0x1F, 0x1F, + 0x07, 0x0F, 0x8F, 0x87, 0xC3, 0x87, 0xC3, 0xE0, 0x03, 0xFF, 0xF0, 0x01, + 0xFF, 0xF8, 0x00, 0xFF, 0xFC, 0x00, 0x7F, 0xFE, 0x00, 0x3F, 0xFF, 0x00, + 0x1F, 0x0F, 0x80, 0x0F, 0x87, 0xC0, 0x07, 0xC3, 0xE0, 0x03, 0xE0, 0xE0, + 0x01, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xFF, 0xF0, 0x01, 0xFF, 0xFC, + 0x00, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0x00, 0x1F, 0xFF, 0x00, 0x00, 0x00, + 0x7F, 0x8E, 0x00, 0xFF, 0xF7, 0x81, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, 0xE1, + 0xFF, 0xFF, 0xF1, 0xFE, 0x03, 0xF8, 0xFC, 0x00, 0xFC, 0xFC, 0x00, 0x3E, + 0x7C, 0x00, 0x1F, 0x7E, 0x00, 0x07, 0x3E, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, 0xF0, 0x0F, + 0xFE, 0xF8, 0x0F, 0xFF, 0xFC, 0x07, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0x00, + 0xFF, 0xFF, 0xC0, 0x01, 0xF3, 0xF0, 0x00, 0xF9, 0xFC, 0x00, 0x7C, 0x7F, + 0x80, 0xFE, 0x3F, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0x80, + 0x7F, 0xFF, 0x00, 0x07, 0xFC, 0x00, 0x3F, 0xE1, 0xFF, 0x1F, 0xFC, 0xFF, + 0xE7, 0xFF, 0x3F, 0xF9, 0xFF, 0xCF, 0xFE, 0x3F, 0xE1, 0xFF, 0x07, 0xC0, + 0x0F, 0x81, 0xF0, 0x03, 0xE0, 0x7C, 0x00, 0xF8, 0x1F, 0x00, 0x3E, 0x07, + 0xC0, 0x0F, 0x81, 0xF0, 0x03, 0xE0, 0x7F, 0xFF, 0xF8, 0x1F, 0xFF, 0xFE, + 0x07, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0xF8, 0x1F, 0x00, + 0x3E, 0x07, 0xC0, 0x0F, 0x81, 0xF0, 0x03, 0xE0, 0x7C, 0x00, 0xF8, 0x1F, + 0x00, 0x3E, 0x07, 0xC0, 0x0F, 0x87, 0xFE, 0x1F, 0xFB, 0xFF, 0xCF, 0xFF, + 0xFF, 0xF3, 0xFF, 0xFF, 0xFC, 0xFF, 0xF7, 0xFE, 0x1F, 0xF8, 0x7F, 0xFF, + 0xDF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF7, 0xFF, 0xFC, 0x03, 0xE0, + 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, + 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, + 0x03, 0xE0, 0x1F, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFD, + 0xFF, 0xFF, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, + 0xE0, 0x3F, 0xFF, 0xF0, 0x0F, 0xFF, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x07, + 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x07, 0xC0, 0xE0, 0x03, 0xE0, 0xF8, 0x01, 0xF0, 0x7C, 0x00, 0xF8, 0x3E, + 0x00, 0x7C, 0x1F, 0x00, 0x3E, 0x0F, 0x80, 0x1F, 0x07, 0xC0, 0x1F, 0x83, + 0xF8, 0x3F, 0x81, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xC0, + 0x07, 0xFF, 0xC0, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0xE0, 0xFF, 0x9F, 0xFE, + 0x3F, 0xFB, 0xFF, 0xC7, 0xFF, 0x7F, 0xF8, 0xFF, 0xE7, 0xFE, 0x0F, 0xF8, + 0x3E, 0x01, 0xF8, 0x07, 0xC0, 0xFE, 0x00, 0xF8, 0x3F, 0x80, 0x1F, 0x0F, + 0xE0, 0x03, 0xE3, 0xF8, 0x00, 0x7D, 0xFC, 0x00, 0x0F, 0xFF, 0x00, 0x01, + 0xFF, 0xF0, 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFF, 0xF0, 0x00, 0xFE, 0x7F, + 0x00, 0x1F, 0x87, 0xF0, 0x03, 0xE0, 0x7E, 0x00, 0x7C, 0x07, 0xE0, 0x0F, + 0x80, 0x7E, 0x01, 0xF0, 0x0F, 0xC0, 0x3E, 0x00, 0xF8, 0x1F, 0xF8, 0x1F, + 0xF7, 0xFF, 0x81, 0xFF, 0xFF, 0xF0, 0x3F, 0xFF, 0xFE, 0x07, 0xFD, 0xFF, + 0x80, 0x7F, 0x00, 0x7F, 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x3F, 0xFF, 0x80, + 0x1F, 0xFF, 0xC0, 0x07, 0xFF, 0xC0, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x0F, 0x80, 0x0E, 0x07, 0xC0, 0x0F, 0x83, 0xE0, 0x07, 0xC1, + 0xF0, 0x03, 0xE0, 0xF8, 0x01, 0xF0, 0x7C, 0x00, 0xF8, 0x3E, 0x00, 0x7D, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xDF, 0xFF, 0xFF, 0xE0, 0x3F, 0x80, 0x03, 0xF8, 0xFF, 0x80, 0x0F, 0xF9, + 0xFF, 0x00, 0x1F, 0xF3, 0xFF, 0x00, 0x7F, 0xE3, 0xFE, 0x00, 0xFF, 0x83, + 0xFE, 0x03, 0xFE, 0x07, 0xFC, 0x07, 0xFC, 0x0F, 0xFC, 0x1F, 0xF8, 0x1F, + 0xF8, 0x3F, 0xF0, 0x3F, 0xF0, 0x7F, 0xE0, 0x7D, 0xF1, 0xF7, 0xC0, 0xFB, + 0xE3, 0xEF, 0x81, 0xF7, 0xEF, 0xDF, 0x03, 0xE7, 0xDF, 0x3E, 0x07, 0xCF, + 0xFE, 0x7C, 0x0F, 0x8F, 0xF8, 0xF8, 0x1F, 0x1F, 0xF1, 0xF0, 0x3E, 0x1F, + 0xE3, 0xE0, 0x7C, 0x3F, 0x87, 0xC0, 0xF8, 0x3F, 0x0F, 0x81, 0xF0, 0x00, + 0x1F, 0x03, 0xE0, 0x00, 0x3E, 0x1F, 0xF8, 0x03, 0xFF, 0x7F, 0xF8, 0x0F, + 0xFF, 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0xE0, 0x3F, 0xFD, 0xFF, 0x80, 0x3F, + 0xF0, 0x7F, 0x00, 0x7F, 0xEF, 0xF8, 0x0F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, + 0xFC, 0x0F, 0xFF, 0x7F, 0xE0, 0x7F, 0xE1, 0xFF, 0x00, 0xF8, 0x1F, 0xF0, + 0x0F, 0x81, 0xFF, 0x80, 0xF8, 0x1F, 0xFC, 0x0F, 0x81, 0xFF, 0xC0, 0xF8, + 0x1F, 0x7E, 0x0F, 0x81, 0xF3, 0xF0, 0xF8, 0x1F, 0x3F, 0x0F, 0x81, 0xF1, + 0xF8, 0xF8, 0x1F, 0x0F, 0xCF, 0x81, 0xF0, 0xFC, 0xF8, 0x1F, 0x07, 0xEF, + 0x81, 0xF0, 0x3F, 0xF8, 0x1F, 0x03, 0xFF, 0x81, 0xF0, 0x1F, 0xF8, 0x1F, + 0x00, 0xFF, 0x81, 0xF0, 0x0F, 0xF8, 0x7F, 0xE0, 0x7F, 0x8F, 0xFF, 0x03, + 0xF8, 0xFF, 0xF0, 0x3F, 0x8F, 0xFF, 0x01, 0xF8, 0x7F, 0xE0, 0x0F, 0x80, + 0x00, 0x3F, 0x80, 0x00, 0x3F, 0xFC, 0x00, 0x0F, 0xFF, 0xE0, 0x03, 0xFF, + 0xFE, 0x00, 0xFF, 0xFF, 0xE0, 0x3F, 0xC1, 0xFE, 0x0F, 0xE0, 0x0F, 0xE1, + 0xF8, 0x00, 0xFC, 0x7E, 0x00, 0x0F, 0xCF, 0x80, 0x00, 0xFB, 0xF0, 0x00, + 0x1F, 0xFC, 0x00, 0x01, 0xFF, 0x80, 0x00, 0x3F, 0xF0, 0x00, 0x07, 0xFE, + 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x1F, 0xF8, 0x00, 0x03, 0xFF, 0x00, 0x00, + 0x7F, 0xF0, 0x00, 0x1F, 0xBE, 0x00, 0x03, 0xE7, 0xE0, 0x00, 0xFC, 0x7E, + 0x00, 0x3F, 0x0F, 0xE0, 0x0F, 0xE0, 0xFF, 0x07, 0xF8, 0x0F, 0xFF, 0xFE, + 0x00, 0xFF, 0xFF, 0x80, 0x0F, 0xFF, 0xE0, 0x00, 0xFF, 0xF8, 0x00, 0x03, + 0xF8, 0x00, 0x7F, 0xFF, 0x80, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xF8, 0xFF, + 0xFF, 0xFC, 0x7F, 0xFF, 0xFE, 0x1F, 0x00, 0xFE, 0x1F, 0x00, 0x3F, 0x1F, + 0x00, 0x1F, 0x1F, 0x00, 0x1F, 0x1F, 0x00, 0x1F, 0x1F, 0x00, 0x1F, 0x1F, + 0x00, 0x3F, 0x1F, 0x00, 0x7E, 0x1F, 0xFF, 0xFE, 0x1F, 0xFF, 0xFC, 0x1F, + 0xFF, 0xF8, 0x1F, 0xFF, 0xF0, 0x1F, 0xFF, 0x80, 0x1F, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x7F, 0xFC, 0x00, 0xFF, + 0xFE, 0x00, 0xFF, 0xFE, 0x00, 0xFF, 0xFE, 0x00, 0x7F, 0xFC, 0x00, 0x00, + 0x3F, 0x80, 0x00, 0x3F, 0xFC, 0x00, 0x0F, 0xFF, 0xE0, 0x03, 0xFF, 0xFE, + 0x00, 0xFF, 0xFF, 0xE0, 0x3F, 0xC1, 0xFE, 0x0F, 0xE0, 0x0F, 0xE1, 0xF8, + 0x00, 0xFC, 0x7E, 0x00, 0x0F, 0xCF, 0x80, 0x00, 0xFB, 0xF0, 0x00, 0x1F, + 0xFC, 0x00, 0x01, 0xFF, 0x80, 0x00, 0x3F, 0xF0, 0x00, 0x07, 0xFE, 0x00, + 0x00, 0xFF, 0xC0, 0x00, 0x1F, 0xF8, 0x00, 0x03, 0xFF, 0x80, 0x00, 0xFD, + 0xF0, 0x00, 0x1F, 0x3F, 0x00, 0x07, 0xE7, 0xF0, 0x01, 0xF8, 0x7F, 0x00, + 0x7F, 0x07, 0xF8, 0x3F, 0xC0, 0xFF, 0xFF, 0xF0, 0x07, 0xFF, 0xFC, 0x00, + 0x7F, 0xFF, 0x00, 0x07, 0xFF, 0xC0, 0x00, 0x7F, 0xC0, 0x00, 0x0F, 0x00, + 0x00, 0x03, 0xFF, 0x87, 0x80, 0xFF, 0xFF, 0xF8, 0x3F, 0xFF, 0xFF, 0x07, + 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xF0, 0x0F, 0x01, 0xF8, 0x00, 0x7F, 0xFF, + 0x80, 0x0F, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xC0, + 0x7F, 0xFF, 0xFE, 0x00, 0xF8, 0x07, 0xE0, 0x0F, 0x80, 0x3F, 0x00, 0xF8, + 0x01, 0xF0, 0x0F, 0x80, 0x1F, 0x00, 0xF8, 0x01, 0xF0, 0x0F, 0x80, 0x3F, + 0x00, 0xF8, 0x0F, 0xE0, 0x0F, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0xC0, 0x0F, + 0xFF, 0xF0, 0x00, 0xFF, 0xFE, 0x00, 0x0F, 0xFF, 0xF0, 0x00, 0xF8, 0x3F, + 0x80, 0x0F, 0x81, 0xFC, 0x00, 0xF8, 0x0F, 0xE0, 0x0F, 0x80, 0x7E, 0x00, + 0xF8, 0x03, 0xF0, 0x7F, 0xF0, 0x1F, 0xEF, 0xFF, 0x81, 0xFF, 0xFF, 0xF8, + 0x0F, 0xFF, 0xFF, 0x80, 0x7F, 0x7F, 0xF0, 0x07, 0xE0, 0x01, 0xFC, 0x70, + 0x1F, 0xFD, 0xE0, 0xFF, 0xFF, 0x87, 0xFF, 0xFE, 0x3F, 0xFF, 0xF8, 0xFC, + 0x0F, 0xE7, 0xE0, 0x1F, 0x9F, 0x00, 0x3E, 0x7C, 0x00, 0xF9, 0xF0, 0x01, + 0xC7, 0xF0, 0x00, 0x0F, 0xF8, 0x00, 0x3F, 0xFF, 0x00, 0x7F, 0xFF, 0x00, + 0xFF, 0xFF, 0x00, 0xFF, 0xFC, 0x00, 0x1F, 0xF8, 0x00, 0x07, 0xE0, 0x00, + 0x0F, 0xDC, 0x00, 0x1F, 0xF8, 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0xC0, 0x0F, + 0xFF, 0xC0, 0xFE, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, 0xCF, 0xFF, 0xFE, 0x1C, + 0xFF, 0xF0, 0x00, 0xFE, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC1, 0xF0, 0x7F, + 0xE0, 0xF8, 0x3F, 0xF0, 0x7C, 0x1F, 0xF8, 0x3E, 0x0F, 0xFC, 0x1F, 0x07, + 0xFE, 0x0F, 0x83, 0xEE, 0x07, 0xC0, 0xE0, 0x03, 0xE0, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, + 0xF0, 0x00, 0x0F, 0xFF, 0x80, 0x0F, 0xFF, 0xE0, 0x07, 0xFF, 0xF0, 0x03, + 0xFF, 0xF8, 0x00, 0xFF, 0xF8, 0x00, 0x7F, 0xE0, 0x7F, 0xEF, 0xFF, 0x0F, + 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0x0F, 0xFF, 0x7F, 0xE0, 0x7F, 0xE1, + 0xF0, 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0xF8, 0x1F, 0x00, + 0x0F, 0x81, 0xF0, 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0xF8, + 0x1F, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0x81, 0xF0, + 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0xF8, 0x1F, 0x00, 0x0F, + 0x81, 0xF0, 0x00, 0xF8, 0x1F, 0x80, 0x1F, 0x80, 0xF8, 0x01, 0xF0, 0x0F, + 0xE0, 0x7F, 0x00, 0x7F, 0xFF, 0xE0, 0x03, 0xFF, 0xFE, 0x00, 0x1F, 0xFF, + 0x80, 0x00, 0xFF, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x7F, 0xE0, 0x1F, 0xFB, + 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFC, 0x0F, 0xFF, 0x7F, + 0xE0, 0x1F, 0xF8, 0x7C, 0x00, 0x0F, 0x80, 0xF8, 0x00, 0x7C, 0x03, 0xE0, + 0x01, 0xF0, 0x07, 0xC0, 0x0F, 0x80, 0x1F, 0x00, 0x3E, 0x00, 0x7E, 0x00, + 0xF8, 0x00, 0xF8, 0x07, 0xC0, 0x03, 0xF0, 0x1F, 0x00, 0x07, 0xC0, 0xF8, + 0x00, 0x1F, 0x03, 0xE0, 0x00, 0x7E, 0x1F, 0x00, 0x00, 0xF8, 0x7C, 0x00, + 0x03, 0xF3, 0xF0, 0x00, 0x07, 0xCF, 0x80, 0x00, 0x1F, 0xBE, 0x00, 0x00, + 0x3F, 0xF0, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x07, + 0xF8, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00, 0xFC, + 0x00, 0x00, 0x7F, 0xE0, 0x7F, 0xEF, 0xFF, 0x0F, 0xFF, 0xFF, 0xF0, 0xFF, + 0xFF, 0xFF, 0x0F, 0xFF, 0x7F, 0xE0, 0x7F, 0xE3, 0xE0, 0x00, 0x3C, 0x3E, + 0x0F, 0x83, 0xC3, 0xE1, 0xF8, 0x3C, 0x3E, 0x1F, 0x87, 0xC3, 0xE1, 0xFC, + 0x7C, 0x3E, 0x3F, 0xC7, 0xC1, 0xE3, 0xFC, 0x7C, 0x1F, 0x3F, 0xE7, 0xC1, + 0xF7, 0xFE, 0x78, 0x1F, 0x7F, 0xE7, 0x81, 0xF7, 0x9F, 0xF8, 0x1F, 0xF9, + 0xFF, 0x81, 0xFF, 0x9F, 0xF8, 0x0F, 0xF9, 0xFF, 0x80, 0xFF, 0x0F, 0xF8, + 0x0F, 0xF0, 0xFF, 0x80, 0xFF, 0x0F, 0xF0, 0x0F, 0xE0, 0x7F, 0x00, 0xFE, + 0x07, 0xF0, 0x0F, 0xE0, 0x7F, 0x00, 0xFC, 0x03, 0xF0, 0x07, 0xC0, 0x3F, + 0x00, 0x7F, 0x80, 0xFF, 0x3F, 0xF0, 0x7F, 0xEF, 0xFC, 0x1F, 0xFB, 0xFF, + 0x07, 0xFE, 0x7F, 0x80, 0xFF, 0x07, 0xE0, 0x3F, 0x00, 0xFC, 0x0F, 0x80, + 0x1F, 0x87, 0xC0, 0x03, 0xF3, 0xE0, 0x00, 0xFF, 0xF8, 0x00, 0x1F, 0xFC, + 0x00, 0x03, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x07, + 0xF0, 0x00, 0x03, 0xFE, 0x00, 0x01, 0xFF, 0xC0, 0x00, 0xFC, 0xF8, 0x00, + 0x7E, 0x3F, 0x00, 0x3F, 0x07, 0xE0, 0x1F, 0x80, 0xFC, 0x07, 0xE0, 0x1F, + 0x07, 0xFC, 0x0F, 0xFB, 0xFF, 0x87, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xF8, + 0x7F, 0xF7, 0xFC, 0x0F, 0xF8, 0x7F, 0x80, 0x7F, 0xBF, 0xF0, 0x3F, 0xFF, + 0xFC, 0x0F, 0xFF, 0xFF, 0x03, 0xFF, 0x7F, 0x80, 0x7F, 0x87, 0xE0, 0x1F, + 0x80, 0xFC, 0x07, 0xC0, 0x1F, 0x03, 0xE0, 0x03, 0xE1, 0xF8, 0x00, 0xFC, + 0x7C, 0x00, 0x1F, 0xBE, 0x00, 0x03, 0xFF, 0x80, 0x00, 0x7F, 0xC0, 0x00, + 0x1F, 0xE0, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x00, + 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x07, 0xC0, 0x00, 0x1F, 0xFF, 0x00, 0x0F, 0xFF, 0xE0, 0x03, + 0xFF, 0xF8, 0x00, 0xFF, 0xFE, 0x00, 0x1F, 0xFF, 0x00, 0x7F, 0xFF, 0xF3, + 0xFF, 0xFF, 0x9F, 0xFF, 0xFC, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0x3E, 0x03, + 0xF1, 0xF0, 0x1F, 0x8F, 0x81, 0xF8, 0x7C, 0x1F, 0x83, 0xE1, 0xF8, 0x0E, + 0x1F, 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, + 0x00, 0xFC, 0x00, 0x0F, 0xE0, 0x70, 0x7E, 0x07, 0xC7, 0xE0, 0x3E, 0x7E, + 0x01, 0xF7, 0xE0, 0x0F, 0xFF, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xFF, 0xBF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xBE, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, + 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, + 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, + 0xFF, 0xBF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x60, 0x00, 0x0F, 0x00, 0x00, + 0xF8, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7E, 0x00, + 0x03, 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x00, 0xF8, + 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x03, + 0xE0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, + 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xF0, + 0x00, 0x1F, 0x00, 0x01, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x07, + 0xC0, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, + 0x1F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, + 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, + 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, + 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x7F, 0xFF, + 0xFF, 0xFF, 0xFF, 0x7F, 0xC0, 0x00, 0x40, 0x00, 0x06, 0x00, 0x00, 0xF0, + 0x00, 0x1F, 0x80, 0x03, 0xFC, 0x00, 0x7F, 0xE0, 0x0F, 0xFF, 0x00, 0xFF, + 0xF8, 0x1F, 0x9F, 0x83, 0xF0, 0xFC, 0x7E, 0x07, 0xEF, 0xC0, 0x3F, 0xF8, + 0x01, 0xFF, 0x80, 0x0F, 0x70, 0x00, 0x60, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF0, 0xE0, 0x78, 0x3E, 0x0F, 0xC3, 0xF0, 0x7C, 0x1E, 0x06, 0x01, 0xFF, + 0x00, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0xE0, 0x1F, 0xFF, 0xF0, 0x0F, 0xFF, + 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x01, 0xFF, + 0xF8, 0x07, 0xFF, 0xF8, 0x1F, 0xFF, 0xF8, 0x3F, 0xFF, 0xF8, 0x7F, 0xFF, + 0xF8, 0x7F, 0x00, 0xF8, 0xFC, 0x00, 0xF8, 0xF8, 0x00, 0xF8, 0xF8, 0x03, + 0xF8, 0xFC, 0x0F, 0xFE, 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x3F, 0xFF, + 0xFF, 0x1F, 0xFE, 0xFE, 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x00, 0x1F, 0xE0, + 0x00, 0x03, 0xFC, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, + 0x3E, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x0F, + 0xE0, 0x03, 0xEF, 0xFF, 0x00, 0x7F, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0x81, + 0xFF, 0xFF, 0xF8, 0x3F, 0xE0, 0x7F, 0x07, 0xF0, 0x03, 0xF0, 0xFC, 0x00, + 0x3E, 0x1F, 0x80, 0x07, 0xE3, 0xE0, 0x00, 0x7C, 0x7C, 0x00, 0x0F, 0x8F, + 0x80, 0x01, 0xF1, 0xF0, 0x00, 0x3E, 0x3E, 0x00, 0x07, 0xC7, 0xE0, 0x01, + 0xF8, 0xFC, 0x00, 0x3E, 0x1F, 0xC0, 0x0F, 0xCF, 0xFE, 0x07, 0xF3, 0xFF, + 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, 0x8F, 0xFF, 0xFF, 0xE0, 0xFE, 0x7F, 0xF0, + 0x00, 0x03, 0xF8, 0x00, 0x00, 0xFF, 0x18, 0x03, 0xFF, 0xFC, 0x0F, 0xFF, + 0xFC, 0x1F, 0xFF, 0xFC, 0x3F, 0xFF, 0xFC, 0x3F, 0x81, 0xFC, 0x7E, 0x00, + 0x7C, 0x7C, 0x00, 0x7C, 0xFC, 0x00, 0x3C, 0xF8, 0x00, 0x38, 0xF8, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0x7C, 0x00, 0x06, 0x7E, 0x00, 0x1F, 0x7F, 0x80, 0x7F, 0x3F, 0xFF, + 0xFF, 0x1F, 0xFF, 0xFE, 0x0F, 0xFF, 0xFC, 0x07, 0xFF, 0xF8, 0x00, 0xFF, + 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x1F, 0xE0, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0xF8, 0x00, 0xFE, 0x3E, 0x00, 0xFF, 0xEF, 0x80, 0xFF, 0xFF, + 0xE0, 0x7F, 0xFF, 0xF8, 0x3F, 0xFF, 0xFE, 0x1F, 0xE0, 0xFF, 0x87, 0xE0, + 0x0F, 0xE1, 0xF0, 0x01, 0xF8, 0xFC, 0x00, 0x7E, 0x3E, 0x00, 0x0F, 0x8F, + 0x80, 0x03, 0xE3, 0xE0, 0x00, 0xF8, 0xF8, 0x00, 0x3E, 0x3E, 0x00, 0x0F, + 0x8F, 0xC0, 0x07, 0xE1, 0xF0, 0x01, 0xF8, 0x7E, 0x00, 0xFE, 0x0F, 0xE0, + 0x7F, 0xE3, 0xFF, 0xFF, 0xFC, 0x7F, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xC0, + 0xFF, 0xEF, 0xE0, 0x0F, 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x03, 0xFF, 0xC0, + 0x0F, 0xFF, 0xE0, 0x1F, 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, 0x7F, 0x81, 0xFC, + 0x7E, 0x00, 0x7E, 0xFC, 0x00, 0x3E, 0xF8, 0x00, 0x3E, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF8, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7F, 0x80, 0x7E, + 0x3F, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0x0F, 0xFF, 0xFE, 0x07, 0xFF, 0xF8, + 0x00, 0xFF, 0x80, 0x00, 0x3F, 0xE0, 0x03, 0xFF, 0xE0, 0x1F, 0xFF, 0xC0, + 0xFF, 0xFF, 0x07, 0xFF, 0xF8, 0x1F, 0x80, 0x00, 0x7C, 0x00, 0x01, 0xF0, + 0x00, 0x07, 0xC0, 0x01, 0xFF, 0xFF, 0x0F, 0xFF, 0xFE, 0x3F, 0xFF, 0xF8, + 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x07, + 0xC0, 0x00, 0x1F, 0x00, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x07, 0xC0, + 0x00, 0x1F, 0x00, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x07, 0xC0, 0x01, + 0xFF, 0xFF, 0x0F, 0xFF, 0xFE, 0x3F, 0xFF, 0xF8, 0xFF, 0xFF, 0xE1, 0xFF, + 0xFF, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xFF, 0xBF, 0x83, 0xFF, 0xFF, 0xE3, + 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xFB, 0xFC, 0x3F, 0xF9, 0xF8, 0x07, 0xF0, + 0xF8, 0x01, 0xF8, 0xFC, 0x00, 0xFC, 0x7C, 0x00, 0x3E, 0x3E, 0x00, 0x1F, + 0x1F, 0x00, 0x0F, 0x8F, 0x80, 0x07, 0xC7, 0xC0, 0x03, 0xE3, 0xF0, 0x03, + 0xF0, 0xF8, 0x01, 0xF8, 0x7E, 0x01, 0xFC, 0x3F, 0xC3, 0xFE, 0x0F, 0xFF, + 0xFF, 0x03, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xC0, 0x3F, 0xFB, 0xE0, 0x07, + 0xF1, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xFE, 0x00, + 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0x00, 0x3F, 0xFE, 0x00, + 0x0F, 0xFC, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, + 0x03, 0xFC, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x0F, 0xC0, 0x07, 0xCF, 0xFC, 0x01, + 0xF7, 0xFF, 0x80, 0x7F, 0xFF, 0xF0, 0x1F, 0xFF, 0xFC, 0x07, 0xFC, 0x1F, + 0x81, 0xFC, 0x03, 0xE0, 0x7E, 0x00, 0xF8, 0x1F, 0x00, 0x3E, 0x07, 0xC0, + 0x0F, 0x81, 0xF0, 0x03, 0xE0, 0x7C, 0x00, 0xF8, 0x1F, 0x00, 0x3E, 0x07, + 0xC0, 0x0F, 0x81, 0xF0, 0x03, 0xE0, 0x7C, 0x00, 0xF8, 0x1F, 0x00, 0x3E, + 0x1F, 0xF0, 0x3F, 0xEF, 0xFE, 0x1F, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xE1, + 0xFF, 0xDF, 0xF0, 0x3F, 0xE0, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, + 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x1F, 0xF8, 0x01, 0xFF, 0xC0, 0x0F, 0xFE, 0x00, 0x7F, 0xF0, + 0x01, 0xFF, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x00, + 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, + 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x7F, 0xFF, 0xF7, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0x00, 0x00, 0x7C, + 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF7, + 0xFF, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, + 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, + 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, + 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x3F, 0x00, 0x3F, 0xBF, 0xFF, 0xBF, 0xFF, + 0x9F, 0xFF, 0xCF, 0xFF, 0x83, 0xFF, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0x80, + 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xF8, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, + 0x87, 0xFC, 0x07, 0xC7, 0xFF, 0x03, 0xE3, 0xFF, 0x81, 0xF1, 0xFF, 0xC0, + 0xF8, 0x7F, 0xC0, 0x7C, 0xFE, 0x00, 0x3E, 0xFE, 0x00, 0x1F, 0xFE, 0x00, + 0x0F, 0xFE, 0x00, 0x07, 0xFE, 0x00, 0x03, 0xFF, 0x80, 0x01, 0xFF, 0xE0, + 0x00, 0xFF, 0xF8, 0x00, 0x7C, 0xFE, 0x00, 0x3E, 0x3F, 0x80, 0x1F, 0x0F, + 0xE0, 0x3F, 0x81, 0xFF, 0xBF, 0xC1, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xF0, + 0x7F, 0xFB, 0xF8, 0x1F, 0xF8, 0x1F, 0xF8, 0x01, 0xFF, 0xC0, 0x0F, 0xFE, + 0x00, 0x7F, 0xF0, 0x01, 0xFF, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, + 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, + 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x00, + 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, + 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x03, 0xFF, + 0xFF, 0xBF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xBF, 0xFF, 0xF8, + 0x00, 0x3C, 0x1F, 0x00, 0xFD, 0xFC, 0xFF, 0x07, 0xFF, 0xFF, 0xFE, 0x1F, + 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, 0xFF, 0xF0, 0xFF, 0x1F, 0x87, 0xC1, 0xF8, + 0x7E, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, + 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, + 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, + 0x1F, 0x07, 0xC1, 0xF1, 0xFE, 0x1F, 0x87, 0xEF, 0xFC, 0x7F, 0x1F, 0xFF, + 0xF1, 0xFC, 0x7F, 0xFF, 0xC7, 0xF1, 0xFD, 0xFE, 0x1F, 0x87, 0xE0, 0x00, + 0x1F, 0x80, 0x1F, 0x9F, 0xF8, 0x1F, 0xDF, 0xFE, 0x0F, 0xFF, 0xFF, 0x87, + 0xFF, 0xFF, 0xC1, 0xFF, 0x07, 0xF0, 0x7F, 0x01, 0xF8, 0x3F, 0x00, 0x7C, + 0x1F, 0x00, 0x3E, 0x0F, 0x80, 0x1F, 0x07, 0xC0, 0x0F, 0x83, 0xE0, 0x07, + 0xC1, 0xF0, 0x03, 0xE0, 0xF8, 0x01, 0xF0, 0x7C, 0x00, 0xF8, 0x3E, 0x00, + 0x7C, 0x1F, 0x00, 0x3E, 0x3F, 0xE0, 0x7F, 0xBF, 0xF8, 0x7F, 0xFF, 0xFC, + 0x3F, 0xFF, 0xFE, 0x1F, 0xFB, 0xFE, 0x07, 0xF8, 0x00, 0x7F, 0x00, 0x01, + 0xFF, 0xF0, 0x01, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0xC1, + 0xFE, 0x0F, 0xF1, 0xFC, 0x01, 0xFC, 0xFC, 0x00, 0x7E, 0xFC, 0x00, 0x1F, + 0xFC, 0x00, 0x07, 0xFE, 0x00, 0x03, 0xFF, 0x00, 0x01, 0xFF, 0x80, 0x00, + 0xFF, 0xC0, 0x00, 0x7F, 0xF0, 0x00, 0x7E, 0xF8, 0x00, 0x7E, 0x7F, 0x00, + 0x7F, 0x1F, 0xC0, 0xFF, 0x07, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0x80, 0x7F, + 0xFF, 0x00, 0x1F, 0xFF, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x07, 0xE0, 0x03, + 0xF9, 0xFF, 0xC0, 0x7F, 0xBF, 0xFE, 0x07, 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, + 0xFF, 0xC3, 0xFF, 0x83, 0xFC, 0x0F, 0xE0, 0x0F, 0xE0, 0xFC, 0x00, 0x7E, + 0x0F, 0xC0, 0x03, 0xF0, 0xF8, 0x00, 0x1F, 0x0F, 0x80, 0x01, 0xF0, 0xF8, + 0x00, 0x1F, 0x0F, 0x80, 0x01, 0xF0, 0xF8, 0x00, 0x3F, 0x0F, 0xC0, 0x03, + 0xF0, 0xFE, 0x00, 0x7E, 0x0F, 0xF8, 0x1F, 0xE0, 0xFF, 0xFF, 0xFC, 0x0F, + 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xF0, 0x0F, 0x9F, 0xFC, 0x00, 0xF8, 0x7F, + 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x7F, 0xF8, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0xFF, 0xFC, + 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x7F, 0xF8, 0x00, 0x00, 0x00, 0x7E, 0x00, + 0x00, 0x3F, 0xF9, 0xFC, 0x0F, 0xFF, 0xDF, 0xE1, 0xFF, 0xFF, 0xFE, 0x3F, + 0xFF, 0xFF, 0xE3, 0xF8, 0x1F, 0xFC, 0x7F, 0x00, 0x7F, 0x07, 0xC0, 0x03, + 0xF0, 0xFC, 0x00, 0x3F, 0x0F, 0x80, 0x01, 0xF0, 0xF8, 0x00, 0x1F, 0x0F, + 0x80, 0x01, 0xF0, 0xF8, 0x00, 0x1F, 0x0F, 0xC0, 0x01, 0xF0, 0xFC, 0x00, + 0x3F, 0x07, 0xE0, 0x07, 0xF0, 0x7F, 0x81, 0xFF, 0x03, 0xFF, 0xFF, 0xF0, + 0x1F, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xF0, 0x03, 0xFF, 0x9F, 0x00, 0x0F, + 0xE1, 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xFF, 0xE0, 0x00, 0x3F, 0xFF, 0x00, + 0x03, 0xFF, 0xF0, 0x00, 0x3F, 0xFF, 0x00, 0x01, 0xFF, 0xE0, 0x00, 0x01, + 0xF0, 0x3F, 0xC7, 0xFC, 0x7F, 0xCF, 0xFE, 0x7F, 0xDF, 0xFF, 0x7F, 0xFF, + 0xFF, 0x3F, 0xFF, 0x0E, 0x07, 0xFC, 0x00, 0x07, 0xF8, 0x00, 0x07, 0xF0, + 0x00, 0x07, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x07, 0xC0, 0x00, 0x07, 0xC0, + 0x00, 0x07, 0xC0, 0x00, 0x07, 0xC0, 0x00, 0x07, 0xC0, 0x00, 0x07, 0xC0, + 0x00, 0x7F, 0xFF, 0xC0, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, + 0xE0, 0x7F, 0xFF, 0xC0, 0x03, 0xFC, 0x60, 0x7F, 0xFF, 0x87, 0xFF, 0xFC, + 0x7F, 0xFF, 0xE7, 0xFF, 0xFF, 0x3F, 0x01, 0xF9, 0xF0, 0x07, 0xCF, 0xC0, + 0x1C, 0x7F, 0xF0, 0x03, 0xFF, 0xF8, 0x0F, 0xFF, 0xF0, 0x3F, 0xFF, 0xC0, + 0x3F, 0xFF, 0x00, 0x0F, 0xFD, 0xC0, 0x07, 0xFE, 0x00, 0x1F, 0xF8, 0x00, + 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0xFD, 0xFF, 0xFF, 0xEF, 0xFF, 0xFE, 0x3F, + 0xFF, 0xC0, 0x07, 0xF8, 0x00, 0x07, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0xFF, + 0xF8, 0x7F, 0xFF, 0xF8, 0xFF, 0xFF, 0xF1, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, + 0x80, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, + 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x03, 0x83, 0xF0, 0x1F, 0x87, + 0xFF, 0xFF, 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xF8, 0x07, 0xFF, 0xC0, 0x03, + 0xFC, 0x00, 0x7F, 0x01, 0xFE, 0x7F, 0x81, 0xFF, 0x3F, 0xC0, 0xFF, 0x9F, + 0xE0, 0x7F, 0xC7, 0xF0, 0x1F, 0xE0, 0xF8, 0x01, 0xF0, 0x7C, 0x00, 0xF8, + 0x3E, 0x00, 0x7C, 0x1F, 0x00, 0x3E, 0x0F, 0x80, 0x1F, 0x07, 0xC0, 0x0F, + 0x83, 0xE0, 0x07, 0xC1, 0xF0, 0x03, 0xE0, 0xF8, 0x01, 0xF0, 0x7C, 0x01, + 0xF8, 0x3F, 0x01, 0xFC, 0x1F, 0xC1, 0xFF, 0x07, 0xFF, 0xFF, 0xC3, 0xFF, + 0xFF, 0xE0, 0xFF, 0xF7, 0xF0, 0x3F, 0xF3, 0xF0, 0x03, 0xF0, 0x00, 0x7F, + 0xE0, 0x7F, 0xEF, 0xFF, 0x0F, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0x0F, + 0xFF, 0x7F, 0xE0, 0x7F, 0xE0, 0xF8, 0x01, 0xF0, 0x0F, 0xC0, 0x1F, 0x00, + 0x7C, 0x03, 0xE0, 0x07, 0xE0, 0x3E, 0x00, 0x3E, 0x07, 0xC0, 0x03, 0xF0, + 0x7C, 0x00, 0x1F, 0x0F, 0x80, 0x01, 0xF8, 0xF8, 0x00, 0x0F, 0x9F, 0x00, + 0x00, 0xFD, 0xF0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0x03, + 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x1F, 0x80, + 0x00, 0x7F, 0x80, 0x1F, 0xEF, 0xFC, 0x03, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, + 0xFC, 0x03, 0xFF, 0x7F, 0x80, 0x1F, 0xE1, 0xF0, 0xF8, 0x7C, 0x1F, 0x1F, + 0x87, 0xC1, 0xF1, 0xF8, 0xFC, 0x1F, 0x1F, 0xCF, 0x80, 0xFB, 0xFC, 0xF8, + 0x0F, 0xBF, 0xDF, 0x80, 0xFB, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0x00, 0x7F, + 0xDF, 0xF0, 0x07, 0xF9, 0xFF, 0x00, 0x7F, 0x9F, 0xE0, 0x07, 0xF0, 0xFE, + 0x00, 0x3F, 0x0F, 0xE0, 0x03, 0xF0, 0x7E, 0x00, 0x3E, 0x07, 0xC0, 0x03, + 0xE0, 0x3C, 0x00, 0x3F, 0xC0, 0xFF, 0x1F, 0xF8, 0x7F, 0xE7, 0xFE, 0x1F, + 0xF9, 0xFF, 0x87, 0xFE, 0x3F, 0xC0, 0xFF, 0x03, 0xF8, 0x7F, 0x00, 0x7F, + 0x3F, 0x80, 0x0F, 0xFF, 0xC0, 0x01, 0xFF, 0xE0, 0x00, 0x3F, 0xE0, 0x00, + 0x07, 0xF8, 0x00, 0x07, 0xFF, 0x00, 0x03, 0xFF, 0xE0, 0x01, 0xFF, 0xFE, + 0x00, 0xFE, 0x1F, 0xC0, 0x7F, 0x03, 0xF8, 0x7F, 0xC0, 0xFF, 0xBF, 0xF8, + 0x7F, 0xFF, 0xFE, 0x1F, 0xFF, 0xFF, 0x87, 0xFF, 0x7F, 0xC0, 0xFF, 0x80, + 0x7F, 0x80, 0x7F, 0xBF, 0xF0, 0x3F, 0xFF, 0xFC, 0x0F, 0xFF, 0xFF, 0x03, + 0xFF, 0x7F, 0x80, 0x7F, 0x8F, 0xC0, 0x07, 0x81, 0xF0, 0x03, 0xE0, 0x7E, + 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xF0, 0x3E, 0x00, 0x7C, 0x0F, 0x80, + 0x0F, 0x87, 0xC0, 0x03, 0xE1, 0xF0, 0x00, 0x7C, 0xF8, 0x00, 0x1F, 0xFE, + 0x00, 0x03, 0xFF, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x80, 0x00, + 0x07, 0xC0, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x1F, 0xFF, 0x80, + 0x0F, 0xFF, 0xF0, 0x03, 0xFF, 0xFC, 0x00, 0xFF, 0xFF, 0x00, 0x1F, 0xFF, + 0x80, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xF0, 0x3F, 0xBE, 0x0F, 0xC3, 0x83, 0xF0, 0x00, 0xFC, 0x00, + 0x3F, 0x00, 0x0F, 0xC0, 0x03, 0xF0, 0x00, 0xFC, 0x00, 0x3F, 0x00, 0x0F, + 0xC0, 0x3B, 0xF0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x78, 0x03, 0xF0, 0x1F, 0xC0, 0xFF, 0x07, + 0xF8, 0x1F, 0x80, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, + 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x0F, 0x81, 0xFE, 0x0F, + 0xF0, 0x3F, 0x80, 0xFF, 0x01, 0xFE, 0x00, 0xFC, 0x01, 0xF0, 0x07, 0xC0, + 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF8, + 0x07, 0xF8, 0x0F, 0xF0, 0x3F, 0xC0, 0x7F, 0x00, 0x78, 0x77, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xE0, 0x78, 0x03, 0xF0, 0x0F, + 0xE0, 0x3F, 0xC0, 0x7F, 0x00, 0x7E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, + 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, + 0x07, 0xC0, 0x1F, 0xE0, 0x3F, 0xC0, 0x7F, 0x03, 0xFC, 0x1F, 0xE0, 0xFC, + 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, + 0x00, 0xF8, 0x07, 0xE0, 0x7F, 0x83, 0xFC, 0x0F, 0xF0, 0x3F, 0x80, 0x78, + 0x00, 0x07, 0x80, 0x00, 0x7F, 0x80, 0x03, 0xFF, 0x03, 0x9F, 0xFE, 0x1F, + 0xFF, 0xFC, 0xFF, 0xF3, 0xFF, 0xFF, 0x87, 0xFF, 0x9C, 0x0F, 0xFC, 0x00, + 0x0F, 0xE0, 0x00, 0x1F, 0x00 }; + +const GFXglyph FreeMonoBold24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 28, 0, 1 }, // 0x20 ' ' + { 0, 7, 31, 28, 10, -29 }, // 0x21 '!' + { 28, 15, 14, 28, 6, -28 }, // 0x22 '"' + { 55, 22, 34, 28, 3, -30 }, // 0x23 '#' + { 149, 19, 38, 28, 5, -31 }, // 0x24 '$' + { 240, 21, 30, 28, 4, -28 }, // 0x25 '%' + { 319, 21, 28, 28, 4, -26 }, // 0x26 '&' + { 393, 6, 14, 28, 11, -28 }, // 0x27 ''' + { 404, 10, 37, 28, 12, -29 }, // 0x28 '(' + { 451, 10, 37, 28, 6, -29 }, // 0x29 ')' + { 498, 21, 19, 28, 4, -28 }, // 0x2A '*' + { 548, 23, 26, 28, 3, -25 }, // 0x2B '+' + { 623, 9, 14, 28, 7, -6 }, // 0x2C ',' + { 639, 24, 5, 28, 2, -15 }, // 0x2D '-' + { 654, 7, 6, 28, 11, -4 }, // 0x2E '.' + { 660, 20, 38, 28, 4, -32 }, // 0x2F '/' + { 755, 21, 31, 28, 4, -29 }, // 0x30 '0' + { 837, 20, 29, 28, 4, -28 }, // 0x31 '1' + { 910, 21, 30, 28, 3, -29 }, // 0x32 '2' + { 989, 21, 31, 28, 4, -29 }, // 0x33 '3' + { 1071, 20, 28, 28, 4, -27 }, // 0x34 '4' + { 1141, 21, 31, 28, 4, -29 }, // 0x35 '5' + { 1223, 20, 31, 28, 5, -29 }, // 0x36 '6' + { 1301, 20, 30, 28, 4, -29 }, // 0x37 '7' + { 1376, 20, 31, 28, 4, -29 }, // 0x38 '8' + { 1454, 20, 31, 28, 5, -29 }, // 0x39 '9' + { 1532, 7, 22, 28, 11, -20 }, // 0x3A ':' + { 1552, 10, 28, 28, 6, -20 }, // 0x3B ';' + { 1587, 24, 21, 28, 2, -23 }, // 0x3C '<' + { 1650, 24, 14, 28, 2, -19 }, // 0x3D '=' + { 1692, 23, 22, 28, 3, -23 }, // 0x3E '>' + { 1756, 20, 29, 28, 5, -27 }, // 0x3F '?' + { 1829, 19, 36, 28, 4, -28 }, // 0x40 '@' + { 1915, 29, 27, 28, -1, -26 }, // 0x41 'A' + { 2013, 26, 27, 28, 1, -26 }, // 0x42 'B' + { 2101, 25, 29, 28, 2, -27 }, // 0x43 'C' + { 2192, 25, 27, 28, 1, -26 }, // 0x44 'D' + { 2277, 25, 27, 28, 1, -26 }, // 0x45 'E' + { 2362, 25, 27, 28, 1, -26 }, // 0x46 'F' + { 2447, 25, 29, 28, 2, -27 }, // 0x47 'G' + { 2538, 26, 27, 28, 1, -26 }, // 0x48 'H' + { 2626, 19, 27, 28, 5, -26 }, // 0x49 'I' + { 2691, 25, 28, 28, 3, -26 }, // 0x4A 'J' + { 2779, 27, 27, 28, 1, -26 }, // 0x4B 'K' + { 2871, 25, 27, 28, 2, -26 }, // 0x4C 'L' + { 2956, 31, 27, 28, -1, -26 }, // 0x4D 'M' + { 3061, 28, 27, 28, 0, -26 }, // 0x4E 'N' + { 3156, 27, 29, 28, 1, -27 }, // 0x4F 'O' + { 3254, 24, 27, 28, 1, -26 }, // 0x50 'P' + { 3335, 27, 35, 28, 1, -27 }, // 0x51 'Q' + { 3454, 28, 27, 28, 0, -26 }, // 0x52 'R' + { 3549, 22, 29, 28, 3, -27 }, // 0x53 'S' + { 3629, 25, 27, 28, 2, -26 }, // 0x54 'T' + { 3714, 28, 28, 28, 0, -26 }, // 0x55 'U' + { 3812, 30, 27, 28, -1, -26 }, // 0x56 'V' + { 3914, 28, 27, 28, 0, -26 }, // 0x57 'W' + { 4009, 26, 27, 28, 1, -26 }, // 0x58 'X' + { 4097, 26, 27, 28, 1, -26 }, // 0x59 'Y' + { 4185, 21, 27, 28, 4, -26 }, // 0x5A 'Z' + { 4256, 10, 37, 28, 12, -29 }, // 0x5B '[' + { 4303, 20, 38, 28, 4, -32 }, // 0x5C '\' + { 4398, 10, 37, 28, 6, -29 }, // 0x5D ']' + { 4445, 20, 15, 28, 4, -29 }, // 0x5E '^' + { 4483, 28, 5, 28, 0, 5 }, // 0x5F '_' + { 4501, 9, 8, 28, 8, -30 }, // 0x60 '`' + { 4510, 24, 23, 28, 2, -21 }, // 0x61 'a' + { 4579, 27, 31, 28, 0, -29 }, // 0x62 'b' + { 4684, 24, 23, 28, 3, -21 }, // 0x63 'c' + { 4753, 26, 31, 28, 2, -29 }, // 0x64 'd' + { 4854, 24, 23, 28, 2, -21 }, // 0x65 'e' + { 4923, 22, 30, 28, 4, -29 }, // 0x66 'f' + { 5006, 25, 31, 28, 2, -21 }, // 0x67 'g' + { 5103, 26, 30, 28, 1, -29 }, // 0x68 'h' + { 5201, 21, 29, 28, 4, -28 }, // 0x69 'i' + { 5278, 17, 38, 28, 5, -28 }, // 0x6A 'j' + { 5359, 25, 30, 28, 2, -29 }, // 0x6B 'k' + { 5453, 21, 30, 28, 4, -29 }, // 0x6C 'l' + { 5532, 30, 22, 28, -1, -21 }, // 0x6D 'm' + { 5615, 25, 22, 28, 1, -21 }, // 0x6E 'n' + { 5684, 25, 23, 28, 2, -21 }, // 0x6F 'o' + { 5756, 28, 31, 28, 0, -21 }, // 0x70 'p' + { 5865, 28, 31, 28, 1, -21 }, // 0x71 'q' + { 5974, 24, 22, 28, 3, -21 }, // 0x72 'r' + { 6040, 21, 23, 28, 4, -21 }, // 0x73 's' + { 6101, 23, 28, 28, 1, -26 }, // 0x74 't' + { 6182, 25, 22, 28, 1, -20 }, // 0x75 'u' + { 6251, 28, 21, 28, 0, -20 }, // 0x76 'v' + { 6325, 28, 21, 28, 0, -20 }, // 0x77 'w' + { 6399, 26, 21, 28, 1, -20 }, // 0x78 'x' + { 6468, 26, 30, 28, 1, -20 }, // 0x79 'y' + { 6566, 19, 21, 28, 5, -20 }, // 0x7A 'z' + { 6616, 14, 37, 28, 7, -29 }, // 0x7B '{' + { 6681, 5, 36, 28, 12, -28 }, // 0x7C '|' + { 6704, 14, 37, 28, 8, -29 }, // 0x7D '}' + { 6769, 22, 10, 28, 3, -17 } }; // 0x7E '~' + +const GFXfont FreeMonoBold24pt7b PROGMEM = { + (uint8_t *)FreeMonoBold24pt7bBitmaps, + (GFXglyph *)FreeMonoBold24pt7bGlyphs, + 0x20, 0x7E, 47 }; + +// Approx. 7469 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBold9pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBold9pt7b.h new file mode 100644 index 0000000..75b1766 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBold9pt7b.h @@ -0,0 +1,189 @@ +const uint8_t FreeMonoBold9pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xD2, 0x1F, 0x80, 0xEC, 0x89, 0x12, 0x24, 0x40, 0x36, 0x36, + 0x36, 0x7F, 0x7F, 0x36, 0xFF, 0xFF, 0x3C, 0x3C, 0x3C, 0x00, 0x18, 0xFF, + 0xFE, 0x3C, 0x1F, 0x1F, 0x83, 0x46, 0x8D, 0xF0, 0xC1, 0x83, 0x00, 0x61, + 0x22, 0x44, 0x86, 0x67, 0x37, 0x11, 0x22, 0x4C, 0x70, 0x3C, 0x7E, 0x60, + 0x60, 0x30, 0x7B, 0xDF, 0xCE, 0xFF, 0x7F, 0xC9, 0x24, 0x37, 0x66, 0xCC, + 0xCC, 0xCC, 0x66, 0x31, 0xCE, 0x66, 0x33, 0x33, 0x33, 0x66, 0xC8, 0x18, + 0x18, 0xFF, 0xFF, 0x3C, 0x3C, 0x66, 0x18, 0x18, 0x18, 0xFF, 0xFF, 0x18, + 0x18, 0x18, 0x18, 0x6B, 0x48, 0xFF, 0xFF, 0xC0, 0xF0, 0x02, 0x0C, 0x18, + 0x60, 0xC3, 0x06, 0x0C, 0x30, 0x61, 0x83, 0x0C, 0x18, 0x20, 0x00, 0x38, + 0xFB, 0xBE, 0x3C, 0x78, 0xF1, 0xE3, 0xC7, 0xDD, 0xF1, 0xC0, 0x38, 0xF3, + 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0xFD, 0xF8, 0x3C, 0xFE, 0xC7, 0x03, + 0x03, 0x06, 0x0C, 0x18, 0x70, 0xE3, 0xFF, 0xFF, 0x7C, 0xFE, 0x03, 0x03, + 0x03, 0x1E, 0x1E, 0x07, 0x03, 0x03, 0xFE, 0x7C, 0x1C, 0x38, 0xB1, 0x64, + 0xD9, 0xBF, 0xFF, 0x3E, 0x7C, 0x7E, 0x3F, 0x18, 0x0F, 0xC7, 0xF3, 0x1C, + 0x06, 0x03, 0xC3, 0xFF, 0x9F, 0x80, 0x0F, 0x3F, 0x30, 0x60, 0x60, 0xDC, + 0xFE, 0xE3, 0xC3, 0x63, 0x7E, 0x3C, 0xFF, 0xFF, 0xC3, 0x03, 0x06, 0x06, + 0x06, 0x0C, 0x0C, 0x0C, 0x18, 0x38, 0xFB, 0x1E, 0x3C, 0x6F, 0x9F, 0x63, + 0xC7, 0x8F, 0xF1, 0xC0, 0x3C, 0x7E, 0xE6, 0xC3, 0xC3, 0xE7, 0x7F, 0x3B, + 0x06, 0x0E, 0xFC, 0xF0, 0xF0, 0x0F, 0x6C, 0x00, 0x1A, 0xD2, 0x00, 0x01, + 0x83, 0x87, 0x0E, 0x0F, 0x80, 0xE0, 0x1C, 0x03, 0xFF, 0xFF, 0xC0, 0x00, + 0x0F, 0xFF, 0xFC, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0xF9, 0xE3, 0xC1, 0x80, + 0x7C, 0xFE, 0xC7, 0x03, 0x0E, 0x1C, 0x00, 0x00, 0x00, 0x30, 0x30, 0x1E, + 0x1F, 0x1C, 0xDC, 0x6C, 0x76, 0x7B, 0x6D, 0xB6, 0xDB, 0x6F, 0xF3, 0xFC, + 0x06, 0x33, 0xF8, 0x78, 0x3C, 0x07, 0xC0, 0x38, 0x05, 0x81, 0xB0, 0x36, + 0x0F, 0xE1, 0xFC, 0x71, 0xDF, 0x7F, 0xEF, 0x80, 0xFF, 0x3F, 0xE6, 0x19, + 0x86, 0x7F, 0x1F, 0xE6, 0x1D, 0x83, 0x60, 0xFF, 0xFF, 0xF0, 0x1F, 0xBF, + 0xD8, 0xF8, 0x3C, 0x06, 0x03, 0x01, 0x80, 0x61, 0xBF, 0xC7, 0xC0, 0xFE, + 0x3F, 0xE6, 0x19, 0x83, 0x60, 0xD8, 0x36, 0x0D, 0x83, 0x61, 0xBF, 0xEF, + 0xE0, 0xFF, 0xFF, 0xD8, 0x6D, 0xB7, 0xC3, 0xE1, 0xB0, 0xC3, 0x61, 0xFF, + 0xFF, 0xE0, 0xFF, 0xFF, 0xD8, 0x6D, 0xB7, 0xC3, 0xE1, 0xB0, 0xC0, 0x60, + 0x7C, 0x3E, 0x00, 0x1F, 0x9F, 0xE6, 0x1B, 0x06, 0xC0, 0x30, 0x0C, 0x7F, + 0x1F, 0xE1, 0x9F, 0xE3, 0xF0, 0xF7, 0xFB, 0xD8, 0xCC, 0x66, 0x33, 0xF9, + 0xFC, 0xC6, 0x63, 0x7B, 0xFD, 0xE0, 0xFF, 0xF3, 0x0C, 0x30, 0xC3, 0x0C, + 0x33, 0xFF, 0xC0, 0x1F, 0xC7, 0xF0, 0x30, 0x0C, 0x03, 0x00, 0xCC, 0x33, + 0x0C, 0xC7, 0x3F, 0x87, 0xC0, 0xF7, 0xBD, 0xE6, 0x61, 0xB0, 0x78, 0x1F, + 0x06, 0xE1, 0x98, 0x63, 0x3C, 0xFF, 0x3C, 0xFC, 0x7E, 0x0C, 0x06, 0x03, + 0x01, 0x80, 0xC6, 0x63, 0x31, 0xFF, 0xFF, 0xE0, 0xE0, 0xFE, 0x3D, 0xC7, + 0x3D, 0xE7, 0xBC, 0xD7, 0x9B, 0xB3, 0x76, 0x60, 0xDE, 0x3F, 0xC7, 0x80, + 0xE1, 0xFE, 0x3D, 0xE3, 0x3C, 0x66, 0xCC, 0xDD, 0x99, 0xB3, 0x1E, 0x63, + 0xDE, 0x3B, 0xC3, 0x00, 0x1F, 0x07, 0xF1, 0xC7, 0x70, 0x7C, 0x07, 0x80, + 0xF0, 0x1F, 0x07, 0x71, 0xC7, 0xF0, 0x7C, 0x00, 0xFE, 0x7F, 0x98, 0x6C, + 0x36, 0x1B, 0xF9, 0xF8, 0xC0, 0x60, 0x7C, 0x3E, 0x00, 0x1F, 0x07, 0xF1, + 0xC7, 0x70, 0x7C, 0x07, 0x80, 0xF0, 0x1F, 0x07, 0x71, 0xC7, 0xF0, 0x7C, + 0x0C, 0x33, 0xFE, 0x7F, 0x80, 0xFC, 0x7F, 0x18, 0xCC, 0x66, 0x73, 0xF1, + 0xF0, 0xCC, 0x63, 0x7D, 0xFE, 0x60, 0x3F, 0xBF, 0xF0, 0x78, 0x0F, 0x03, + 0xF8, 0x3F, 0x83, 0xC3, 0xFF, 0xBF, 0x80, 0xFF, 0xFF, 0xF6, 0x7B, 0x3D, + 0x98, 0xC0, 0x60, 0x30, 0x18, 0x3F, 0x1F, 0x80, 0xF1, 0xFE, 0x3D, 0x83, + 0x30, 0x66, 0x0C, 0xC1, 0x98, 0x33, 0x06, 0x60, 0xC7, 0xF0, 0x7C, 0x00, + 0xFB, 0xFF, 0x7D, 0xC3, 0x18, 0xC3, 0x18, 0x36, 0x06, 0xC0, 0x50, 0x0E, + 0x01, 0xC0, 0x10, 0x00, 0xFB, 0xFE, 0xF6, 0x0D, 0x93, 0x6E, 0xDB, 0xB7, + 0xAD, 0xEE, 0x7B, 0x8E, 0xE3, 0x18, 0xF3, 0xFC, 0xF7, 0x38, 0xFC, 0x1E, + 0x03, 0x01, 0xE0, 0xCC, 0x73, 0xBC, 0xFF, 0x3C, 0xF3, 0xFC, 0xF7, 0x38, + 0xCC, 0x1E, 0x07, 0x80, 0xC0, 0x30, 0x0C, 0x0F, 0xC3, 0xF0, 0xFE, 0xFE, + 0xC6, 0xCC, 0x18, 0x18, 0x30, 0x63, 0xC3, 0xFF, 0xFF, 0xFF, 0xCC, 0xCC, + 0xCC, 0xCC, 0xCC, 0xFF, 0x01, 0x03, 0x06, 0x06, 0x0C, 0x0C, 0x18, 0x18, + 0x30, 0x30, 0x60, 0x60, 0xC0, 0x80, 0xFF, 0x33, 0x33, 0x33, 0x33, 0x33, + 0xFF, 0x10, 0x71, 0xE3, 0x6C, 0x70, 0x40, 0xFF, 0xFF, 0xFC, 0x88, 0x80, + 0x7E, 0x3F, 0x8F, 0xCF, 0xEE, 0x36, 0x1B, 0xFE, 0xFF, 0xE0, 0x38, 0x06, + 0x01, 0xBC, 0x7F, 0x9C, 0x76, 0x0D, 0x83, 0x71, 0xFF, 0xEE, 0xF0, 0x3F, + 0xBF, 0xF8, 0x78, 0x3C, 0x07, 0x05, 0xFE, 0x7E, 0x03, 0x80, 0xE0, 0x18, + 0xF6, 0x7F, 0xB8, 0xEC, 0x1B, 0x06, 0xE3, 0x9F, 0xF3, 0xFC, 0x3E, 0x3F, + 0xB0, 0xFF, 0xFF, 0xFE, 0x01, 0xFE, 0x7E, 0x1F, 0x3F, 0x30, 0x7E, 0x7E, + 0x30, 0x30, 0x30, 0x30, 0xFE, 0xFE, 0x3F, 0xBF, 0xF9, 0xD8, 0x6C, 0x37, + 0x39, 0xFC, 0x76, 0x03, 0x01, 0x8F, 0xC7, 0xC0, 0xE0, 0x70, 0x18, 0x0D, + 0xC7, 0xF3, 0x99, 0x8C, 0xC6, 0x63, 0x7B, 0xFD, 0xE0, 0x18, 0x18, 0x00, + 0x78, 0x78, 0x18, 0x18, 0x18, 0x18, 0xFF, 0xFF, 0x18, 0x60, 0x3F, 0xFC, + 0x30, 0xC3, 0x0C, 0x30, 0xC3, 0x0F, 0xFF, 0x80, 0xE0, 0x70, 0x18, 0x0D, + 0xE6, 0xF3, 0xE1, 0xE0, 0xF8, 0x6E, 0x73, 0xF9, 0xE0, 0x78, 0x78, 0x18, + 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0xFF, 0xFF, 0xFD, 0x9F, 0xF9, 0x9B, + 0x33, 0x66, 0x6C, 0xCD, 0xBD, 0xFF, 0xBF, 0xEE, 0x7F, 0x98, 0xCC, 0x66, + 0x33, 0x1B, 0xDF, 0xEF, 0x3E, 0x3F, 0xB8, 0xF8, 0x3C, 0x1F, 0x1D, 0xFC, + 0x7C, 0xEF, 0x1F, 0xF9, 0xC3, 0xB0, 0x36, 0x06, 0xE1, 0xDF, 0xF3, 0x78, + 0x60, 0x0C, 0x03, 0xE0, 0x7C, 0x00, 0x1E, 0xEF, 0xFF, 0x87, 0x60, 0x6C, + 0x0D, 0xC3, 0x9F, 0xF0, 0xF6, 0x00, 0xC0, 0x18, 0x0F, 0x81, 0xF0, 0x77, + 0xBF, 0xCF, 0x06, 0x03, 0x01, 0x83, 0xF9, 0xFC, 0x3F, 0xFF, 0xC3, 0xFC, + 0x3F, 0xC3, 0xFF, 0xFC, 0x60, 0x60, 0x60, 0xFE, 0xFE, 0x60, 0x60, 0x60, + 0x61, 0x7F, 0x3E, 0xE7, 0x73, 0x98, 0xCC, 0x66, 0x33, 0x19, 0xFE, 0x7F, + 0xFB, 0xFF, 0x7C, 0xC6, 0x18, 0xC1, 0xB0, 0x36, 0x03, 0x80, 0x70, 0xF1, + 0xFE, 0x3D, 0xBB, 0x37, 0x63, 0xF8, 0x77, 0x0E, 0xE1, 0x8C, 0xF7, 0xFB, + 0xCD, 0x83, 0x83, 0xC3, 0xBB, 0xDF, 0xEF, 0xF3, 0xFC, 0xF6, 0x18, 0xCC, + 0x33, 0x07, 0x81, 0xE0, 0x30, 0x0C, 0x06, 0x0F, 0xC3, 0xF0, 0xFF, 0xFF, + 0x30, 0xC3, 0x0C, 0x7F, 0xFF, 0x37, 0x66, 0x66, 0xCC, 0x66, 0x66, 0x73, + 0xFF, 0xFF, 0xFF, 0xF0, 0xCE, 0x66, 0x66, 0x33, 0x66, 0x66, 0xEC, 0x70, + 0x7C, 0xF3, 0xC0, 0xC0 }; + +const GFXglyph FreeMonoBold9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 11, 0, 1 }, // 0x20 ' ' + { 0, 3, 11, 11, 4, -10 }, // 0x21 '!' + { 5, 7, 5, 11, 2, -10 }, // 0x22 '"' + { 10, 8, 12, 11, 1, -10 }, // 0x23 '#' + { 22, 7, 14, 11, 2, -11 }, // 0x24 '$' + { 35, 7, 11, 11, 2, -10 }, // 0x25 '%' + { 45, 8, 10, 11, 1, -9 }, // 0x26 '&' + { 55, 3, 5, 11, 4, -10 }, // 0x27 ''' + { 57, 4, 14, 11, 5, -10 }, // 0x28 '(' + { 64, 4, 14, 11, 2, -10 }, // 0x29 ')' + { 71, 8, 7, 11, 2, -10 }, // 0x2A '*' + { 78, 8, 9, 11, 2, -8 }, // 0x2B '+' + { 87, 3, 5, 11, 3, -1 }, // 0x2C ',' + { 89, 9, 2, 11, 1, -5 }, // 0x2D '-' + { 92, 2, 2, 11, 4, -1 }, // 0x2E '.' + { 93, 7, 15, 11, 2, -12 }, // 0x2F '/' + { 107, 7, 12, 11, 2, -11 }, // 0x30 '0' + { 118, 7, 11, 11, 2, -10 }, // 0x31 '1' + { 128, 8, 12, 11, 1, -11 }, // 0x32 '2' + { 140, 8, 12, 11, 2, -11 }, // 0x33 '3' + { 152, 7, 10, 11, 2, -9 }, // 0x34 '4' + { 161, 9, 11, 11, 1, -10 }, // 0x35 '5' + { 174, 8, 12, 11, 2, -11 }, // 0x36 '6' + { 186, 8, 11, 11, 1, -10 }, // 0x37 '7' + { 197, 7, 12, 11, 2, -11 }, // 0x38 '8' + { 208, 8, 12, 11, 2, -11 }, // 0x39 '9' + { 220, 2, 8, 11, 4, -7 }, // 0x3A ':' + { 222, 3, 11, 11, 3, -7 }, // 0x3B ';' + { 227, 9, 8, 11, 1, -8 }, // 0x3C '<' + { 236, 9, 6, 11, 1, -7 }, // 0x3D '=' + { 243, 9, 8, 11, 1, -8 }, // 0x3E '>' + { 252, 8, 11, 11, 2, -10 }, // 0x3F '?' + { 263, 9, 15, 11, 1, -11 }, // 0x40 '@' + { 280, 11, 11, 11, 0, -10 }, // 0x41 'A' + { 296, 10, 11, 11, 1, -10 }, // 0x42 'B' + { 310, 9, 11, 11, 1, -10 }, // 0x43 'C' + { 323, 10, 11, 11, 0, -10 }, // 0x44 'D' + { 337, 9, 11, 11, 1, -10 }, // 0x45 'E' + { 350, 9, 11, 11, 1, -10 }, // 0x46 'F' + { 363, 10, 11, 11, 1, -10 }, // 0x47 'G' + { 377, 9, 11, 11, 1, -10 }, // 0x48 'H' + { 390, 6, 11, 11, 3, -10 }, // 0x49 'I' + { 399, 10, 11, 11, 1, -10 }, // 0x4A 'J' + { 413, 10, 11, 11, 1, -10 }, // 0x4B 'K' + { 427, 9, 11, 11, 1, -10 }, // 0x4C 'L' + { 440, 11, 11, 11, 0, -10 }, // 0x4D 'M' + { 456, 11, 11, 11, 0, -10 }, // 0x4E 'N' + { 472, 11, 11, 11, 0, -10 }, // 0x4F 'O' + { 488, 9, 11, 11, 1, -10 }, // 0x50 'P' + { 501, 11, 14, 11, 0, -10 }, // 0x51 'Q' + { 521, 9, 11, 11, 1, -10 }, // 0x52 'R' + { 534, 9, 11, 11, 1, -10 }, // 0x53 'S' + { 547, 9, 11, 11, 1, -10 }, // 0x54 'T' + { 560, 11, 11, 11, 0, -10 }, // 0x55 'U' + { 576, 11, 11, 11, 0, -10 }, // 0x56 'V' + { 592, 10, 11, 11, 0, -10 }, // 0x57 'W' + { 606, 10, 11, 11, 0, -10 }, // 0x58 'X' + { 620, 10, 11, 11, 0, -10 }, // 0x59 'Y' + { 634, 8, 11, 11, 2, -10 }, // 0x5A 'Z' + { 645, 4, 14, 11, 5, -10 }, // 0x5B '[' + { 652, 7, 15, 11, 2, -12 }, // 0x5C '\' + { 666, 4, 14, 11, 2, -10 }, // 0x5D ']' + { 673, 7, 6, 11, 2, -11 }, // 0x5E '^' + { 679, 11, 2, 11, 0, 3 }, // 0x5F '_' + { 682, 3, 3, 11, 3, -11 }, // 0x60 '`' + { 684, 9, 8, 11, 1, -7 }, // 0x61 'a' + { 693, 10, 11, 11, 0, -10 }, // 0x62 'b' + { 707, 9, 8, 11, 1, -7 }, // 0x63 'c' + { 716, 10, 11, 11, 1, -10 }, // 0x64 'd' + { 730, 9, 8, 11, 1, -7 }, // 0x65 'e' + { 739, 8, 11, 11, 2, -10 }, // 0x66 'f' + { 750, 9, 12, 11, 1, -7 }, // 0x67 'g' + { 764, 9, 11, 11, 1, -10 }, // 0x68 'h' + { 777, 8, 11, 11, 2, -10 }, // 0x69 'i' + { 788, 6, 15, 11, 2, -10 }, // 0x6A 'j' + { 800, 9, 11, 11, 1, -10 }, // 0x6B 'k' + { 813, 8, 11, 11, 2, -10 }, // 0x6C 'l' + { 824, 11, 8, 11, 0, -7 }, // 0x6D 'm' + { 835, 9, 8, 11, 1, -7 }, // 0x6E 'n' + { 844, 9, 8, 11, 1, -7 }, // 0x6F 'o' + { 853, 11, 12, 11, 0, -7 }, // 0x70 'p' + { 870, 11, 12, 11, 0, -7 }, // 0x71 'q' + { 887, 9, 8, 11, 1, -7 }, // 0x72 'r' + { 896, 8, 8, 11, 2, -7 }, // 0x73 's' + { 904, 8, 11, 11, 1, -10 }, // 0x74 't' + { 915, 9, 8, 11, 1, -7 }, // 0x75 'u' + { 924, 11, 8, 11, 0, -7 }, // 0x76 'v' + { 935, 11, 8, 11, 0, -7 }, // 0x77 'w' + { 946, 9, 8, 11, 1, -7 }, // 0x78 'x' + { 955, 10, 12, 11, 0, -7 }, // 0x79 'y' + { 970, 7, 8, 11, 2, -7 }, // 0x7A 'z' + { 977, 4, 14, 11, 3, -10 }, // 0x7B '{' + { 984, 2, 14, 11, 5, -10 }, // 0x7C '|' + { 988, 4, 14, 11, 4, -10 }, // 0x7D '}' + { 995, 9, 4, 11, 1, -6 } }; // 0x7E '~' + +const GFXfont FreeMonoBold9pt7b PROGMEM = { + (uint8_t *)FreeMonoBold9pt7bBitmaps, + (GFXglyph *)FreeMonoBold9pt7bGlyphs, + 0x20, 0x7E, 18 }; + +// Approx. 1672 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique12pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique12pt7b.h new file mode 100644 index 0000000..cc3ecb2 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique12pt7b.h @@ -0,0 +1,269 @@ +const uint8_t FreeMonoBoldOblique12pt7bBitmaps[] PROGMEM = { + 0x1C, 0xF3, 0xCE, 0x38, 0xE7, 0x1C, 0x61, 0x86, 0x00, 0x63, 0x8C, 0x00, + 0xE7, 0xE7, 0xE6, 0xC6, 0xC6, 0xC4, 0x84, 0x03, 0x30, 0x19, 0x81, 0xDC, + 0x0C, 0xE0, 0x66, 0x1F, 0xFC, 0xFF, 0xE1, 0x98, 0x0C, 0xC0, 0xEE, 0x06, + 0x70, 0xFF, 0xCF, 0xFE, 0x1D, 0xC0, 0xCC, 0x06, 0x60, 0x77, 0x03, 0x30, + 0x00, 0x01, 0x00, 0x70, 0x0C, 0x07, 0xF1, 0xFE, 0x71, 0xCC, 0x11, 0x80, + 0x3F, 0x03, 0xF0, 0x0F, 0x20, 0x6E, 0x0D, 0xC3, 0x3F, 0xE7, 0xF8, 0x1C, + 0x03, 0x00, 0x60, 0x0C, 0x00, 0x0E, 0x03, 0xE0, 0xC4, 0x10, 0x82, 0x30, + 0x7C, 0x07, 0x78, 0x7C, 0x7F, 0x19, 0xF0, 0x62, 0x08, 0x41, 0x18, 0x3E, + 0x03, 0x80, 0x07, 0xC1, 0xF8, 0x62, 0x0C, 0x01, 0x80, 0x38, 0x0F, 0x03, + 0xF7, 0x6F, 0xD8, 0xF3, 0x1E, 0x7F, 0xE7, 0xF8, 0xFF, 0x6D, 0x20, 0x06, + 0x1C, 0x70, 0xC3, 0x06, 0x18, 0x30, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x30, + 0x70, 0x60, 0xC1, 0x00, 0x0C, 0x18, 0x38, 0x30, 0x60, 0xC1, 0x83, 0x06, + 0x0C, 0x30, 0x61, 0xC3, 0x0E, 0x38, 0x61, 0xC2, 0x00, 0x06, 0x00, 0xC0, + 0x18, 0x3F, 0x7F, 0xFE, 0xFF, 0x07, 0x81, 0xF8, 0x77, 0x0C, 0x60, 0x03, + 0x00, 0x70, 0x07, 0x00, 0x60, 0x06, 0x0F, 0xFF, 0xFF, 0xF0, 0xE0, 0x0C, + 0x00, 0xC0, 0x0C, 0x01, 0xC0, 0x18, 0x00, 0x1C, 0xE3, 0x1C, 0x63, 0x08, + 0x00, 0x7F, 0xFF, 0xFF, 0xC0, 0x7F, 0x00, 0x00, 0x08, 0x00, 0x70, 0x01, + 0x80, 0x0E, 0x00, 0x70, 0x03, 0x80, 0x0C, 0x00, 0x70, 0x03, 0x80, 0x0C, + 0x00, 0x70, 0x03, 0x80, 0x0C, 0x00, 0x70, 0x03, 0x80, 0x0C, 0x00, 0x70, + 0x03, 0x80, 0x0C, 0x00, 0x20, 0x00, 0x07, 0x83, 0xF8, 0xE3, 0x98, 0x37, + 0x06, 0xC0, 0xD8, 0x1B, 0x03, 0xE0, 0xF8, 0x1B, 0x03, 0x60, 0xEE, 0x38, + 0xFE, 0x0F, 0x00, 0x03, 0xC1, 0xF0, 0x7E, 0x0C, 0xC0, 0x38, 0x07, 0x00, + 0xC0, 0x18, 0x07, 0x00, 0xE0, 0x18, 0x03, 0x00, 0x61, 0xFF, 0xFF, 0xF0, + 0x03, 0xE0, 0x3F, 0x83, 0x8E, 0x38, 0x31, 0x81, 0x80, 0x18, 0x01, 0xC0, + 0x1C, 0x01, 0xC0, 0x38, 0x03, 0x80, 0x38, 0x47, 0x87, 0x3F, 0xF3, 0xFF, + 0x80, 0x07, 0xC1, 0xFF, 0x18, 0x70, 0x03, 0x00, 0x30, 0x06, 0x07, 0xC0, + 0x7C, 0x00, 0xE0, 0x06, 0x00, 0x60, 0x06, 0xC1, 0xCF, 0xF8, 0x7E, 0x00, + 0x01, 0xE0, 0x3C, 0x0F, 0x03, 0x60, 0xCC, 0x3B, 0x8E, 0x63, 0x8C, 0x61, + 0x9F, 0xFB, 0xFF, 0x01, 0x81, 0xF8, 0x3F, 0x00, 0x0F, 0xF1, 0xFE, 0x18, + 0x01, 0x80, 0x18, 0x03, 0xF8, 0x3F, 0xC3, 0x8E, 0x00, 0x60, 0x06, 0x00, + 0x60, 0x0C, 0xC1, 0xCF, 0xF8, 0x7E, 0x00, 0x03, 0xE1, 0xFC, 0x70, 0x1C, + 0x03, 0x00, 0xC0, 0x1B, 0xC7, 0xFC, 0xF3, 0x98, 0x33, 0x06, 0x60, 0xCE, + 0x30, 0xFC, 0x0F, 0x00, 0xFF, 0xFF, 0xFB, 0x07, 0x60, 0xC0, 0x38, 0x06, + 0x01, 0xC0, 0x30, 0x0E, 0x01, 0x80, 0x70, 0x1C, 0x03, 0x80, 0x60, 0x08, + 0x00, 0x07, 0x83, 0xF8, 0xE3, 0xB0, 0x36, 0x06, 0xC0, 0xDC, 0x31, 0xFC, + 0x3F, 0x8C, 0x3B, 0x03, 0x60, 0x6C, 0x39, 0xFE, 0x1F, 0x00, 0x07, 0x81, + 0xF8, 0x63, 0x98, 0x33, 0x06, 0x60, 0xCE, 0x79, 0xFF, 0x1E, 0xC0, 0x18, + 0x06, 0x01, 0xC0, 0x71, 0xFC, 0x3E, 0x00, 0x19, 0xCC, 0x00, 0x00, 0x00, + 0x67, 0x30, 0x06, 0x1C, 0x30, 0x00, 0x00, 0x00, 0x00, 0x38, 0x71, 0xC3, + 0x0E, 0x18, 0x20, 0x00, 0x00, 0x18, 0x03, 0xC0, 0x7C, 0x1F, 0x03, 0xE0, + 0x3E, 0x00, 0x7C, 0x01, 0xF0, 0x03, 0xE0, 0x07, 0x80, 0x08, 0x7F, 0xFB, + 0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFB, 0xFF, 0xC0, 0x30, 0x01, + 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x3E, 0x00, 0x7C, 0x1F, 0x03, 0xE0, 0x7C, + 0x07, 0x80, 0x20, 0x00, 0x3E, 0x7F, 0xB0, 0xF8, 0x30, 0x18, 0x1C, 0x1C, + 0x3C, 0x38, 0x18, 0x00, 0x06, 0x07, 0x03, 0x00, 0x03, 0xC0, 0x7E, 0x0C, + 0x71, 0x83, 0x30, 0x33, 0x0F, 0x33, 0xE6, 0x76, 0x6C, 0x66, 0xC6, 0x6C, + 0x6C, 0xFC, 0xC7, 0xEC, 0x00, 0xC0, 0x0C, 0x00, 0xE3, 0x07, 0xF0, 0x3C, + 0x00, 0x07, 0xF0, 0x1F, 0xE0, 0x07, 0xC0, 0x1F, 0x80, 0x3B, 0x00, 0xE7, + 0x01, 0x8E, 0x07, 0x1C, 0x1F, 0xF8, 0x3F, 0xF0, 0xE0, 0x71, 0x80, 0xEF, + 0xC7, 0xFF, 0x8F, 0xC0, 0x3F, 0xF1, 0xFF, 0xC3, 0x06, 0x38, 0x31, 0xC1, + 0x8C, 0x18, 0x7F, 0xC3, 0xFE, 0x38, 0x39, 0xC0, 0xCC, 0x06, 0x60, 0x6F, + 0xFF, 0x7F, 0xE0, 0x03, 0xEC, 0x3F, 0xF1, 0xC3, 0x8C, 0x06, 0x60, 0x19, + 0x80, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x03, 0x00, 0x0C, 0x03, 0x3C, 0x1C, + 0x7F, 0xE0, 0x7E, 0x00, 0x3F, 0xE1, 0xFF, 0x87, 0x0C, 0x30, 0x31, 0x81, + 0x8C, 0x0C, 0xE0, 0x67, 0x03, 0x30, 0x31, 0x81, 0x8C, 0x0C, 0xE1, 0xCF, + 0xFC, 0x7F, 0x80, 0x1F, 0xFE, 0x3F, 0xFC, 0x38, 0x38, 0x70, 0x70, 0xCC, + 0xC1, 0x98, 0x03, 0xF0, 0x0F, 0xE0, 0x1D, 0x80, 0x31, 0x18, 0x60, 0x70, + 0xC0, 0xE7, 0xFF, 0x9F, 0xFF, 0x00, 0x1F, 0xFF, 0x1F, 0xFE, 0x0E, 0x06, + 0x0C, 0x0E, 0x0C, 0xC4, 0x0C, 0xC0, 0x1F, 0xC0, 0x1F, 0xC0, 0x19, 0xC0, + 0x19, 0x80, 0x18, 0x00, 0x38, 0x00, 0xFF, 0x00, 0xFF, 0x00, 0x07, 0xEC, + 0x7F, 0xF3, 0x83, 0x9C, 0x06, 0x60, 0x19, 0x80, 0x0C, 0x00, 0x30, 0xFE, + 0xC3, 0xFB, 0x01, 0xCC, 0x07, 0x3C, 0x38, 0x7F, 0xE0, 0x7E, 0x00, 0x0F, + 0xBF, 0x1F, 0xBE, 0x0E, 0x0C, 0x0C, 0x0C, 0x0C, 0x1C, 0x0C, 0x1C, 0x1F, + 0xF8, 0x1F, 0xF8, 0x18, 0x18, 0x18, 0x38, 0x18, 0x38, 0x38, 0x30, 0x7C, + 0xFC, 0xFC, 0xF8, 0x3F, 0xF3, 0xFF, 0x03, 0x00, 0x70, 0x07, 0x00, 0x60, + 0x06, 0x00, 0x60, 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xC0, 0xFF, 0xCF, 0xFC, + 0x03, 0xFF, 0x03, 0xFF, 0x00, 0x38, 0x00, 0x30, 0x00, 0x30, 0x00, 0x30, + 0x00, 0x70, 0x20, 0x70, 0x60, 0x60, 0x60, 0x60, 0x60, 0xE0, 0xE1, 0xC0, + 0xFF, 0x80, 0x3F, 0x00, 0x1F, 0x9F, 0x1F, 0x9E, 0x0E, 0x38, 0x0C, 0x70, + 0x0C, 0xE0, 0x0F, 0xC0, 0x1F, 0xC0, 0x1F, 0xE0, 0x1C, 0xE0, 0x18, 0x60, + 0x18, 0x70, 0x38, 0x70, 0xFE, 0x3C, 0xFC, 0x3C, 0x3F, 0xC1, 0xFE, 0x01, + 0x80, 0x1C, 0x00, 0xE0, 0x06, 0x00, 0x30, 0x01, 0x80, 0x1C, 0x18, 0xE0, + 0xC6, 0x06, 0x30, 0x7F, 0xFF, 0xFF, 0xF8, 0x1E, 0x07, 0x87, 0x81, 0xE0, + 0xF0, 0xF0, 0x7C, 0x7C, 0x1F, 0x1F, 0x06, 0xCF, 0x81, 0xBF, 0x60, 0xEF, + 0x98, 0x3B, 0xEE, 0x0C, 0x73, 0x83, 0x1C, 0xC0, 0xC0, 0x30, 0xFC, 0x7E, + 0x3F, 0x1F, 0x80, 0x3C, 0x3F, 0x3E, 0x3F, 0x1E, 0x0C, 0x1F, 0x1C, 0x1F, + 0x1C, 0x1B, 0x98, 0x3B, 0x98, 0x3B, 0x98, 0x31, 0xF8, 0x31, 0xF8, 0x30, + 0xF0, 0x70, 0xF0, 0xFC, 0x70, 0xF8, 0x70, 0x03, 0xE0, 0x3F, 0xE1, 0xC3, + 0x8C, 0x07, 0x60, 0x0D, 0x80, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x1B, 0x00, + 0x6E, 0x03, 0x1C, 0x38, 0x7F, 0xC0, 0x7C, 0x00, 0x3F, 0xE1, 0xFF, 0x83, + 0x0E, 0x38, 0x31, 0xC1, 0x8C, 0x0C, 0x60, 0xC3, 0xFC, 0x3F, 0xC1, 0xC0, + 0x0C, 0x00, 0x60, 0x0F, 0xF0, 0x7F, 0x80, 0x03, 0xE0, 0x3F, 0xE1, 0xC3, + 0x8C, 0x07, 0x60, 0x0D, 0x80, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x1B, 0x00, + 0x6E, 0x03, 0x1C, 0x38, 0x7F, 0xC0, 0xFC, 0x03, 0x02, 0x1F, 0xFC, 0xFF, + 0xE0, 0x1F, 0xF0, 0x3F, 0xF0, 0x38, 0x70, 0x60, 0x60, 0xC0, 0xC1, 0x87, + 0x07, 0xFC, 0x0F, 0xF0, 0x18, 0xF0, 0x30, 0xE0, 0x60, 0xC1, 0xC1, 0xCF, + 0xE1, 0xFF, 0xC3, 0xC0, 0x0F, 0xB1, 0xFF, 0x30, 0xE6, 0x06, 0x60, 0x67, + 0x80, 0x7F, 0x01, 0xFC, 0x01, 0xC4, 0x0C, 0xC0, 0xCE, 0x18, 0xFF, 0x8B, + 0xE0, 0x7F, 0xFB, 0xFF, 0xD9, 0xCF, 0xCE, 0x7C, 0x63, 0x63, 0x18, 0x18, + 0x01, 0xC0, 0x0E, 0x00, 0x60, 0x03, 0x00, 0x18, 0x0F, 0xF8, 0x7F, 0xC0, + 0x7E, 0xFF, 0xF3, 0xF3, 0x03, 0x1C, 0x0C, 0x60, 0x31, 0x81, 0xC6, 0x06, + 0x38, 0x18, 0xE0, 0x63, 0x03, 0x8C, 0x0C, 0x30, 0x70, 0x7F, 0x80, 0xF8, + 0x00, 0xFC, 0x7F, 0xF8, 0xFD, 0xC0, 0x61, 0x81, 0xC3, 0x87, 0x07, 0x0C, + 0x0E, 0x38, 0x0C, 0x60, 0x19, 0xC0, 0x3F, 0x00, 0x7C, 0x00, 0xF8, 0x00, + 0xE0, 0x01, 0x80, 0x00, 0x7E, 0x7E, 0xFC, 0xFD, 0xC0, 0x73, 0x9C, 0xE7, + 0x79, 0x8E, 0xF7, 0x1B, 0xEE, 0x36, 0xD8, 0x7D, 0xF0, 0xF3, 0xE1, 0xE7, + 0x83, 0x8F, 0x07, 0x1E, 0x1C, 0x38, 0x00, 0x1F, 0x1F, 0x1F, 0x1F, 0x0E, + 0x1C, 0x07, 0x38, 0x07, 0x70, 0x03, 0xE0, 0x03, 0xC0, 0x03, 0xC0, 0x07, + 0xE0, 0x0E, 0xE0, 0x1C, 0x70, 0x38, 0x70, 0xFC, 0xFC, 0xFC, 0xFC, 0xF8, + 0xFF, 0xC7, 0xCC, 0x38, 0x73, 0x83, 0x9C, 0x0F, 0xC0, 0x7C, 0x01, 0xC0, + 0x0C, 0x00, 0x60, 0x03, 0x00, 0x38, 0x0F, 0xF8, 0x7F, 0x80, 0x0F, 0xF8, + 0x7F, 0xE1, 0xC7, 0x86, 0x1C, 0x18, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xC0, + 0x0E, 0x00, 0x70, 0xC3, 0x83, 0x1C, 0x1C, 0x7F, 0xF3, 0xFF, 0x80, 0x0F, + 0x87, 0xC3, 0x03, 0x81, 0xC0, 0xC0, 0x60, 0x30, 0x38, 0x1C, 0x0C, 0x06, + 0x03, 0x03, 0x81, 0xC0, 0xC0, 0x60, 0x3E, 0x3F, 0x00, 0x41, 0xC3, 0x83, + 0x07, 0x0E, 0x1C, 0x18, 0x38, 0x70, 0xE0, 0xC1, 0xC3, 0x83, 0x06, 0x0E, + 0x1C, 0x18, 0x20, 0x1F, 0x0F, 0x80, 0xC0, 0xE0, 0x70, 0x30, 0x18, 0x0C, + 0x0E, 0x07, 0x03, 0x01, 0x80, 0xC0, 0xE0, 0x70, 0x30, 0x18, 0x7C, 0x3E, + 0x00, 0x02, 0x01, 0x80, 0xF0, 0x7E, 0x3B, 0x9C, 0x7E, 0x1F, 0x03, 0xFF, + 0xFF, 0xFF, 0xFC, 0xCE, 0x73, 0x1F, 0xC3, 0xFE, 0x00, 0x60, 0x06, 0x0F, + 0xE3, 0xFE, 0x70, 0xCC, 0x0C, 0xC3, 0xCF, 0xFF, 0x7F, 0xF0, 0x1E, 0x00, + 0x3C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xDF, 0x81, 0xFF, 0x83, 0xC3, 0x8F, + 0x03, 0x1C, 0x06, 0x38, 0x0C, 0x70, 0x18, 0xE0, 0x63, 0xE1, 0x9F, 0xFE, + 0x3D, 0xF8, 0x00, 0x0F, 0xF3, 0xFF, 0x30, 0x76, 0x07, 0xE0, 0x6C, 0x00, + 0xC0, 0x0C, 0x00, 0xE0, 0x67, 0xFE, 0x3F, 0x80, 0x00, 0x3C, 0x00, 0xF0, + 0x01, 0xC0, 0x06, 0x07, 0xD8, 0x7F, 0xE3, 0x0F, 0x98, 0x1E, 0x60, 0x73, + 0x01, 0xCC, 0x07, 0x30, 0x3C, 0xE1, 0xF1, 0xFF, 0xE3, 0xF7, 0x80, 0x0F, + 0xC1, 0xFE, 0x78, 0x76, 0x03, 0xFF, 0xFF, 0xFF, 0xC0, 0x0C, 0x00, 0xE0, + 0xE7, 0xFE, 0x1F, 0x80, 0x00, 0xFC, 0x07, 0xF8, 0x0C, 0x00, 0x38, 0x01, + 0xFF, 0x07, 0xFE, 0x01, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x18, 0x00, 0x30, + 0x00, 0x60, 0x01, 0xC0, 0x1F, 0xF8, 0x3F, 0xF0, 0x00, 0x0F, 0xBC, 0x7F, + 0xF3, 0x0F, 0x18, 0x1C, 0xC0, 0x73, 0x01, 0x8C, 0x0E, 0x30, 0x38, 0xE3, + 0xE1, 0xFF, 0x83, 0xEC, 0x00, 0x30, 0x01, 0xC0, 0x06, 0x07, 0xF0, 0x1F, + 0x80, 0x1E, 0x01, 0xF0, 0x03, 0x00, 0x18, 0x00, 0xDE, 0x0F, 0xF8, 0x78, + 0xC3, 0x86, 0x18, 0x30, 0xC1, 0x8E, 0x1C, 0x70, 0xE3, 0x06, 0x7E, 0xFF, + 0xE7, 0xE0, 0x03, 0x80, 0x70, 0x00, 0x0F, 0xC1, 0xF0, 0x06, 0x00, 0xC0, + 0x38, 0x07, 0x00, 0xC0, 0x18, 0x03, 0x0F, 0xFF, 0xFF, 0xC0, 0x00, 0x70, + 0x07, 0x00, 0x00, 0xFF, 0x1F, 0xF0, 0x07, 0x00, 0x70, 0x06, 0x00, 0x60, + 0x06, 0x00, 0xE0, 0x0E, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x1C, 0x03, 0x87, + 0xF0, 0xFE, 0x00, 0x1E, 0x00, 0x78, 0x00, 0xE0, 0x03, 0x80, 0x0C, 0xFC, + 0x33, 0xE0, 0xDE, 0x07, 0xE0, 0x1F, 0x00, 0x7C, 0x01, 0xF8, 0x06, 0xF0, + 0x39, 0xC3, 0xE7, 0xEF, 0x1F, 0x80, 0x0F, 0x81, 0xF0, 0x06, 0x01, 0xC0, + 0x38, 0x06, 0x00, 0xC0, 0x18, 0x07, 0x00, 0xE0, 0x18, 0x03, 0x00, 0x61, + 0xFF, 0xFF, 0xF8, 0x3F, 0xBC, 0x7F, 0xFC, 0xF3, 0x98, 0xC6, 0x33, 0x9C, + 0xE7, 0x39, 0xCC, 0x63, 0x18, 0xC6, 0x31, 0x8D, 0xF7, 0xBF, 0xEF, 0x78, + 0x3D, 0xE1, 0xFF, 0x8F, 0x8C, 0x38, 0x61, 0x83, 0x0C, 0x18, 0xE1, 0xC7, + 0x0E, 0x30, 0x67, 0xEF, 0xFE, 0x7E, 0x07, 0xC1, 0xFE, 0x38, 0x76, 0x03, + 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x06, 0xE1, 0xC7, 0xF8, 0x3E, 0x00, 0x1E, + 0xFC, 0x1F, 0xFE, 0x0F, 0x87, 0x0F, 0x03, 0x0E, 0x03, 0x0E, 0x03, 0x0E, + 0x07, 0x0E, 0x06, 0x1F, 0x0C, 0x1F, 0xF8, 0x19, 0xF0, 0x18, 0x00, 0x18, + 0x00, 0x38, 0x00, 0xFE, 0x00, 0xFE, 0x00, 0x0F, 0xDE, 0x3F, 0xFC, 0xC3, + 0xE3, 0x03, 0x84, 0x07, 0x18, 0x0E, 0x30, 0x1C, 0x60, 0x78, 0xE1, 0xE0, + 0xFF, 0xC0, 0xF9, 0x80, 0x03, 0x00, 0x0E, 0x00, 0x1C, 0x01, 0xFC, 0x03, + 0xF8, 0x1E, 0x78, 0x7F, 0xF0, 0x7C, 0xC3, 0xC0, 0x0E, 0x00, 0x30, 0x00, + 0xC0, 0x03, 0x00, 0x1C, 0x03, 0xFF, 0x0F, 0xFC, 0x00, 0x07, 0xF1, 0xFF, + 0x30, 0x73, 0x86, 0x3F, 0x81, 0xFE, 0x03, 0xE6, 0x06, 0xE0, 0xEF, 0xFC, + 0xFF, 0x00, 0x0C, 0x07, 0x01, 0x83, 0xFF, 0xFF, 0xCE, 0x03, 0x00, 0xC0, + 0x30, 0x1C, 0x07, 0x01, 0x83, 0x7F, 0xCF, 0xC0, 0xF0, 0xFF, 0x1F, 0x60, + 0x76, 0x07, 0x60, 0x76, 0x06, 0x60, 0x66, 0x0E, 0x61, 0xE7, 0xFF, 0x3E, + 0xF0, 0x7E, 0x7E, 0xFC, 0xFC, 0xE0, 0xC0, 0xC3, 0x81, 0x86, 0x03, 0x98, + 0x07, 0x70, 0x06, 0xC0, 0x0F, 0x80, 0x1E, 0x00, 0x38, 0x00, 0xF8, 0x7F, + 0xE3, 0xE6, 0x63, 0x1B, 0xDC, 0x6F, 0x61, 0xFF, 0x87, 0xFC, 0x1E, 0xF0, + 0x73, 0x81, 0xCE, 0x06, 0x38, 0x00, 0x3E, 0x7C, 0xF9, 0xF1, 0xE7, 0x03, + 0xF8, 0x07, 0xC0, 0x1F, 0x01, 0xFC, 0x0F, 0x38, 0x78, 0xFB, 0xF7, 0xEF, + 0x9F, 0x80, 0x1F, 0x1F, 0x3E, 0x1F, 0x1C, 0x1C, 0x0C, 0x18, 0x0E, 0x38, + 0x0E, 0x70, 0x06, 0x60, 0x07, 0xE0, 0x07, 0xC0, 0x07, 0xC0, 0x03, 0x80, + 0x07, 0x00, 0x07, 0x00, 0x0E, 0x00, 0xFF, 0x00, 0xFF, 0x00, 0x1F, 0xF1, + 0xFF, 0x38, 0xE3, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC6, 0x38, 0x67, + 0xFE, 0x7F, 0xE0, 0x01, 0xC0, 0xF0, 0x70, 0x18, 0x06, 0x03, 0x80, 0xE0, + 0x30, 0x1C, 0x3E, 0x0F, 0x00, 0x60, 0x18, 0x06, 0x03, 0x80, 0xC0, 0x30, + 0x0F, 0x01, 0xC0, 0x0C, 0x71, 0xC7, 0x18, 0x63, 0x8E, 0x30, 0xC3, 0x1C, + 0x71, 0x86, 0x38, 0xE3, 0x04, 0x00, 0x0E, 0x07, 0x80, 0xC0, 0x60, 0x70, + 0x30, 0x18, 0x0C, 0x06, 0x01, 0xC1, 0xE1, 0xC0, 0xC0, 0xE0, 0x70, 0x30, + 0x38, 0x78, 0x38, 0x00, 0x3C, 0x27, 0xE6, 0xEF, 0xCC, 0x38 }; + +const GFXglyph FreeMonoBoldOblique12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 14, 0, 1 }, // 0x20 ' ' + { 0, 6, 15, 14, 6, -14 }, // 0x21 '!' + { 12, 8, 7, 14, 6, -13 }, // 0x22 '"' + { 19, 13, 18, 14, 2, -15 }, // 0x23 '#' + { 49, 11, 20, 14, 3, -16 }, // 0x24 '$' + { 77, 11, 15, 14, 3, -14 }, // 0x25 '%' + { 98, 11, 13, 14, 2, -12 }, // 0x26 '&' + { 116, 3, 7, 14, 8, -13 }, // 0x27 ''' + { 119, 7, 19, 14, 7, -14 }, // 0x28 '(' + { 136, 7, 19, 14, 2, -14 }, // 0x29 ')' + { 153, 11, 10, 14, 4, -14 }, // 0x2A '*' + { 167, 12, 13, 14, 3, -12 }, // 0x2B '+' + { 187, 6, 7, 14, 3, -2 }, // 0x2C ',' + { 193, 13, 2, 14, 2, -7 }, // 0x2D '-' + { 197, 3, 3, 14, 6, -2 }, // 0x2E '.' + { 199, 14, 20, 14, 2, -16 }, // 0x2F '/' + { 234, 11, 15, 14, 3, -14 }, // 0x30 '0' + { 255, 11, 15, 14, 2, -14 }, // 0x31 '1' + { 276, 13, 15, 14, 1, -14 }, // 0x32 '2' + { 301, 12, 15, 14, 2, -14 }, // 0x33 '3' + { 324, 11, 14, 14, 3, -13 }, // 0x34 '4' + { 344, 12, 15, 14, 2, -14 }, // 0x35 '5' + { 367, 11, 15, 14, 4, -14 }, // 0x36 '6' + { 388, 11, 15, 14, 4, -14 }, // 0x37 '7' + { 409, 11, 15, 14, 3, -14 }, // 0x38 '8' + { 430, 11, 15, 14, 3, -14 }, // 0x39 '9' + { 451, 5, 11, 14, 5, -10 }, // 0x3A ':' + { 458, 7, 15, 14, 3, -10 }, // 0x3B ';' + { 472, 13, 11, 14, 2, -11 }, // 0x3C '<' + { 490, 13, 7, 14, 2, -9 }, // 0x3D '=' + { 502, 13, 11, 14, 2, -11 }, // 0x3E '>' + { 520, 9, 14, 14, 5, -13 }, // 0x3F '?' + { 536, 12, 19, 14, 2, -14 }, // 0x40 '@' + { 565, 15, 14, 14, 0, -13 }, // 0x41 'A' + { 592, 13, 14, 14, 1, -13 }, // 0x42 'B' + { 615, 14, 14, 14, 2, -13 }, // 0x43 'C' + { 640, 13, 14, 14, 1, -13 }, // 0x44 'D' + { 663, 15, 14, 14, 0, -13 }, // 0x45 'E' + { 690, 16, 14, 14, 0, -13 }, // 0x46 'F' + { 718, 14, 14, 14, 1, -13 }, // 0x47 'G' + { 743, 16, 14, 14, 0, -13 }, // 0x48 'H' + { 771, 12, 14, 14, 2, -13 }, // 0x49 'I' + { 792, 16, 14, 14, 0, -13 }, // 0x4A 'J' + { 820, 16, 14, 14, 0, -13 }, // 0x4B 'K' + { 848, 13, 14, 14, 1, -13 }, // 0x4C 'L' + { 871, 18, 14, 14, 0, -13 }, // 0x4D 'M' + { 903, 16, 14, 14, 1, -13 }, // 0x4E 'N' + { 931, 14, 14, 14, 1, -13 }, // 0x4F 'O' + { 956, 13, 14, 14, 1, -13 }, // 0x50 'P' + { 979, 14, 17, 14, 1, -13 }, // 0x51 'Q' + { 1009, 15, 14, 14, 0, -13 }, // 0x52 'R' + { 1036, 12, 14, 14, 3, -13 }, // 0x53 'S' + { 1057, 13, 14, 14, 2, -13 }, // 0x54 'T' + { 1080, 14, 14, 14, 2, -13 }, // 0x55 'U' + { 1105, 15, 14, 14, 1, -13 }, // 0x56 'V' + { 1132, 15, 14, 14, 1, -13 }, // 0x57 'W' + { 1159, 16, 14, 14, 0, -13 }, // 0x58 'X' + { 1187, 13, 14, 14, 2, -13 }, // 0x59 'Y' + { 1210, 14, 14, 14, 1, -13 }, // 0x5A 'Z' + { 1235, 9, 19, 14, 5, -14 }, // 0x5B '[' + { 1257, 7, 20, 14, 5, -16 }, // 0x5C '\' + { 1275, 9, 19, 14, 3, -14 }, // 0x5D ']' + { 1297, 10, 8, 14, 4, -15 }, // 0x5E '^' + { 1307, 15, 2, 14, -1, 4 }, // 0x5F '_' + { 1311, 4, 4, 14, 7, -15 }, // 0x60 '`' + { 1313, 12, 11, 14, 2, -10 }, // 0x61 'a' + { 1330, 15, 15, 14, -1, -14 }, // 0x62 'b' + { 1359, 12, 11, 14, 2, -10 }, // 0x63 'c' + { 1376, 14, 15, 14, 2, -14 }, // 0x64 'd' + { 1403, 12, 11, 14, 2, -10 }, // 0x65 'e' + { 1420, 15, 15, 14, 2, -14 }, // 0x66 'f' + { 1449, 14, 16, 14, 2, -10 }, // 0x67 'g' + { 1477, 13, 15, 14, 1, -14 }, // 0x68 'h' + { 1502, 11, 14, 14, 2, -13 }, // 0x69 'i' + { 1522, 12, 19, 14, 1, -13 }, // 0x6A 'j' + { 1551, 14, 15, 14, 1, -14 }, // 0x6B 'k' + { 1578, 11, 15, 14, 2, -14 }, // 0x6C 'l' + { 1599, 15, 11, 14, 0, -10 }, // 0x6D 'm' + { 1620, 13, 11, 14, 1, -10 }, // 0x6E 'n' + { 1638, 12, 11, 14, 2, -10 }, // 0x6F 'o' + { 1655, 16, 16, 14, -1, -10 }, // 0x70 'p' + { 1687, 15, 16, 14, 1, -10 }, // 0x71 'q' + { 1717, 14, 11, 14, 1, -10 }, // 0x72 'r' + { 1737, 12, 11, 14, 2, -10 }, // 0x73 's' + { 1754, 10, 14, 14, 2, -13 }, // 0x74 't' + { 1772, 12, 11, 14, 2, -10 }, // 0x75 'u' + { 1789, 15, 11, 14, 1, -10 }, // 0x76 'v' + { 1810, 14, 11, 14, 2, -10 }, // 0x77 'w' + { 1830, 14, 11, 14, 1, -10 }, // 0x78 'x' + { 1850, 16, 16, 14, 0, -10 }, // 0x79 'y' + { 1882, 12, 11, 14, 2, -10 }, // 0x7A 'z' + { 1899, 10, 19, 14, 4, -14 }, // 0x7B '{' + { 1923, 6, 19, 14, 5, -14 }, // 0x7C '|' + { 1938, 9, 19, 14, 3, -14 }, // 0x7D '}' + { 1960, 12, 4, 14, 3, -7 } }; // 0x7E '~' + +const GFXfont FreeMonoBoldOblique12pt7b PROGMEM = { + (uint8_t *)FreeMonoBoldOblique12pt7bBitmaps, + (GFXglyph *)FreeMonoBoldOblique12pt7bGlyphs, + 0x20, 0x7E, 24 }; + +// Approx. 2638 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique18pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique18pt7b.h new file mode 100644 index 0000000..bc4f20e --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique18pt7b.h @@ -0,0 +1,460 @@ +const uint8_t FreeMonoBoldOblique18pt7bBitmaps[] PROGMEM = { + 0x0F, 0x07, 0xC7, 0xE3, 0xF1, 0xF0, 0xF8, 0xFC, 0x7C, 0x3E, 0x1F, 0x0F, + 0x07, 0x87, 0xC3, 0xC1, 0xE0, 0x60, 0x00, 0x38, 0x3E, 0x1F, 0x0F, 0x83, + 0x80, 0xF8, 0xFF, 0x0E, 0xF1, 0xEF, 0x1E, 0xE1, 0xCE, 0x1C, 0xC1, 0xCC, + 0x18, 0xC1, 0x88, 0x18, 0x00, 0xE3, 0x80, 0x79, 0xE0, 0x1C, 0x70, 0x07, + 0x1C, 0x03, 0xCF, 0x00, 0xF3, 0xC0, 0x38, 0xE0, 0x7F, 0xFF, 0x3F, 0xFF, + 0xCF, 0xFF, 0xF3, 0xFF, 0xF8, 0x3C, 0xF0, 0x0F, 0x3C, 0x03, 0x8E, 0x0F, + 0xFF, 0xE3, 0xFF, 0xFC, 0xFF, 0xFF, 0x3F, 0xFF, 0x83, 0xCF, 0x00, 0xF3, + 0xC0, 0x38, 0xE0, 0x1E, 0x78, 0x07, 0x9E, 0x01, 0xC7, 0x00, 0x71, 0xC0, + 0x00, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x07, 0x80, 0x03, 0xF0, 0x03, 0xFF, + 0x81, 0xFF, 0xF0, 0xFF, 0xF8, 0x3C, 0x1E, 0x1E, 0x07, 0x87, 0x80, 0x01, + 0xF0, 0x00, 0x7F, 0xC0, 0x0F, 0xFC, 0x01, 0xFF, 0x80, 0x07, 0xF0, 0x00, + 0x3C, 0x70, 0x0F, 0x3C, 0x03, 0xCF, 0x83, 0xE3, 0xFF, 0xF8, 0xFF, 0xFC, + 0x3F, 0xFE, 0x0C, 0xFE, 0x00, 0x1C, 0x00, 0x07, 0x00, 0x03, 0xC0, 0x00, + 0xF0, 0x00, 0x18, 0x00, 0x03, 0xC0, 0x0F, 0xE0, 0x1C, 0x70, 0x30, 0x30, + 0x30, 0x30, 0x30, 0x70, 0x38, 0xE0, 0x1F, 0xC3, 0x0F, 0x1F, 0x01, 0xFC, + 0x0F, 0xE0, 0x7F, 0x00, 0xF8, 0xF0, 0x83, 0xF8, 0x07, 0x1C, 0x0E, 0x0C, + 0x0C, 0x0C, 0x0C, 0x1C, 0x0E, 0x38, 0x07, 0xF0, 0x03, 0xC0, 0x00, 0x7A, + 0x01, 0xFF, 0x03, 0xFF, 0x07, 0xFE, 0x0F, 0x9C, 0x0F, 0x00, 0x0F, 0x00, + 0x0F, 0x00, 0x07, 0x80, 0x1F, 0x80, 0x3F, 0xC0, 0x7F, 0xCF, 0x79, 0xFF, + 0xF1, 0xFE, 0xF1, 0xFC, 0xF0, 0xF8, 0xFF, 0xFE, 0xFF, 0xFE, 0x7F, 0xFE, + 0x1F, 0xBC, 0x7B, 0xFD, 0xEF, 0x73, 0x9C, 0xC6, 0x00, 0x01, 0xC0, 0xF0, + 0x3C, 0x1E, 0x0F, 0x03, 0xC1, 0xE0, 0x70, 0x3C, 0x0F, 0x07, 0x81, 0xE0, + 0x78, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3E, + 0x07, 0x81, 0xE0, 0x7C, 0x1F, 0x03, 0x80, 0x07, 0x03, 0xC0, 0xF8, 0x3E, + 0x07, 0x81, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, + 0xF0, 0x78, 0x1E, 0x07, 0x81, 0xC0, 0xF0, 0x3C, 0x1E, 0x07, 0x83, 0xC1, + 0xE0, 0x78, 0x3C, 0x0E, 0x00, 0x00, 0xC0, 0x03, 0xC0, 0x07, 0x00, 0x0E, + 0x02, 0x3C, 0x0F, 0xFF, 0xFF, 0xFF, 0xBF, 0xFE, 0x1F, 0xF0, 0x1F, 0x80, + 0x7F, 0x81, 0xEF, 0x07, 0x8F, 0x0F, 0x1E, 0x08, 0x10, 0x00, 0x00, 0x70, + 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xE0, 0x00, 0x38, 0x00, + 0x1E, 0x03, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x0F, + 0x00, 0x03, 0xC0, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x07, 0x80, + 0x01, 0xC0, 0x00, 0x70, 0x00, 0x0F, 0x87, 0x87, 0x83, 0x83, 0xC1, 0xC1, + 0xC0, 0xC0, 0xE0, 0x60, 0x00, 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFE, 0x77, 0xFF, 0xF7, 0x00, 0x00, 0x00, 0x38, 0x00, 0x03, 0xC0, + 0x00, 0x1C, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xE0, 0x00, 0x0F, + 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x07, 0x80, 0x00, + 0x78, 0x00, 0x03, 0xC0, 0x00, 0x3C, 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, + 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0xF0, + 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x07, 0x80, 0x00, 0x78, 0x00, 0x03, + 0xC0, 0x00, 0x3C, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x00, 0xFC, 0x01, 0xFF, + 0x01, 0xFF, 0xC1, 0xFF, 0xE1, 0xF1, 0xF9, 0xE0, 0x7C, 0xF0, 0x1E, 0xF0, + 0x0F, 0x78, 0x07, 0xB8, 0x03, 0x9C, 0x03, 0xDE, 0x01, 0xCF, 0x00, 0xE7, + 0x00, 0x73, 0xC0, 0x79, 0xE0, 0x3C, 0xF0, 0x1C, 0x78, 0x1E, 0x3E, 0x1E, + 0x0F, 0xFF, 0x07, 0xFF, 0x01, 0xFF, 0x00, 0x7E, 0x00, 0x00, 0x7C, 0x03, + 0xF8, 0x0F, 0xE0, 0x7F, 0xC0, 0xF7, 0x81, 0x8F, 0x00, 0x1C, 0x00, 0x38, + 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x0E, 0x00, 0x3C, 0x00, + 0x78, 0x00, 0xF0, 0x01, 0xC0, 0x03, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xEF, 0xFF, 0xC0, 0x00, 0x1F, 0x00, 0x07, 0xFC, 0x00, 0xFF, 0xE0, 0x1F, + 0xFF, 0x03, 0xC1, 0xF0, 0x78, 0x0F, 0x07, 0x80, 0xF0, 0x70, 0x0F, 0x00, + 0x01, 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x3F, 0x00, + 0x07, 0xE0, 0x01, 0xFC, 0x00, 0x3F, 0x80, 0x07, 0xE0, 0x01, 0xF8, 0x00, + 0x3F, 0x03, 0x87, 0xFF, 0xF8, 0x7F, 0xFF, 0x87, 0xFF, 0xF8, 0xFF, 0xFF, + 0x00, 0x00, 0xFE, 0x00, 0xFF, 0xC0, 0x7F, 0xF8, 0x3F, 0xFF, 0x0E, 0x07, + 0xC0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, 0x00, 0x07, 0x80, 0x1F, 0xC0, + 0x0F, 0xE0, 0x03, 0xF0, 0x00, 0xFF, 0x00, 0x03, 0xE0, 0x00, 0x78, 0x00, + 0x1E, 0x00, 0x07, 0x80, 0x03, 0xC0, 0x03, 0xF1, 0xFF, 0xF8, 0xFF, 0xFC, + 0x3F, 0xFE, 0x03, 0xFE, 0x00, 0x00, 0x1F, 0x00, 0x3F, 0x00, 0x7F, 0x00, + 0xFE, 0x00, 0xFE, 0x01, 0xEE, 0x03, 0xDE, 0x07, 0x9E, 0x0F, 0x1C, 0x1E, + 0x1C, 0x3C, 0x3C, 0x78, 0x3C, 0xFF, 0xFE, 0xFF, 0xFE, 0xFF, 0xFE, 0xFF, + 0xFC, 0x00, 0x70, 0x03, 0xFC, 0x07, 0xFC, 0x07, 0xFC, 0x07, 0xF8, 0x07, + 0xFF, 0xC1, 0xFF, 0xF0, 0x7F, 0xFC, 0x3F, 0xFE, 0x0F, 0x00, 0x03, 0xC0, + 0x00, 0xE0, 0x00, 0x3B, 0xE0, 0x1F, 0xFE, 0x07, 0xFF, 0xC1, 0xFF, 0xF8, + 0x78, 0x3E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, + 0x0F, 0x18, 0x0F, 0xCF, 0xFF, 0xE3, 0xFF, 0xF0, 0x7F, 0xF8, 0x07, 0xF0, + 0x00, 0x00, 0x0F, 0xC0, 0x0F, 0xFC, 0x03, 0xFF, 0x81, 0xFF, 0xE0, 0x7F, + 0x00, 0x1F, 0x80, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x9F, + 0x01, 0xEF, 0xF0, 0x3F, 0xFF, 0x0F, 0xFF, 0xF1, 0xFC, 0x3E, 0x3E, 0x03, + 0xC7, 0x80, 0x78, 0xF0, 0x0F, 0x1E, 0x03, 0xC3, 0xE0, 0xF8, 0x7F, 0xFE, + 0x07, 0xFF, 0x80, 0x7F, 0xE0, 0x07, 0xF0, 0x00, 0x7F, 0xFF, 0x7F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x0E, 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x3C, + 0x00, 0x78, 0x00, 0x70, 0x00, 0xF0, 0x00, 0xE0, 0x01, 0xE0, 0x01, 0xC0, + 0x03, 0xC0, 0x07, 0x80, 0x07, 0x80, 0x0F, 0x00, 0x0E, 0x00, 0x1E, 0x00, + 0x1C, 0x00, 0x1C, 0x00, 0x00, 0x7E, 0x00, 0x3F, 0xF0, 0x0F, 0xFF, 0x03, + 0xFF, 0xF0, 0xF8, 0x3E, 0x3E, 0x03, 0xC7, 0x80, 0x78, 0xF0, 0x0F, 0x1E, + 0x03, 0xC3, 0xE0, 0xF0, 0x3F, 0xFC, 0x03, 0xFF, 0x00, 0xFF, 0xE0, 0x7F, + 0xFE, 0x1F, 0x83, 0xE3, 0xC0, 0x3C, 0xF0, 0x07, 0x9E, 0x01, 0xF3, 0xE0, + 0x7C, 0x7F, 0xFF, 0x87, 0xFF, 0xE0, 0x7F, 0xF0, 0x03, 0xF8, 0x00, 0x00, + 0x7E, 0x00, 0x7F, 0xC0, 0x3F, 0xF8, 0x1F, 0xFE, 0x0F, 0x87, 0xC3, 0xC0, + 0xF1, 0xE0, 0x3C, 0x78, 0x0F, 0x1E, 0x03, 0xC7, 0x81, 0xF1, 0xF1, 0xFC, + 0x7F, 0xFE, 0x0F, 0xFF, 0x81, 0xFD, 0xE0, 0x3E, 0xF0, 0x00, 0x7C, 0x00, + 0x3E, 0x00, 0x1F, 0x00, 0x1F, 0x81, 0xFF, 0xC0, 0xFF, 0xE0, 0x3F, 0xE0, + 0x07, 0xE0, 0x00, 0x1C, 0x7C, 0xF9, 0xF1, 0xC0, 0x00, 0x00, 0x00, 0x00, + 0x03, 0x8F, 0x9F, 0x3E, 0x38, 0x01, 0xC0, 0x7C, 0x0F, 0x81, 0xF0, 0x3C, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xC0, 0xF0, 0x1E, + 0x07, 0x80, 0xE0, 0x38, 0x07, 0x01, 0xC0, 0x30, 0x0E, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xFC, 0x00, 0xFE, 0x00, 0xFE, 0x00, + 0xFE, 0x01, 0xFE, 0x01, 0xFE, 0x00, 0xFE, 0x00, 0x0F, 0xE0, 0x00, 0xFE, + 0x00, 0x1F, 0xC0, 0x01, 0xFC, 0x00, 0x1F, 0xC0, 0x01, 0xF0, 0x00, 0x38, + 0x3F, 0xFF, 0xEF, 0xFF, 0xFD, 0xFF, 0xFF, 0x9F, 0xFF, 0xE0, 0x00, 0x00, + 0x00, 0x00, 0x1F, 0xFF, 0xF7, 0xFF, 0xFE, 0xFF, 0xFF, 0xDF, 0xFF, 0xF0, + 0x00, 0x00, 0x03, 0x80, 0x00, 0xFC, 0x00, 0x0F, 0xE0, 0x00, 0x7F, 0x00, + 0x07, 0xF0, 0x00, 0x3F, 0x80, 0x01, 0xFC, 0x00, 0x1F, 0xC0, 0x0F, 0xE0, + 0x07, 0xF0, 0x07, 0xF8, 0x03, 0xF8, 0x01, 0xFC, 0x00, 0x3E, 0x00, 0x07, + 0x00, 0x00, 0x07, 0xE0, 0xFF, 0xC7, 0xFF, 0xBF, 0xFF, 0xF0, 0x7F, 0x80, + 0xFE, 0x03, 0xC0, 0x0F, 0x00, 0x78, 0x0F, 0xE1, 0xFE, 0x0F, 0xF0, 0x7E, + 0x01, 0xE0, 0x07, 0x00, 0x00, 0x00, 0x70, 0x03, 0xE0, 0x0F, 0x80, 0x3E, + 0x00, 0x70, 0x00, 0x00, 0x3E, 0x00, 0x3F, 0xE0, 0x1F, 0xF8, 0x0F, 0x0F, + 0x07, 0x01, 0xC3, 0x80, 0x71, 0xE0, 0x1C, 0x70, 0x0E, 0x18, 0x0F, 0x8E, + 0x1F, 0xE3, 0x8F, 0xF0, 0xE7, 0x9C, 0x33, 0xC7, 0x1C, 0xE1, 0xC7, 0x38, + 0x71, 0xCF, 0x18, 0x73, 0xFE, 0x38, 0x7F, 0xCE, 0x0F, 0xF3, 0x80, 0x00, + 0xE0, 0x00, 0x38, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0xC0, 0x7F, 0xF0, 0x0F, + 0xF8, 0x01, 0xF8, 0x00, 0x01, 0xFF, 0x80, 0x07, 0xFE, 0x00, 0x1F, 0xF8, + 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x00, 0x07, 0xBC, 0x00, + 0x1C, 0xF0, 0x00, 0xF3, 0xC0, 0x07, 0x87, 0x80, 0x1E, 0x1E, 0x00, 0xF0, + 0x78, 0x07, 0xFF, 0xE0, 0x1F, 0xFF, 0x80, 0xFF, 0xFF, 0x07, 0xFF, 0xFC, + 0x1E, 0x00, 0xF1, 0xFE, 0x1F, 0xFF, 0xF8, 0x7F, 0xFF, 0xE1, 0xFF, 0xFF, + 0x07, 0xF8, 0x0F, 0xFF, 0xC0, 0x7F, 0xFF, 0x87, 0xFF, 0xFC, 0x1F, 0xFF, + 0xF0, 0x38, 0x0F, 0x81, 0xC0, 0x3C, 0x1E, 0x01, 0xE0, 0xF0, 0x3E, 0x07, + 0xFF, 0xE0, 0x3F, 0xFE, 0x03, 0xFF, 0xF8, 0x1F, 0xFF, 0xE0, 0xE0, 0x1F, + 0x87, 0x00, 0x3C, 0x38, 0x01, 0xE3, 0xC0, 0x0F, 0x1E, 0x00, 0xF3, 0xFF, + 0xFF, 0xBF, 0xFF, 0xF9, 0xFF, 0xFF, 0x8F, 0xFF, 0xF0, 0x00, 0x00, 0x7F, + 0x30, 0x0F, 0xFF, 0xC1, 0xFF, 0xFE, 0x1F, 0xFF, 0xF1, 0xF8, 0x3F, 0x1F, + 0x00, 0x78, 0xF0, 0x03, 0xCF, 0x80, 0x1C, 0x78, 0x00, 0x03, 0xC0, 0x00, + 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, + 0x00, 0x1F, 0x00, 0x38, 0x7E, 0x07, 0xC3, 0xFF, 0xFC, 0x0F, 0xFF, 0xC0, + 0x3F, 0xFC, 0x00, 0x7F, 0x80, 0x00, 0x0F, 0xFF, 0x80, 0x7F, 0xFE, 0x07, + 0xFF, 0xF8, 0x1F, 0xFF, 0xE0, 0x78, 0x1F, 0x03, 0x80, 0x7C, 0x1C, 0x01, + 0xE1, 0xE0, 0x0F, 0x0F, 0x00, 0x78, 0x70, 0x03, 0xC3, 0x80, 0x1E, 0x1C, + 0x00, 0xF1, 0xE0, 0x0F, 0x0F, 0x00, 0x78, 0x70, 0x07, 0xC3, 0x80, 0x7C, + 0x3C, 0x07, 0xC3, 0xFF, 0xFC, 0x3F, 0xFF, 0xC1, 0xFF, 0xFC, 0x0F, 0xFF, + 0x80, 0x00, 0x07, 0xFF, 0xFC, 0x3F, 0xFF, 0xF0, 0xFF, 0xFF, 0xC3, 0xFF, + 0xFF, 0x03, 0xC0, 0x3C, 0x0F, 0x00, 0xE0, 0x3C, 0x73, 0x80, 0xE3, 0xCC, + 0x03, 0xFF, 0x00, 0x1F, 0xFC, 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0x80, 0x07, + 0x1E, 0x00, 0x3C, 0x70, 0x00, 0xF0, 0x07, 0x03, 0xC0, 0x1C, 0x0E, 0x00, + 0xF1, 0xFF, 0xFF, 0xC7, 0xFF, 0xFE, 0x3F, 0xFF, 0xF8, 0x7F, 0xFF, 0xE0, + 0x07, 0xFF, 0xFE, 0x1F, 0xFF, 0xFC, 0x3F, 0xFF, 0xF0, 0x7F, 0xFF, 0xE0, + 0x3C, 0x01, 0xC0, 0x70, 0x07, 0x80, 0xE1, 0x8E, 0x03, 0xC7, 0x1C, 0x07, + 0xFE, 0x00, 0x0F, 0xFC, 0x00, 0x1F, 0xF8, 0x00, 0x3F, 0xF0, 0x00, 0xF1, + 0xC0, 0x01, 0xE3, 0x80, 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0xFF, 0xE0, 0x03, 0xFF, 0xC0, 0x07, 0xFF, 0x80, 0x0F, 0xFE, 0x00, + 0x00, 0x00, 0x3F, 0x18, 0x0F, 0xFF, 0xC0, 0xFF, 0xFE, 0x0F, 0xFF, 0xF0, + 0xFC, 0x0F, 0x0F, 0x80, 0x38, 0xF8, 0x01, 0x87, 0x80, 0x00, 0x78, 0x00, + 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x7F, 0xEF, 0x07, 0xFF, 0x78, + 0x3F, 0xFB, 0xC0, 0xFF, 0x9E, 0x00, 0x38, 0xFC, 0x03, 0xC3, 0xFF, 0xFE, + 0x1F, 0xFF, 0xE0, 0x3F, 0xFC, 0x00, 0x7F, 0x80, 0x00, 0x03, 0xF8, 0xFE, + 0x0F, 0xF3, 0xFC, 0x1F, 0xE7, 0xF8, 0x3F, 0x8F, 0xE0, 0x3C, 0x07, 0x80, + 0x70, 0x0E, 0x00, 0xE0, 0x1C, 0x03, 0xC0, 0x78, 0x07, 0x80, 0xF0, 0x0F, + 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x3F, 0xFF, 0x00, 0xFF, 0xFE, 0x01, 0xE0, + 0x3C, 0x03, 0x80, 0x70, 0x07, 0x00, 0xE0, 0x1E, 0x03, 0xC0, 0xFF, 0x1F, + 0xE1, 0xFE, 0x7F, 0xC7, 0xFC, 0xFF, 0x87, 0xF1, 0xFE, 0x00, 0x07, 0xFF, + 0xE1, 0xFF, 0xFC, 0x3F, 0xFF, 0x87, 0xFF, 0xE0, 0x07, 0x80, 0x00, 0xE0, + 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0x80, + 0x00, 0x70, 0x00, 0x1E, 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x0E, 0x00, + 0x01, 0xC0, 0x0F, 0xFF, 0xC3, 0xFF, 0xF8, 0x7F, 0xFF, 0x07, 0xFF, 0xE0, + 0x00, 0x3F, 0xFE, 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x03, 0xFF, 0xE0, + 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, 0x01, 0xE0, 0x00, + 0x03, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x80, 0x1C, 0x03, 0x80, + 0x78, 0x0F, 0x00, 0xF0, 0x1E, 0x01, 0xC0, 0x38, 0x07, 0x80, 0x70, 0x1F, + 0x01, 0xFF, 0xFC, 0x03, 0xFF, 0xF0, 0x03, 0xFF, 0xC0, 0x00, 0xFC, 0x00, + 0x00, 0x07, 0xF8, 0xFC, 0x1F, 0xFB, 0xFC, 0x3F, 0xE7, 0xF0, 0x7F, 0xCF, + 0xE0, 0x3C, 0x1E, 0x00, 0x70, 0xF8, 0x00, 0xE3, 0xE0, 0x03, 0xCF, 0x00, + 0x07, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xF0, 0x00, + 0xF9, 0xF0, 0x01, 0xE1, 0xE0, 0x03, 0x83, 0xE0, 0x07, 0x03, 0xC0, 0x1E, + 0x07, 0x80, 0xFF, 0x8F, 0xE3, 0xFF, 0x0F, 0xC7, 0xFE, 0x1F, 0x8F, 0xF8, + 0x3E, 0x00, 0x0F, 0xFE, 0x00, 0xFF, 0xF0, 0x1F, 0xFE, 0x00, 0xFF, 0xE0, + 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x03, 0xC0, + 0x00, 0x3C, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x07, 0x80, 0x60, 0x78, + 0x0F, 0x07, 0x80, 0xF0, 0x70, 0x0E, 0x07, 0x00, 0xE7, 0xFF, 0xFE, 0xFF, + 0xFF, 0xEF, 0xFF, 0xFE, 0xFF, 0xFF, 0xC0, 0x0F, 0xC0, 0x1F, 0x87, 0xE0, + 0x0F, 0xC7, 0xF8, 0x0F, 0xE1, 0xFC, 0x0F, 0xE0, 0x7E, 0x07, 0xE0, 0x3F, + 0x07, 0xF0, 0x3F, 0xC7, 0xF8, 0x1F, 0xE3, 0xF8, 0x0E, 0xF3, 0xDC, 0x07, + 0x7B, 0xDE, 0x03, 0x9F, 0xEF, 0x03, 0xCF, 0xE7, 0x81, 0xE7, 0xE3, 0x80, + 0xE3, 0xF1, 0xC0, 0x70, 0xF1, 0xE0, 0x38, 0x70, 0xF0, 0x3C, 0x00, 0x70, + 0x3F, 0xC1, 0xFE, 0x3F, 0xE1, 0xFF, 0x1F, 0xF0, 0xFF, 0x8F, 0xF0, 0x7F, + 0x80, 0x0F, 0xC1, 0xFE, 0x1F, 0xC1, 0xFF, 0x1F, 0xC3, 0xFE, 0x1F, 0xE1, + 0xFE, 0x07, 0xE0, 0x38, 0x07, 0xF0, 0x78, 0x07, 0xF0, 0x78, 0x0F, 0xF8, + 0x70, 0x0F, 0x78, 0x70, 0x0E, 0x78, 0xF0, 0x0E, 0x7C, 0xF0, 0x1E, 0x3C, + 0xF0, 0x1E, 0x3E, 0xE0, 0x1E, 0x1E, 0xE0, 0x1C, 0x1F, 0xE0, 0x1C, 0x0F, + 0xE0, 0x3C, 0x0F, 0xE0, 0x7F, 0x87, 0xC0, 0xFF, 0x87, 0xC0, 0xFF, 0x87, + 0xC0, 0xFF, 0x03, 0xC0, 0x00, 0x7E, 0x00, 0x1F, 0xF8, 0x07, 0xFF, 0xC0, + 0xFF, 0xFE, 0x1F, 0x87, 0xE3, 0xE0, 0x1F, 0x3C, 0x01, 0xF7, 0xC0, 0x0F, + 0x78, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x01, + 0xEF, 0x00, 0x3E, 0xF8, 0x03, 0xCF, 0x80, 0x7C, 0x7C, 0x1F, 0x87, 0xFF, + 0xF0, 0x3F, 0xFE, 0x01, 0xFF, 0x80, 0x07, 0xE0, 0x00, 0x0F, 0xFF, 0x80, + 0x7F, 0xFF, 0x07, 0xFF, 0xFC, 0x1F, 0xFF, 0xF0, 0x38, 0x0F, 0x81, 0xC0, + 0x3C, 0x1E, 0x01, 0xE0, 0xF0, 0x0F, 0x07, 0x00, 0xF0, 0x38, 0x0F, 0x83, + 0xFF, 0xF8, 0x1F, 0xFF, 0x80, 0xFF, 0xF8, 0x07, 0xFF, 0x00, 0x38, 0x00, + 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x03, 0xFF, 0x80, 0x3F, 0xFC, 0x01, 0xFF, + 0xE0, 0x0F, 0xFE, 0x00, 0x00, 0x00, 0x7E, 0x00, 0x1F, 0xF8, 0x07, 0xFF, + 0xC0, 0xFF, 0xFE, 0x1F, 0x87, 0xE3, 0xE0, 0x1F, 0x3C, 0x01, 0xF7, 0xC0, + 0x0F, 0x78, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, + 0x01, 0xEF, 0x00, 0x3E, 0xF8, 0x03, 0xCF, 0x80, 0x7C, 0x7C, 0x1F, 0x87, + 0xFF, 0xF0, 0x3F, 0xFE, 0x01, 0xFF, 0x80, 0x07, 0xE0, 0x01, 0xFE, 0x30, + 0x3F, 0xFF, 0x87, 0xFF, 0xF0, 0x7F, 0xFF, 0x07, 0x83, 0xC0, 0x07, 0xFF, + 0x80, 0x3F, 0xFF, 0x80, 0xFF, 0xFF, 0x03, 0xFF, 0xFE, 0x03, 0xC0, 0xF8, + 0x0E, 0x01, 0xE0, 0x38, 0x07, 0x81, 0xE0, 0x3E, 0x07, 0x83, 0xF0, 0x1F, + 0xFF, 0x80, 0x7F, 0xFC, 0x01, 0xFF, 0xC0, 0x0F, 0xFF, 0x80, 0x3C, 0x3E, + 0x00, 0xE0, 0x7C, 0x03, 0x80, 0xF0, 0x1E, 0x03, 0xE1, 0xFF, 0x07, 0xFF, + 0xFC, 0x1F, 0xFF, 0xF0, 0x3F, 0xFF, 0x80, 0xF8, 0x00, 0x7C, 0xE0, 0x7F, + 0xFC, 0x1F, 0xFF, 0x87, 0xFF, 0xE0, 0xF8, 0x7C, 0x3C, 0x07, 0x87, 0x80, + 0xE0, 0xF0, 0x00, 0x1F, 0x00, 0x03, 0xFE, 0x00, 0x3F, 0xF8, 0x03, 0xFF, + 0x80, 0x07, 0xF8, 0x40, 0x1F, 0x3C, 0x01, 0xE7, 0x80, 0x3C, 0xFC, 0x1F, + 0x1F, 0xFF, 0xE3, 0xFF, 0xF8, 0x7F, 0xFE, 0x00, 0x7E, 0x00, 0x7F, 0xFF, + 0xEF, 0xFF, 0xFD, 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0x0E, 0x1F, 0xE1, 0xC3, + 0xBC, 0x78, 0x77, 0x0F, 0x1E, 0xE1, 0xC1, 0x80, 0x38, 0x00, 0x0F, 0x00, + 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x3C, 0x00, + 0x07, 0x80, 0x0F, 0xFE, 0x03, 0xFF, 0xE0, 0x7F, 0xFC, 0x0F, 0xFF, 0x00, + 0x7F, 0x8F, 0xF3, 0xFE, 0x7F, 0xDF, 0xF7, 0xFC, 0xFF, 0x1F, 0xE3, 0xC0, + 0x3C, 0x1C, 0x01, 0xE0, 0xE0, 0x0F, 0x0F, 0x00, 0x70, 0x78, 0x03, 0x83, + 0xC0, 0x3C, 0x1C, 0x01, 0xE0, 0xE0, 0x0E, 0x0F, 0x00, 0x70, 0x78, 0x03, + 0x83, 0xC0, 0x3C, 0x1F, 0x01, 0xC0, 0xFC, 0x3E, 0x03, 0xFF, 0xE0, 0x1F, + 0xFE, 0x00, 0x7F, 0xE0, 0x00, 0xFC, 0x00, 0x00, 0x7F, 0x81, 0xFE, 0xFF, + 0x87, 0xFF, 0xFF, 0x0F, 0xFB, 0xFC, 0x1F, 0xE1, 0xC0, 0x0F, 0x03, 0xC0, + 0x1C, 0x07, 0x80, 0x78, 0x0F, 0x01, 0xE0, 0x1E, 0x03, 0x80, 0x1E, 0x0F, + 0x00, 0x3C, 0x3C, 0x00, 0x78, 0x70, 0x00, 0xF1, 0xE0, 0x01, 0xE7, 0x80, + 0x01, 0xEF, 0x00, 0x03, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, + 0x0F, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x7F, 0x87, 0xFF, + 0xFF, 0x1F, 0xFF, 0xF8, 0x7F, 0xFF, 0xE1, 0xFE, 0x78, 0x00, 0xF1, 0xE3, + 0xC3, 0x87, 0x8F, 0x0E, 0x1E, 0x7C, 0x78, 0x79, 0xF9, 0xC1, 0xEF, 0xEF, + 0x07, 0xBF, 0xBC, 0x1D, 0xFE, 0xE0, 0x77, 0x7F, 0x81, 0xFD, 0xFE, 0x07, + 0xE3, 0xF0, 0x3F, 0x8F, 0xC0, 0xFC, 0x3F, 0x03, 0xF0, 0xF8, 0x0F, 0x83, + 0xE0, 0x3E, 0x0F, 0x80, 0xF0, 0x3C, 0x00, 0x07, 0xE0, 0x7E, 0x0F, 0xF0, + 0xFF, 0x0F, 0xF0, 0xFE, 0x0F, 0xE0, 0xFE, 0x03, 0xC0, 0xF8, 0x01, 0xE1, + 0xE0, 0x01, 0xF3, 0xC0, 0x00, 0xF7, 0x80, 0x00, 0x7F, 0x00, 0x00, 0x7E, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xEF, + 0x00, 0x07, 0xCF, 0x80, 0x0F, 0x87, 0xC0, 0x1F, 0x03, 0xC0, 0x7F, 0x07, + 0xF0, 0xFF, 0x8F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xE0, 0x7E, 0x0F, + 0xEF, 0xF0, 0xFF, 0xFF, 0x0F, 0xEF, 0xE0, 0xFE, 0x3C, 0x0F, 0x01, 0xE1, + 0xE0, 0x1E, 0x3E, 0x00, 0xF7, 0xC0, 0x0F, 0xF8, 0x00, 0x7F, 0x00, 0x07, + 0xE0, 0x00, 0x3C, 0x00, 0x03, 0x80, 0x00, 0x78, 0x00, 0x07, 0x80, 0x00, + 0x78, 0x00, 0x07, 0x00, 0x07, 0xFF, 0x00, 0xFF, 0xF8, 0x0F, 0xFF, 0x00, + 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xE0, 0xFF, 0xFC, 0x3F, 0xFF, 0x87, 0xFF, + 0xF0, 0xF0, 0x7C, 0x1C, 0x1F, 0x03, 0x87, 0xC0, 0x61, 0xF0, 0x00, 0x7C, + 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x07, + 0x07, 0xC0, 0xE1, 0xF0, 0x3C, 0x7C, 0x07, 0x9F, 0xFF, 0xF3, 0xFF, 0xFC, + 0x7F, 0xFF, 0x8F, 0xFF, 0xF0, 0x07, 0xF8, 0x3F, 0xC1, 0xFE, 0x0F, 0xE0, + 0x70, 0x07, 0x80, 0x3C, 0x01, 0xC0, 0x0E, 0x00, 0xF0, 0x07, 0x80, 0x3C, + 0x01, 0xC0, 0x0E, 0x00, 0xF0, 0x07, 0x80, 0x38, 0x01, 0xC0, 0x0E, 0x00, + 0xF0, 0x07, 0x80, 0x38, 0x01, 0xC0, 0x1F, 0xE0, 0xFF, 0x07, 0xF8, 0x3F, + 0x80, 0xE0, 0x38, 0x0F, 0x03, 0xC0, 0xF0, 0x1C, 0x07, 0x81, 0xE0, 0x78, + 0x0E, 0x03, 0xC0, 0xF0, 0x3C, 0x07, 0x01, 0xE0, 0x78, 0x1E, 0x03, 0x80, + 0xF0, 0x3C, 0x0F, 0x01, 0xE0, 0x78, 0x1E, 0x03, 0x80, 0xF0, 0x3C, 0x06, + 0x07, 0xF8, 0x3F, 0xC1, 0xFC, 0x0F, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, + 0x1C, 0x00, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0x80, 0x1C, 0x01, 0xE0, 0x0F, + 0x00, 0x78, 0x03, 0x80, 0x1C, 0x01, 0xE0, 0x0F, 0x00, 0x70, 0x03, 0x80, + 0x1C, 0x0F, 0xE0, 0xFF, 0x07, 0xF0, 0x3F, 0x80, 0x00, 0x40, 0x01, 0x80, + 0x07, 0x80, 0x3F, 0x80, 0xFF, 0x03, 0xFF, 0x0F, 0x9F, 0x3E, 0x1E, 0xF8, + 0x3F, 0xE0, 0x3F, 0x00, 0x30, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xF0, 0xC3, 0xC7, 0x0E, 0x3C, 0x30, 0x00, 0xFE, 0x00, + 0x7F, 0xF0, 0x1F, 0xFF, 0x03, 0xFF, 0xE0, 0x00, 0x3C, 0x07, 0xFF, 0x83, + 0xFF, 0xF0, 0xFF, 0xFC, 0x3F, 0xFF, 0x8F, 0x80, 0xF3, 0xE0, 0x1E, 0x78, + 0x1F, 0x8F, 0xFF, 0xFF, 0xFF, 0xFF, 0xDF, 0xFF, 0xF8, 0xFE, 0x7E, 0x07, + 0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFC, 0x00, 0x03, 0xF0, 0x00, 0x01, 0xC0, + 0x00, 0x0F, 0x00, 0x00, 0x3C, 0xFC, 0x00, 0xEF, 0xFC, 0x03, 0xFF, 0xF8, + 0x1F, 0xFF, 0xE0, 0x7E, 0x0F, 0xC1, 0xE0, 0x1F, 0x07, 0x00, 0x3C, 0x1C, + 0x00, 0xF0, 0xE0, 0x03, 0xC3, 0x80, 0x1E, 0x0F, 0x00, 0xF8, 0x3E, 0x07, + 0xC7, 0xFF, 0xFF, 0x3F, 0xFF, 0xF8, 0xFF, 0xFF, 0x81, 0xF1, 0xF8, 0x00, + 0x00, 0xFE, 0x60, 0xFF, 0xFC, 0x3F, 0xFF, 0x8F, 0xFF, 0xF3, 0xF0, 0x3C, + 0xF8, 0x03, 0x9E, 0x00, 0x67, 0x80, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, + 0xC0, 0x00, 0x7E, 0x01, 0xC7, 0xFF, 0xF8, 0xFF, 0xFE, 0x0F, 0xFF, 0x80, + 0x7F, 0x80, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, + 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x70, 0x07, 0xE3, 0x80, 0xFF, 0xDC, 0x0F, + 0xFF, 0xE0, 0xFF, 0xFF, 0x0F, 0xC1, 0xF0, 0xF8, 0x07, 0x87, 0x80, 0x1C, + 0x78, 0x00, 0xE3, 0xC0, 0x0F, 0x1E, 0x00, 0x70, 0xF0, 0x07, 0x87, 0xE0, + 0xFC, 0x1F, 0xFF, 0xF8, 0xFF, 0xFF, 0xC3, 0xFF, 0xFE, 0x07, 0xE3, 0xE0, + 0x00, 0xFC, 0x01, 0xFF, 0xC0, 0xFF, 0xF8, 0x7F, 0xFE, 0x3E, 0x0F, 0xCE, + 0x00, 0xF7, 0x00, 0x3D, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xE0, 0x1E, 0xFF, 0xFF, 0x9F, 0xFF, 0xE3, 0xFF, 0xF0, 0x3F, 0xF0, + 0x00, 0x0F, 0xF0, 0x01, 0xFF, 0xC0, 0x1F, 0xFE, 0x01, 0xFF, 0xE0, 0x0F, + 0x00, 0x00, 0xF0, 0x00, 0x3F, 0xFF, 0x03, 0xFF, 0xF8, 0x1F, 0xFF, 0xC0, + 0xFF, 0xFC, 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x38, 0x00, 0x01, 0xC0, + 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x00, 0x00, 0x38, 0x00, 0x1F, + 0xFF, 0x81, 0xFF, 0xFC, 0x0F, 0xFF, 0xE0, 0x7F, 0xFE, 0x00, 0x01, 0xF9, + 0xF8, 0x3F, 0xFF, 0xC3, 0xFF, 0xFE, 0x7F, 0xFF, 0xE3, 0xE0, 0xFC, 0x3E, + 0x03, 0xE1, 0xE0, 0x0E, 0x1E, 0x00, 0x70, 0xF0, 0x03, 0x87, 0x80, 0x3C, + 0x3E, 0x03, 0xE1, 0xF8, 0x7E, 0x07, 0xFF, 0xF0, 0x3F, 0xFF, 0x80, 0xFF, + 0xFC, 0x01, 0xF9, 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x80, + 0x7F, 0xF8, 0x07, 0xFF, 0x80, 0x3F, 0xF8, 0x00, 0xFF, 0x00, 0x00, 0x0F, + 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x03, 0xC0, 0x00, + 0x38, 0x00, 0x03, 0x9F, 0x00, 0x7F, 0xFC, 0x07, 0xFF, 0xC0, 0x7F, 0xFE, + 0x07, 0xC3, 0xE0, 0x70, 0x1E, 0x0F, 0x01, 0xC0, 0xF0, 0x1C, 0x0E, 0x03, + 0xC0, 0xE0, 0x3C, 0x1E, 0x03, 0x81, 0xE0, 0x38, 0x7F, 0x0F, 0xFF, 0xF8, + 0xFF, 0xFF, 0x8F, 0xF7, 0xF0, 0xFE, 0x00, 0x78, 0x00, 0x78, 0x00, 0x78, + 0x00, 0x78, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xF0, 0x0F, 0xF0, 0x1F, 0xF0, + 0x0F, 0xF0, 0x00, 0xF0, 0x00, 0xE0, 0x00, 0xE0, 0x01, 0xE0, 0x01, 0xE0, + 0x01, 0xE0, 0x01, 0xC0, 0x01, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFE, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0xF8, 0x00, 0x3C, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFC, 0x3F, 0xFE, 0x0F, 0xFF, 0x81, 0xFF, + 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x01, 0xC0, 0x00, 0xF0, + 0x00, 0x3C, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, 0x00, 0x78, 0x00, + 0x1E, 0x00, 0x07, 0x00, 0x01, 0xC0, 0x00, 0xF0, 0x00, 0x7C, 0x1F, 0xFE, + 0x0F, 0xFF, 0x03, 0xFF, 0x80, 0x7F, 0x80, 0x00, 0x07, 0xE0, 0x00, 0xFE, + 0x00, 0x0F, 0xE0, 0x00, 0x7C, 0x00, 0x01, 0xC0, 0x00, 0x3C, 0x00, 0x03, + 0xCF, 0xF0, 0x3C, 0xFF, 0x03, 0x9F, 0xF0, 0x38, 0xFE, 0x07, 0xBF, 0x00, + 0x7F, 0xC0, 0x07, 0xF8, 0x00, 0x7F, 0x00, 0x07, 0xF8, 0x00, 0xFF, 0xC0, + 0x0F, 0x7E, 0x00, 0xE3, 0xF0, 0x7E, 0x1F, 0xE7, 0xE1, 0xFE, 0xFE, 0x3F, + 0xE7, 0xE1, 0xFC, 0x03, 0xFC, 0x07, 0xFC, 0x07, 0xF8, 0x07, 0xF8, 0x00, + 0x78, 0x00, 0x78, 0x00, 0x78, 0x00, 0x70, 0x00, 0x70, 0x00, 0xF0, 0x00, + 0xF0, 0x00, 0xE0, 0x00, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, + 0xC0, 0x01, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x1F, + 0x7C, 0x78, 0x7F, 0xFF, 0xF8, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, 0xF0, 0xF1, + 0xF1, 0xE1, 0xC3, 0x83, 0xC7, 0x87, 0x07, 0x8F, 0x0E, 0x0E, 0x1C, 0x3C, + 0x1C, 0x38, 0x78, 0x78, 0x70, 0xE0, 0xF1, 0xE1, 0xC1, 0xC7, 0xE3, 0xC3, + 0xFF, 0xCF, 0xC7, 0xFF, 0x9F, 0x9F, 0xFF, 0x3E, 0x3E, 0x0F, 0x8F, 0x80, + 0xFD, 0xFF, 0x07, 0xFF, 0xF8, 0x3F, 0xFF, 0xE0, 0x7E, 0x1F, 0x07, 0xC0, + 0x78, 0x3C, 0x03, 0x81, 0xE0, 0x1C, 0x0E, 0x01, 0xE0, 0x70, 0x0F, 0x07, + 0x80, 0x70, 0x3C, 0x03, 0x87, 0xF0, 0x3F, 0x7F, 0xC3, 0xFF, 0xFE, 0x1F, + 0xEF, 0xE0, 0xFE, 0x01, 0xFC, 0x01, 0xFF, 0x80, 0xFF, 0xF8, 0x7F, 0xFE, + 0x3E, 0x0F, 0xDF, 0x01, 0xF7, 0x80, 0x3F, 0xC0, 0x0F, 0xF0, 0x03, 0xFC, + 0x01, 0xEF, 0x80, 0xFB, 0xF0, 0x7C, 0x7F, 0xFF, 0x1F, 0xFF, 0x03, 0xFF, + 0x80, 0x3F, 0x80, 0x07, 0xC7, 0xE0, 0x1F, 0xBF, 0xF0, 0x3F, 0xFF, 0xF0, + 0x7F, 0xFF, 0xE0, 0x3F, 0x07, 0xE0, 0x78, 0x03, 0xC0, 0xE0, 0x07, 0x81, + 0xC0, 0x0F, 0x07, 0x00, 0x1E, 0x0F, 0x00, 0x78, 0x1E, 0x01, 0xF0, 0x3E, + 0x07, 0xC0, 0xFF, 0xFF, 0x81, 0xFF, 0xFE, 0x03, 0xDF, 0xF0, 0x07, 0x1F, + 0x80, 0x0E, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x78, 0x00, 0x03, 0xFE, 0x00, + 0x0F, 0xFE, 0x00, 0x1F, 0xF8, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x01, 0xF8, + 0xF8, 0x1F, 0xFF, 0xF1, 0xFF, 0xFF, 0xCF, 0xFF, 0xFE, 0x3E, 0x07, 0xC1, + 0xF0, 0x0F, 0x07, 0x80, 0x1C, 0x3C, 0x00, 0x70, 0xF0, 0x03, 0x83, 0xC0, + 0x0E, 0x0F, 0x80, 0x78, 0x3F, 0x07, 0xE0, 0x7F, 0xFF, 0x81, 0xFF, 0xFC, + 0x03, 0xFF, 0x70, 0x03, 0xF3, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0xE0, 0x00, 0x3F, 0xE0, 0x01, 0xFF, 0xC0, 0x07, 0xFF, 0x00, 0x1F, + 0xF8, 0x00, 0x0F, 0xC3, 0xC1, 0xFC, 0xFF, 0x1F, 0xFF, 0xF1, 0xFF, 0xFE, + 0x03, 0xFC, 0x00, 0x3F, 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x07, 0x80, + 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0xF0, 0x00, 0xFF, 0xFC, 0x0F, 0xFF, + 0xE0, 0xFF, 0xFC, 0x0F, 0xFF, 0xC0, 0x03, 0xF3, 0x0F, 0xFF, 0x3F, 0xFF, + 0x3F, 0xFF, 0x7C, 0x0E, 0x78, 0x00, 0x7F, 0xE0, 0x3F, 0xFC, 0x1F, 0xFF, + 0x00, 0x3F, 0x70, 0x0F, 0xF8, 0x1F, 0xFF, 0xFE, 0xFF, 0xFC, 0xFF, 0xF8, + 0x0F, 0xE0, 0x06, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0E, 0x00, 0x0E, 0x00, + 0x7F, 0xFE, 0xFF, 0xFE, 0xFF, 0xFE, 0xFF, 0xFC, 0x1C, 0x00, 0x3C, 0x00, + 0x3C, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x78, 0x00, 0x7C, 0x0E, + 0x7F, 0xFF, 0x7F, 0xFE, 0x3F, 0xFC, 0x0F, 0xE0, 0x7C, 0x0F, 0xFF, 0x07, + 0xFF, 0x81, 0xFF, 0xE0, 0x7E, 0x78, 0x03, 0x9E, 0x00, 0xE7, 0x80, 0x79, + 0xE0, 0x1E, 0x78, 0x07, 0x1E, 0x01, 0xC7, 0x80, 0xF1, 0xE0, 0xFC, 0x7F, + 0xFF, 0x9F, 0xFF, 0xE3, 0xFF, 0xF8, 0x3E, 0x7C, 0x7F, 0x87, 0xFF, 0xFC, + 0x7F, 0xFF, 0xE3, 0xFF, 0xFF, 0x1F, 0xE1, 0xE0, 0x3C, 0x0F, 0x03, 0xC0, + 0x78, 0x3C, 0x01, 0xE1, 0xC0, 0x0F, 0x1E, 0x00, 0x79, 0xE0, 0x03, 0xCE, + 0x00, 0x0F, 0xF0, 0x00, 0x7F, 0x00, 0x03, 0xF0, 0x00, 0x0F, 0x80, 0x00, + 0x78, 0x00, 0x7E, 0x03, 0xF7, 0xF0, 0x3F, 0xFF, 0x81, 0xFD, 0xF8, 0x0F, + 0xE7, 0x8E, 0x1C, 0x3C, 0xF9, 0xE1, 0xE7, 0xCE, 0x0F, 0x7E, 0xF0, 0x7B, + 0xF7, 0x03, 0xFF, 0xF8, 0x1F, 0xDF, 0x80, 0xFC, 0xFC, 0x07, 0xE7, 0xE0, + 0x3E, 0x3E, 0x01, 0xF1, 0xF0, 0x0F, 0x07, 0x00, 0x0F, 0xE3, 0xF8, 0xFF, + 0x1F, 0xC7, 0xF9, 0xFE, 0x1F, 0x87, 0xF0, 0x7E, 0x7C, 0x01, 0xFF, 0xC0, + 0x07, 0xFC, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x1F, 0xF0, 0x01, 0xF7, + 0xC0, 0x1F, 0x1F, 0x03, 0xF0, 0x7C, 0x7F, 0xCF, 0xFB, 0xFE, 0x7F, 0xDF, + 0xE3, 0xFC, 0x07, 0xF0, 0x7F, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x07, + 0xE0, 0xFE, 0x03, 0xC0, 0x78, 0x03, 0xC0, 0x78, 0x03, 0xC0, 0xF0, 0x01, + 0xE1, 0xE0, 0x01, 0xE1, 0xC0, 0x01, 0xE3, 0xC0, 0x00, 0xF7, 0x80, 0x00, + 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7C, 0x00, 0x00, + 0x78, 0x00, 0x00, 0x70, 0x00, 0x00, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x7F, + 0xF0, 0x00, 0xFF, 0xF8, 0x00, 0xFF, 0xF0, 0x00, 0x7F, 0xF0, 0x00, 0x1F, + 0xFF, 0xC7, 0xFF, 0xF1, 0xFF, 0xF8, 0xFF, 0xFE, 0x3C, 0x1F, 0x0E, 0x1F, + 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, + 0xF8, 0x3C, 0xFF, 0xFF, 0x3F, 0xFF, 0xCF, 0xFF, 0xE3, 0xFF, 0xF8, 0x00, + 0xF0, 0x1F, 0x03, 0xF0, 0x7E, 0x07, 0x80, 0x70, 0x0F, 0x00, 0xF0, 0x0E, + 0x00, 0xE0, 0x1E, 0x01, 0xC0, 0xFC, 0x0F, 0x80, 0xF8, 0x0F, 0xC0, 0x3C, + 0x03, 0xC0, 0x38, 0x03, 0x80, 0x78, 0x07, 0x80, 0x78, 0x07, 0xE0, 0x7E, + 0x03, 0xE0, 0x1C, 0x00, 0x02, 0x07, 0x07, 0x0F, 0x0F, 0x0E, 0x0E, 0x0E, + 0x1E, 0x1E, 0x1C, 0x1C, 0x1C, 0x3C, 0x3C, 0x38, 0x38, 0x38, 0x78, 0x78, + 0x70, 0x70, 0x70, 0xF0, 0xF0, 0xE0, 0xE0, 0x01, 0xC0, 0x1F, 0x00, 0xFC, + 0x07, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1C, 0x00, 0xE0, 0x0F, 0x00, + 0x78, 0x03, 0xC0, 0x1F, 0x80, 0x7C, 0x03, 0xE0, 0x3F, 0x03, 0xC0, 0x1C, + 0x00, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0x80, 0x3C, 0x0F, 0xE0, 0x7E, 0x07, + 0xE0, 0x1E, 0x00, 0x0F, 0x00, 0x1F, 0xC0, 0x1F, 0xF0, 0xFF, 0xFC, 0xFF, + 0x3F, 0xFF, 0x0F, 0xF8, 0x03, 0xF8, 0x00, 0xF0 }; + +const GFXglyph FreeMonoBoldOblique18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 21, 0, 1 }, // 0x20 ' ' + { 0, 9, 22, 21, 9, -21 }, // 0x21 '!' + { 25, 12, 10, 21, 9, -20 }, // 0x22 '"' + { 40, 18, 25, 21, 4, -22 }, // 0x23 '#' + { 97, 18, 28, 21, 4, -23 }, // 0x24 '$' + { 160, 16, 21, 21, 5, -20 }, // 0x25 '%' + { 202, 16, 20, 21, 4, -19 }, // 0x26 '&' + { 242, 5, 10, 21, 12, -20 }, // 0x27 ''' + { 249, 10, 27, 21, 11, -21 }, // 0x28 '(' + { 283, 10, 27, 21, 4, -21 }, // 0x29 ')' + { 317, 15, 15, 21, 6, -21 }, // 0x2A '*' + { 346, 18, 19, 21, 4, -18 }, // 0x2B '+' + { 389, 9, 10, 21, 4, -3 }, // 0x2C ',' + { 401, 18, 4, 21, 4, -11 }, // 0x2D '-' + { 410, 5, 5, 21, 8, -4 }, // 0x2E '.' + { 414, 21, 28, 21, 2, -23 }, // 0x2F '/' + { 488, 17, 23, 21, 5, -22 }, // 0x30 '0' + { 537, 15, 22, 21, 3, -21 }, // 0x31 '1' + { 579, 20, 23, 21, 2, -22 }, // 0x32 '2' + { 637, 18, 23, 21, 3, -22 }, // 0x33 '3' + { 689, 16, 21, 21, 4, -20 }, // 0x34 '4' + { 731, 18, 22, 21, 4, -21 }, // 0x35 '5' + { 781, 19, 23, 21, 5, -22 }, // 0x36 '6' + { 836, 16, 22, 21, 6, -21 }, // 0x37 '7' + { 880, 19, 23, 21, 3, -22 }, // 0x38 '8' + { 935, 18, 23, 21, 4, -22 }, // 0x39 '9' + { 987, 7, 16, 21, 9, -15 }, // 0x3A ':' + { 1001, 11, 22, 21, 4, -15 }, // 0x3B ';' + { 1032, 18, 16, 21, 4, -17 }, // 0x3C '<' + { 1068, 19, 10, 21, 3, -14 }, // 0x3D '=' + { 1092, 19, 16, 21, 3, -17 }, // 0x3E '>' + { 1130, 14, 21, 21, 8, -20 }, // 0x3F '?' + { 1167, 18, 27, 21, 3, -21 }, // 0x40 '@' + { 1228, 22, 21, 21, 0, -20 }, // 0x41 'A' + { 1286, 21, 21, 21, 1, -20 }, // 0x42 'B' + { 1342, 21, 21, 21, 2, -20 }, // 0x43 'C' + { 1398, 21, 21, 21, 1, -20 }, // 0x44 'D' + { 1454, 22, 21, 21, 0, -20 }, // 0x45 'E' + { 1512, 23, 21, 21, 0, -20 }, // 0x46 'F' + { 1573, 21, 21, 21, 2, -20 }, // 0x47 'G' + { 1629, 23, 21, 21, 0, -20 }, // 0x48 'H' + { 1690, 19, 21, 21, 2, -20 }, // 0x49 'I' + { 1740, 23, 21, 21, 0, -20 }, // 0x4A 'J' + { 1801, 23, 21, 21, 0, -20 }, // 0x4B 'K' + { 1862, 20, 21, 21, 1, -20 }, // 0x4C 'L' + { 1915, 25, 21, 21, 0, -20 }, // 0x4D 'M' + { 1981, 24, 21, 21, 1, -20 }, // 0x4E 'N' + { 2044, 20, 21, 21, 2, -20 }, // 0x4F 'O' + { 2097, 21, 21, 21, 1, -20 }, // 0x50 'P' + { 2153, 20, 26, 21, 2, -20 }, // 0x51 'Q' + { 2218, 22, 21, 21, 0, -20 }, // 0x52 'R' + { 2276, 19, 21, 21, 3, -20 }, // 0x53 'S' + { 2326, 19, 21, 21, 3, -20 }, // 0x54 'T' + { 2376, 21, 21, 21, 3, -20 }, // 0x55 'U' + { 2432, 23, 21, 21, 1, -20 }, // 0x56 'V' + { 2493, 22, 21, 21, 2, -20 }, // 0x57 'W' + { 2551, 24, 21, 21, 0, -20 }, // 0x58 'X' + { 2614, 20, 21, 21, 3, -20 }, // 0x59 'Y' + { 2667, 19, 21, 21, 2, -20 }, // 0x5A 'Z' + { 2717, 13, 27, 21, 8, -21 }, // 0x5B '[' + { 2761, 10, 28, 21, 8, -23 }, // 0x5C '\' + { 2796, 13, 27, 21, 4, -21 }, // 0x5D ']' + { 2840, 15, 11, 21, 6, -21 }, // 0x5E '^' + { 2861, 21, 4, 21, -1, 4 }, // 0x5F '_' + { 2872, 6, 6, 21, 10, -22 }, // 0x60 '`' + { 2877, 19, 16, 21, 2, -15 }, // 0x61 'a' + { 2915, 22, 22, 21, 0, -21 }, // 0x62 'b' + { 2976, 19, 16, 21, 3, -15 }, // 0x63 'c' + { 3014, 21, 22, 21, 3, -21 }, // 0x64 'd' + { 3072, 18, 16, 21, 3, -15 }, // 0x65 'e' + { 3108, 21, 22, 21, 3, -21 }, // 0x66 'f' + { 3166, 21, 23, 21, 2, -15 }, // 0x67 'g' + { 3227, 20, 22, 21, 1, -21 }, // 0x68 'h' + { 3282, 16, 22, 21, 3, -21 }, // 0x69 'i' + { 3326, 18, 29, 21, 2, -21 }, // 0x6A 'j' + { 3392, 20, 22, 21, 1, -21 }, // 0x6B 'k' + { 3447, 16, 22, 21, 3, -21 }, // 0x6C 'l' + { 3491, 23, 16, 21, 0, -15 }, // 0x6D 'm' + { 3537, 21, 16, 21, 1, -15 }, // 0x6E 'n' + { 3579, 18, 16, 21, 3, -15 }, // 0x6F 'o' + { 3615, 23, 23, 21, -1, -15 }, // 0x70 'p' + { 3682, 22, 23, 21, 2, -15 }, // 0x71 'q' + { 3746, 20, 16, 21, 2, -15 }, // 0x72 'r' + { 3786, 16, 16, 21, 4, -15 }, // 0x73 's' + { 3818, 16, 21, 21, 4, -20 }, // 0x74 't' + { 3860, 18, 16, 21, 3, -15 }, // 0x75 'u' + { 3896, 21, 16, 21, 2, -15 }, // 0x76 'v' + { 3938, 21, 16, 21, 3, -15 }, // 0x77 'w' + { 3980, 21, 16, 21, 1, -15 }, // 0x78 'x' + { 4022, 24, 23, 21, -1, -15 }, // 0x79 'y' + { 4091, 18, 16, 21, 3, -15 }, // 0x7A 'z' + { 4127, 12, 27, 21, 8, -21 }, // 0x7B '{' + { 4168, 8, 27, 21, 8, -21 }, // 0x7C '|' + { 4195, 13, 27, 21, 4, -21 }, // 0x7D '}' + { 4239, 17, 8, 21, 4, -13 } }; // 0x7E '~' + +const GFXfont FreeMonoBoldOblique18pt7b PROGMEM = { + (uint8_t *)FreeMonoBoldOblique18pt7bBitmaps, + (GFXglyph *)FreeMonoBoldOblique18pt7bGlyphs, + 0x20, 0x7E, 35 }; + +// Approx. 4928 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique24pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique24pt7b.h new file mode 100644 index 0000000..a2bbbdf --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique24pt7b.h @@ -0,0 +1,742 @@ +const uint8_t FreeMonoBoldOblique24pt7bBitmaps[] PROGMEM = { + 0x01, 0xE0, 0x3F, 0x07, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xE0, 0xFE, + 0x0F, 0xE0, 0xFE, 0x0F, 0xC0, 0xFC, 0x1F, 0xC1, 0xF8, 0x1F, 0x81, 0xF8, + 0x1F, 0x81, 0xF0, 0x1F, 0x01, 0xF0, 0x1E, 0x00, 0x80, 0x00, 0x00, 0x00, + 0x00, 0x03, 0xC0, 0x7E, 0x0F, 0xE0, 0xFE, 0x0F, 0xC0, 0x78, 0x00, 0x7E, + 0x1F, 0xBF, 0x0F, 0xDF, 0x87, 0xCF, 0x83, 0xE7, 0xC1, 0xF3, 0xE0, 0xF1, + 0xE0, 0xF8, 0xF0, 0x7C, 0x78, 0x3C, 0x38, 0x1E, 0x1C, 0x0F, 0x0E, 0x07, + 0x0E, 0x03, 0x83, 0x01, 0x80, 0x00, 0x1C, 0x1C, 0x00, 0x3E, 0x3E, 0x00, + 0x3E, 0x3E, 0x00, 0x3C, 0x3C, 0x00, 0x7C, 0x7C, 0x00, 0x7C, 0x7C, 0x00, + 0x7C, 0x7C, 0x00, 0xF8, 0xF8, 0x00, 0xF8, 0xF8, 0x00, 0xF8, 0xF8, 0x0F, + 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0x1F, + 0xFF, 0xFE, 0x03, 0xE3, 0xE0, 0x03, 0xE3, 0xE0, 0x03, 0xC3, 0xC0, 0x07, + 0xC7, 0xC0, 0x7F, 0xFF, 0xF8, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFC, 0xFF, + 0xFF, 0xF8, 0xFF, 0xFF, 0xF0, 0x0F, 0x0F, 0x00, 0x1F, 0x1F, 0x00, 0x1F, + 0x1F, 0x00, 0x1F, 0x1F, 0x00, 0x3E, 0x1E, 0x00, 0x3E, 0x3E, 0x00, 0x3E, + 0x3E, 0x00, 0x3C, 0x3C, 0x00, 0x7C, 0x7C, 0x00, 0x38, 0x38, 0x00, 0x00, + 0x00, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0xFF, 0x00, 0x01, 0xFF, 0xFC, 0x03, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, + 0x01, 0xFF, 0xFF, 0x81, 0xFC, 0x1F, 0xC1, 0xF8, 0x03, 0xC0, 0xF8, 0x01, + 0xE0, 0x7C, 0x00, 0x40, 0x3F, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x0F, 0xFF, + 0x80, 0x03, 0xFF, 0xF8, 0x00, 0xFF, 0xFE, 0x00, 0x0F, 0xFF, 0x00, 0x00, + 0x7F, 0xC0, 0x00, 0x07, 0xE0, 0xE0, 0x01, 0xF0, 0xF0, 0x00, 0xF8, 0xF8, + 0x00, 0xFC, 0x7E, 0x00, 0xFC, 0x3F, 0x81, 0xFE, 0x1F, 0xFF, 0xFE, 0x0F, + 0xFF, 0xFE, 0x0F, 0xFF, 0xFE, 0x03, 0xFF, 0xFC, 0x00, 0x07, 0xF0, 0x00, + 0x01, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x00, 0xF8, + 0x00, 0x0F, 0xF8, 0x00, 0x7F, 0xE0, 0x03, 0xC3, 0xC0, 0x0E, 0x07, 0x00, + 0x70, 0x1C, 0x01, 0xC0, 0x70, 0x07, 0x01, 0xC0, 0x1C, 0x0E, 0x00, 0x78, + 0x78, 0x00, 0xFF, 0xC0, 0x03, 0xFE, 0x1F, 0x03, 0xE3, 0xFC, 0x00, 0x7F, + 0xC0, 0x0F, 0xF8, 0x03, 0xFF, 0x00, 0x7F, 0xC0, 0x03, 0xF8, 0x7C, 0x0F, + 0x07, 0xFC, 0x00, 0x3F, 0xF0, 0x01, 0xE1, 0xE0, 0x07, 0x03, 0x80, 0x38, + 0x0E, 0x00, 0xE0, 0x38, 0x03, 0x80, 0xE0, 0x0E, 0x07, 0x00, 0x3C, 0x3C, + 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1F, 0x00, + 0x01, 0xFF, 0x80, 0x3F, 0xFC, 0x03, 0xFF, 0xE0, 0x1F, 0xFE, 0x01, 0xF1, + 0xE0, 0x1F, 0x04, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, + 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x07, 0xF8, 0x00, 0x7F, 0xE3, + 0xE7, 0xFF, 0x3F, 0x7E, 0xFF, 0xFB, 0xE7, 0xFF, 0x9E, 0x1F, 0xF1, 0xF0, + 0xFF, 0x8F, 0x83, 0xF8, 0x7C, 0x1F, 0xC3, 0xF0, 0xFF, 0x9F, 0xFF, 0xFC, + 0x7F, 0xFF, 0xE3, 0xFF, 0xFF, 0x0F, 0xFD, 0xF0, 0x1F, 0x80, 0x00, 0x7E, + 0xFD, 0xF3, 0xE7, 0xCF, 0x3E, 0x7C, 0xF1, 0xE3, 0xC7, 0x0E, 0x18, 0x00, + 0x00, 0x18, 0x00, 0xF0, 0x07, 0xC0, 0x3F, 0x01, 0xF8, 0x07, 0xC0, 0x3E, + 0x01, 0xF8, 0x07, 0xC0, 0x3E, 0x00, 0xF8, 0x07, 0xC0, 0x1F, 0x00, 0xF8, + 0x03, 0xE0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x3E, 0x00, 0xF8, + 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, + 0x00, 0xFC, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x80, 0x7E, 0x00, 0xFC, 0x03, + 0xF0, 0x07, 0xC0, 0x1E, 0x00, 0x00, 0xC0, 0x07, 0x80, 0x3F, 0x00, 0xFC, + 0x03, 0xF0, 0x07, 0xE0, 0x1F, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xF0, 0x07, + 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, + 0xF0, 0x07, 0xC0, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x1F, 0x00, 0x7C, 0x01, + 0xF0, 0x0F, 0x80, 0x3E, 0x01, 0xF0, 0x0F, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, + 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x3E, 0x00, 0xF0, 0x00, 0x00, 0x3C, + 0x00, 0x01, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x08, + 0x3C, 0x09, 0xF9, 0xE7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, + 0x87, 0xFF, 0xE0, 0x07, 0xF8, 0x00, 0x7F, 0xC0, 0x07, 0xFF, 0x00, 0x7F, + 0xF8, 0x07, 0xE7, 0xE0, 0x3E, 0x3F, 0x01, 0xE0, 0xF8, 0x0E, 0x07, 0x80, + 0x00, 0x07, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x0F, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x3E, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x7C, 0x00, + 0x00, 0x78, 0x00, 0x00, 0x78, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xF0, 0x00, + 0x01, 0xF0, 0x00, 0x00, 0xE0, 0x00, 0x03, 0xF0, 0x7E, 0x07, 0xC0, 0xFC, + 0x0F, 0x81, 0xF0, 0x1E, 0x03, 0xE0, 0x3C, 0x07, 0x80, 0x78, 0x0F, 0x00, + 0xE0, 0x0C, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x3C, 0xFF, 0xFF, 0xFF, 0xCF, 0x00, + 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x01, 0xF0, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, + 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1F, + 0x80, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x07, 0xE0, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x01, 0xF0, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x07, 0x00, 0x00, + 0x00, 0x00, 0x0F, 0xC0, 0x00, 0xFF, 0xE0, 0x03, 0xFF, 0xE0, 0x1F, 0xFF, + 0xE0, 0x7F, 0xFF, 0xC0, 0xFC, 0x1F, 0x83, 0xF0, 0x1F, 0x8F, 0xC0, 0x1F, + 0x1F, 0x00, 0x3E, 0x7C, 0x00, 0x7C, 0xF8, 0x00, 0xF9, 0xF0, 0x01, 0xF3, + 0xC0, 0x07, 0xCF, 0x80, 0x0F, 0x9F, 0x00, 0x1E, 0x3E, 0x00, 0x3C, 0x78, + 0x00, 0xF8, 0xF0, 0x01, 0xF3, 0xE0, 0x03, 0xE7, 0xC0, 0x07, 0x8F, 0x80, + 0x1F, 0x1F, 0x00, 0x3E, 0x3E, 0x00, 0xF8, 0x7C, 0x01, 0xF0, 0xFC, 0x07, + 0xC1, 0xFC, 0x3F, 0x81, 0xFF, 0xFE, 0x03, 0xFF, 0xF8, 0x03, 0xFF, 0xE0, + 0x03, 0xFF, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x7E, + 0x00, 0x0F, 0xF0, 0x01, 0xFF, 0x80, 0x1F, 0xFC, 0x03, 0xFB, 0xE0, 0x1F, + 0x9E, 0x00, 0xF1, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xE0, + 0x00, 0x1E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x03, + 0xC0, 0x00, 0x1E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, + 0x03, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, + 0x01, 0xFF, 0xFF, 0x9F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x3F, + 0xFF, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x03, 0xFF, 0x80, 0x03, 0xFF, 0xF0, + 0x01, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0x80, 0x7F, 0x07, 0xF0, 0x1F, 0x00, + 0xFC, 0x0F, 0x80, 0x1F, 0x03, 0xE0, 0x07, 0xC0, 0xF0, 0x01, 0xF0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x03, 0xF8, + 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, + 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, 0x80, 0x70, 0x3F, 0x80, 0x3E, 0x1F, + 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFC, + 0x3F, 0xFF, 0xFF, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x0F, 0xFE, 0x00, 0x1F, + 0xFF, 0x80, 0x1F, 0xFF, 0xE0, 0x1F, 0xFF, 0xF8, 0x0F, 0x81, 0xFC, 0x07, + 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x0F, 0xC0, + 0x00, 0x07, 0xC0, 0x00, 0x0F, 0xC0, 0x01, 0xFF, 0xC0, 0x01, 0xFF, 0xC0, + 0x00, 0xFF, 0x80, 0x00, 0x7F, 0xE0, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0x1F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, + 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFC, 0x3C, 0x01, + 0xFC, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, 0xFC, 0x0F, 0xFF, 0xFC, 0x03, 0xFF, + 0xFC, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0xFC, 0x00, 0x07, 0xF0, 0x00, + 0x3F, 0xC0, 0x01, 0xFE, 0x00, 0x0F, 0xF8, 0x00, 0x7F, 0xE0, 0x03, 0xFF, + 0x80, 0x1F, 0xBE, 0x00, 0x7C, 0xF0, 0x03, 0xE7, 0xC0, 0x1F, 0x1F, 0x00, + 0xF8, 0x7C, 0x07, 0xE1, 0xE0, 0x3F, 0x07, 0x81, 0xF8, 0x3E, 0x07, 0xC0, + 0xF8, 0x3E, 0x03, 0xC1, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0xBF, 0xFF, 0xFE, + 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0x80, 0x00, 0xF8, 0x00, 0x3F, 0xF8, 0x01, + 0xFF, 0xE0, 0x07, 0xFF, 0x80, 0x1F, 0xFE, 0x00, 0x7F, 0xF0, 0x01, 0xFF, + 0xFF, 0x00, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xC0, 0x3F, 0xFF, 0xE0, 0x3F, + 0xFF, 0xE0, 0x1F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, + 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, 0xF7, 0xF0, 0x00, 0xFF, 0xFE, 0x00, + 0x7F, 0xFF, 0x80, 0x3F, 0xFF, 0xE0, 0x1F, 0xFF, 0xF0, 0x0F, 0x01, 0xFC, + 0x00, 0x00, 0x7E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, + 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0xF8, 0x3C, 0x03, 0xFC, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, + 0xFC, 0x0F, 0xFF, 0xFC, 0x03, 0xFF, 0xF8, 0x00, 0x3F, 0xE0, 0x00, 0x00, + 0x01, 0xFC, 0x00, 0x07, 0xFE, 0x00, 0x1F, 0xFF, 0x00, 0x7F, 0xFF, 0x00, + 0xFF, 0xFE, 0x01, 0xFE, 0x1C, 0x03, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x0F, + 0xC0, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x3E, 0x00, 0x3E, + 0xFF, 0x80, 0x7D, 0xFF, 0xC0, 0x7F, 0xFF, 0xE0, 0x7F, 0xFF, 0xE0, 0x7F, + 0x87, 0xF0, 0xFF, 0x03, 0xF0, 0xFC, 0x01, 0xF0, 0xF8, 0x01, 0xF0, 0xF8, + 0x01, 0xF0, 0xF8, 0x01, 0xF0, 0xF8, 0x03, 0xE0, 0xF8, 0x03, 0xE0, 0xFC, + 0x07, 0xC0, 0xFE, 0x0F, 0xC0, 0x7F, 0xFF, 0x80, 0x7F, 0xFF, 0x00, 0x3F, + 0xFE, 0x00, 0x1F, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x7F, 0xFF, 0xFD, 0xFF, + 0xFF, 0xE7, 0xFF, 0xFF, 0xBF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFB, 0xE0, 0x07, + 0xCF, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, + 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x01, + 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, + 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x00, + 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, + 0x00, 0x1F, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0xFF, + 0xE0, 0x07, 0xFF, 0xE0, 0x1F, 0xFF, 0xE0, 0x7F, 0xFF, 0xC0, 0xFC, 0x1F, + 0xC3, 0xF0, 0x1F, 0x8F, 0xC0, 0x1F, 0x1F, 0x00, 0x3E, 0x3E, 0x00, 0x7C, + 0x7C, 0x01, 0xF0, 0xFC, 0x07, 0xE0, 0xFC, 0x1F, 0x81, 0xFF, 0xFE, 0x01, + 0xFF, 0xF0, 0x01, 0xFF, 0xE0, 0x0F, 0xFF, 0xE0, 0x3F, 0xFF, 0xE0, 0xFE, + 0x0F, 0xC3, 0xF0, 0x0F, 0xC7, 0xC0, 0x0F, 0x9F, 0x00, 0x1F, 0x3E, 0x00, + 0x3E, 0x7C, 0x00, 0xFC, 0xFC, 0x03, 0xF1, 0xFC, 0x1F, 0xE3, 0xFF, 0xFF, + 0x83, 0xFF, 0xFE, 0x03, 0xFF, 0xF8, 0x03, 0xFF, 0xC0, 0x01, 0xFC, 0x00, + 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x3F, 0xF8, 0x00, 0xFF, 0xFC, 0x01, 0xFF, + 0xFE, 0x03, 0xFF, 0xFE, 0x03, 0xF0, 0x7F, 0x07, 0xE0, 0x3F, 0x07, 0xC0, + 0x1F, 0x0F, 0xC0, 0x1F, 0x0F, 0x80, 0x1F, 0x0F, 0x80, 0x1F, 0x0F, 0x80, + 0x3F, 0x0F, 0xC0, 0x7F, 0x0F, 0xE1, 0xFF, 0x07, 0xFF, 0xFE, 0x07, 0xFF, + 0xFE, 0x03, 0xFF, 0xBE, 0x01, 0xFF, 0x7C, 0x00, 0xFC, 0x7C, 0x00, 0x00, + 0xFC, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x03, 0xF0, 0x00, 0x0F, + 0xE0, 0x00, 0x1F, 0xC0, 0x38, 0x7F, 0x80, 0x7F, 0xFF, 0x00, 0xFF, 0xFE, + 0x00, 0xFF, 0xF8, 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0x80, 0x00, 0x07, 0x83, + 0xF1, 0xFC, 0x7F, 0x1F, 0x83, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3C, 0x1F, 0x8F, 0xE3, 0xF8, 0xFC, + 0x1E, 0x00, 0x00, 0x3C, 0x00, 0xFC, 0x03, 0xF8, 0x07, 0xF0, 0x0F, 0xC0, + 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xF8, 0x03, 0xE0, 0x0F, 0xC0, + 0x1F, 0x00, 0x7C, 0x00, 0xF0, 0x03, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x38, + 0x00, 0xF0, 0x01, 0xC0, 0x07, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, + 0x03, 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xE0, 0x00, + 0x7F, 0xC0, 0x00, 0xFF, 0x80, 0x03, 0xFF, 0x00, 0x07, 0xFE, 0x00, 0x0F, + 0xFC, 0x00, 0x1F, 0xF0, 0x00, 0x1F, 0xFC, 0x00, 0x01, 0xFF, 0x00, 0x00, + 0x3F, 0xE0, 0x00, 0x0F, 0xFC, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x3F, 0xE0, + 0x00, 0x07, 0xFC, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, + 0x80, 0x1F, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xFC, 0xFF, + 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, + 0xF3, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0x80, 0x00, + 0x00, 0x00, 0x07, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, + 0xFF, 0x80, 0x00, 0x1F, 0xF0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0xFF, 0xC0, + 0x00, 0x1F, 0xF0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x7F, + 0xE0, 0x00, 0xFF, 0xC0, 0x01, 0xFF, 0x80, 0x03, 0xFE, 0x00, 0x07, 0xFC, + 0x00, 0x1F, 0xF8, 0x00, 0x3F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0x80, + 0x00, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFC, 0x01, 0xFF, + 0xE1, 0xFF, 0xFE, 0x3F, 0xFF, 0xE7, 0xFF, 0xFF, 0xF8, 0x1F, 0xFE, 0x00, + 0xFF, 0x80, 0x1F, 0xF0, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x0F, + 0xE0, 0x07, 0xF8, 0x07, 0xFE, 0x01, 0xFF, 0x80, 0x7F, 0xC0, 0x0F, 0xE0, + 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x03, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xF0, 0x00, 0x3F, 0x00, 0x0F, 0xE0, 0x01, 0xFC, 0x00, + 0x3F, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x7F, 0xF0, 0x01, + 0xFF, 0xF0, 0x0F, 0xFF, 0xE0, 0x3F, 0x07, 0xE0, 0x7C, 0x07, 0xC1, 0xE0, + 0x07, 0x87, 0xC0, 0x0F, 0x0F, 0x00, 0x1C, 0x3C, 0x00, 0x78, 0x78, 0x07, + 0xF1, 0xE0, 0x3F, 0xE3, 0xC1, 0xFF, 0x87, 0x87, 0xFF, 0x0E, 0x1F, 0x9E, + 0x3C, 0x7C, 0x3C, 0x78, 0xF0, 0x78, 0xF3, 0xC0, 0xE1, 0xC7, 0x83, 0xC3, + 0x8F, 0x07, 0x8F, 0x1E, 0x0F, 0x1E, 0x3E, 0x1C, 0x3C, 0x7F, 0xFC, 0x78, + 0x7F, 0xFC, 0xF0, 0x7F, 0xF1, 0xE0, 0x3F, 0xE3, 0xC0, 0x00, 0x07, 0x80, + 0x00, 0x0F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x3F, 0x01, + 0xC0, 0x7F, 0xFF, 0x80, 0x7F, 0xFE, 0x00, 0x7F, 0xF8, 0x00, 0x3F, 0x80, + 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x01, 0xFF, 0xF8, 0x00, 0x07, 0xFF, 0xE0, + 0x00, 0x1F, 0xFF, 0x80, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x0F, 0xFC, 0x00, + 0x00, 0x7F, 0xF0, 0x00, 0x01, 0xE7, 0xC0, 0x00, 0x0F, 0x9F, 0x00, 0x00, + 0x7C, 0x7C, 0x00, 0x01, 0xE1, 0xF8, 0x00, 0x0F, 0x87, 0xE0, 0x00, 0x7C, + 0x0F, 0x80, 0x01, 0xF0, 0x3E, 0x00, 0x0F, 0x80, 0xF8, 0x00, 0x3F, 0xFF, + 0xF0, 0x01, 0xFF, 0xFF, 0xC0, 0x0F, 0xFF, 0xFF, 0x00, 0x3F, 0xFF, 0xFC, + 0x01, 0xFF, 0xFF, 0xF8, 0x0F, 0xC0, 0x07, 0xE0, 0x3E, 0x00, 0x0F, 0x87, + 0xFF, 0x03, 0xFF, 0xBF, 0xFC, 0x1F, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xFF, + 0xC1, 0xFF, 0xEF, 0xFE, 0x07, 0xFF, 0x00, 0x03, 0xFF, 0xFF, 0x80, 0x3F, + 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0xFC, 0x0F, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, + 0xFF, 0x80, 0x7C, 0x00, 0xFC, 0x03, 0xE0, 0x03, 0xE0, 0x1E, 0x00, 0x1F, + 0x01, 0xF0, 0x00, 0xF8, 0x0F, 0x80, 0x0F, 0x80, 0x7C, 0x01, 0xF8, 0x03, + 0xFF, 0xFF, 0x80, 0x1F, 0xFF, 0xF8, 0x01, 0xFF, 0xFF, 0xC0, 0x0F, 0xFF, + 0xFF, 0x80, 0x7F, 0xFF, 0xFC, 0x03, 0xC0, 0x0F, 0xF0, 0x3E, 0x00, 0x1F, + 0x81, 0xF0, 0x00, 0x7C, 0x0F, 0x80, 0x03, 0xE0, 0x78, 0x00, 0x1F, 0x03, + 0xC0, 0x03, 0xF1, 0xFF, 0xFF, 0xFF, 0x9F, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, + 0xFF, 0x87, 0xFF, 0xFF, 0xF0, 0x1F, 0xFF, 0xFE, 0x00, 0x00, 0x07, 0xF0, + 0x00, 0x03, 0xFF, 0xE6, 0x00, 0x7F, 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0x03, + 0xFF, 0xFF, 0xF0, 0x7F, 0x81, 0xFF, 0x0F, 0xE0, 0x07, 0xE1, 0xF8, 0x00, + 0x3E, 0x1F, 0x00, 0x03, 0xE3, 0xF0, 0x00, 0x3C, 0x3E, 0x00, 0x03, 0xC7, + 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x0F, 0xC0, + 0x00, 0x70, 0x7E, 0x00, 0x1F, 0x07, 0xF8, 0x07, 0xF0, 0x3F, 0xFF, 0xFF, + 0x03, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xF8, 0x00, 0x7F, 0xFE, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x03, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, 0xF0, 0x07, 0xFF, + 0xFF, 0x80, 0x7F, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0xE0, 0x1F, 0x00, 0xFE, + 0x01, 0xF0, 0x07, 0xE0, 0x1E, 0x00, 0x3F, 0x01, 0xE0, 0x01, 0xF0, 0x3E, + 0x00, 0x1F, 0x03, 0xE0, 0x01, 0xF0, 0x3E, 0x00, 0x1F, 0x03, 0xC0, 0x01, + 0xF0, 0x7C, 0x00, 0x1F, 0x07, 0xC0, 0x03, 0xF0, 0x7C, 0x00, 0x3E, 0x07, + 0x80, 0x03, 0xE0, 0x78, 0x00, 0x7E, 0x0F, 0x80, 0x07, 0xC0, 0xF8, 0x00, + 0xFC, 0x0F, 0x80, 0x1F, 0x80, 0xF0, 0x07, 0xF0, 0x7F, 0xFF, 0xFE, 0x07, + 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, + 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xF8, 0x3F, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, + 0xFE, 0x1F, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0xFF, 0x00, 0x78, 0x00, 0xF8, + 0x07, 0xC0, 0x07, 0xC0, 0x3E, 0x00, 0x3E, 0x01, 0xF0, 0xF1, 0xE0, 0x0F, + 0x0F, 0x8E, 0x00, 0x78, 0x7C, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x3F, 0xFE, + 0x00, 0x01, 0xFF, 0xF0, 0x00, 0x0F, 0xFF, 0x80, 0x00, 0xFF, 0xFC, 0x00, + 0x07, 0xC3, 0xC0, 0x00, 0x3E, 0x1E, 0x1E, 0x01, 0xE0, 0xE0, 0xF0, 0x0F, + 0x00, 0x0F, 0x80, 0xF8, 0x00, 0x7C, 0x07, 0xC0, 0x03, 0xE1, 0xFF, 0xFF, + 0xFE, 0x1F, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xFC, + 0x3F, 0xFF, 0xFF, 0xC0, 0x03, 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xF8, + 0x1F, 0xFF, 0xFF, 0xF0, 0x3F, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, 0xFF, 0xC0, + 0x1F, 0x00, 0x0F, 0x80, 0x3E, 0x00, 0x1E, 0x00, 0x78, 0x00, 0x7C, 0x00, + 0xF0, 0x70, 0xF8, 0x03, 0xE1, 0xF0, 0xE0, 0x07, 0xC3, 0xC0, 0x00, 0x0F, + 0xFF, 0x80, 0x00, 0x1F, 0xFF, 0x00, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0xFF, + 0xFC, 0x00, 0x01, 0xFF, 0xF0, 0x00, 0x03, 0xC3, 0xE0, 0x00, 0x07, 0x87, + 0xC0, 0x00, 0x1F, 0x07, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x3F, 0xFF, 0x80, + 0x00, 0xFF, 0xFF, 0x00, 0x01, 0xFF, 0xFE, 0x00, 0x01, 0xFF, 0xF8, 0x00, + 0x00, 0x00, 0x07, 0xF8, 0x60, 0x03, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xF0, + 0x1F, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xE0, 0x7F, 0x80, 0xFE, 0x0F, 0xE0, + 0x03, 0xE0, 0xF8, 0x00, 0x3C, 0x1F, 0x00, 0x03, 0xC3, 0xF0, 0x00, 0x00, + 0x3E, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, 0x7F, 0xFC, 0xF8, 0x0F, 0xFF, + 0xEF, 0x80, 0xFF, 0xFE, 0xF8, 0x0F, 0xFF, 0xCF, 0x80, 0x7F, 0xF8, 0xF8, + 0x00, 0x1F, 0x0F, 0xC0, 0x01, 0xF0, 0xFE, 0x00, 0x1F, 0x07, 0xF8, 0x07, + 0xE0, 0x7F, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFC, 0x00, + 0x7F, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x01, 0xFF, 0x0F, 0xF8, 0x0F, + 0xFC, 0x7F, 0xF0, 0x7F, 0xF1, 0xFF, 0xC1, 0xFF, 0xC7, 0xFE, 0x03, 0xFE, + 0x1F, 0xF0, 0x07, 0xC0, 0x0F, 0x80, 0x1F, 0x00, 0x3C, 0x00, 0x78, 0x00, + 0xF0, 0x01, 0xE0, 0x07, 0xC0, 0x0F, 0x80, 0x1F, 0x00, 0x3E, 0x00, 0x7C, + 0x00, 0xFF, 0xFF, 0xE0, 0x03, 0xFF, 0xFF, 0x80, 0x1F, 0xFF, 0xFE, 0x00, + 0x7F, 0xFF, 0xF8, 0x01, 0xFF, 0xFF, 0xC0, 0x07, 0x80, 0x1F, 0x00, 0x1E, + 0x00, 0x7C, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, 0x07, 0xC0, 0x0F, 0x80, + 0x1E, 0x00, 0x3C, 0x00, 0xF8, 0x07, 0xFE, 0x1F, 0xF8, 0x3F, 0xF8, 0xFF, + 0xF0, 0xFF, 0xE3, 0xFF, 0xC3, 0xFF, 0x8F, 0xFE, 0x0F, 0xFC, 0x3F, 0xF8, + 0x00, 0x03, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, 0xE0, 0xFF, + 0xFF, 0xF0, 0x7F, 0xFF, 0xF0, 0x00, 0x7C, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, + 0x03, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x07, 0x80, 0x00, 0x07, 0xC0, 0x01, 0xFF, 0xFF, + 0xC1, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xF8, 0x1F, 0xFF, + 0xF8, 0x00, 0x00, 0x07, 0xFF, 0xFE, 0x00, 0x1F, 0xFF, 0xFC, 0x00, 0x3F, + 0xFF, 0xF8, 0x00, 0x7F, 0xFF, 0xF0, 0x00, 0x7F, 0xFF, 0xC0, 0x00, 0x01, + 0xF0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x0F, + 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x00, 0xF8, + 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x07, 0xC0, 0x07, 0x00, 0x0F, 0x80, + 0x1F, 0x00, 0x1F, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x78, 0x00, 0x78, 0x01, + 0xF0, 0x01, 0xF0, 0x03, 0xE0, 0x03, 0xE0, 0x07, 0xC0, 0x0F, 0x80, 0x0F, + 0x80, 0x3F, 0x00, 0x1F, 0xC0, 0xFC, 0x00, 0x7F, 0xFF, 0xF8, 0x00, 0xFF, + 0xFF, 0xE0, 0x00, 0x7F, 0xFF, 0x00, 0x00, 0x3F, 0xFC, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x00, 0x03, 0xFF, 0xC3, 0xFE, 0x0F, 0xFF, 0x8F, 0xFC, 0x1F, + 0xFF, 0x3F, 0xF8, 0x3F, 0xFE, 0x7F, 0xF0, 0x7F, 0xF8, 0x7F, 0xC0, 0x1F, + 0x01, 0xFC, 0x00, 0x3E, 0x07, 0xF0, 0x00, 0x78, 0x3F, 0x80, 0x01, 0xF0, + 0xFE, 0x00, 0x03, 0xE3, 0xF0, 0x00, 0x07, 0xDF, 0xC0, 0x00, 0x0F, 0xFE, + 0x00, 0x00, 0x1F, 0xFE, 0x00, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0xFF, 0xFE, + 0x00, 0x01, 0xFC, 0xFC, 0x00, 0x03, 0xE0, 0xFC, 0x00, 0x0F, 0x81, 0xF8, + 0x00, 0x1F, 0x01, 0xF8, 0x00, 0x3E, 0x03, 0xF0, 0x00, 0x78, 0x03, 0xE0, + 0x00, 0xF0, 0x07, 0xE0, 0x1F, 0xFE, 0x0F, 0xF8, 0x7F, 0xFC, 0x1F, 0xF8, + 0xFF, 0xF8, 0x1F, 0xF1, 0xFF, 0xF0, 0x3F, 0xE1, 0xFF, 0xC0, 0x7F, 0x80, + 0x03, 0xFF, 0xF8, 0x00, 0xFF, 0xFF, 0x00, 0x1F, 0xFF, 0xE0, 0x03, 0xFF, + 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x01, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x00, + 0x3E, 0x00, 0x00, 0x07, 0xC0, 0x0E, 0x00, 0xF0, 0x01, 0xE0, 0x3E, 0x00, + 0x7C, 0x07, 0xC0, 0x0F, 0x80, 0xF8, 0x01, 0xF0, 0x1E, 0x00, 0x7C, 0x07, + 0xC0, 0x0F, 0x9F, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, + 0x9F, 0xFF, 0xFF, 0xF1, 0xFF, 0xFF, 0xFE, 0x00, 0x03, 0xFC, 0x00, 0x3F, + 0xC1, 0xFF, 0x00, 0x1F, 0xF0, 0x7F, 0xC0, 0x07, 0xFC, 0x1F, 0xF0, 0x03, + 0xFE, 0x01, 0xFE, 0x01, 0xFE, 0x00, 0xFF, 0x80, 0xFF, 0x80, 0x3F, 0xE0, + 0x3F, 0xE0, 0x0F, 0xF8, 0x1F, 0xF0, 0x03, 0xFF, 0x0F, 0xFC, 0x00, 0xF7, + 0xC3, 0xFF, 0x00, 0x7D, 0xF1, 0xF7, 0xC0, 0x1F, 0x7C, 0xFD, 0xF0, 0x07, + 0xDF, 0xBE, 0x78, 0x01, 0xE3, 0xFF, 0x3E, 0x00, 0x78, 0xFF, 0xCF, 0x80, + 0x3E, 0x3F, 0xE3, 0xE0, 0x0F, 0x87, 0xF0, 0xF8, 0x03, 0xE1, 0xFC, 0x3C, + 0x00, 0xF0, 0x7E, 0x1F, 0x00, 0x7C, 0x1F, 0x07, 0xC0, 0x1F, 0x00, 0x01, + 0xF0, 0x07, 0xC0, 0x00, 0x78, 0x07, 0xFE, 0x01, 0xFF, 0x83, 0xFF, 0xC0, + 0xFF, 0xF0, 0xFF, 0xF0, 0x7F, 0xFC, 0x3F, 0xF8, 0x1F, 0xFE, 0x0F, 0xFC, + 0x03, 0xFF, 0x00, 0x07, 0xF8, 0x07, 0xFF, 0x0F, 0xFC, 0x0F, 0xFF, 0x0F, + 0xFC, 0x0F, 0xFF, 0x0F, 0xFC, 0x0F, 0xFF, 0x0F, 0xFE, 0x0F, 0xFE, 0x01, + 0xFE, 0x00, 0xF8, 0x01, 0xFF, 0x00, 0xF0, 0x01, 0xFF, 0x01, 0xF0, 0x03, + 0xFF, 0x81, 0xF0, 0x03, 0xFF, 0x81, 0xF0, 0x03, 0xEF, 0xC1, 0xF0, 0x03, + 0xCF, 0xC1, 0xE0, 0x07, 0xC7, 0xE3, 0xE0, 0x07, 0xC7, 0xE3, 0xE0, 0x07, + 0xC3, 0xF3, 0xE0, 0x07, 0xC3, 0xF3, 0xC0, 0x07, 0x81, 0xF7, 0xC0, 0x0F, + 0x81, 0xFF, 0xC0, 0x0F, 0x80, 0xFF, 0xC0, 0x0F, 0x80, 0xFF, 0xC0, 0x0F, + 0x00, 0xFF, 0x80, 0x0F, 0x00, 0x7F, 0x80, 0x7F, 0xF0, 0x7F, 0x80, 0xFF, + 0xF0, 0x3F, 0x80, 0xFF, 0xF0, 0x3F, 0x00, 0xFF, 0xF0, 0x1F, 0x00, 0x7F, + 0xE0, 0x1F, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xFF, 0x80, 0x01, 0xFF, + 0xF8, 0x00, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xF8, 0x0F, 0xF0, 0x7F, 0x83, + 0xF8, 0x03, 0xF0, 0xFC, 0x00, 0x7E, 0x1F, 0x00, 0x07, 0xE7, 0xE0, 0x00, + 0x7C, 0xF8, 0x00, 0x0F, 0xBE, 0x00, 0x01, 0xF7, 0xC0, 0x00, 0x3E, 0xF0, + 0x00, 0x07, 0xFE, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x3E, 0xF8, 0x00, 0x07, + 0xDF, 0x00, 0x00, 0xFB, 0xE0, 0x00, 0x3E, 0x7C, 0x00, 0x0F, 0xCF, 0xC0, + 0x01, 0xF0, 0xF8, 0x00, 0x7E, 0x1F, 0x80, 0x3F, 0x83, 0xFC, 0x1F, 0xE0, + 0x3F, 0xFF, 0xF8, 0x03, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0x00, 0x03, 0xFF, + 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xF8, + 0x07, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xF0, 0x0F, + 0x80, 0x7F, 0x00, 0xF8, 0x01, 0xF0, 0x0F, 0x00, 0x1F, 0x01, 0xF0, 0x01, + 0xF0, 0x1F, 0x00, 0x1F, 0x01, 0xF0, 0x03, 0xE0, 0x1E, 0x00, 0x7E, 0x01, + 0xE0, 0x0F, 0xC0, 0x3F, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, + 0xE0, 0x03, 0xFF, 0xFC, 0x00, 0x7F, 0xFE, 0x00, 0x07, 0xC0, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x78, 0x00, 0x00, 0x7F, 0xFF, + 0x00, 0x0F, 0xFF, 0xF0, 0x00, 0xFF, 0xFF, 0x00, 0x0F, 0xFF, 0xF0, 0x00, + 0x7F, 0xFE, 0x00, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xFF, 0x80, 0x03, + 0xFF, 0xF8, 0x00, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xF8, 0x0F, 0xF0, 0x7F, + 0x83, 0xF8, 0x03, 0xF0, 0xFC, 0x00, 0x3F, 0x1F, 0x00, 0x07, 0xE7, 0xC0, + 0x00, 0x7D, 0xF8, 0x00, 0x0F, 0xBE, 0x00, 0x01, 0xF7, 0xC0, 0x00, 0x3F, + 0xF0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x3E, 0xF8, 0x00, + 0x07, 0xDF, 0x00, 0x01, 0xFB, 0xE0, 0x00, 0x3E, 0x7E, 0x00, 0x0F, 0x8F, + 0xC0, 0x03, 0xF0, 0xFC, 0x01, 0xFC, 0x1F, 0xE0, 0xFF, 0x01, 0xFF, 0xFF, + 0xC0, 0x1F, 0xFF, 0xF0, 0x01, 0xFF, 0xFC, 0x00, 0x1F, 0xFE, 0x00, 0x01, + 0xFE, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1F, 0xF8, 0x38, 0x0F, 0xFF, 0xFF, + 0x81, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xFC, 0x0F, 0xFF, 0xFF, 0x00, 0xF0, + 0x1F, 0x80, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0xFC, 0x01, 0xFF, + 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xFF, 0x00, 0x7C, 0x03, + 0xF8, 0x03, 0xE0, 0x07, 0xC0, 0x1E, 0x00, 0x3E, 0x00, 0xF0, 0x01, 0xF0, + 0x0F, 0x80, 0x1F, 0x80, 0x7C, 0x01, 0xF8, 0x03, 0xE0, 0x3F, 0x80, 0x1F, + 0xFF, 0xFC, 0x01, 0xFF, 0xFF, 0x80, 0x0F, 0xFF, 0xF8, 0x00, 0x7F, 0xFF, + 0x00, 0x03, 0xFF, 0xFC, 0x00, 0x1E, 0x07, 0xF0, 0x01, 0xF0, 0x1F, 0xC0, + 0x0F, 0x80, 0x7E, 0x00, 0x7C, 0x03, 0xF8, 0x03, 0xC0, 0x0F, 0xC0, 0xFF, + 0xE0, 0x7F, 0xCF, 0xFF, 0x01, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xC0, + 0x3F, 0xDF, 0xFC, 0x01, 0xFC, 0x00, 0x0F, 0xE1, 0x80, 0x0F, 0xFF, 0xF0, + 0x0F, 0xFF, 0xFC, 0x07, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xC1, 0xFC, 0x0F, + 0xE0, 0x7C, 0x01, 0xF8, 0x3E, 0x00, 0x3E, 0x0F, 0x80, 0x0F, 0x03, 0xE0, + 0x03, 0xC0, 0xFC, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x07, 0xFF, 0x80, 0x01, + 0xFF, 0xFC, 0x00, 0x3F, 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, 0x07, 0xFE, + 0x00, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xE1, 0xE0, 0x00, 0xF8, 0xF8, 0x00, + 0x3E, 0x3E, 0x00, 0x1F, 0x8F, 0xC0, 0x0F, 0xC3, 0xFC, 0x0F, 0xF0, 0xFF, + 0xFF, 0xF8, 0x3F, 0xFF, 0xFC, 0x0F, 0xFF, 0xFE, 0x03, 0x9F, 0xFE, 0x00, + 0x01, 0xFE, 0x00, 0x00, 0x3F, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0xF7, 0xFF, + 0xFF, 0xFD, 0xFF, 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, 0x9F, 0x07, 0x83, 0xE7, + 0x83, 0xE0, 0xFB, 0xE0, 0xF8, 0x3E, 0xF8, 0x3E, 0x0F, 0x3E, 0x0F, 0x07, + 0xCF, 0x07, 0xC1, 0xF3, 0x81, 0xF0, 0x38, 0x00, 0x7C, 0x00, 0x00, 0x1E, + 0x00, 0x00, 0x07, 0x80, 0x00, 0x03, 0xE0, 0x00, 0x00, 0xF8, 0x00, 0x00, + 0x3E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, + 0x00, 0x7C, 0x00, 0x07, 0xFF, 0xF8, 0x01, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, + 0x80, 0x3F, 0xFF, 0xE0, 0x07, 0xFF, 0xF0, 0x00, 0x3F, 0xF0, 0x7F, 0xE7, + 0xFF, 0x8F, 0xFF, 0x7F, 0xF9, 0xFF, 0xF7, 0xFF, 0x1F, 0xFE, 0x7F, 0xF0, + 0xFF, 0xC1, 0xE0, 0x01, 0xF0, 0x1E, 0x00, 0x1F, 0x03, 0xE0, 0x01, 0xF0, + 0x3E, 0x00, 0x1F, 0x03, 0xE0, 0x01, 0xE0, 0x3C, 0x00, 0x3E, 0x07, 0xC0, + 0x03, 0xE0, 0x7C, 0x00, 0x3E, 0x07, 0xC0, 0x03, 0xC0, 0x7C, 0x00, 0x3C, + 0x07, 0x80, 0x07, 0xC0, 0xF8, 0x00, 0x7C, 0x0F, 0x80, 0x07, 0xC0, 0xF8, + 0x00, 0x78, 0x0F, 0x80, 0x0F, 0x80, 0xFC, 0x01, 0xF8, 0x0F, 0xC0, 0x3F, + 0x00, 0xFF, 0x07, 0xE0, 0x07, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xC0, 0x03, + 0xFF, 0xF0, 0x00, 0x0F, 0xFE, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x7F, 0xF0, + 0x1F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFC, 0x0F, + 0xFF, 0x7F, 0xE0, 0x3F, 0xF8, 0x7C, 0x00, 0x1F, 0x01, 0xF0, 0x00, 0xF8, + 0x07, 0xC0, 0x03, 0xE0, 0x1F, 0x80, 0x1F, 0x00, 0x3E, 0x00, 0xF8, 0x00, + 0xF8, 0x03, 0xE0, 0x03, 0xE0, 0x1F, 0x00, 0x0F, 0xC0, 0xFC, 0x00, 0x1F, + 0x03, 0xE0, 0x00, 0x7C, 0x1F, 0x00, 0x01, 0xF0, 0xFC, 0x00, 0x07, 0xC3, + 0xE0, 0x00, 0x1F, 0x9F, 0x00, 0x00, 0x3E, 0xFC, 0x00, 0x00, 0xFB, 0xE0, + 0x00, 0x03, 0xFF, 0x00, 0x00, 0x0F, 0xFC, 0x00, 0x00, 0x3F, 0xE0, 0x00, + 0x00, 0x7F, 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x00, 0x7F, 0xF0, 0x3F, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, + 0xFC, 0x1F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFE, 0x07, 0xFF, 0x1E, 0x00, + 0x01, 0xE0, 0xF0, 0x7C, 0x1F, 0x0F, 0x87, 0xE0, 0xF0, 0x7C, 0x3F, 0x0F, + 0x83, 0xE3, 0xF8, 0x7C, 0x1F, 0x1F, 0xE3, 0xC0, 0xF9, 0xFF, 0x3E, 0x07, + 0xCF, 0xF9, 0xF0, 0x3E, 0xFF, 0xCF, 0x01, 0xF7, 0xBE, 0xF8, 0x0F, 0xFD, + 0xF7, 0xC0, 0x7B, 0xCF, 0xFC, 0x03, 0xFE, 0x7F, 0xE0, 0x3F, 0xE3, 0xFF, + 0x01, 0xFF, 0x0F, 0xF0, 0x0F, 0xF0, 0x7F, 0x80, 0x7F, 0x83, 0xFC, 0x03, + 0xF8, 0x1F, 0xC0, 0x1F, 0xC0, 0xFE, 0x00, 0xFC, 0x07, 0xF0, 0x07, 0xE0, + 0x3F, 0x00, 0x3E, 0x01, 0xF8, 0x00, 0x01, 0xFE, 0x03, 0xFE, 0x03, 0xFF, + 0x07, 0xFF, 0x07, 0xFF, 0x07, 0xFF, 0x07, 0xFE, 0x07, 0xFE, 0x03, 0xFC, + 0x03, 0xFC, 0x00, 0xFC, 0x03, 0xF0, 0x00, 0xFE, 0x07, 0xE0, 0x00, 0x7E, + 0x1F, 0xC0, 0x00, 0x3F, 0x3F, 0x00, 0x00, 0x1F, 0xFE, 0x00, 0x00, 0x1F, + 0xFC, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, + 0xE0, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x7F, + 0xF8, 0x00, 0x00, 0xFC, 0xFC, 0x00, 0x01, 0xF8, 0x7E, 0x00, 0x03, 0xF0, + 0x7E, 0x00, 0x07, 0xE0, 0x3F, 0x00, 0x0F, 0xC0, 0x1F, 0x80, 0x7F, 0xE0, + 0x7F, 0xE0, 0xFF, 0xE0, 0xFF, 0xE0, 0xFF, 0xE0, 0xFF, 0xE0, 0xFF, 0xE0, + 0xFF, 0xE0, 0x7F, 0xC0, 0xFF, 0xC0, 0x7F, 0xC0, 0x7F, 0xFF, 0xF0, 0x3F, + 0xFF, 0xFC, 0x0F, 0xFF, 0xFF, 0x03, 0xFF, 0x7F, 0x80, 0xFF, 0x87, 0xC0, + 0x1F, 0x01, 0xF8, 0x0F, 0x80, 0x3E, 0x07, 0xC0, 0x0F, 0xC3, 0xE0, 0x01, + 0xF1, 0xF0, 0x00, 0x7E, 0xF8, 0x00, 0x0F, 0xFC, 0x00, 0x03, 0xFE, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x00, 0xF0, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, + 0xE0, 0x00, 0x00, 0x78, 0x00, 0x07, 0xFF, 0xF0, 0x03, 0xFF, 0xFE, 0x00, + 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xC0, 0x0F, 0xFF, 0xE0, 0x00, 0x01, 0xFF, + 0xFF, 0xC0, 0x3F, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xE0, + 0x3F, 0xFF, 0xFC, 0x07, 0xC0, 0x3F, 0x00, 0xF8, 0x0F, 0xC0, 0x1F, 0x03, + 0xF0, 0x03, 0xC0, 0xFC, 0x00, 0xF8, 0x3F, 0x00, 0x0E, 0x0F, 0xC0, 0x00, + 0x03, 0xF0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x1F, 0x80, + 0x00, 0x07, 0xE0, 0x00, 0x01, 0xF8, 0x0E, 0x00, 0x7E, 0x03, 0xE0, 0x1F, + 0x80, 0x7C, 0x07, 0xE0, 0x0F, 0x01, 0xF8, 0x03, 0xE0, 0x7E, 0x00, 0x7C, + 0x1F, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xFC, 0x0F, 0xFF, + 0xFF, 0x81, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0xFF, 0xC0, 0x3F, 0xF0, 0x0F, + 0xFC, 0x07, 0xFF, 0x01, 0xFF, 0x80, 0x7C, 0x00, 0x1E, 0x00, 0x07, 0x80, + 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x07, 0xC0, 0x01, + 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0x80, 0x03, 0xE0, 0x00, 0xF8, + 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x1F, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, + 0x80, 0x03, 0xC0, 0x01, 0xF0, 0x00, 0x7F, 0xE0, 0x1F, 0xF8, 0x07, 0xFE, + 0x01, 0xFF, 0x80, 0xFF, 0xC0, 0x00, 0x20, 0x03, 0xC0, 0x3E, 0x01, 0xF0, + 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x3E, 0x01, 0xF0, 0x0F, 0x80, + 0x7C, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x0F, 0x80, 0x7C, 0x03, + 0xE0, 0x1F, 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0x7C, 0x03, 0xE0, 0x1F, + 0x00, 0xF8, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x1F, 0x00, 0xF8, + 0x07, 0xC0, 0x3E, 0x00, 0xF0, 0x07, 0x80, 0x38, 0x00, 0xFF, 0xC0, 0x7F, + 0xE0, 0x1F, 0xF8, 0x07, 0xFE, 0x01, 0xFF, 0x80, 0x03, 0xE0, 0x00, 0xF0, + 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xE0, 0x00, 0x78, 0x00, + 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, + 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x78, 0x00, 0x3E, 0x00, 0x0F, 0x80, + 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3C, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, + 0xF0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x0F, 0x80, 0x7F, 0xE0, 0x3F, 0xF8, + 0x0F, 0xFC, 0x03, 0xFF, 0x00, 0xFF, 0xC0, 0x00, 0x00, 0x08, 0x00, 0x01, + 0xC0, 0x00, 0x3C, 0x00, 0x07, 0xE0, 0x00, 0xFE, 0x00, 0x1F, 0xF0, 0x03, + 0xFF, 0x80, 0xFF, 0xF8, 0x1F, 0xCF, 0xC3, 0xF8, 0xFE, 0x7E, 0x07, 0xEF, + 0xC0, 0x3F, 0xF8, 0x03, 0xFF, 0x00, 0x1F, 0xE0, 0x00, 0xE0, 0x7F, 0xFF, + 0xFF, 0xFB, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xEF, 0xFF, 0xFF, 0xFF, 0x00, 0x60, 0xF0, 0xF8, 0x7C, 0x3E, 0x1F, 0x0F, + 0x06, 0x00, 0x3F, 0xE0, 0x03, 0xFF, 0xF8, 0x07, 0xFF, 0xFC, 0x07, 0xFF, + 0xFE, 0x07, 0xFF, 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0x3E, 0x00, 0x7F, 0xFE, 0x03, 0xFF, 0xFC, 0x0F, 0xFF, 0xFC, 0x1F, 0xFF, + 0xFC, 0x3F, 0xFF, 0xFC, 0x7F, 0x00, 0x78, 0x7C, 0x00, 0x78, 0xF8, 0x00, + 0xF8, 0xF8, 0x03, 0xF8, 0xFC, 0x0F, 0xFE, 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, + 0xFF, 0x7F, 0xFF, 0xFF, 0x3F, 0xFD, 0xFE, 0x0F, 0xE0, 0x00, 0x03, 0xFC, + 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x0F, 0xF0, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x00, 0xF0, 0xFE, 0x00, 0x0F, 0xBF, 0xFC, 0x00, 0x7F, + 0xFF, 0xF8, 0x03, 0xFF, 0xFF, 0xC0, 0x1F, 0xFF, 0xFF, 0x00, 0xFF, 0x03, + 0xF8, 0x0F, 0xE0, 0x07, 0xE0, 0x7E, 0x00, 0x3F, 0x03, 0xE0, 0x00, 0xF8, + 0x1F, 0x00, 0x07, 0xC0, 0xF0, 0x00, 0x3E, 0x0F, 0x80, 0x01, 0xF0, 0x7C, + 0x00, 0x1F, 0x03, 0xE0, 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0xC0, 0xFC, 0x00, + 0x7C, 0x0F, 0xE0, 0x07, 0xE3, 0xFF, 0xC0, 0xFE, 0x3F, 0xFF, 0xFF, 0xE1, + 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xE0, 0x7F, 0x9F, 0xFC, 0x00, 0x00, + 0x3F, 0x80, 0x00, 0x00, 0x1F, 0xE3, 0x80, 0x7F, 0xFF, 0xC0, 0x7F, 0xFF, + 0xE0, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xF8, 0xFF, 0x01, 0xFC, 0x7E, 0x00, + 0x7C, 0x7E, 0x00, 0x3E, 0x3E, 0x00, 0x0E, 0x3E, 0x00, 0x00, 0x1F, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, + 0x00, 0x01, 0xF0, 0x00, 0x00, 0xFC, 0x00, 0x0C, 0x7F, 0x80, 0x3F, 0x1F, + 0xFF, 0xFF, 0x8F, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0x00, + 0x0F, 0xFC, 0x00, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x01, 0xFE, 0x00, 0x00, + 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x7C, 0x00, 0x3F, 0x87, 0xC0, 0x0F, + 0xFF, 0x7C, 0x03, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, + 0x81, 0xFC, 0x0F, 0xF8, 0x3F, 0x00, 0x3F, 0x83, 0xE0, 0x01, 0xF0, 0x7C, + 0x00, 0x1F, 0x07, 0xC0, 0x01, 0xF0, 0xF8, 0x00, 0x1F, 0x0F, 0x80, 0x01, + 0xF0, 0xF8, 0x00, 0x1E, 0x0F, 0x80, 0x03, 0xE0, 0xF8, 0x00, 0x3E, 0x0F, + 0xC0, 0x07, 0xE0, 0xFC, 0x00, 0xFE, 0x07, 0xF0, 0x3F, 0xF8, 0x7F, 0xFF, + 0xFF, 0xC3, 0xFF, 0xFF, 0xFC, 0x3F, 0xFF, 0xFF, 0xC0, 0xFF, 0xE7, 0xF8, + 0x03, 0xF8, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0xF0, 0x03, 0xFF, + 0xF8, 0x07, 0xFF, 0xFC, 0x0F, 0xFF, 0xFE, 0x1F, 0xE0, 0x7E, 0x3F, 0x80, + 0x1F, 0x3F, 0x00, 0x0F, 0x7E, 0x00, 0x0F, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x00, + 0x00, 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x1C, 0x7F, 0x01, 0xFE, 0x7F, 0xFF, + 0xFE, 0x3F, 0xFF, 0xFE, 0x1F, 0xFF, 0xFC, 0x0F, 0xFF, 0xF0, 0x03, 0xFF, + 0x00, 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFF, 0xF0, + 0x00, 0xFF, 0xFF, 0x00, 0x1F, 0xFF, 0xE0, 0x01, 0xF0, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x7F, 0xFF, 0xF0, + 0x0F, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0x00, 0xFF, + 0xFF, 0xE0, 0x00, 0x78, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, + 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0x03, 0xE0, 0x00, 0x07, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xF0, 0x0F, + 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xF0, 0x07, 0xFF, 0xFE, 0x00, 0x00, 0x3F, + 0x80, 0x00, 0x0F, 0xFE, 0xFF, 0x03, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xFF, + 0x0F, 0xFF, 0xFF, 0xF1, 0xFC, 0x1F, 0xFE, 0x3F, 0x80, 0x7F, 0x03, 0xE0, + 0x03, 0xF0, 0x7E, 0x00, 0x3E, 0x07, 0xC0, 0x03, 0xE0, 0xF8, 0x00, 0x3E, + 0x0F, 0x80, 0x03, 0xE0, 0xF8, 0x00, 0x3E, 0x0F, 0x80, 0x03, 0xC0, 0xF8, + 0x00, 0x7C, 0x0F, 0xC0, 0x0F, 0xC0, 0xFC, 0x01, 0xFC, 0x07, 0xF0, 0x7F, + 0x80, 0x7F, 0xFF, 0xF8, 0x03, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xF8, 0x00, + 0xFF, 0xEF, 0x80, 0x03, 0xF0, 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, + 0xF0, 0x00, 0x00, 0x7E, 0x00, 0x1F, 0xFF, 0xE0, 0x03, 0xFF, 0xFC, 0x00, + 0x3F, 0xFF, 0x80, 0x03, 0xFF, 0xE0, 0x00, 0x3F, 0xF8, 0x00, 0x00, 0x03, + 0xF8, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x3F, 0xE0, 0x00, + 0x07, 0xF0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, + 0x00, 0x01, 0xF1, 0xF8, 0x00, 0x79, 0xFF, 0x80, 0x1E, 0xFF, 0xF0, 0x0F, + 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x80, 0xFF, 0x07, 0xE0, 0x3F, 0x00, 0xF8, + 0x1F, 0x80, 0x3E, 0x07, 0xC0, 0x0F, 0x81, 0xF0, 0x03, 0xC0, 0x7C, 0x00, + 0xF0, 0x1E, 0x00, 0x7C, 0x0F, 0x80, 0x1F, 0x03, 0xE0, 0x07, 0xC0, 0xF8, + 0x01, 0xE0, 0x3C, 0x00, 0xF8, 0x0F, 0x00, 0x3E, 0x1F, 0xF8, 0x3F, 0xEF, + 0xFE, 0x1F, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xF0, 0x3F, + 0xE0, 0x00, 0x07, 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x1F, 0x80, 0x00, 0x3E, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0xFF, 0xC0, 0x07, 0xFF, 0x80, 0x0F, 0xFE, 0x00, 0x1F, 0xFC, 0x00, + 0x3F, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x80, 0x00, + 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF0, 0x00, 0x01, + 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x3F, 0xFF, + 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, + 0x80, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xF0, 0x00, 0x07, + 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0xFF, 0xFE, 0x07, 0xFF, 0xFC, 0x0F, 0xFF, 0xF8, 0x1F, 0xFF, 0xF0, + 0x3F, 0xFF, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x07, 0xC0, 0x00, + 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF8, 0x00, 0x01, + 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0xC0, + 0xFF, 0xFF, 0x03, 0xFF, 0xFC, 0x07, 0xFF, 0xF0, 0x0F, 0xFF, 0xC0, 0x0F, + 0xFC, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, 0xC0, + 0x00, 0x1F, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x0F, + 0x80, 0x00, 0x03, 0xE0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x3C, 0x3F, 0xF0, + 0x1F, 0x1F, 0xFC, 0x07, 0xC7, 0xFF, 0x01, 0xF1, 0xFF, 0xC0, 0x78, 0x7F, + 0xE0, 0x1E, 0x7F, 0x80, 0x0F, 0xBF, 0x80, 0x03, 0xFF, 0xC0, 0x00, 0xFF, + 0xC0, 0x00, 0x3F, 0xE0, 0x00, 0x0F, 0xFC, 0x00, 0x07, 0xFF, 0x80, 0x01, + 0xF7, 0xF0, 0x00, 0x7C, 0xFE, 0x00, 0x1E, 0x1F, 0xC0, 0x0F, 0x83, 0xF8, + 0x1F, 0xE0, 0xFF, 0xEF, 0xF8, 0x3F, 0xFB, 0xFE, 0x1F, 0xFE, 0xFF, 0x07, + 0xFF, 0x9F, 0xC0, 0xFF, 0xC0, 0x00, 0x7F, 0xF0, 0x01, 0xFF, 0xC0, 0x03, + 0xFF, 0x80, 0x07, 0xFF, 0x00, 0x0F, 0xFE, 0x00, 0x00, 0x7C, 0x00, 0x00, + 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, + 0x00, 0x07, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0xF8, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x80, 0x00, + 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x7F, 0xFF, 0xF9, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0x00, 0x00, 0x07, 0x81, 0xE0, + 0x3F, 0xBF, 0x9F, 0xE1, 0xFF, 0xFE, 0xFF, 0x87, 0xFF, 0xFF, 0xFF, 0x1F, + 0xFF, 0xFF, 0xFC, 0x7F, 0xC7, 0xF1, 0xF0, 0x7E, 0x1F, 0x87, 0xC1, 0xF0, + 0x7C, 0x1F, 0x07, 0x81, 0xE0, 0x7C, 0x1E, 0x0F, 0x81, 0xE0, 0xF8, 0x3E, + 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3C, 0x0F, 0x03, + 0xC1, 0xF0, 0x7C, 0x0F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF1, + 0xFE, 0x1F, 0x87, 0xEF, 0xFC, 0x7F, 0x1F, 0xFF, 0xF3, 0xFC, 0x7F, 0xFF, + 0xCF, 0xF3, 0xFF, 0xFE, 0x3F, 0x8F, 0xE0, 0x00, 0x01, 0xF8, 0x01, 0xF9, + 0xFF, 0x80, 0xFE, 0xFF, 0xF0, 0x7F, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0x83, + 0xFF, 0x07, 0xE0, 0x3F, 0x00, 0xF8, 0x1F, 0x80, 0x3E, 0x07, 0xC0, 0x0F, + 0x81, 0xF0, 0x03, 0xC0, 0x7C, 0x00, 0xF0, 0x1E, 0x00, 0x7C, 0x0F, 0x80, + 0x1F, 0x03, 0xE0, 0x07, 0xC0, 0xF8, 0x01, 0xE0, 0x3C, 0x00, 0xF8, 0x0F, + 0x00, 0x3E, 0x1F, 0xF8, 0x3F, 0xEF, 0xFE, 0x1F, 0xFF, 0xFF, 0x87, 0xFF, + 0xFF, 0xE1, 0xFF, 0xFF, 0xF0, 0x3F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x7F, + 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xF0, 0xFF, + 0x03, 0xF8, 0xFE, 0x00, 0xFE, 0x7C, 0x00, 0x3F, 0x7C, 0x00, 0x0F, 0xBE, + 0x00, 0x07, 0xFE, 0x00, 0x03, 0xFF, 0x00, 0x01, 0xFF, 0x80, 0x00, 0xFF, + 0xC0, 0x00, 0xFB, 0xE0, 0x00, 0xFD, 0xF8, 0x00, 0x7C, 0xFE, 0x00, 0xFE, + 0x3F, 0x81, 0xFE, 0x1F, 0xFF, 0xFE, 0x07, 0xFF, 0xFE, 0x01, 0xFF, 0xFC, + 0x00, 0x7F, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x00, 0x3F, 0x80, 0x07, + 0xF9, 0xFF, 0xC0, 0x1F, 0xF7, 0xFF, 0xC0, 0x3F, 0xFF, 0xFF, 0xC0, 0x7F, + 0xFF, 0xFF, 0xC0, 0x7F, 0xF0, 0x3F, 0x80, 0x3F, 0x80, 0x1F, 0x80, 0x7E, + 0x00, 0x3F, 0x00, 0xF8, 0x00, 0x3E, 0x01, 0xF0, 0x00, 0x7C, 0x03, 0xC0, + 0x00, 0xF8, 0x0F, 0x80, 0x01, 0xF0, 0x1F, 0x00, 0x07, 0xE0, 0x3E, 0x00, + 0x0F, 0x80, 0x7C, 0x00, 0x3F, 0x01, 0xFC, 0x00, 0xFC, 0x03, 0xFE, 0x07, + 0xF8, 0x07, 0xFF, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0x80, 0x1E, 0xFF, 0xFC, + 0x00, 0x7C, 0xFF, 0xF0, 0x00, 0xF8, 0x7F, 0x00, 0x01, 0xF0, 0x00, 0x00, + 0x03, 0xE0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, + 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x1F, + 0xFF, 0x80, 0x00, 0x3F, 0xFE, 0x00, 0x00, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x07, 0xFF, 0x3F, 0xC0, 0xFF, 0xFD, 0xFE, 0x0F, 0xFF, 0xFF, 0xF0, 0xFF, + 0xFF, 0xFF, 0x8F, 0xE0, 0x7F, 0xF8, 0xFC, 0x00, 0xFE, 0x07, 0xC0, 0x03, + 0xE0, 0x7C, 0x00, 0x1F, 0x03, 0xE0, 0x00, 0xF8, 0x1E, 0x00, 0x07, 0xC1, + 0xF0, 0x00, 0x3E, 0x0F, 0x80, 0x01, 0xE0, 0x7C, 0x00, 0x1F, 0x03, 0xF0, + 0x01, 0xF8, 0x1F, 0x80, 0x1F, 0xC0, 0xFF, 0x03, 0xFC, 0x03, 0xFF, 0xFF, + 0xE0, 0x1F, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xF8, 0x00, 0xFF, 0xE7, 0xC0, + 0x01, 0xFC, 0x3C, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x07, 0xFF, 0x80, 0x00, 0x7F, + 0xFE, 0x00, 0x07, 0xFF, 0xF0, 0x00, 0x3F, 0xFF, 0x00, 0x00, 0xFF, 0xF0, + 0x00, 0x00, 0x00, 0x0F, 0x80, 0x3F, 0xC3, 0xFE, 0x07, 0xFC, 0xFF, 0xE0, + 0x7F, 0xDF, 0xFF, 0x07, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0x1C, 0x00, 0x7F, + 0xC0, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x0F, 0xC0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x01, 0xE0, 0x00, + 0x07, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0x00, 0xFF, + 0xFF, 0xF0, 0x07, 0xFF, 0xFE, 0x00, 0x00, 0x3F, 0xCE, 0x03, 0xFF, 0xFC, + 0x0F, 0xFF, 0xF8, 0x3F, 0xFF, 0xF0, 0xFF, 0xFF, 0xC3, 0xF8, 0x0F, 0x87, + 0xC0, 0x0E, 0x0F, 0x80, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xFF, 0x80, 0x3F, + 0xFF, 0xC0, 0x3F, 0xFF, 0xC0, 0x1F, 0xFF, 0xC0, 0x01, 0xFF, 0x80, 0x00, + 0x3F, 0x1C, 0x00, 0x3E, 0x7C, 0x00, 0x7C, 0xFC, 0x03, 0xF3, 0xFF, 0xFF, + 0xE7, 0xFF, 0xFF, 0x8F, 0xFF, 0xFE, 0x1F, 0xFF, 0xF0, 0x00, 0xFF, 0x00, + 0x00, 0x03, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, + 0x80, 0x00, 0x78, 0x00, 0x7F, 0xFF, 0xEF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xE1, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xE0, 0x00, + 0x1E, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x3C, 0x00, + 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7E, 0x00, 0xF7, 0xFF, + 0xFF, 0x7F, 0xFF, 0xF3, 0xFF, 0xFE, 0x1F, 0xFF, 0x80, 0x7F, 0x80, 0x7F, + 0x01, 0xFF, 0xFE, 0x07, 0xFF, 0xF8, 0x1F, 0xFF, 0xF0, 0x3F, 0xFF, 0xE0, + 0x3F, 0xC7, 0xC0, 0x07, 0x8F, 0x80, 0x1F, 0x3E, 0x00, 0x3E, 0x7C, 0x00, + 0x7C, 0xF8, 0x00, 0xF1, 0xF0, 0x03, 0xE3, 0xE0, 0x07, 0xC7, 0xC0, 0x0F, + 0x8F, 0x80, 0x1F, 0x1F, 0x00, 0x7C, 0x3E, 0x01, 0xF8, 0x7E, 0x0F, 0xFC, + 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xF1, 0xFF, 0xEF, 0xE1, 0xFF, 0xBF, 0x80, + 0xFC, 0x00, 0x00, 0x7F, 0xF0, 0x7F, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xF0, + 0xFF, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xE0, 0xFF, 0xE1, 0xF8, 0x03, 0xE0, + 0x0F, 0x80, 0x3E, 0x00, 0xF8, 0x07, 0xC0, 0x0F, 0x80, 0xF8, 0x00, 0xFC, + 0x1F, 0x80, 0x07, 0xC1, 0xF0, 0x00, 0x7C, 0x3E, 0x00, 0x07, 0xE7, 0xE0, + 0x00, 0x3E, 0x7C, 0x00, 0x03, 0xEF, 0x80, 0x00, 0x3F, 0xF0, 0x00, 0x03, + 0xFF, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0x7F, 0xC0, 0x1F, 0xEF, 0xFC, 0x03, 0xFF, + 0xFF, 0xC0, 0x7F, 0xFF, 0xFC, 0x07, 0xFE, 0x7F, 0x80, 0x3F, 0xC3, 0xE1, + 0xF0, 0xF8, 0x3E, 0x3F, 0x0F, 0x03, 0xE3, 0xF1, 0xF0, 0x3E, 0x7F, 0x1E, + 0x03, 0xE7, 0xF3, 0xE0, 0x3E, 0xFF, 0xBC, 0x03, 0xFF, 0xFF, 0xC0, 0x3F, + 0xFF, 0xFC, 0x03, 0xFE, 0xFF, 0x80, 0x3F, 0xEF, 0xF8, 0x03, 0xFC, 0xFF, + 0x00, 0x3F, 0x8F, 0xF0, 0x03, 0xF8, 0x7E, 0x00, 0x3F, 0x07, 0xE0, 0x01, + 0xF0, 0x7C, 0x00, 0x1E, 0x07, 0xC0, 0x00, 0x03, 0xFE, 0x0F, 0xF8, 0x3F, + 0xF0, 0xFF, 0xC1, 0xFF, 0x8F, 0xFE, 0x0F, 0xFC, 0x7F, 0xF0, 0x7F, 0xC1, + 0xFF, 0x00, 0xFE, 0x1F, 0xC0, 0x03, 0xF9, 0xFC, 0x00, 0x0F, 0xFF, 0xC0, + 0x00, 0x3F, 0xF8, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, + 0x7F, 0xE0, 0x00, 0x0F, 0xFF, 0x80, 0x00, 0xFE, 0xFE, 0x00, 0x0F, 0xE3, + 0xF8, 0x00, 0xFE, 0x0F, 0xE0, 0x3F, 0xE0, 0x7F, 0xC3, 0xFF, 0x87, 0xFF, + 0x3F, 0xFC, 0x7F, 0xF9, 0xFF, 0xE3, 0xFF, 0x87, 0xFE, 0x0F, 0xF8, 0x00, + 0x01, 0xFE, 0x03, 0xFE, 0x03, 0xFF, 0x07, 0xFF, 0x07, 0xFF, 0x07, 0xFF, + 0x07, 0xFF, 0x07, 0xFE, 0x03, 0xFC, 0x03, 0xFC, 0x01, 0xF8, 0x01, 0xF0, + 0x00, 0xF8, 0x03, 0xF0, 0x00, 0xF8, 0x03, 0xE0, 0x00, 0xFC, 0x07, 0xC0, + 0x00, 0x7C, 0x0F, 0x80, 0x00, 0x7C, 0x0F, 0x80, 0x00, 0x7E, 0x1F, 0x00, + 0x00, 0x7E, 0x3E, 0x00, 0x00, 0x3E, 0x7C, 0x00, 0x00, 0x3E, 0x7C, 0x00, + 0x00, 0x3F, 0xF8, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0x1F, 0xE0, 0x00, + 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x7F, 0xFF, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, + 0xFF, 0xFF, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x7F, 0xFE, 0x00, 0x00, + 0x07, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, + 0xE0, 0xFF, 0xFF, 0xE0, 0x7C, 0x0F, 0xE0, 0x3C, 0x0F, 0xE0, 0x1E, 0x0F, + 0xC0, 0x00, 0x1F, 0xC0, 0x00, 0x1F, 0xC0, 0x00, 0x1F, 0xC0, 0x00, 0x1F, + 0x80, 0x00, 0x3F, 0x80, 0x00, 0x3F, 0x80, 0x00, 0x3F, 0x80, 0xF0, 0x3F, + 0x00, 0xF8, 0x3F, 0xFF, 0xFC, 0x3F, 0xFF, 0xFE, 0x1F, 0xFF, 0xFE, 0x0F, + 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0x80, 0x00, 0x0F, 0x00, 0x1F, 0xC0, 0x1F, + 0xE0, 0x1F, 0xF0, 0x0F, 0xE0, 0x0F, 0xC0, 0x07, 0xC0, 0x07, 0xC0, 0x03, + 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x78, 0x00, 0x7C, 0x00, 0x3E, 0x00, + 0x1F, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x3F, 0x80, 0x3F, 0xC0, 0x1F, 0xC0, + 0x0F, 0xE0, 0x07, 0xF8, 0x00, 0xFC, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, + 0x80, 0x07, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, + 0x7E, 0x00, 0x3F, 0x80, 0x1F, 0xE0, 0x07, 0xF0, 0x03, 0xF8, 0x00, 0x78, + 0x00, 0x01, 0xE0, 0x3C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, 0x80, 0xF0, 0x3E, + 0x07, 0xC0, 0xF0, 0x1E, 0x03, 0xC0, 0xF8, 0x1F, 0x03, 0xC0, 0x78, 0x0F, + 0x03, 0xE0, 0x7C, 0x0F, 0x01, 0xE0, 0x3C, 0x0F, 0x81, 0xF0, 0x3C, 0x07, + 0x80, 0xF0, 0x3E, 0x07, 0xC0, 0xF0, 0x1E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, + 0xC0, 0x70, 0x00, 0x00, 0xF0, 0x00, 0xFC, 0x00, 0x7F, 0x00, 0x3F, 0xC0, + 0x0F, 0xE0, 0x03, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, + 0x00, 0x0F, 0x80, 0x07, 0x80, 0x03, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, + 0xF8, 0x00, 0x7E, 0x00, 0x3F, 0xC0, 0x0F, 0xE0, 0x07, 0xF0, 0x07, 0xF8, + 0x07, 0xF8, 0x03, 0xE0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF0, 0x00, 0x78, + 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x00, 0x1F, 0x80, 0x7F, + 0xC0, 0x7F, 0xC0, 0x3F, 0xC0, 0x1F, 0xC0, 0x07, 0x80, 0x00, 0x03, 0xE0, + 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0xE0, 0x39, 0xFF, 0xE0, 0xF7, 0xFF, 0xE7, + 0xFF, 0xCF, 0xFF, 0xFE, 0x0F, 0xFF, 0x38, 0x0F, 0xFC, 0x00, 0x0F, 0xE0, + 0x00, 0x0F, 0x80 }; + +const GFXglyph FreeMonoBoldOblique24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 28, 0, 1 }, // 0x20 ' ' + { 0, 12, 31, 28, 12, -29 }, // 0x21 '!' + { 47, 17, 14, 28, 11, -28 }, // 0x22 '"' + { 77, 24, 34, 28, 5, -30 }, // 0x23 '#' + { 179, 25, 38, 28, 4, -31 }, // 0x24 '$' + { 298, 22, 30, 28, 6, -28 }, // 0x25 '%' + { 381, 21, 28, 28, 5, -26 }, // 0x26 '&' + { 455, 7, 14, 28, 16, -28 }, // 0x27 ''' + { 468, 14, 37, 28, 14, -29 }, // 0x28 '(' + { 533, 14, 37, 28, 5, -29 }, // 0x29 ')' + { 598, 21, 19, 28, 8, -28 }, // 0x2A '*' + { 648, 24, 26, 28, 5, -25 }, // 0x2B '+' + { 726, 12, 14, 28, 6, -6 }, // 0x2C ',' + { 747, 24, 5, 28, 5, -15 }, // 0x2D '-' + { 762, 7, 6, 28, 11, -4 }, // 0x2E '.' + { 768, 28, 38, 28, 3, -32 }, // 0x2F '/' + { 901, 23, 31, 28, 6, -29 }, // 0x30 '0' + { 991, 21, 30, 28, 4, -29 }, // 0x31 '1' + { 1070, 26, 30, 28, 3, -29 }, // 0x32 '2' + { 1168, 25, 31, 28, 4, -29 }, // 0x33 '3' + { 1265, 22, 28, 28, 5, -27 }, // 0x34 '4' + { 1342, 25, 31, 28, 4, -29 }, // 0x35 '5' + { 1439, 24, 31, 28, 7, -29 }, // 0x36 '6' + { 1532, 22, 30, 28, 9, -29 }, // 0x37 '7' + { 1615, 23, 31, 28, 6, -29 }, // 0x38 '8' + { 1705, 24, 31, 28, 5, -29 }, // 0x39 '9' + { 1798, 10, 22, 28, 11, -20 }, // 0x3A ':' + { 1826, 15, 28, 28, 5, -20 }, // 0x3B ';' + { 1879, 25, 21, 28, 5, -23 }, // 0x3C '<' + { 1945, 26, 14, 28, 4, -19 }, // 0x3D '=' + { 1991, 25, 22, 28, 4, -23 }, // 0x3E '>' + { 2060, 19, 29, 28, 10, -27 }, // 0x3F '?' + { 2129, 23, 36, 28, 5, -28 }, // 0x40 '@' + { 2233, 30, 27, 28, 0, -26 }, // 0x41 'A' + { 2335, 29, 27, 28, 1, -26 }, // 0x42 'B' + { 2433, 28, 29, 28, 3, -27 }, // 0x43 'C' + { 2535, 28, 27, 28, 1, -26 }, // 0x44 'D' + { 2630, 29, 27, 28, 1, -26 }, // 0x45 'E' + { 2728, 31, 27, 28, 0, -26 }, // 0x46 'F' + { 2833, 28, 29, 28, 3, -27 }, // 0x47 'G' + { 2935, 30, 27, 28, 1, -26 }, // 0x48 'H' + { 3037, 25, 27, 28, 3, -26 }, // 0x49 'I' + { 3122, 31, 28, 28, 0, -26 }, // 0x4A 'J' + { 3231, 31, 27, 28, 0, -26 }, // 0x4B 'K' + { 3336, 27, 27, 28, 1, -26 }, // 0x4C 'L' + { 3428, 34, 27, 28, 0, -26 }, // 0x4D 'M' + { 3543, 32, 27, 28, 1, -26 }, // 0x4E 'N' + { 3651, 27, 29, 28, 3, -27 }, // 0x4F 'O' + { 3749, 28, 27, 28, 1, -26 }, // 0x50 'P' + { 3844, 27, 35, 28, 3, -27 }, // 0x51 'Q' + { 3963, 29, 27, 28, 0, -26 }, // 0x52 'R' + { 4061, 26, 29, 28, 3, -27 }, // 0x53 'S' + { 4156, 26, 27, 28, 4, -26 }, // 0x54 'T' + { 4244, 28, 28, 28, 4, -26 }, // 0x55 'U' + { 4342, 30, 27, 28, 2, -26 }, // 0x56 'V' + { 4444, 29, 27, 28, 3, -26 }, // 0x57 'W' + { 4542, 32, 27, 28, 0, -26 }, // 0x58 'X' + { 4650, 26, 27, 28, 4, -26 }, // 0x59 'Y' + { 4738, 27, 27, 28, 2, -26 }, // 0x5A 'Z' + { 4830, 18, 37, 28, 10, -29 }, // 0x5B '[' + { 4914, 13, 38, 28, 10, -32 }, // 0x5C '\' + { 4976, 18, 37, 28, 5, -29 }, // 0x5D ']' + { 5060, 20, 15, 28, 8, -29 }, // 0x5E '^' + { 5098, 29, 5, 28, -2, 5 }, // 0x5F '_' + { 5117, 8, 8, 28, 13, -30 }, // 0x60 '`' + { 5125, 24, 23, 28, 3, -21 }, // 0x61 'a' + { 5194, 29, 31, 28, 0, -29 }, // 0x62 'b' + { 5307, 25, 23, 28, 3, -21 }, // 0x63 'c' + { 5379, 28, 31, 28, 3, -29 }, // 0x64 'd' + { 5488, 24, 23, 28, 3, -21 }, // 0x65 'e' + { 5557, 28, 30, 28, 4, -29 }, // 0x66 'f' + { 5662, 28, 31, 28, 3, -21 }, // 0x67 'g' + { 5771, 26, 30, 28, 2, -29 }, // 0x68 'h' + { 5869, 23, 29, 28, 3, -28 }, // 0x69 'i' + { 5953, 23, 38, 28, 3, -28 }, // 0x6A 'j' + { 6063, 26, 30, 28, 2, -29 }, // 0x6B 'k' + { 6161, 23, 30, 28, 3, -29 }, // 0x6C 'l' + { 6248, 30, 22, 28, 0, -21 }, // 0x6D 'm' + { 6331, 26, 22, 28, 2, -21 }, // 0x6E 'n' + { 6403, 25, 23, 28, 3, -21 }, // 0x6F 'o' + { 6475, 31, 31, 28, -1, -21 }, // 0x70 'p' + { 6596, 29, 31, 28, 2, -21 }, // 0x71 'q' + { 6709, 28, 22, 28, 2, -21 }, // 0x72 'r' + { 6786, 23, 23, 28, 4, -21 }, // 0x73 's' + { 6853, 20, 28, 28, 5, -26 }, // 0x74 't' + { 6923, 23, 22, 28, 5, -20 }, // 0x75 'u' + { 6987, 28, 21, 28, 3, -20 }, // 0x76 'v' + { 7061, 28, 21, 28, 3, -20 }, // 0x77 'w' + { 7135, 29, 21, 28, 1, -20 }, // 0x78 'x' + { 7212, 32, 30, 28, -1, -20 }, // 0x79 'y' + { 7332, 25, 21, 28, 4, -20 }, // 0x7A 'z' + { 7398, 17, 37, 28, 10, -29 }, // 0x7B '{' + { 7477, 11, 36, 28, 11, -28 }, // 0x7C '|' + { 7527, 17, 37, 28, 6, -29 }, // 0x7D '}' + { 7606, 23, 10, 28, 5, -17 } }; // 0x7E '~' + +const GFXfont FreeMonoBoldOblique24pt7b PROGMEM = { + (uint8_t *)FreeMonoBoldOblique24pt7bBitmaps, + (GFXglyph *)FreeMonoBoldOblique24pt7bGlyphs, + 0x20, 0x7E, 47 }; + +// Approx. 8307 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique9pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique9pt7b.h new file mode 100644 index 0000000..b530723 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique9pt7b.h @@ -0,0 +1,203 @@ +const uint8_t FreeMonoBoldOblique9pt7bBitmaps[] PROGMEM = { + 0x39, 0xCC, 0x67, 0x31, 0x8C, 0x07, 0x38, 0x6C, 0xD9, 0x36, 0x48, 0x80, + 0x09, 0x0D, 0x86, 0xCF, 0xF7, 0xF9, 0xB3, 0xFD, 0xFE, 0x6C, 0x36, 0x1B, + 0x00, 0x00, 0x06, 0x07, 0x07, 0xE6, 0x33, 0x01, 0xE0, 0x7C, 0x06, 0x43, + 0x33, 0xBF, 0x83, 0x03, 0x00, 0x80, 0x1C, 0x11, 0x10, 0x88, 0x83, 0xB8, + 0xF3, 0xB8, 0x22, 0x21, 0x11, 0x07, 0x00, 0x0F, 0x1F, 0x30, 0x30, 0x38, + 0x7B, 0xDF, 0xCE, 0xFF, 0x7E, 0xFA, 0x80, 0x19, 0x8C, 0xC6, 0x63, 0x18, + 0xC6, 0x31, 0xC6, 0x30, 0x31, 0xC6, 0x31, 0x8C, 0x63, 0x31, 0x98, 0xCC, + 0x40, 0x08, 0x08, 0xFF, 0xFF, 0x38, 0x6C, 0x6C, 0x0C, 0x06, 0x03, 0x1F, + 0xFF, 0xF8, 0xC0, 0x60, 0x30, 0x10, 0x00, 0x36, 0x4C, 0x80, 0xFF, 0xFF, + 0xC0, 0xFC, 0x00, 0x00, 0x0C, 0x03, 0x00, 0xC0, 0x18, 0x06, 0x01, 0x80, + 0x30, 0x0C, 0x03, 0x00, 0x60, 0x18, 0x06, 0x00, 0xC0, 0x30, 0x00, 0x0F, + 0x0F, 0xCC, 0x6C, 0x36, 0x1B, 0x0D, 0x05, 0x86, 0xC3, 0x63, 0x3F, 0x8F, + 0x00, 0x06, 0x1C, 0x3C, 0x6C, 0x0C, 0x0C, 0x08, 0x18, 0x18, 0x18, 0xFE, + 0xFE, 0x07, 0x83, 0xF1, 0x8C, 0x43, 0x00, 0xC0, 0xE0, 0x70, 0x38, 0x38, + 0x1C, 0x6F, 0xF3, 0xFC, 0x1F, 0x1F, 0xC0, 0x60, 0x30, 0x30, 0x70, 0x38, + 0x06, 0x03, 0x03, 0xBF, 0x9F, 0x80, 0x03, 0x07, 0x0B, 0x1B, 0x32, 0x66, + 0xFF, 0xFF, 0x1E, 0x1E, 0x3F, 0x9F, 0x98, 0x0F, 0xC7, 0xF3, 0x18, 0x0C, + 0x06, 0x06, 0x7F, 0x1E, 0x00, 0x07, 0x87, 0xCE, 0x06, 0x06, 0x03, 0xF3, + 0xFD, 0xC6, 0xC3, 0x63, 0xBF, 0x8F, 0x80, 0xFF, 0xFF, 0xC3, 0x06, 0x06, + 0x0C, 0x18, 0x18, 0x30, 0x30, 0x60, 0x1F, 0x1F, 0xDC, 0x6C, 0x36, 0x31, + 0xF1, 0xF8, 0xC6, 0xC3, 0x63, 0xBF, 0x8F, 0x80, 0x1E, 0x3F, 0x33, 0x63, + 0x63, 0x67, 0x7F, 0x3E, 0x06, 0x1C, 0xF8, 0xF0, 0x77, 0x00, 0x00, 0xEE, + 0x1C, 0x70, 0x00, 0x00, 0x03, 0x0C, 0x61, 0x08, 0x00, 0x00, 0xC1, 0xE1, + 0xE1, 0xE0, 0xF0, 0x07, 0x00, 0xF0, 0x0C, 0x7F, 0xDF, 0xF0, 0x00, 0x00, + 0x7F, 0xFF, 0xF0, 0x30, 0x0F, 0x00, 0xE0, 0x1E, 0x07, 0xC7, 0x87, 0x83, + 0x00, 0x7D, 0xFF, 0x18, 0x30, 0xE3, 0x9C, 0x30, 0x01, 0xC3, 0x80, 0x0F, + 0x0F, 0xCC, 0x6C, 0x36, 0x72, 0x79, 0x7D, 0xB6, 0xDA, 0x6F, 0xB3, 0xD8, + 0x0C, 0x07, 0xE1, 0xE0, 0x0F, 0x83, 0xF0, 0x1E, 0x03, 0xC0, 0xD8, 0x31, + 0x87, 0xF1, 0xFE, 0x30, 0xDF, 0x3F, 0xC7, 0x80, 0x3F, 0xC7, 0xFC, 0x61, + 0x8C, 0x31, 0xFC, 0x3F, 0x84, 0x19, 0x83, 0x30, 0x6F, 0xFB, 0xFE, 0x00, + 0x0F, 0xF1, 0xFF, 0x30, 0x66, 0x06, 0x60, 0x0C, 0x00, 0xC0, 0x0C, 0x00, + 0xE0, 0xC7, 0xF8, 0x3F, 0x00, 0x3F, 0x87, 0xF8, 0x63, 0x8C, 0x31, 0x06, + 0x60, 0xCC, 0x19, 0x86, 0x31, 0xCF, 0xF3, 0xF8, 0x00, 0x3F, 0xE3, 0xFE, + 0x18, 0x61, 0xB6, 0x1F, 0x01, 0xF0, 0x32, 0x03, 0x00, 0x30, 0x4F, 0xFC, + 0xFF, 0xC0, 0x3F, 0xF3, 0xFE, 0x18, 0x61, 0xB6, 0x1F, 0x03, 0xF0, 0x32, + 0x03, 0x00, 0x30, 0x0F, 0xC0, 0xFC, 0x00, 0x0F, 0xE3, 0xFC, 0xC1, 0x30, + 0x06, 0x01, 0x80, 0x31, 0xF6, 0x3E, 0xE1, 0x9F, 0xF0, 0xF8, 0x00, 0x1E, + 0xF3, 0xCF, 0x18, 0x61, 0x84, 0x10, 0xC3, 0xFC, 0x3F, 0xC3, 0x08, 0x31, + 0x8F, 0xBC, 0xFB, 0xC0, 0x3F, 0xCF, 0xF0, 0x60, 0x10, 0x0C, 0x03, 0x00, + 0xC0, 0x20, 0x18, 0x3F, 0xCF, 0xF0, 0x07, 0xF0, 0x7F, 0x00, 0x80, 0x18, + 0x01, 0x80, 0x18, 0x61, 0x84, 0x10, 0xC3, 0x0F, 0xE0, 0x7C, 0x00, 0x3E, + 0xE7, 0xFC, 0x66, 0x0D, 0x81, 0x60, 0x7C, 0x0E, 0xC1, 0x98, 0x31, 0x1F, + 0x3B, 0xE7, 0x00, 0x3F, 0x07, 0xE0, 0x30, 0x06, 0x00, 0xC0, 0x10, 0x06, + 0x00, 0xC3, 0x18, 0x6F, 0xFB, 0xFF, 0x00, 0x38, 0x39, 0xC3, 0xC7, 0x3C, + 0x79, 0xE3, 0xDA, 0x1F, 0xF0, 0x9D, 0x8C, 0xCC, 0x60, 0x67, 0xCF, 0x3C, + 0x78, 0x3C, 0xF9, 0xE7, 0x87, 0x18, 0x3C, 0xC1, 0x66, 0x1B, 0xB0, 0xCD, + 0x06, 0x78, 0x31, 0xC3, 0xCE, 0x3E, 0x30, 0x0F, 0x0F, 0xE7, 0x1D, 0x83, + 0xC0, 0xF0, 0x3C, 0x0F, 0x06, 0xE3, 0x9F, 0xC3, 0xC0, 0x3F, 0xC7, 0xFC, + 0x61, 0x8C, 0x31, 0x8E, 0x3F, 0x87, 0xE1, 0x80, 0x30, 0x0F, 0xC3, 0xF0, + 0x00, 0x0F, 0x0F, 0xE7, 0x1D, 0x83, 0xC0, 0xF0, 0x3C, 0x0F, 0x06, 0xE3, + 0x1F, 0xC3, 0xC0, 0x80, 0x7F, 0x3F, 0xC0, 0x3F, 0xC3, 0xFE, 0x18, 0x61, + 0x86, 0x10, 0xE3, 0xFC, 0x3F, 0x83, 0x18, 0x31, 0xCF, 0x8F, 0xF8, 0x70, + 0x1E, 0xCF, 0xF7, 0x19, 0x80, 0x70, 0x1F, 0x81, 0xF3, 0x0C, 0xC3, 0x3F, + 0x8B, 0xC0, 0x7F, 0xCF, 0xF9, 0x93, 0x66, 0x60, 0xC0, 0x18, 0x02, 0x00, + 0xC0, 0x18, 0x0F, 0xC1, 0xF8, 0x00, 0xF9, 0xFF, 0x7D, 0x83, 0x30, 0x64, + 0x09, 0x83, 0x30, 0x66, 0x0C, 0xE3, 0x0F, 0xC0, 0xF0, 0x00, 0xF9, 0xFE, + 0x3D, 0x83, 0x30, 0xC6, 0x30, 0xE6, 0x0D, 0x81, 0xB0, 0x3C, 0x07, 0x00, + 0x60, 0x00, 0xF9, 0xFF, 0x3D, 0x83, 0x36, 0x64, 0xC8, 0xBF, 0x35, 0xE7, + 0xB8, 0xE7, 0x1C, 0xE3, 0x18, 0x00, 0x3C, 0xF3, 0xCF, 0x1C, 0xC0, 0xD8, + 0x0F, 0x00, 0x60, 0x0F, 0x01, 0xB8, 0x31, 0x8F, 0x3C, 0xF3, 0xC0, 0x79, + 0xEE, 0x38, 0xC6, 0x19, 0x81, 0xE0, 0x38, 0x06, 0x00, 0xC0, 0x18, 0x0F, + 0xC3, 0xF8, 0x00, 0x3F, 0xCF, 0xF3, 0x18, 0xCC, 0x06, 0x03, 0x01, 0x80, + 0xC6, 0x61, 0xBF, 0xCF, 0xF0, 0x1E, 0x3C, 0xC1, 0x83, 0x06, 0x08, 0x30, + 0x60, 0xC1, 0x06, 0x0F, 0x1E, 0x00, 0x06, 0x31, 0x86, 0x31, 0x8C, 0x31, + 0x8C, 0x61, 0x8C, 0x60, 0x1E, 0x78, 0x30, 0x60, 0xC1, 0x86, 0x0C, 0x18, + 0x30, 0x41, 0x8F, 0x1E, 0x00, 0x08, 0x1C, 0x3C, 0x76, 0xE7, 0xC3, 0x7F, + 0xFF, 0xFC, 0x88, 0x80, 0x0F, 0x07, 0xE1, 0xF9, 0xFE, 0xE3, 0x30, 0xCF, + 0xFD, 0xFF, 0x38, 0x07, 0x00, 0x60, 0x0F, 0xC1, 0xFC, 0x71, 0xCC, 0x19, + 0x83, 0x30, 0xDF, 0xFB, 0xBC, 0x00, 0x1F, 0xCF, 0xF6, 0x1B, 0x00, 0xC0, + 0x30, 0x0F, 0xF1, 0xF8, 0x01, 0xE0, 0x38, 0x03, 0x0F, 0x63, 0xFC, 0xC3, + 0x30, 0x66, 0x0C, 0xC3, 0x9F, 0xF9, 0xF7, 0x00, 0x1F, 0x1F, 0xD8, 0x3F, + 0xFF, 0xFE, 0x1B, 0xFC, 0xF8, 0x07, 0xC3, 0xF1, 0x81, 0xFE, 0x7F, 0x84, + 0x03, 0x00, 0xC0, 0x30, 0x3F, 0x8F, 0xE0, 0x1E, 0xE7, 0xFD, 0x86, 0x60, + 0xCC, 0x19, 0xC6, 0x3F, 0xC1, 0xD8, 0x03, 0x00, 0xE1, 0xF8, 0x3E, 0x00, + 0x38, 0x1E, 0x01, 0x00, 0xDC, 0x3F, 0x8C, 0x62, 0x19, 0x84, 0x63, 0x3D, + 0xFF, 0x7C, 0x06, 0x03, 0x00, 0x03, 0xC3, 0xE0, 0x20, 0x30, 0x18, 0x0C, + 0x3F, 0xFF, 0xE0, 0x01, 0x81, 0x80, 0x07, 0xF3, 0xF8, 0x0C, 0x04, 0x06, + 0x03, 0x01, 0x80, 0xC0, 0x40, 0x67, 0xE3, 0xE0, 0x38, 0x0E, 0x01, 0x80, + 0x4F, 0x37, 0xCF, 0x83, 0xC0, 0xF0, 0x26, 0x39, 0xEE, 0x78, 0x1F, 0x0F, + 0x01, 0x80, 0xC0, 0x60, 0x20, 0x30, 0x18, 0x0C, 0x3F, 0xFF, 0xE0, 0x7E, + 0xE7, 0xFF, 0x33, 0x32, 0x63, 0x66, 0x36, 0x62, 0xF7, 0x7F, 0x67, 0x77, + 0x8F, 0xF8, 0xC3, 0x10, 0x66, 0x08, 0xC3, 0x3C, 0x7F, 0x8F, 0x1F, 0x0F, + 0xE6, 0x1F, 0x03, 0xC0, 0xF8, 0x67, 0xF0, 0xF8, 0x3F, 0xE3, 0xFF, 0x1C, + 0x31, 0x83, 0x18, 0x31, 0x86, 0x3F, 0xE3, 0x78, 0x30, 0x03, 0x00, 0xFC, + 0x0F, 0x80, 0x1E, 0xEF, 0xFD, 0x86, 0x60, 0xCC, 0x19, 0xC7, 0x3F, 0xE1, + 0xE8, 0x03, 0x00, 0x60, 0x3E, 0x07, 0xC0, 0x39, 0xDF, 0xF1, 0xC0, 0x60, + 0x10, 0x0C, 0x0F, 0xF3, 0xF8, 0x1F, 0x7F, 0x63, 0x7E, 0x1F, 0xC3, 0xFE, + 0xFC, 0x10, 0x08, 0x0C, 0x1F, 0xEF, 0xF1, 0x80, 0x80, 0xC0, 0x60, 0x3F, + 0x8F, 0x80, 0xF3, 0xFC, 0xF6, 0x09, 0x86, 0x61, 0x98, 0xE7, 0xF8, 0xFE, + 0xFB, 0xFF, 0x7C, 0xC6, 0x19, 0x83, 0x60, 0x6C, 0x07, 0x00, 0xC0, 0xF1, + 0xFE, 0x3D, 0xB3, 0x37, 0xC7, 0xF8, 0xEE, 0x1D, 0xC3, 0x30, 0x79, 0xEF, + 0x38, 0xEE, 0x0F, 0x01, 0xE0, 0x6E, 0x3C, 0xE7, 0xBC, 0x3C, 0xF3, 0x8F, + 0x18, 0xC1, 0x9C, 0x19, 0x81, 0xF0, 0x0E, 0x00, 0xE0, 0x0C, 0x01, 0x80, + 0xFC, 0x0F, 0xC0, 0x7F, 0xBF, 0xD9, 0xC1, 0x83, 0x83, 0x1B, 0xFD, 0xFE, + 0x06, 0x1C, 0x60, 0xC1, 0x86, 0x3C, 0x70, 0x30, 0x41, 0x83, 0x07, 0x06, + 0x00, 0x33, 0x32, 0x26, 0x66, 0x44, 0xCC, 0xC8, 0x0C, 0x0E, 0x04, 0x0C, + 0x0C, 0x0C, 0x0F, 0x0F, 0x18, 0x18, 0x10, 0x30, 0xF0, 0xE0, 0x38, 0x7C, + 0xF7, 0xC1, 0xC0 }; + +const GFXglyph FreeMonoBoldOblique9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 11, 0, 1 }, // 0x20 ' ' + { 0, 5, 11, 11, 4, -10 }, // 0x21 '!' + { 7, 7, 5, 11, 4, -10 }, // 0x22 '"' + { 12, 9, 12, 11, 2, -10 }, // 0x23 '#' + { 26, 9, 14, 11, 2, -11 }, // 0x24 '$' + { 42, 9, 11, 11, 2, -10 }, // 0x25 '%' + { 55, 8, 10, 11, 2, -9 }, // 0x26 '&' + { 65, 2, 5, 11, 6, -10 }, // 0x27 ''' + { 67, 5, 14, 11, 5, -10 }, // 0x28 '(' + { 76, 5, 14, 11, 2, -10 }, // 0x29 ')' + { 85, 8, 7, 11, 3, -10 }, // 0x2A '*' + { 92, 9, 9, 11, 2, -8 }, // 0x2B '+' + { 103, 4, 5, 11, 2, -1 }, // 0x2C ',' + { 106, 9, 2, 11, 2, -5 }, // 0x2D '-' + { 109, 3, 2, 11, 4, -1 }, // 0x2E '.' + { 110, 11, 15, 11, 1, -12 }, // 0x2F '/' + { 131, 9, 12, 11, 2, -11 }, // 0x30 '0' + { 145, 8, 12, 11, 2, -11 }, // 0x31 '1' + { 157, 10, 12, 11, 1, -11 }, // 0x32 '2' + { 172, 9, 12, 11, 2, -11 }, // 0x33 '3' + { 186, 8, 10, 11, 2, -9 }, // 0x34 '4' + { 196, 9, 11, 11, 3, -10 }, // 0x35 '5' + { 209, 9, 12, 11, 3, -11 }, // 0x36 '6' + { 223, 8, 11, 11, 3, -10 }, // 0x37 '7' + { 234, 9, 12, 11, 2, -11 }, // 0x38 '8' + { 248, 8, 12, 11, 3, -11 }, // 0x39 '9' + { 260, 4, 8, 11, 4, -7 }, // 0x3A ':' + { 264, 6, 11, 11, 2, -7 }, // 0x3B ';' + { 273, 10, 8, 11, 2, -8 }, // 0x3C '<' + { 283, 10, 6, 11, 1, -7 }, // 0x3D '=' + { 291, 10, 8, 11, 1, -8 }, // 0x3E '>' + { 301, 7, 11, 11, 4, -10 }, // 0x3F '?' + { 311, 9, 15, 11, 2, -11 }, // 0x40 '@' + { 328, 11, 11, 11, 0, -10 }, // 0x41 'A' + { 344, 11, 11, 11, 0, -10 }, // 0x42 'B' + { 360, 12, 11, 11, 1, -10 }, // 0x43 'C' + { 377, 11, 11, 11, 0, -10 }, // 0x44 'D' + { 393, 12, 11, 11, 0, -10 }, // 0x45 'E' + { 410, 12, 11, 11, 0, -10 }, // 0x46 'F' + { 427, 11, 11, 11, 1, -10 }, // 0x47 'G' + { 443, 12, 11, 11, 0, -10 }, // 0x48 'H' + { 460, 10, 11, 11, 1, -10 }, // 0x49 'I' + { 474, 12, 11, 11, 0, -10 }, // 0x4A 'J' + { 491, 11, 11, 11, 0, -10 }, // 0x4B 'K' + { 507, 11, 11, 11, 0, -10 }, // 0x4C 'L' + { 523, 13, 11, 11, 0, -10 }, // 0x4D 'M' + { 541, 13, 11, 11, 0, -10 }, // 0x4E 'N' + { 559, 10, 11, 11, 1, -10 }, // 0x4F 'O' + { 573, 11, 11, 11, 0, -10 }, // 0x50 'P' + { 589, 10, 14, 11, 1, -10 }, // 0x51 'Q' + { 607, 12, 11, 11, 0, -10 }, // 0x52 'R' + { 624, 10, 11, 11, 2, -10 }, // 0x53 'S' + { 638, 11, 11, 11, 1, -10 }, // 0x54 'T' + { 654, 11, 11, 11, 1, -10 }, // 0x55 'U' + { 670, 11, 11, 11, 1, -10 }, // 0x56 'V' + { 686, 11, 11, 11, 1, -10 }, // 0x57 'W' + { 702, 12, 11, 11, 0, -10 }, // 0x58 'X' + { 719, 11, 11, 11, 1, -10 }, // 0x59 'Y' + { 735, 10, 11, 11, 1, -10 }, // 0x5A 'Z' + { 749, 7, 14, 11, 4, -10 }, // 0x5B '[' + { 762, 5, 15, 11, 4, -12 }, // 0x5C '\' + { 772, 7, 14, 11, 2, -10 }, // 0x5D ']' + { 785, 8, 6, 11, 3, -11 }, // 0x5E '^' + { 791, 11, 2, 11, -1, 3 }, // 0x5F '_' + { 794, 3, 3, 11, 5, -11 }, // 0x60 '`' + { 796, 10, 8, 11, 1, -7 }, // 0x61 'a' + { 806, 11, 11, 11, 0, -10 }, // 0x62 'b' + { 822, 10, 8, 11, 1, -7 }, // 0x63 'c' + { 832, 11, 11, 11, 1, -10 }, // 0x64 'd' + { 848, 9, 8, 11, 1, -7 }, // 0x65 'e' + { 857, 10, 11, 11, 2, -10 }, // 0x66 'f' + { 871, 11, 12, 11, 1, -7 }, // 0x67 'g' + { 888, 10, 11, 11, 1, -10 }, // 0x68 'h' + { 902, 9, 11, 11, 1, -10 }, // 0x69 'i' + { 915, 9, 15, 11, 1, -10 }, // 0x6A 'j' + { 932, 10, 11, 11, 1, -10 }, // 0x6B 'k' + { 946, 9, 11, 11, 1, -10 }, // 0x6C 'l' + { 959, 12, 8, 11, 0, -7 }, // 0x6D 'm' + { 971, 11, 8, 11, 1, -7 }, // 0x6E 'n' + { 982, 10, 8, 11, 1, -7 }, // 0x6F 'o' + { 992, 12, 12, 11, -1, -7 }, // 0x70 'p' + { 1010, 11, 12, 11, 1, -7 }, // 0x71 'q' + { 1027, 10, 8, 11, 1, -7 }, // 0x72 'r' + { 1037, 8, 8, 11, 2, -7 }, // 0x73 's' + { 1045, 9, 11, 11, 1, -10 }, // 0x74 't' + { 1058, 10, 8, 11, 1, -7 }, // 0x75 'u' + { 1068, 11, 8, 11, 1, -7 }, // 0x76 'v' + { 1079, 11, 8, 11, 1, -7 }, // 0x77 'w' + { 1090, 11, 8, 11, 1, -7 }, // 0x78 'x' + { 1101, 12, 12, 11, 0, -7 }, // 0x79 'y' + { 1119, 9, 8, 11, 2, -7 }, // 0x7A 'z' + { 1128, 7, 14, 11, 3, -10 }, // 0x7B '{' + { 1141, 4, 14, 11, 4, -10 }, // 0x7C '|' + { 1148, 8, 14, 11, 2, -10 }, // 0x7D '}' + { 1162, 9, 4, 11, 2, -6 } }; // 0x7E '~' + +const GFXfont FreeMonoBoldOblique9pt7b PROGMEM = { + (uint8_t *)FreeMonoBoldOblique9pt7bBitmaps, + (GFXglyph *)FreeMonoBoldOblique9pt7bGlyphs, + 0x20, 0x7E, 18 }; + +// Approx. 1839 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique12pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique12pt7b.h new file mode 100644 index 0000000..83a9a77 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique12pt7b.h @@ -0,0 +1,248 @@ +const uint8_t FreeMonoOblique12pt7bBitmaps[] PROGMEM = { + 0x11, 0x11, 0x12, 0x22, 0x22, 0x00, 0x0E, 0xE0, 0xE7, 0xE7, 0xC6, 0xC6, + 0xC6, 0x84, 0x84, 0x02, 0x40, 0x88, 0x12, 0x02, 0x40, 0x48, 0x7F, 0xC2, + 0x40, 0x48, 0x11, 0x1F, 0xF8, 0x48, 0x09, 0x02, 0x40, 0x48, 0x09, 0x02, + 0x20, 0x02, 0x01, 0x00, 0xF4, 0xC3, 0x60, 0x50, 0x04, 0x00, 0xC0, 0x0F, + 0x00, 0x60, 0x0A, 0x02, 0x81, 0x30, 0xC7, 0xC0, 0x80, 0x20, 0x08, 0x00, + 0x0E, 0x02, 0x20, 0x84, 0x10, 0x82, 0x20, 0x38, 0x00, 0x38, 0x38, 0x38, + 0x08, 0xE0, 0x22, 0x08, 0x41, 0x08, 0x22, 0x03, 0x80, 0x07, 0x84, 0x04, + 0x02, 0x01, 0x00, 0xC1, 0xA2, 0x8A, 0x85, 0x43, 0x31, 0x8F, 0x60, 0xFF, + 0x6D, 0x20, 0x00, 0x44, 0x42, 0x21, 0x08, 0x84, 0x21, 0x08, 0x42, 0x10, + 0x42, 0x00, 0x00, 0x84, 0x10, 0x84, 0x21, 0x08, 0x46, 0x21, 0x10, 0x88, + 0x44, 0x00, 0x04, 0x02, 0x02, 0x1D, 0x13, 0xF0, 0x40, 0x50, 0x48, 0x44, + 0x00, 0x02, 0x00, 0x40, 0x08, 0x02, 0x00, 0x41, 0xFF, 0xC1, 0x00, 0x20, + 0x08, 0x01, 0x00, 0x20, 0x00, 0x1C, 0xE3, 0x18, 0x63, 0x08, 0x00, 0xFF, + 0xE0, 0x7F, 0x00, 0x00, 0x08, 0x00, 0x80, 0x04, 0x00, 0x40, 0x04, 0x00, + 0x60, 0x02, 0x00, 0x20, 0x03, 0x00, 0x10, 0x01, 0x00, 0x18, 0x00, 0x80, + 0x08, 0x00, 0x80, 0x04, 0x00, 0x40, 0x04, 0x00, 0x00, 0x07, 0x06, 0x23, + 0x04, 0x81, 0x40, 0x50, 0x14, 0x06, 0x02, 0x80, 0xA0, 0x28, 0x0A, 0x04, + 0x83, 0x11, 0x83, 0x80, 0x03, 0x03, 0x83, 0x83, 0x43, 0x20, 0x10, 0x08, + 0x08, 0x04, 0x02, 0x01, 0x01, 0x00, 0x80, 0x43, 0xFE, 0x01, 0xC0, 0x62, + 0x0C, 0x10, 0x81, 0x00, 0x10, 0x02, 0x00, 0x60, 0x0C, 0x01, 0x00, 0x20, + 0x0C, 0x01, 0x80, 0x20, 0x04, 0x04, 0xFF, 0xC0, 0x07, 0xC3, 0x0C, 0x00, + 0x80, 0x10, 0x06, 0x01, 0x81, 0xC0, 0x0C, 0x00, 0x40, 0x08, 0x01, 0x00, + 0x20, 0x09, 0x86, 0x0F, 0x00, 0x00, 0xC0, 0x50, 0x24, 0x12, 0x04, 0x82, + 0x21, 0x08, 0x82, 0x21, 0x10, 0x4F, 0xF8, 0x04, 0x01, 0x00, 0x80, 0xF8, + 0x0F, 0xE2, 0x00, 0x40, 0x08, 0x01, 0x00, 0x4E, 0x0E, 0x20, 0x02, 0x00, + 0x40, 0x08, 0x01, 0x00, 0x40, 0x19, 0x06, 0x1F, 0x00, 0x01, 0xE0, 0xC0, + 0x60, 0x18, 0x02, 0x00, 0x80, 0x13, 0xC5, 0x88, 0xE0, 0x98, 0x12, 0x02, + 0x40, 0x48, 0x10, 0x84, 0x0F, 0x00, 0xFF, 0xA0, 0x20, 0x08, 0x04, 0x01, + 0x00, 0x80, 0x20, 0x10, 0x04, 0x02, 0x00, 0x80, 0x40, 0x10, 0x08, 0x02, + 0x00, 0x07, 0x81, 0x08, 0x40, 0x90, 0x12, 0x02, 0x40, 0x84, 0x20, 0x78, + 0x30, 0x88, 0x0A, 0x01, 0x40, 0x28, 0x08, 0x82, 0x0F, 0x80, 0x07, 0x81, + 0x08, 0x40, 0x90, 0x12, 0x02, 0x40, 0xC8, 0x39, 0x8D, 0x1E, 0x40, 0x08, + 0x02, 0x00, 0xC0, 0x30, 0x18, 0x3E, 0x00, 0x19, 0xCC, 0x00, 0x00, 0x0C, + 0xE6, 0x00, 0x06, 0x1C, 0x30, 0x00, 0x00, 0x00, 0x1C, 0x30, 0xE1, 0x86, + 0x08, 0x00, 0x00, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x06, 0x00, 0x30, + 0x00, 0xC0, 0x06, 0x00, 0x18, 0x00, 0xC0, 0x7F, 0xF8, 0x00, 0x00, 0x01, + 0xFF, 0xE0, 0x18, 0x00, 0xC0, 0x03, 0x00, 0x18, 0x00, 0x60, 0x03, 0x00, + 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x00, 0x3E, 0xC3, 0x81, 0x01, 0x03, + 0x06, 0x18, 0x20, 0x20, 0x00, 0x00, 0x00, 0xE0, 0xE0, 0x07, 0x82, 0x31, + 0x04, 0x81, 0x20, 0x48, 0x74, 0x65, 0x21, 0x48, 0x92, 0x28, 0x7A, 0x00, + 0x80, 0x20, 0x04, 0x00, 0xF8, 0x07, 0xE0, 0x02, 0x80, 0x0A, 0x00, 0x48, + 0x01, 0x20, 0x08, 0x40, 0x41, 0x01, 0x04, 0x0F, 0xF0, 0x20, 0x41, 0x01, + 0x04, 0x02, 0x20, 0x0B, 0xE1, 0xF0, 0x1F, 0xF0, 0x40, 0xC2, 0x02, 0x10, + 0x10, 0x81, 0x84, 0x18, 0x7F, 0x82, 0x02, 0x10, 0x08, 0x80, 0x44, 0x02, + 0x60, 0x22, 0x03, 0x7F, 0xE0, 0x07, 0x91, 0x87, 0x20, 0x34, 0x02, 0x40, + 0x08, 0x00, 0x80, 0x08, 0x00, 0x80, 0x08, 0x00, 0x80, 0x04, 0x04, 0x61, + 0x81, 0xE0, 0x1F, 0xE0, 0x41, 0x82, 0x06, 0x10, 0x11, 0x00, 0x88, 0x04, + 0x40, 0x22, 0x01, 0x10, 0x11, 0x00, 0x88, 0x08, 0x40, 0xC2, 0x0C, 0x7F, + 0x80, 0x1F, 0xFC, 0x20, 0x10, 0x80, 0x82, 0x00, 0x08, 0x00, 0x22, 0x01, + 0xF8, 0x04, 0x20, 0x10, 0x00, 0x40, 0x01, 0x01, 0x0C, 0x04, 0x20, 0x13, + 0xFF, 0xC0, 0x1F, 0xFC, 0x20, 0x10, 0x80, 0x42, 0x01, 0x08, 0x00, 0x22, + 0x01, 0xF8, 0x04, 0x20, 0x10, 0x00, 0x40, 0x01, 0x00, 0x0C, 0x00, 0x20, + 0x03, 0xF8, 0x00, 0x07, 0xD0, 0x83, 0x30, 0x12, 0x00, 0x40, 0x04, 0x00, + 0x80, 0x08, 0x00, 0x83, 0xE8, 0x04, 0x80, 0x4C, 0x04, 0x60, 0x41, 0xF8, + 0x0F, 0x3C, 0x08, 0x10, 0x20, 0x20, 0x40, 0x40, 0x81, 0x01, 0x02, 0x03, + 0xFC, 0x08, 0x08, 0x10, 0x10, 0x20, 0x40, 0x40, 0x80, 0x81, 0x02, 0x02, + 0x1F, 0x1E, 0x00, 0x3F, 0xE0, 0x40, 0x08, 0x01, 0x00, 0x20, 0x08, 0x01, + 0x00, 0x20, 0x04, 0x00, 0x80, 0x20, 0x04, 0x00, 0x81, 0xFF, 0x00, 0x03, + 0xFE, 0x00, 0x20, 0x00, 0x80, 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x08, + 0x00, 0x20, 0x40, 0x40, 0x80, 0x81, 0x01, 0x02, 0x04, 0x06, 0x10, 0x07, + 0xC0, 0x00, 0x1F, 0x1E, 0x10, 0x10, 0x20, 0xC0, 0x43, 0x00, 0x88, 0x01, + 0x20, 0x07, 0xC0, 0x0C, 0x40, 0x10, 0x40, 0x20, 0x80, 0x41, 0x01, 0x81, + 0x02, 0x02, 0x1F, 0x87, 0x00, 0x3F, 0x80, 0x40, 0x04, 0x00, 0x40, 0x08, + 0x00, 0x80, 0x08, 0x00, 0x80, 0x08, 0x01, 0x01, 0x10, 0x11, 0x02, 0x10, + 0x2F, 0xFE, 0x1C, 0x03, 0x85, 0x03, 0x02, 0x82, 0x81, 0x41, 0x40, 0xA1, + 0x20, 0x89, 0x30, 0x44, 0x90, 0x22, 0x88, 0x11, 0x44, 0x08, 0x42, 0x08, + 0x03, 0x04, 0x01, 0x02, 0x00, 0x87, 0xC3, 0xE0, 0x3C, 0x3E, 0x18, 0x08, + 0x38, 0x20, 0x50, 0x41, 0x20, 0x82, 0x61, 0x04, 0x42, 0x08, 0x88, 0x10, + 0x90, 0x41, 0x20, 0x83, 0x41, 0x02, 0x82, 0x06, 0x1F, 0x04, 0x00, 0x03, + 0xC0, 0x61, 0x84, 0x04, 0x40, 0x14, 0x00, 0xA0, 0x06, 0x00, 0x30, 0x01, + 0x80, 0x14, 0x00, 0xA0, 0x08, 0x80, 0x86, 0x18, 0x0F, 0x00, 0x1F, 0xE0, + 0x40, 0x82, 0x02, 0x10, 0x10, 0x80, 0x84, 0x08, 0x40, 0x83, 0xF8, 0x10, + 0x00, 0x80, 0x04, 0x00, 0x60, 0x02, 0x00, 0x7F, 0x00, 0x03, 0xC0, 0x61, + 0x84, 0x04, 0x40, 0x14, 0x00, 0xA0, 0x06, 0x00, 0x30, 0x01, 0x80, 0x14, + 0x00, 0xA0, 0x08, 0x80, 0x86, 0x18, 0x1F, 0x00, 0x40, 0x0F, 0xC4, 0x41, + 0xC0, 0x1F, 0xE0, 0x40, 0x82, 0x02, 0x10, 0x10, 0x80, 0x84, 0x08, 0x60, + 0x83, 0xF8, 0x10, 0xC0, 0x82, 0x04, 0x08, 0x40, 0x42, 0x03, 0x7E, 0x0C, + 0x07, 0xA3, 0x0C, 0x40, 0x90, 0x12, 0x00, 0x40, 0x06, 0x00, 0x3C, 0x00, + 0x40, 0x0A, 0x01, 0x40, 0x4C, 0x11, 0x7C, 0x00, 0xFF, 0xE8, 0x42, 0x84, + 0x20, 0x40, 0x04, 0x00, 0x80, 0x08, 0x00, 0x80, 0x08, 0x00, 0x80, 0x10, + 0x01, 0x00, 0x10, 0x0F, 0xE0, 0xF8, 0xF9, 0x00, 0x88, 0x08, 0x80, 0x44, + 0x02, 0x20, 0x11, 0x01, 0x08, 0x08, 0x80, 0x44, 0x02, 0x20, 0x31, 0x01, + 0x04, 0x30, 0x1E, 0x00, 0xF8, 0x7D, 0x00, 0x42, 0x01, 0x08, 0x08, 0x20, + 0x40, 0x81, 0x02, 0x08, 0x08, 0x20, 0x11, 0x00, 0x48, 0x01, 0x20, 0x05, + 0x00, 0x14, 0x00, 0x60, 0x00, 0xF8, 0x7D, 0x00, 0x44, 0x01, 0x11, 0x84, + 0x46, 0x21, 0x18, 0x84, 0xA2, 0x12, 0x90, 0x91, 0x42, 0x45, 0x0A, 0x14, + 0x28, 0x60, 0xC1, 0x83, 0x06, 0x00, 0x1E, 0x1E, 0x10, 0x10, 0x10, 0x40, + 0x21, 0x00, 0x24, 0x00, 0x78, 0x00, 0x60, 0x01, 0xC0, 0x06, 0x80, 0x09, + 0x80, 0x21, 0x00, 0x81, 0x02, 0x02, 0x1E, 0x1F, 0x00, 0xF0, 0xF4, 0x04, + 0x20, 0x82, 0x18, 0x11, 0x01, 0x20, 0x1C, 0x00, 0x80, 0x08, 0x00, 0x80, + 0x10, 0x01, 0x00, 0x10, 0x0F, 0xE0, 0x0F, 0xF1, 0x01, 0x10, 0x21, 0x04, + 0x00, 0x80, 0x10, 0x02, 0x00, 0x40, 0x0C, 0x01, 0x82, 0x10, 0x22, 0x04, + 0x40, 0x47, 0xFC, 0x0E, 0x20, 0x40, 0x81, 0x02, 0x08, 0x10, 0x20, 0x40, + 0x82, 0x04, 0x08, 0x10, 0x20, 0x81, 0xE0, 0x84, 0x20, 0x84, 0x20, 0x84, + 0x21, 0x04, 0x21, 0x08, 0x21, 0x08, 0x40, 0x1E, 0x04, 0x08, 0x20, 0x40, + 0x81, 0x02, 0x04, 0x10, 0x20, 0x40, 0x81, 0x02, 0x08, 0x11, 0xE0, 0x04, + 0x06, 0x04, 0x84, 0x44, 0x14, 0x0C, 0xFF, 0xFE, 0x99, 0x90, 0x1F, 0xC0, + 0x06, 0x00, 0x20, 0x02, 0x1F, 0xE6, 0x04, 0xC0, 0x48, 0x04, 0x81, 0xC7, + 0xEF, 0x18, 0x00, 0x40, 0x02, 0x00, 0x10, 0x00, 0x80, 0x09, 0xF0, 0x50, + 0xC3, 0x03, 0x10, 0x08, 0x80, 0x48, 0x02, 0x40, 0x23, 0x03, 0x1C, 0x33, + 0xBE, 0x00, 0x0F, 0xD3, 0x07, 0x60, 0x24, 0x02, 0x80, 0x08, 0x00, 0x80, + 0x08, 0x06, 0x41, 0xC3, 0xF0, 0x00, 0x38, 0x00, 0x40, 0x02, 0x00, 0x20, + 0x01, 0x07, 0xC8, 0x43, 0x44, 0x0E, 0x40, 0x24, 0x01, 0x20, 0x09, 0x00, + 0xC8, 0x0E, 0x20, 0xE0, 0xF9, 0xC0, 0x0F, 0x86, 0x09, 0x00, 0xA0, 0x1F, + 0xFF, 0x00, 0x20, 0x06, 0x00, 0x60, 0xC7, 0xE0, 0x01, 0xF8, 0x10, 0x01, + 0x00, 0x08, 0x00, 0x40, 0x1F, 0xF0, 0x20, 0x01, 0x00, 0x08, 0x00, 0x40, + 0x04, 0x00, 0x20, 0x01, 0x00, 0x08, 0x03, 0xFE, 0x00, 0x0F, 0x31, 0x86, + 0x10, 0x10, 0x80, 0x88, 0x04, 0x40, 0x22, 0x02, 0x10, 0x10, 0x43, 0x81, + 0xE4, 0x00, 0x40, 0x02, 0x00, 0x20, 0x3E, 0x00, 0x1C, 0x00, 0x20, 0x03, + 0x00, 0x10, 0x00, 0x80, 0x05, 0xF0, 0x30, 0xC3, 0x02, 0x10, 0x10, 0x80, + 0x84, 0x0C, 0x20, 0x63, 0x02, 0x10, 0x13, 0xE3, 0xE0, 0x01, 0x80, 0x40, + 0x10, 0x00, 0x00, 0x07, 0xC0, 0x20, 0x08, 0x02, 0x00, 0x80, 0x20, 0x10, + 0x04, 0x01, 0x0F, 0xFC, 0x00, 0x40, 0x10, 0x0C, 0x00, 0x00, 0x07, 0xF0, + 0x04, 0x01, 0x00, 0x40, 0x20, 0x08, 0x02, 0x00, 0x80, 0x20, 0x10, 0x04, + 0x01, 0x00, 0x8F, 0xC0, 0x18, 0x00, 0x80, 0x08, 0x00, 0x80, 0x08, 0x01, + 0x1F, 0x10, 0x81, 0x30, 0x14, 0x01, 0xC0, 0x26, 0x02, 0x20, 0x21, 0x02, + 0x08, 0xE1, 0xE0, 0x0F, 0x80, 0x40, 0x10, 0x04, 0x01, 0x00, 0x40, 0x20, + 0x08, 0x02, 0x00, 0x80, 0x20, 0x10, 0x04, 0x01, 0x0F, 0xFC, 0x3B, 0xB8, + 0x33, 0x91, 0x08, 0x44, 0x21, 0x10, 0x84, 0x42, 0x12, 0x10, 0x48, 0x42, + 0x21, 0x0B, 0xC6, 0x30, 0x19, 0xE0, 0xE3, 0x08, 0x11, 0x01, 0x10, 0x11, + 0x02, 0x10, 0x21, 0x02, 0x20, 0x2F, 0x87, 0x0F, 0x86, 0x19, 0x80, 0xA0, + 0x18, 0x03, 0x00, 0x60, 0x14, 0x06, 0x61, 0x87, 0xC0, 0x19, 0xF0, 0x28, + 0x20, 0xC0, 0x42, 0x01, 0x10, 0x04, 0x40, 0x11, 0x00, 0x86, 0x06, 0x14, + 0x30, 0xCF, 0x02, 0x00, 0x08, 0x00, 0x20, 0x03, 0xF0, 0x00, 0x0F, 0x39, + 0x85, 0x18, 0x18, 0x80, 0x88, 0x04, 0x40, 0x22, 0x01, 0x18, 0x18, 0x63, + 0x81, 0xE4, 0x00, 0x20, 0x01, 0x00, 0x10, 0x07, 0xE0, 0x1C, 0x78, 0x2C, + 0x01, 0x80, 0x18, 0x00, 0x80, 0x04, 0x00, 0x20, 0x02, 0x00, 0x10, 0x07, + 0xFC, 0x00, 0x0F, 0x44, 0x32, 0x04, 0x80, 0x1E, 0x00, 0x60, 0x0A, 0x02, + 0xC1, 0x2F, 0x80, 0x10, 0x08, 0x04, 0x02, 0x0F, 0xF9, 0x00, 0x80, 0x40, + 0x20, 0x20, 0x10, 0x08, 0x04, 0x19, 0xF0, 0xE0, 0xF2, 0x02, 0x40, 0x24, + 0x02, 0x40, 0x24, 0x06, 0x40, 0x44, 0x04, 0x41, 0xC3, 0xE6, 0xF8, 0xFA, + 0x01, 0x08, 0x10, 0x41, 0x02, 0x08, 0x10, 0x80, 0x48, 0x02, 0x40, 0x14, + 0x00, 0xC0, 0x00, 0xE0, 0x7A, 0x01, 0x10, 0x08, 0x8C, 0x84, 0xA4, 0x25, + 0x21, 0x4A, 0x0A, 0x50, 0x63, 0x02, 0x18, 0x00, 0x1E, 0x3C, 0x20, 0x40, + 0x46, 0x00, 0xB0, 0x03, 0x00, 0x0E, 0x00, 0xC8, 0x06, 0x10, 0x20, 0x23, + 0xE3, 0xC0, 0x3C, 0x3C, 0x40, 0x20, 0x81, 0x02, 0x08, 0x08, 0x20, 0x31, + 0x00, 0x48, 0x01, 0x40, 0x05, 0x00, 0x08, 0x00, 0x40, 0x02, 0x00, 0x08, + 0x03, 0xF0, 0x00, 0x3F, 0xC4, 0x18, 0x06, 0x01, 0x80, 0x60, 0x10, 0x04, + 0x01, 0x00, 0x40, 0x9F, 0xF0, 0x06, 0x10, 0x20, 0x41, 0x02, 0x04, 0x08, + 0x21, 0x80, 0x81, 0x02, 0x08, 0x10, 0x20, 0x40, 0xC0, 0x01, 0x11, 0x12, + 0x22, 0x24, 0x44, 0x44, 0x88, 0x80, 0x0C, 0x08, 0x10, 0x20, 0x40, 0x82, + 0x04, 0x08, 0x0C, 0x20, 0x81, 0x02, 0x04, 0x08, 0x21, 0x80, 0x38, 0x28, + 0x88, 0x0E, 0x00 }; + +const GFXglyph FreeMonoOblique12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 14, 0, 1 }, // 0x20 ' ' + { 0, 4, 15, 14, 6, -14 }, // 0x21 '!' + { 8, 8, 7, 14, 5, -14 }, // 0x22 '"' + { 15, 11, 16, 14, 3, -14 }, // 0x23 '#' + { 37, 10, 18, 14, 4, -15 }, // 0x24 '$' + { 60, 11, 15, 14, 3, -14 }, // 0x25 '%' + { 81, 9, 12, 14, 3, -11 }, // 0x26 '&' + { 95, 3, 7, 14, 8, -14 }, // 0x27 ''' + { 98, 5, 18, 14, 8, -14 }, // 0x28 '(' + { 110, 5, 18, 14, 4, -14 }, // 0x29 ')' + { 122, 9, 9, 14, 5, -14 }, // 0x2A '*' + { 133, 11, 11, 14, 3, -11 }, // 0x2B '+' + { 149, 6, 7, 14, 3, -3 }, // 0x2C ',' + { 155, 11, 1, 14, 3, -6 }, // 0x2D '-' + { 157, 3, 3, 14, 6, -2 }, // 0x2E '.' + { 159, 13, 18, 14, 2, -15 }, // 0x2F '/' + { 189, 10, 15, 14, 4, -14 }, // 0x30 '0' + { 208, 9, 15, 14, 3, -14 }, // 0x31 '1' + { 225, 12, 15, 14, 2, -14 }, // 0x32 '2' + { 248, 11, 15, 14, 3, -14 }, // 0x33 '3' + { 269, 10, 15, 14, 3, -14 }, // 0x34 '4' + { 288, 11, 15, 14, 3, -14 }, // 0x35 '5' + { 309, 11, 15, 14, 4, -14 }, // 0x36 '6' + { 330, 10, 15, 14, 5, -14 }, // 0x37 '7' + { 349, 11, 15, 14, 3, -14 }, // 0x38 '8' + { 370, 11, 15, 14, 3, -14 }, // 0x39 '9' + { 391, 5, 10, 14, 5, -9 }, // 0x3A ':' + { 398, 7, 13, 14, 3, -9 }, // 0x3B ';' + { 410, 12, 11, 14, 3, -11 }, // 0x3C '<' + { 427, 13, 4, 14, 2, -8 }, // 0x3D '=' + { 434, 12, 11, 14, 2, -11 }, // 0x3E '>' + { 451, 8, 14, 14, 6, -13 }, // 0x3F '?' + { 465, 10, 16, 14, 3, -14 }, // 0x40 '@' + { 485, 14, 14, 14, 0, -13 }, // 0x41 'A' + { 510, 13, 14, 14, 1, -13 }, // 0x42 'B' + { 533, 12, 14, 14, 3, -13 }, // 0x43 'C' + { 554, 13, 14, 14, 1, -13 }, // 0x44 'D' + { 577, 14, 14, 14, 1, -13 }, // 0x45 'E' + { 602, 14, 14, 14, 1, -13 }, // 0x46 'F' + { 627, 12, 14, 14, 3, -13 }, // 0x47 'G' + { 648, 15, 14, 14, 1, -13 }, // 0x48 'H' + { 675, 11, 14, 14, 3, -13 }, // 0x49 'I' + { 695, 15, 14, 14, 2, -13 }, // 0x4A 'J' + { 722, 15, 14, 14, 1, -13 }, // 0x4B 'K' + { 749, 12, 14, 14, 2, -13 }, // 0x4C 'L' + { 770, 17, 14, 14, 0, -13 }, // 0x4D 'M' + { 800, 15, 14, 14, 1, -13 }, // 0x4E 'N' + { 827, 13, 14, 14, 2, -13 }, // 0x4F 'O' + { 850, 13, 14, 14, 1, -13 }, // 0x50 'P' + { 873, 13, 17, 14, 2, -13 }, // 0x51 'Q' + { 901, 13, 14, 14, 1, -13 }, // 0x52 'R' + { 924, 11, 14, 14, 3, -13 }, // 0x53 'S' + { 944, 12, 14, 14, 4, -13 }, // 0x54 'T' + { 965, 13, 14, 14, 3, -13 }, // 0x55 'U' + { 988, 14, 14, 14, 3, -13 }, // 0x56 'V' + { 1013, 14, 14, 14, 3, -13 }, // 0x57 'W' + { 1038, 15, 14, 14, 1, -13 }, // 0x58 'X' + { 1065, 12, 14, 14, 4, -13 }, // 0x59 'Y' + { 1086, 12, 14, 14, 2, -13 }, // 0x5A 'Z' + { 1107, 7, 18, 14, 6, -14 }, // 0x5B '[' + { 1123, 5, 18, 14, 6, -15 }, // 0x5C '\' + { 1135, 7, 18, 14, 3, -14 }, // 0x5D ']' + { 1151, 9, 6, 14, 5, -14 }, // 0x5E '^' + { 1158, 15, 1, 14, -1, 3 }, // 0x5F '_' + { 1160, 3, 4, 14, 6, -15 }, // 0x60 '`' + { 1162, 12, 10, 14, 2, -9 }, // 0x61 'a' + { 1177, 13, 15, 14, 1, -14 }, // 0x62 'b' + { 1202, 12, 10, 14, 3, -9 }, // 0x63 'c' + { 1217, 13, 15, 14, 2, -14 }, // 0x64 'd' + { 1242, 11, 10, 14, 3, -9 }, // 0x65 'e' + { 1256, 13, 15, 14, 3, -14 }, // 0x66 'f' + { 1281, 13, 14, 14, 3, -9 }, // 0x67 'g' + { 1304, 13, 15, 14, 1, -14 }, // 0x68 'h' + { 1329, 10, 15, 14, 2, -14 }, // 0x69 'i' + { 1348, 10, 19, 14, 2, -14 }, // 0x6A 'j' + { 1372, 12, 15, 14, 2, -14 }, // 0x6B 'k' + { 1395, 10, 15, 14, 2, -14 }, // 0x6C 'l' + { 1414, 14, 10, 14, 0, -9 }, // 0x6D 'm' + { 1432, 12, 10, 14, 1, -9 }, // 0x6E 'n' + { 1447, 11, 10, 14, 3, -9 }, // 0x6F 'o' + { 1461, 14, 14, 14, 0, -9 }, // 0x70 'p' + { 1486, 13, 14, 14, 3, -9 }, // 0x71 'q' + { 1509, 13, 10, 14, 2, -9 }, // 0x72 'r' + { 1526, 10, 10, 14, 3, -9 }, // 0x73 's' + { 1539, 9, 14, 14, 3, -13 }, // 0x74 't' + { 1555, 12, 10, 14, 2, -9 }, // 0x75 'u' + { 1570, 13, 10, 14, 3, -9 }, // 0x76 'v' + { 1587, 13, 10, 14, 3, -9 }, // 0x77 'w' + { 1604, 14, 10, 14, 1, -9 }, // 0x78 'x' + { 1622, 14, 14, 14, 1, -9 }, // 0x79 'y' + { 1647, 11, 10, 14, 3, -9 }, // 0x7A 'z' + { 1661, 7, 18, 14, 5, -14 }, // 0x7B '{' + { 1677, 4, 17, 14, 6, -13 }, // 0x7C '|' + { 1686, 7, 18, 14, 4, -14 }, // 0x7D '}' + { 1702, 11, 3, 14, 3, -7 } }; // 0x7E '~' + +const GFXfont FreeMonoOblique12pt7b PROGMEM = { + (uint8_t *)FreeMonoOblique12pt7bBitmaps, + (GFXglyph *)FreeMonoOblique12pt7bGlyphs, + 0x20, 0x7E, 24 }; + +// Approx. 2379 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique18pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique18pt7b.h new file mode 100644 index 0000000..1979e72 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique18pt7b.h @@ -0,0 +1,398 @@ +const uint8_t FreeMonoOblique18pt7bBitmaps[] PROGMEM = { + 0x00, 0x1C, 0x38, 0x70, 0xC1, 0x83, 0x06, 0x18, 0x30, 0x60, 0xC1, 0x02, + 0x04, 0x00, 0x00, 0x01, 0xC7, 0x8F, 0x1C, 0x00, 0x78, 0x7B, 0xC3, 0xFC, + 0x3D, 0xE1, 0xEF, 0x0F, 0x70, 0x73, 0x83, 0x98, 0x18, 0xC0, 0xC6, 0x06, + 0x00, 0x00, 0x8C, 0x01, 0x18, 0x06, 0x20, 0x08, 0x40, 0x11, 0x80, 0x62, + 0x00, 0xC4, 0x01, 0x18, 0x02, 0x30, 0x7F, 0xFC, 0x10, 0x80, 0x23, 0x00, + 0xC4, 0x01, 0x88, 0x3F, 0xFF, 0x04, 0x60, 0x18, 0x80, 0x21, 0x00, 0x46, + 0x01, 0x88, 0x03, 0x10, 0x04, 0x60, 0x08, 0xC0, 0x31, 0x00, 0x00, 0x30, + 0x00, 0x20, 0x00, 0x20, 0x00, 0xF9, 0x03, 0x0F, 0x06, 0x03, 0x04, 0x03, + 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x03, 0xC0, 0x00, 0x78, + 0x00, 0x0C, 0x00, 0x04, 0x00, 0x04, 0x40, 0x04, 0x40, 0x08, 0x40, 0x18, + 0xF0, 0x60, 0x9F, 0x80, 0x02, 0x00, 0x06, 0x00, 0x04, 0x00, 0x04, 0x00, + 0x04, 0x00, 0x03, 0xC0, 0x0C, 0x60, 0x08, 0x20, 0x10, 0x20, 0x10, 0x20, + 0x10, 0x40, 0x18, 0x80, 0x0F, 0x00, 0x00, 0x0F, 0x00, 0x78, 0x07, 0xC0, + 0x3C, 0x00, 0xE0, 0x00, 0x01, 0xE0, 0x02, 0x18, 0x04, 0x08, 0x08, 0x08, + 0x08, 0x08, 0x08, 0x10, 0x0C, 0x20, 0x07, 0xC0, 0x01, 0xF0, 0x11, 0x81, + 0x00, 0x10, 0x00, 0x80, 0x04, 0x00, 0x20, 0x01, 0x80, 0x04, 0x00, 0xF0, + 0x09, 0x86, 0x84, 0x48, 0x32, 0x40, 0xA2, 0x07, 0x10, 0x30, 0x43, 0x81, + 0xE7, 0x80, 0x7B, 0xFD, 0xEF, 0x73, 0x98, 0xC6, 0x00, 0x01, 0x02, 0x06, + 0x0C, 0x0C, 0x18, 0x10, 0x30, 0x30, 0x60, 0x60, 0x60, 0xC0, 0xC0, 0xC0, + 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0x40, 0x60, 0x60, 0x20, 0x04, 0x06, + 0x06, 0x02, 0x02, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x06, + 0x06, 0x06, 0x0C, 0x0C, 0x0C, 0x18, 0x10, 0x30, 0x60, 0x40, 0xC0, 0x01, + 0x00, 0x04, 0x00, 0x10, 0x00, 0xC6, 0xE3, 0xF8, 0x7E, 0x00, 0x70, 0x03, + 0x40, 0x19, 0x80, 0xC2, 0x06, 0x0C, 0x00, 0x00, 0xC0, 0x01, 0x00, 0x02, + 0x00, 0x04, 0x00, 0x08, 0x00, 0x20, 0x00, 0x40, 0x00, 0x80, 0xFF, 0xFE, + 0x02, 0x00, 0x08, 0x00, 0x10, 0x00, 0x20, 0x00, 0x40, 0x00, 0x80, 0x02, + 0x00, 0x04, 0x00, 0x0F, 0x87, 0x87, 0x83, 0x83, 0xC1, 0xC1, 0xC0, 0xC0, + 0xE0, 0x60, 0x00, 0xFF, 0xFF, 0x77, 0xFF, 0xF7, 0x00, 0x00, 0x00, 0x60, + 0x00, 0x08, 0x00, 0x02, 0x00, 0x00, 0xC0, 0x00, 0x30, 0x00, 0x04, 0x00, + 0x01, 0x80, 0x00, 0x60, 0x00, 0x08, 0x00, 0x03, 0x00, 0x00, 0xC0, 0x00, + 0x10, 0x00, 0x06, 0x00, 0x01, 0x80, 0x00, 0x20, 0x00, 0x0C, 0x00, 0x03, + 0x00, 0x00, 0x40, 0x00, 0x18, 0x00, 0x06, 0x00, 0x00, 0x80, 0x00, 0x20, + 0x00, 0x0C, 0x00, 0x03, 0x00, 0x00, 0x40, 0x00, 0x08, 0x00, 0x00, 0x01, + 0xF0, 0x18, 0x60, 0x80, 0x86, 0x01, 0x10, 0x04, 0x80, 0x12, 0x00, 0x50, + 0x01, 0x40, 0x0D, 0x00, 0x24, 0x00, 0xA0, 0x02, 0x80, 0x1A, 0x00, 0x48, + 0x01, 0x20, 0x0C, 0x80, 0x22, 0x01, 0x84, 0x0C, 0x18, 0x60, 0x3E, 0x00, + 0x00, 0x60, 0x07, 0x00, 0x68, 0x06, 0x40, 0xE4, 0x04, 0x20, 0x01, 0x00, + 0x08, 0x00, 0x40, 0x04, 0x00, 0x20, 0x01, 0x00, 0x08, 0x00, 0x80, 0x04, + 0x00, 0x20, 0x01, 0x00, 0x08, 0x00, 0x80, 0x04, 0x0F, 0xFF, 0x80, 0x00, + 0x3C, 0x00, 0x61, 0x80, 0x40, 0x40, 0x40, 0x10, 0x60, 0x08, 0x00, 0x04, + 0x00, 0x02, 0x00, 0x02, 0x00, 0x03, 0x00, 0x03, 0x00, 0x07, 0x00, 0x07, + 0x00, 0x06, 0x00, 0x06, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0C, 0x00, 0x0C, + 0x00, 0x1C, 0x01, 0x1C, 0x00, 0x8F, 0xFF, 0xC0, 0x00, 0xFC, 0x03, 0x06, + 0x06, 0x03, 0x00, 0x01, 0x00, 0x01, 0x00, 0x01, 0x00, 0x02, 0x00, 0x02, + 0x00, 0x0C, 0x00, 0xF0, 0x00, 0x18, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, + 0x00, 0x02, 0x00, 0x02, 0x00, 0x04, 0x00, 0x04, 0x40, 0x18, 0x70, 0x30, + 0x0F, 0xC0, 0x00, 0x1C, 0x00, 0xD0, 0x06, 0x80, 0x32, 0x00, 0x88, 0x04, + 0x20, 0x30, 0x81, 0x84, 0x04, 0x10, 0x20, 0x41, 0x81, 0x0C, 0x08, 0x60, + 0x21, 0x00, 0x8F, 0xFF, 0x80, 0x18, 0x00, 0x40, 0x01, 0x00, 0x04, 0x00, + 0x10, 0x07, 0xE0, 0x03, 0xFF, 0x03, 0x00, 0x01, 0x80, 0x00, 0x80, 0x00, + 0x40, 0x00, 0x20, 0x00, 0x30, 0x00, 0x1B, 0xE0, 0x0E, 0x0C, 0x00, 0x02, + 0x00, 0x00, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0x10, 0x00, 0x08, 0x00, + 0x08, 0x00, 0x04, 0x60, 0x04, 0x18, 0x04, 0x06, 0x0C, 0x00, 0xF8, 0x00, + 0x00, 0x3F, 0x00, 0xC0, 0x03, 0x00, 0x04, 0x00, 0x08, 0x00, 0x10, 0x00, + 0x30, 0x00, 0x20, 0x00, 0x40, 0x00, 0x43, 0xE0, 0x4C, 0x30, 0xB0, 0x18, + 0xE0, 0x08, 0xC0, 0x08, 0x80, 0x08, 0x80, 0x08, 0x80, 0x10, 0xC0, 0x10, + 0x40, 0x20, 0x20, 0xC0, 0x1F, 0x00, 0xFF, 0xFC, 0x00, 0xE0, 0x04, 0x00, + 0x60, 0x02, 0x00, 0x30, 0x01, 0x00, 0x18, 0x00, 0x80, 0x0C, 0x00, 0x40, + 0x06, 0x00, 0x20, 0x03, 0x00, 0x10, 0x01, 0x80, 0x08, 0x00, 0xC0, 0x04, + 0x00, 0x60, 0x02, 0x00, 0x00, 0x00, 0xF0, 0x06, 0x18, 0x10, 0x18, 0x40, + 0x11, 0x00, 0x22, 0x00, 0x44, 0x00, 0x88, 0x02, 0x18, 0x08, 0x18, 0x60, + 0x1F, 0x80, 0xC1, 0x82, 0x01, 0x88, 0x01, 0x20, 0x02, 0x40, 0x04, 0x80, + 0x09, 0x00, 0x23, 0x00, 0x83, 0x06, 0x01, 0xF0, 0x00, 0x00, 0xF0, 0x06, + 0x18, 0x10, 0x10, 0x40, 0x30, 0x80, 0x22, 0x00, 0x44, 0x00, 0x88, 0x03, + 0x10, 0x0E, 0x30, 0x34, 0x30, 0xD0, 0x3E, 0x20, 0x00, 0x40, 0x01, 0x00, + 0x02, 0x00, 0x08, 0x00, 0x20, 0x00, 0xC0, 0x02, 0x00, 0x18, 0x0F, 0xC0, + 0x00, 0x1C, 0x7C, 0xF9, 0xF1, 0xC0, 0x00, 0x00, 0x00, 0x01, 0xC7, 0xCF, + 0x9F, 0x1C, 0x00, 0x01, 0xC0, 0x7C, 0x0F, 0x81, 0xF0, 0x1C, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x3E, 0x07, 0x81, 0xE0, 0x3C, 0x0F, 0x01, + 0xC0, 0x70, 0x0E, 0x03, 0x80, 0x60, 0x00, 0x00, 0x01, 0x80, 0x03, 0x80, + 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x00, + 0xE0, 0x00, 0x1C, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x07, + 0x00, 0x00, 0xE0, 0x00, 0x38, 0x7F, 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x18, 0x00, 0x03, 0x80, + 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x00, 0xE0, + 0x00, 0x0E, 0x00, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0x03, + 0x80, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0x00, 0x1F, 0xCE, 0x06, 0x80, + 0x38, 0x01, 0x80, 0x10, 0x01, 0x00, 0x20, 0x04, 0x01, 0x80, 0xF0, 0x18, + 0x01, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78, 0x0F, 0x80, 0xF8, + 0x07, 0x00, 0x01, 0xF0, 0x0C, 0x30, 0x30, 0x30, 0x40, 0x21, 0x00, 0x44, + 0x00, 0x88, 0x01, 0x10, 0x1E, 0x40, 0xC4, 0x86, 0x11, 0x08, 0x22, 0x20, + 0x48, 0x40, 0x90, 0x82, 0x21, 0x84, 0x40, 0xFC, 0x80, 0x01, 0x00, 0x02, + 0x00, 0x04, 0x00, 0x04, 0x00, 0x0C, 0x18, 0x07, 0xC0, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x68, 0x00, 0x06, 0x40, 0x00, 0x32, 0x00, 0x03, 0x10, 0x00, + 0x10, 0x80, 0x01, 0x84, 0x00, 0x18, 0x10, 0x00, 0xC0, 0x80, 0x0C, 0x04, + 0x00, 0x60, 0x20, 0x06, 0x01, 0x00, 0x3F, 0xFC, 0x02, 0x00, 0x20, 0x10, + 0x01, 0x01, 0x00, 0x08, 0x08, 0x00, 0x40, 0x80, 0x02, 0x0C, 0x00, 0x09, + 0xFC, 0x07, 0xF0, 0x0F, 0xFF, 0x00, 0x40, 0x60, 0x20, 0x0C, 0x08, 0x01, + 0x02, 0x00, 0x40, 0x80, 0x10, 0x40, 0x08, 0x10, 0x06, 0x04, 0x03, 0x01, + 0xFF, 0x80, 0x40, 0x38, 0x20, 0x02, 0x08, 0x00, 0x42, 0x00, 0x10, 0x80, + 0x04, 0x40, 0x01, 0x10, 0x00, 0x84, 0x00, 0x41, 0x00, 0x23, 0xFF, 0xF0, + 0x00, 0xFC, 0x40, 0xC1, 0xF0, 0xC0, 0x1C, 0x60, 0x06, 0x10, 0x00, 0x88, + 0x00, 0x24, 0x00, 0x01, 0x00, 0x00, 0x40, 0x00, 0x30, 0x00, 0x08, 0x00, + 0x02, 0x00, 0x00, 0x80, 0x00, 0x20, 0x00, 0x08, 0x00, 0x03, 0x00, 0x00, + 0x40, 0x06, 0x08, 0x03, 0x01, 0x83, 0x80, 0x3F, 0x00, 0x0F, 0xFE, 0x00, + 0x80, 0xC0, 0x20, 0x18, 0x10, 0x02, 0x04, 0x00, 0x41, 0x00, 0x10, 0x40, + 0x04, 0x20, 0x01, 0x08, 0x00, 0x42, 0x00, 0x10, 0x80, 0x08, 0x20, 0x02, + 0x10, 0x00, 0x84, 0x00, 0x21, 0x00, 0x10, 0x40, 0x08, 0x20, 0x06, 0x08, + 0x03, 0x02, 0x01, 0x83, 0xFF, 0x80, 0x0F, 0xFF, 0xE0, 0x10, 0x02, 0x02, + 0x00, 0x60, 0x20, 0x06, 0x02, 0x00, 0x60, 0x20, 0x00, 0x04, 0x00, 0x00, + 0x40, 0x80, 0x04, 0x10, 0x00, 0x7F, 0x00, 0x04, 0x10, 0x00, 0x81, 0x00, + 0x08, 0x00, 0x00, 0x80, 0x00, 0x08, 0x00, 0x81, 0x00, 0x08, 0x10, 0x00, + 0x81, 0x00, 0x18, 0x10, 0x01, 0x8F, 0xFF, 0xF0, 0x0F, 0xFF, 0xF0, 0x10, + 0x03, 0x02, 0x00, 0x30, 0x20, 0x03, 0x02, 0x00, 0x20, 0x20, 0x00, 0x04, + 0x00, 0x00, 0x40, 0x80, 0x04, 0x10, 0x00, 0x7F, 0x00, 0x04, 0x10, 0x00, + 0x81, 0x00, 0x08, 0x00, 0x00, 0x80, 0x00, 0x08, 0x00, 0x01, 0x00, 0x00, + 0x10, 0x00, 0x01, 0x00, 0x00, 0x10, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0xFE, + 0x40, 0xC0, 0xF0, 0x40, 0x1C, 0x20, 0x03, 0x10, 0x00, 0x88, 0x00, 0x02, + 0x00, 0x01, 0x00, 0x00, 0x40, 0x00, 0x10, 0x00, 0x08, 0x00, 0x02, 0x01, + 0xFE, 0x80, 0x02, 0x20, 0x00, 0x88, 0x00, 0x22, 0x00, 0x08, 0x40, 0x04, + 0x18, 0x01, 0x03, 0x81, 0xC0, 0x3F, 0x80, 0x07, 0xE1, 0xF8, 0x08, 0x02, + 0x00, 0x80, 0x10, 0x04, 0x00, 0x80, 0x20, 0x04, 0x01, 0x00, 0x20, 0x18, + 0x02, 0x00, 0x80, 0x10, 0x04, 0x00, 0x80, 0x3F, 0xFC, 0x01, 0x00, 0x60, + 0x10, 0x02, 0x00, 0x80, 0x10, 0x04, 0x00, 0x80, 0x20, 0x04, 0x02, 0x00, + 0x40, 0x10, 0x02, 0x00, 0x80, 0x10, 0x04, 0x00, 0x81, 0xF8, 0x3F, 0x00, + 0x0F, 0xFF, 0x80, 0x10, 0x00, 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x02, + 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, + 0x10, 0x00, 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x02, 0x00, 0x01, 0x00, + 0x01, 0x00, 0x00, 0x80, 0x1F, 0xFF, 0x00, 0x00, 0xFF, 0xF0, 0x00, 0x20, + 0x00, 0x02, 0x00, 0x00, 0x20, 0x00, 0x02, 0x00, 0x00, 0x20, 0x00, 0x04, + 0x00, 0x00, 0x40, 0x00, 0x04, 0x00, 0x00, 0x40, 0x00, 0x0C, 0x04, 0x00, + 0x80, 0x40, 0x08, 0x08, 0x00, 0x80, 0x80, 0x08, 0x08, 0x01, 0x00, 0x80, + 0x10, 0x0C, 0x02, 0x00, 0x60, 0xC0, 0x01, 0xF0, 0x00, 0x0F, 0xE1, 0xF8, + 0x08, 0x03, 0x00, 0x80, 0x60, 0x04, 0x06, 0x00, 0x20, 0x60, 0x01, 0x06, + 0x00, 0x10, 0xC0, 0x00, 0x8C, 0x00, 0x04, 0xC0, 0x00, 0x2F, 0x80, 0x01, + 0x8E, 0x00, 0x18, 0x30, 0x00, 0x80, 0xC0, 0x04, 0x06, 0x00, 0x20, 0x10, + 0x02, 0x00, 0xC0, 0x10, 0x06, 0x00, 0x80, 0x30, 0x04, 0x00, 0x81, 0xFC, + 0x07, 0x80, 0x07, 0xFC, 0x00, 0x10, 0x00, 0x08, 0x00, 0x02, 0x00, 0x00, + 0x80, 0x00, 0x20, 0x00, 0x08, 0x00, 0x04, 0x00, 0x01, 0x00, 0x00, 0x40, + 0x00, 0x10, 0x00, 0x08, 0x00, 0x02, 0x00, 0x00, 0x80, 0x10, 0x20, 0x04, + 0x08, 0x01, 0x04, 0x00, 0x81, 0x00, 0x20, 0x40, 0x0B, 0xFF, 0xFE, 0x0F, + 0x00, 0x1E, 0x03, 0x00, 0x38, 0x05, 0x00, 0x68, 0x04, 0x80, 0x68, 0x04, + 0x80, 0xC8, 0x04, 0x80, 0x90, 0x04, 0x81, 0x90, 0x08, 0x43, 0x10, 0x08, + 0x42, 0x10, 0x08, 0x46, 0x10, 0x08, 0x4C, 0x20, 0x10, 0x2C, 0x20, 0x10, + 0x38, 0x20, 0x10, 0x30, 0x20, 0x10, 0x00, 0x40, 0x10, 0x00, 0x40, 0x20, + 0x00, 0x40, 0x20, 0x00, 0x40, 0x20, 0x00, 0x40, 0xFC, 0x07, 0xE0, 0x1F, + 0x01, 0xFC, 0x0C, 0x00, 0x80, 0x78, 0x02, 0x01, 0xE0, 0x18, 0x04, 0x80, + 0x60, 0x13, 0x01, 0x00, 0x4C, 0x04, 0x03, 0x18, 0x10, 0x0C, 0x60, 0xC0, + 0x20, 0x83, 0x00, 0x83, 0x08, 0x06, 0x0C, 0x20, 0x18, 0x18, 0x80, 0x40, + 0x66, 0x01, 0x00, 0x98, 0x04, 0x03, 0x40, 0x30, 0x0D, 0x00, 0xC0, 0x14, + 0x02, 0x00, 0x70, 0x3F, 0x80, 0xC0, 0x00, 0xF8, 0x01, 0x83, 0x01, 0x00, + 0xC1, 0x00, 0x21, 0x00, 0x19, 0x00, 0x04, 0x80, 0x02, 0x80, 0x01, 0x40, + 0x00, 0xC0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x28, 0x00, 0x14, 0x00, 0x12, + 0x00, 0x09, 0x80, 0x08, 0x40, 0x08, 0x30, 0x08, 0x0C, 0x18, 0x01, 0xF0, + 0x00, 0x0F, 0xFE, 0x00, 0x40, 0x60, 0x20, 0x0C, 0x08, 0x01, 0x02, 0x00, + 0x40, 0x80, 0x10, 0x40, 0x04, 0x10, 0x02, 0x04, 0x01, 0x01, 0x01, 0x80, + 0x7F, 0x80, 0x20, 0x00, 0x08, 0x00, 0x02, 0x00, 0x00, 0x80, 0x00, 0x40, + 0x00, 0x10, 0x00, 0x04, 0x00, 0x01, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xF8, + 0x01, 0x83, 0x01, 0x00, 0xC1, 0x00, 0x21, 0x00, 0x19, 0x00, 0x05, 0x00, + 0x02, 0x80, 0x01, 0x40, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x28, + 0x00, 0x14, 0x00, 0x12, 0x00, 0x09, 0x80, 0x08, 0x40, 0x08, 0x30, 0x08, + 0x0C, 0x18, 0x03, 0xF0, 0x00, 0xC0, 0x01, 0xC0, 0x01, 0xFE, 0x18, 0xC0, + 0xF0, 0x0F, 0xFE, 0x00, 0x40, 0x60, 0x20, 0x0C, 0x08, 0x01, 0x02, 0x00, + 0x40, 0x80, 0x10, 0x40, 0x04, 0x10, 0x02, 0x04, 0x01, 0x01, 0x01, 0x80, + 0x7F, 0x80, 0x20, 0x60, 0x08, 0x0C, 0x02, 0x03, 0x80, 0x80, 0x60, 0x40, + 0x18, 0x10, 0x03, 0x04, 0x00, 0xC1, 0x00, 0x1B, 0xF8, 0x07, 0x00, 0x7E, + 0x40, 0x60, 0xF0, 0x20, 0x1C, 0x10, 0x02, 0x08, 0x00, 0x82, 0x00, 0x00, + 0x80, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xC0, 0x00, + 0x18, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x11, 0x00, 0x04, 0x40, 0x02, + 0x38, 0x01, 0x0B, 0x81, 0x82, 0x3F, 0x80, 0x3F, 0xFF, 0xA0, 0x20, 0x50, + 0x10, 0x28, 0x08, 0x24, 0x08, 0x10, 0x04, 0x00, 0x02, 0x00, 0x01, 0x00, + 0x01, 0x00, 0x00, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, + 0x00, 0x08, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x1F, + 0xFC, 0x00, 0x7E, 0x0F, 0xC4, 0x00, 0x42, 0x00, 0x10, 0x80, 0x08, 0x20, + 0x02, 0x08, 0x00, 0x82, 0x00, 0x21, 0x00, 0x08, 0x40, 0x04, 0x10, 0x01, + 0x04, 0x00, 0x41, 0x00, 0x10, 0x80, 0x0C, 0x20, 0x02, 0x08, 0x00, 0x82, + 0x00, 0x60, 0x80, 0x10, 0x10, 0x08, 0x06, 0x0C, 0x00, 0x7C, 0x00, 0xFE, + 0x03, 0xF9, 0x80, 0x02, 0x0C, 0x00, 0x30, 0x20, 0x01, 0x01, 0x00, 0x10, + 0x08, 0x01, 0x80, 0x60, 0x08, 0x03, 0x00, 0xC0, 0x18, 0x04, 0x00, 0x40, + 0x60, 0x02, 0x06, 0x00, 0x10, 0x20, 0x00, 0xC3, 0x00, 0x06, 0x10, 0x00, + 0x31, 0x80, 0x00, 0x88, 0x00, 0x04, 0x80, 0x00, 0x2C, 0x00, 0x01, 0xC0, + 0x00, 0x0E, 0x00, 0x00, 0x7F, 0x07, 0xF2, 0x00, 0x04, 0x20, 0x00, 0xC2, + 0x00, 0x08, 0x20, 0xC0, 0x82, 0x0C, 0x18, 0x21, 0xA1, 0x02, 0x1A, 0x10, + 0x23, 0x23, 0x04, 0x32, 0x30, 0x46, 0x22, 0x04, 0x62, 0x60, 0x4C, 0x26, + 0x04, 0xC2, 0x40, 0x58, 0x24, 0x05, 0x82, 0xC0, 0x70, 0x28, 0x07, 0x02, + 0x80, 0xE0, 0x38, 0x0E, 0x03, 0x00, 0x0F, 0xC1, 0xF8, 0x30, 0x03, 0x00, + 0xC0, 0x30, 0x06, 0x03, 0x00, 0x18, 0x10, 0x00, 0xC1, 0x00, 0x03, 0x18, + 0x00, 0x09, 0x80, 0x00, 0x78, 0x00, 0x01, 0x80, 0x00, 0x1C, 0x00, 0x01, + 0xA0, 0x00, 0x19, 0x80, 0x01, 0x84, 0x00, 0x18, 0x30, 0x01, 0x80, 0xC0, + 0x08, 0x06, 0x00, 0x80, 0x18, 0x08, 0x00, 0xC1, 0xF8, 0x3F, 0x80, 0x7E, + 0x0F, 0xC4, 0x00, 0xC1, 0x80, 0x60, 0x20, 0x30, 0x0C, 0x08, 0x03, 0x04, + 0x00, 0x43, 0x00, 0x19, 0x80, 0x02, 0xC0, 0x00, 0xE0, 0x00, 0x10, 0x00, + 0x04, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, 0x20, 0x00, 0x08, 0x00, 0x02, + 0x00, 0x01, 0x00, 0x00, 0x40, 0x03, 0xFF, 0x80, 0x0F, 0xFF, 0x86, 0x00, + 0x82, 0x00, 0x81, 0x00, 0xC1, 0x80, 0xC0, 0xC0, 0xC0, 0x00, 0xC0, 0x00, + 0xC0, 0x00, 0x40, 0x00, 0x40, 0x00, 0x60, 0x00, 0x60, 0x00, 0x60, 0x00, + 0x60, 0x10, 0x60, 0x18, 0x20, 0x08, 0x20, 0x04, 0x20, 0x02, 0x30, 0x03, + 0x1F, 0xFF, 0x80, 0x07, 0xE0, 0x80, 0x10, 0x02, 0x00, 0xC0, 0x18, 0x02, + 0x00, 0x40, 0x18, 0x03, 0x00, 0x40, 0x08, 0x01, 0x00, 0x60, 0x0C, 0x01, + 0x00, 0x20, 0x04, 0x01, 0x80, 0x30, 0x04, 0x00, 0x80, 0x10, 0x06, 0x00, + 0xFC, 0x00, 0x80, 0x80, 0x80, 0x40, 0x40, 0x40, 0x20, 0x20, 0x20, 0x20, + 0x10, 0x10, 0x10, 0x10, 0x08, 0x08, 0x08, 0x08, 0x04, 0x04, 0x04, 0x04, + 0x02, 0x02, 0x02, 0x02, 0x00, 0x07, 0xE0, 0x0C, 0x01, 0x00, 0x20, 0x04, + 0x01, 0x80, 0x30, 0x04, 0x00, 0x80, 0x30, 0x06, 0x00, 0x80, 0x10, 0x02, + 0x00, 0xC0, 0x18, 0x02, 0x00, 0x40, 0x18, 0x03, 0x00, 0x40, 0x08, 0x03, + 0x00, 0x60, 0xF8, 0x00, 0x01, 0x00, 0x1C, 0x01, 0xB0, 0x19, 0x81, 0x86, + 0x18, 0x11, 0x80, 0xD8, 0x03, 0x80, 0x18, 0xFF, 0xFF, 0xF8, 0xC7, 0x1C, + 0x71, 0x80, 0x03, 0xF8, 0x0C, 0x0C, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, + 0x00, 0x02, 0x07, 0xFC, 0x18, 0x0C, 0x20, 0x04, 0x40, 0x04, 0x80, 0x04, + 0x80, 0x08, 0x80, 0x38, 0xC0, 0xE8, 0x3F, 0x0F, 0x0F, 0x00, 0x00, 0x20, + 0x00, 0x04, 0x00, 0x01, 0x80, 0x00, 0x30, 0x00, 0x04, 0x00, 0x00, 0x87, + 0xC0, 0x13, 0x0C, 0x06, 0x80, 0x40, 0xE0, 0x0C, 0x18, 0x00, 0x82, 0x00, + 0x10, 0xC0, 0x02, 0x10, 0x00, 0x42, 0x00, 0x08, 0x40, 0x02, 0x08, 0x00, + 0x43, 0x80, 0x10, 0x70, 0x04, 0x09, 0x83, 0x0F, 0x1F, 0x80, 0x01, 0xFC, + 0x83, 0x03, 0xC6, 0x00, 0xE4, 0x00, 0x22, 0x00, 0x12, 0x00, 0x01, 0x00, + 0x01, 0x00, 0x00, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0x18, 0x00, 0x64, + 0x00, 0x61, 0x81, 0xC0, 0x7F, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x30, 0x00, + 0x0C, 0x00, 0x02, 0x00, 0x00, 0x80, 0x00, 0x60, 0x3F, 0x18, 0x10, 0x64, + 0x18, 0x0D, 0x08, 0x01, 0xC2, 0x00, 0x71, 0x00, 0x0C, 0x80, 0x02, 0x20, + 0x00, 0x88, 0x00, 0x62, 0x00, 0x18, 0x80, 0x0E, 0x20, 0x03, 0x04, 0x03, + 0x40, 0xC1, 0xB0, 0x1F, 0x8F, 0x00, 0x01, 0xF0, 0x0E, 0x0C, 0x18, 0x06, + 0x30, 0x02, 0x60, 0x01, 0x40, 0x01, 0xC0, 0x01, 0xFF, 0xFF, 0x80, 0x00, + 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x60, 0x06, 0x30, 0x1C, 0x0F, 0xE0, + 0x00, 0x1F, 0xE0, 0x0C, 0x00, 0x03, 0x00, 0x00, 0x40, 0x00, 0x08, 0x00, + 0x02, 0x00, 0x07, 0xFF, 0xC0, 0x08, 0x00, 0x01, 0x00, 0x00, 0x20, 0x00, + 0x08, 0x00, 0x01, 0x00, 0x00, 0x20, 0x00, 0x04, 0x00, 0x00, 0x80, 0x00, + 0x20, 0x00, 0x04, 0x00, 0x00, 0x80, 0x00, 0x10, 0x00, 0x04, 0x00, 0x0F, + 0xFF, 0x00, 0x03, 0xE3, 0xE1, 0x83, 0x60, 0x40, 0x38, 0x10, 0x03, 0x04, + 0x00, 0x60, 0x80, 0x0C, 0x20, 0x01, 0x84, 0x00, 0x20, 0x80, 0x04, 0x10, + 0x01, 0x82, 0x00, 0x30, 0x60, 0x0C, 0x04, 0x02, 0x80, 0x61, 0x90, 0x07, + 0xC6, 0x00, 0x00, 0xC0, 0x00, 0x10, 0x00, 0x02, 0x00, 0x00, 0x80, 0x00, + 0x30, 0x00, 0x0C, 0x00, 0xFE, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x40, 0x00, + 0x10, 0x00, 0x08, 0x00, 0x02, 0x00, 0x00, 0x80, 0x00, 0x23, 0xE0, 0x0B, + 0x0C, 0x05, 0x00, 0x81, 0x80, 0x20, 0x40, 0x08, 0x10, 0x02, 0x08, 0x00, + 0x82, 0x00, 0x60, 0x80, 0x18, 0x20, 0x06, 0x10, 0x01, 0x84, 0x00, 0x61, + 0x00, 0x30, 0x40, 0x0C, 0xFC, 0x1F, 0xC0, 0x00, 0x30, 0x00, 0x60, 0x00, + 0xC0, 0x01, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x20, + 0x00, 0x40, 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x08, 0x00, 0x10, 0x00, + 0x40, 0x00, 0x80, 0x01, 0x00, 0x02, 0x00, 0x08, 0x00, 0x10, 0x1F, 0xFF, + 0x80, 0x00, 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x07, 0xFE, 0x00, 0x04, 0x00, 0x08, 0x00, 0x10, 0x00, 0x20, + 0x00, 0x80, 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x08, 0x00, 0x20, 0x00, + 0x40, 0x00, 0x80, 0x01, 0x00, 0x06, 0x00, 0x08, 0x00, 0x10, 0x00, 0x20, + 0x00, 0x80, 0x03, 0x00, 0x0C, 0x0F, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x60, + 0x00, 0x10, 0x00, 0x04, 0x00, 0x01, 0x00, 0x00, 0xC0, 0x00, 0x30, 0xFC, + 0x08, 0x18, 0x02, 0x0C, 0x00, 0x8C, 0x00, 0x66, 0x00, 0x1B, 0x00, 0x05, + 0x80, 0x01, 0xB0, 0x00, 0x46, 0x00, 0x31, 0xC0, 0x0C, 0x30, 0x02, 0x06, + 0x00, 0x80, 0xC0, 0x60, 0x30, 0xF8, 0x1F, 0x80, 0x01, 0xF8, 0x00, 0x20, + 0x00, 0x40, 0x00, 0x80, 0x01, 0x00, 0x04, 0x00, 0x08, 0x00, 0x10, 0x00, + 0x20, 0x00, 0x80, 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x08, 0x00, 0x20, + 0x00, 0x40, 0x00, 0x80, 0x01, 0x00, 0x04, 0x00, 0x08, 0x0F, 0xFF, 0xC0, + 0x1C, 0xF1, 0xE0, 0xF1, 0xE3, 0x0E, 0x1C, 0x10, 0xC1, 0x81, 0x08, 0x10, + 0x30, 0x81, 0x03, 0x18, 0x10, 0x21, 0x83, 0x02, 0x10, 0x30, 0x21, 0x02, + 0x06, 0x10, 0x20, 0x63, 0x02, 0x04, 0x30, 0x60, 0x42, 0x06, 0x04, 0xF8, + 0x70, 0xF0, 0x0E, 0x3E, 0x01, 0x60, 0x81, 0xC0, 0x20, 0xC0, 0x10, 0x40, + 0x08, 0x20, 0x04, 0x30, 0x02, 0x10, 0x02, 0x08, 0x01, 0x04, 0x00, 0x82, + 0x00, 0x42, 0x00, 0x21, 0x00, 0x20, 0x80, 0x13, 0xF0, 0x3E, 0x01, 0xF0, + 0x06, 0x0C, 0x18, 0x06, 0x20, 0x03, 0x60, 0x01, 0x40, 0x01, 0x80, 0x01, + 0x80, 0x01, 0x80, 0x01, 0x80, 0x02, 0x80, 0x06, 0xC0, 0x04, 0x40, 0x18, + 0x30, 0x60, 0x1F, 0x80, 0x0F, 0x1F, 0x80, 0x16, 0x0C, 0x01, 0xC0, 0x20, + 0x30, 0x03, 0x03, 0x00, 0x10, 0x20, 0x01, 0x02, 0x00, 0x10, 0x40, 0x01, + 0x04, 0x00, 0x10, 0x40, 0x02, 0x06, 0x00, 0x60, 0x60, 0x04, 0x0B, 0x00, + 0x80, 0x98, 0x30, 0x08, 0xFC, 0x00, 0x80, 0x00, 0x08, 0x00, 0x01, 0x00, + 0x00, 0x10, 0x00, 0x01, 0x00, 0x00, 0x10, 0x00, 0x0F, 0xF0, 0x00, 0x03, + 0xF1, 0xE1, 0x83, 0x20, 0x40, 0x34, 0x10, 0x03, 0x84, 0x00, 0x30, 0x80, + 0x04, 0x20, 0x00, 0x84, 0x00, 0x10, 0x80, 0x06, 0x10, 0x00, 0xC2, 0x00, + 0x30, 0x60, 0x0E, 0x04, 0x03, 0x40, 0x60, 0xC8, 0x07, 0xE2, 0x00, 0x00, + 0x40, 0x00, 0x08, 0x00, 0x01, 0x00, 0x00, 0x20, 0x00, 0x08, 0x00, 0x01, + 0x00, 0x03, 0xFC, 0x00, 0x0F, 0x87, 0xC0, 0x23, 0x08, 0x04, 0xC0, 0x00, + 0xE0, 0x00, 0x18, 0x00, 0x02, 0x00, 0x00, 0x80, 0x00, 0x10, 0x00, 0x02, + 0x00, 0x00, 0x40, 0x00, 0x10, 0x00, 0x02, 0x00, 0x00, 0x40, 0x00, 0x08, + 0x00, 0x3F, 0xFE, 0x00, 0x01, 0xFA, 0x0C, 0x1C, 0x20, 0x08, 0x80, 0x11, + 0x00, 0x03, 0x00, 0x03, 0xF8, 0x00, 0x7C, 0x00, 0x0C, 0x00, 0x09, 0x00, + 0x16, 0x00, 0x2C, 0x00, 0x9E, 0x06, 0x27, 0xF0, 0x00, 0x08, 0x00, 0x40, + 0x02, 0x00, 0x10, 0x00, 0x80, 0x7F, 0xFC, 0x40, 0x02, 0x00, 0x10, 0x00, + 0x80, 0x08, 0x00, 0x40, 0x02, 0x00, 0x10, 0x01, 0x00, 0x08, 0x00, 0x40, + 0x02, 0x00, 0xD8, 0x1C, 0x3F, 0x00, 0xF0, 0x1E, 0x20, 0x04, 0x80, 0x09, + 0x00, 0x12, 0x00, 0x24, 0x00, 0xC8, 0x01, 0x20, 0x02, 0x40, 0x04, 0x80, + 0x09, 0x00, 0x12, 0x00, 0x64, 0x03, 0x8C, 0x1D, 0x0F, 0xC3, 0x80, 0xFE, + 0x0F, 0xE6, 0x00, 0x20, 0x40, 0x08, 0x08, 0x03, 0x01, 0x80, 0x40, 0x30, + 0x18, 0x06, 0x02, 0x00, 0x40, 0x80, 0x08, 0x30, 0x01, 0x84, 0x00, 0x31, + 0x80, 0x02, 0x20, 0x00, 0x48, 0x00, 0x09, 0x00, 0x01, 0xC0, 0x00, 0xF8, + 0x0F, 0xA0, 0x01, 0x90, 0x00, 0x88, 0x40, 0xC4, 0x30, 0x42, 0x18, 0x61, + 0x1A, 0x20, 0x8D, 0x10, 0x4C, 0x98, 0x26, 0x48, 0x16, 0x2C, 0x0B, 0x14, + 0x07, 0x0A, 0x03, 0x07, 0x01, 0x81, 0x00, 0x0F, 0x83, 0xE0, 0xC0, 0x18, + 0x0C, 0x0C, 0x01, 0x83, 0x00, 0x18, 0xC0, 0x01, 0xB0, 0x00, 0x1C, 0x00, + 0x03, 0x00, 0x00, 0xF0, 0x00, 0x63, 0x00, 0x18, 0x30, 0x06, 0x06, 0x01, + 0x80, 0x60, 0x60, 0x06, 0x3F, 0x07, 0xE0, 0x0F, 0xC0, 0xF8, 0x30, 0x01, + 0x00, 0x80, 0x18, 0x04, 0x00, 0x80, 0x30, 0x0C, 0x01, 0x80, 0xC0, 0x04, + 0x04, 0x00, 0x30, 0x60, 0x01, 0x86, 0x00, 0x04, 0x20, 0x00, 0x23, 0x00, + 0x01, 0xB0, 0x00, 0x0D, 0x00, 0x00, 0x38, 0x00, 0x01, 0x80, 0x00, 0x08, + 0x00, 0x00, 0xC0, 0x00, 0x04, 0x00, 0x00, 0x60, 0x00, 0x06, 0x00, 0x00, + 0x20, 0x00, 0x7F, 0xE0, 0x00, 0x1F, 0xFF, 0x10, 0x06, 0x10, 0x0C, 0x10, + 0x18, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x06, + 0x00, 0x0C, 0x00, 0x18, 0x04, 0x30, 0x0C, 0x60, 0x0C, 0xFF, 0xF8, 0x00, + 0xE0, 0x20, 0x08, 0x01, 0x00, 0x20, 0x04, 0x01, 0x00, 0x20, 0x04, 0x00, + 0x80, 0x20, 0x08, 0x0E, 0x00, 0x60, 0x04, 0x00, 0x80, 0x10, 0x02, 0x00, + 0x40, 0x08, 0x02, 0x00, 0x40, 0x08, 0x01, 0x00, 0x18, 0x00, 0x00, 0x10, + 0xC3, 0x08, 0x20, 0x86, 0x18, 0x41, 0x04, 0x30, 0xC2, 0x08, 0x21, 0x86, + 0x10, 0x43, 0x0C, 0x20, 0x06, 0x00, 0x40, 0x10, 0x04, 0x01, 0x00, 0x40, + 0x10, 0x04, 0x02, 0x00, 0x80, 0x20, 0x0C, 0x01, 0xC0, 0xC0, 0x40, 0x10, + 0x04, 0x03, 0x00, 0x80, 0x20, 0x08, 0x02, 0x01, 0x00, 0xC0, 0xE0, 0x00, + 0x1E, 0x02, 0x66, 0x0D, 0x86, 0x16, 0x06, 0x48, 0x07, 0x00 }; + +const GFXglyph FreeMonoOblique18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 21, 0, 1 }, // 0x20 ' ' + { 0, 7, 22, 21, 9, -21 }, // 0x21 '!' + { 20, 13, 10, 21, 7, -20 }, // 0x22 '"' + { 37, 15, 24, 21, 5, -21 }, // 0x23 '#' + { 82, 16, 26, 21, 4, -22 }, // 0x24 '$' + { 134, 16, 21, 21, 5, -20 }, // 0x25 '%' + { 176, 13, 18, 21, 5, -17 }, // 0x26 '&' + { 206, 5, 10, 21, 12, -20 }, // 0x27 ''' + { 213, 8, 25, 21, 12, -20 }, // 0x28 '(' + { 238, 8, 25, 21, 5, -20 }, // 0x29 ')' + { 263, 14, 11, 21, 7, -19 }, // 0x2A '*' + { 283, 15, 17, 21, 5, -17 }, // 0x2B '+' + { 315, 9, 10, 21, 4, -4 }, // 0x2C ',' + { 327, 16, 1, 21, 5, -9 }, // 0x2D '-' + { 329, 5, 5, 21, 8, -4 }, // 0x2E '.' + { 333, 19, 26, 21, 3, -22 }, // 0x2F '/' + { 395, 14, 21, 21, 5, -20 }, // 0x30 '0' + { 432, 13, 21, 21, 4, -20 }, // 0x31 '1' + { 467, 17, 21, 21, 3, -20 }, // 0x32 '2' + { 512, 16, 21, 21, 3, -20 }, // 0x33 '3' + { 554, 14, 21, 21, 5, -20 }, // 0x34 '4' + { 591, 17, 21, 21, 4, -20 }, // 0x35 '5' + { 636, 16, 21, 21, 6, -20 }, // 0x36 '6' + { 678, 13, 21, 21, 8, -20 }, // 0x37 '7' + { 713, 15, 21, 21, 5, -20 }, // 0x38 '8' + { 753, 15, 21, 21, 5, -20 }, // 0x39 '9' + { 793, 7, 15, 21, 8, -14 }, // 0x3A ':' + { 807, 11, 20, 21, 4, -14 }, // 0x3B ';' + { 835, 17, 16, 21, 5, -17 }, // 0x3C '<' + { 869, 19, 6, 21, 3, -12 }, // 0x3D '=' + { 884, 18, 16, 21, 3, -17 }, // 0x3E '>' + { 920, 12, 20, 21, 8, -19 }, // 0x3F '?' + { 950, 15, 23, 21, 5, -20 }, // 0x40 '@' + { 994, 21, 20, 21, 0, -19 }, // 0x41 'A' + { 1047, 18, 20, 21, 2, -19 }, // 0x42 'B' + { 1092, 18, 20, 21, 4, -19 }, // 0x43 'C' + { 1137, 18, 20, 21, 2, -19 }, // 0x44 'D' + { 1182, 20, 20, 21, 2, -19 }, // 0x45 'E' + { 1232, 20, 20, 21, 2, -19 }, // 0x46 'F' + { 1282, 18, 20, 21, 4, -19 }, // 0x47 'G' + { 1327, 21, 20, 21, 2, -19 }, // 0x48 'H' + { 1380, 17, 20, 21, 4, -19 }, // 0x49 'I' + { 1423, 20, 20, 21, 4, -19 }, // 0x4A 'J' + { 1473, 21, 20, 21, 2, -19 }, // 0x4B 'K' + { 1526, 18, 20, 21, 2, -19 }, // 0x4C 'L' + { 1571, 24, 20, 21, 1, -19 }, // 0x4D 'M' + { 1631, 22, 20, 21, 2, -19 }, // 0x4E 'N' + { 1686, 17, 20, 21, 4, -19 }, // 0x4F 'O' + { 1729, 18, 20, 21, 2, -19 }, // 0x50 'P' + { 1774, 17, 24, 21, 4, -19 }, // 0x51 'Q' + { 1825, 18, 20, 21, 2, -19 }, // 0x52 'R' + { 1870, 18, 20, 21, 3, -19 }, // 0x53 'S' + { 1915, 17, 20, 21, 5, -19 }, // 0x54 'T' + { 1958, 18, 20, 21, 5, -19 }, // 0x55 'U' + { 2003, 21, 20, 21, 4, -19 }, // 0x56 'V' + { 2056, 20, 20, 21, 4, -19 }, // 0x57 'W' + { 2106, 21, 20, 21, 2, -19 }, // 0x58 'X' + { 2159, 18, 20, 21, 5, -19 }, // 0x59 'Y' + { 2204, 17, 20, 21, 4, -19 }, // 0x5A 'Z' + { 2247, 11, 25, 21, 9, -20 }, // 0x5B '[' + { 2282, 8, 27, 21, 9, -22 }, // 0x5C '\' + { 2309, 11, 25, 21, 5, -20 }, // 0x5D ']' + { 2344, 13, 9, 21, 7, -20 }, // 0x5E '^' + { 2359, 21, 1, 21, -1, 4 }, // 0x5F '_' + { 2362, 5, 5, 21, 9, -21 }, // 0x60 '`' + { 2366, 16, 15, 21, 3, -14 }, // 0x61 'a' + { 2396, 19, 21, 21, 1, -20 }, // 0x62 'b' + { 2446, 17, 15, 21, 4, -14 }, // 0x63 'c' + { 2478, 18, 21, 21, 4, -20 }, // 0x64 'd' + { 2526, 16, 15, 21, 4, -14 }, // 0x65 'e' + { 2556, 19, 21, 21, 4, -20 }, // 0x66 'f' + { 2606, 19, 22, 21, 4, -14 }, // 0x67 'g' + { 2659, 18, 21, 21, 2, -20 }, // 0x68 'h' + { 2707, 15, 22, 21, 3, -21 }, // 0x69 'i' + { 2749, 15, 29, 21, 3, -21 }, // 0x6A 'j' + { 2804, 18, 21, 21, 2, -20 }, // 0x6B 'k' + { 2852, 15, 21, 21, 3, -20 }, // 0x6C 'l' + { 2892, 20, 15, 21, 1, -14 }, // 0x6D 'm' + { 2930, 17, 15, 21, 2, -14 }, // 0x6E 'n' + { 2962, 16, 15, 21, 4, -14 }, // 0x6F 'o' + { 2992, 20, 22, 21, 0, -14 }, // 0x70 'p' + { 3047, 19, 22, 21, 4, -14 }, // 0x71 'q' + { 3100, 19, 15, 21, 3, -14 }, // 0x72 'r' + { 3136, 15, 15, 21, 4, -14 }, // 0x73 's' + { 3165, 13, 20, 21, 5, -19 }, // 0x74 't' + { 3198, 15, 15, 21, 4, -14 }, // 0x75 'u' + { 3227, 19, 15, 21, 4, -14 }, // 0x76 'v' + { 3263, 17, 15, 21, 5, -14 }, // 0x77 'w' + { 3295, 19, 15, 21, 2, -14 }, // 0x78 'x' + { 3331, 21, 22, 21, 1, -14 }, // 0x79 'y' + { 3389, 16, 15, 21, 4, -14 }, // 0x7A 'z' + { 3419, 11, 25, 21, 8, -20 }, // 0x7B '{' + { 3454, 6, 24, 21, 9, -19 }, // 0x7C '|' + { 3472, 10, 25, 21, 6, -20 }, // 0x7D '}' + { 3504, 15, 5, 21, 5, -11 } }; // 0x7E '~' + +const GFXfont FreeMonoOblique18pt7b PROGMEM = { + (uint8_t *)FreeMonoOblique18pt7bBitmaps, + (GFXglyph *)FreeMonoOblique18pt7bGlyphs, + 0x20, 0x7E, 35 }; + +// Approx. 4186 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique24pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique24pt7b.h new file mode 100644 index 0000000..8a5592c --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique24pt7b.h @@ -0,0 +1,643 @@ +const uint8_t FreeMonoOblique24pt7bBitmaps[] PROGMEM = { + 0x01, 0xC0, 0xF0, 0x3C, 0x0E, 0x03, 0x81, 0xE0, 0x78, 0x1C, 0x07, 0x01, + 0xC0, 0xE0, 0x38, 0x0E, 0x03, 0x00, 0xC0, 0x70, 0x1C, 0x06, 0x01, 0x80, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1C, 0x0F, 0x83, 0xE0, 0xF8, + 0x1C, 0x00, 0x7E, 0x3F, 0x7E, 0x3F, 0x7C, 0x3E, 0x7C, 0x3E, 0x7C, 0x3E, + 0x78, 0x3C, 0xF8, 0x7C, 0xF0, 0x78, 0xF0, 0x78, 0xF0, 0x78, 0xE0, 0x70, + 0xE0, 0x70, 0xE0, 0x70, 0xC0, 0x60, 0x00, 0x18, 0x30, 0x00, 0x61, 0x80, + 0x01, 0x86, 0x00, 0x04, 0x18, 0x00, 0x30, 0xC0, 0x00, 0xC3, 0x00, 0x03, + 0x0C, 0x00, 0x18, 0x30, 0x00, 0x61, 0x80, 0x01, 0x86, 0x00, 0x06, 0x18, + 0x07, 0xFF, 0xFF, 0x1F, 0xFF, 0xFC, 0x03, 0x0C, 0x00, 0x18, 0x30, 0x00, + 0x61, 0x80, 0x01, 0x86, 0x00, 0x06, 0x18, 0x00, 0x30, 0xC0, 0x1F, 0xFF, + 0xF8, 0x7F, 0xFF, 0xE0, 0x18, 0x30, 0x00, 0x61, 0x80, 0x01, 0x86, 0x00, + 0x06, 0x18, 0x00, 0x30, 0x40, 0x00, 0xC3, 0x00, 0x03, 0x0C, 0x00, 0x18, + 0x30, 0x00, 0x61, 0x80, 0x01, 0x86, 0x00, 0x06, 0x18, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x18, 0x00, 0x00, 0x80, 0x00, 0x3F, 0x00, 0x07, 0xFD, 0x80, + 0x70, 0x7C, 0x06, 0x00, 0xE0, 0x60, 0x02, 0x07, 0x00, 0x10, 0x30, 0x00, + 0x01, 0x80, 0x00, 0x0C, 0x00, 0x00, 0x70, 0x00, 0x01, 0xF0, 0x00, 0x07, + 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x18, + 0x00, 0x00, 0xC2, 0x00, 0x06, 0x30, 0x00, 0x61, 0x80, 0x03, 0x1E, 0x00, + 0x30, 0xFC, 0x07, 0x06, 0x7F, 0xF0, 0x00, 0xFE, 0x00, 0x01, 0x80, 0x00, + 0x0C, 0x00, 0x00, 0x60, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0x80, + 0x00, 0x00, 0x78, 0x00, 0x07, 0xF8, 0x00, 0x38, 0x60, 0x01, 0xC0, 0xC0, + 0x06, 0x03, 0x00, 0x30, 0x0C, 0x00, 0xC0, 0x30, 0x03, 0x01, 0x80, 0x0C, + 0x0E, 0x00, 0x38, 0x70, 0x00, 0x7F, 0x81, 0xC0, 0xF8, 0x3F, 0x00, 0x07, + 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xC0, 0x00, 0x78, 0x00, 0x01, + 0x00, 0x78, 0x00, 0x07, 0xF8, 0x00, 0x38, 0x60, 0x01, 0x80, 0xC0, 0x06, + 0x03, 0x00, 0x30, 0x0C, 0x00, 0xC0, 0x30, 0x03, 0x01, 0x80, 0x0C, 0x0E, + 0x00, 0x18, 0x70, 0x00, 0x7F, 0x80, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, + 0x0F, 0xF8, 0x03, 0x8E, 0x00, 0xC0, 0x00, 0x38, 0x00, 0x06, 0x00, 0x00, + 0xC0, 0x00, 0x18, 0x00, 0x01, 0x00, 0x00, 0x30, 0x00, 0x06, 0x00, 0x03, + 0xE0, 0x01, 0xCC, 0x0E, 0x60, 0xC3, 0xD8, 0x18, 0x63, 0x03, 0x18, 0xC0, + 0x33, 0x18, 0x06, 0xC3, 0x00, 0x70, 0x60, 0x0E, 0x0C, 0x01, 0xC0, 0xC0, + 0x78, 0x1C, 0x3B, 0xE1, 0xFE, 0x3C, 0x1F, 0x00, 0x00, 0x7E, 0xFD, 0xF3, + 0xE7, 0xCF, 0x3E, 0x78, 0xF1, 0xE3, 0x87, 0x0E, 0x18, 0x00, 0x00, 0x60, + 0x18, 0x07, 0x00, 0xC0, 0x30, 0x0E, 0x01, 0x80, 0x70, 0x0C, 0x03, 0x80, + 0x60, 0x1C, 0x03, 0x80, 0xE0, 0x1C, 0x03, 0x80, 0xF0, 0x1C, 0x03, 0x80, + 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x30, + 0x06, 0x00, 0xC0, 0x1C, 0x01, 0x80, 0x30, 0x02, 0x00, 0x01, 0x80, 0x30, + 0x06, 0x00, 0xE0, 0x0C, 0x01, 0x80, 0x30, 0x07, 0x00, 0xE0, 0x1C, 0x03, + 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x38, 0x07, 0x00, + 0xE0, 0x3C, 0x07, 0x00, 0xE0, 0x38, 0x07, 0x01, 0xC0, 0x38, 0x0E, 0x01, + 0x80, 0x70, 0x0C, 0x03, 0x00, 0xC0, 0x10, 0x00, 0x00, 0x20, 0x00, 0x18, + 0x00, 0x06, 0x00, 0x01, 0x80, 0x00, 0xC0, 0x00, 0x30, 0x0E, 0x0C, 0x0B, + 0xF3, 0x3E, 0x3F, 0xFE, 0x01, 0xFC, 0x00, 0x3C, 0x00, 0x1F, 0x00, 0x0E, + 0x60, 0x07, 0x18, 0x01, 0x83, 0x00, 0xC0, 0xC0, 0x60, 0x30, 0x00, 0x00, + 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x18, + 0x00, 0x00, 0x60, 0x00, 0x01, 0x80, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, + 0x00, 0xC0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x30, 0x00, 0x01, + 0x80, 0x00, 0x06, 0x00, 0x00, 0x18, 0x00, 0x00, 0x60, 0x00, 0x01, 0x80, + 0x00, 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, + 0x03, 0xF0, 0x7E, 0x07, 0xC0, 0xF8, 0x0F, 0x81, 0xF0, 0x1E, 0x03, 0xE0, + 0x3C, 0x07, 0x80, 0x70, 0x0F, 0x00, 0xE0, 0x0C, 0x00, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xE0, 0x3C, 0xFF, 0xFF, 0xFF, 0xCF, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x03, 0x00, 0x00, 0x06, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x0C, + 0x00, 0x00, 0x18, 0x00, 0x00, 0x30, 0x00, 0x00, 0x30, 0x00, 0x00, 0x60, + 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x01, 0x80, 0x00, 0x03, 0x00, + 0x00, 0x07, 0x00, 0x00, 0x06, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x1C, 0x00, + 0x00, 0x18, 0x00, 0x00, 0x30, 0x00, 0x00, 0x70, 0x00, 0x00, 0x60, 0x00, + 0x00, 0xC0, 0x00, 0x01, 0x80, 0x00, 0x01, 0x80, 0x00, 0x03, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x06, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x18, 0x00, 0x00, + 0x18, 0x00, 0x00, 0x30, 0x00, 0x00, 0x60, 0x00, 0x00, 0xE0, 0x00, 0x00, + 0xC0, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x3F, 0x00, 0x0F, 0xF8, 0x01, + 0xC1, 0xC0, 0x38, 0x0E, 0x07, 0x00, 0x60, 0xE0, 0x03, 0x0C, 0x00, 0x31, + 0x80, 0x03, 0x18, 0x00, 0x33, 0x00, 0x03, 0x30, 0x00, 0x33, 0x00, 0x03, + 0x20, 0x00, 0x26, 0x00, 0x06, 0x60, 0x00, 0x66, 0x00, 0x06, 0x40, 0x00, + 0x4C, 0x00, 0x0C, 0xC0, 0x00, 0xCC, 0x00, 0x0C, 0xC0, 0x01, 0x8C, 0x00, + 0x18, 0xC0, 0x01, 0x8C, 0x00, 0x30, 0xC0, 0x07, 0x06, 0x00, 0xE0, 0x60, + 0x1C, 0x03, 0x87, 0x80, 0x3F, 0xF0, 0x00, 0xFC, 0x00, 0x00, 0x0E, 0x00, + 0x0F, 0x00, 0x0F, 0x80, 0x0E, 0xC0, 0x1C, 0xC0, 0x1C, 0x60, 0x1C, 0x30, + 0x08, 0x18, 0x00, 0x1C, 0x00, 0x0C, 0x00, 0x06, 0x00, 0x03, 0x00, 0x01, + 0x80, 0x01, 0xC0, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x18, 0x00, + 0x18, 0x00, 0x0C, 0x00, 0x06, 0x00, 0x03, 0x00, 0x01, 0x80, 0x01, 0x80, + 0x00, 0xC0, 0x00, 0x60, 0x00, 0x30, 0x1F, 0xFF, 0xFF, 0xFF, 0xF8, 0x00, + 0x07, 0xE0, 0x00, 0x3F, 0xE0, 0x01, 0xE0, 0xE0, 0x07, 0x00, 0xE0, 0x1C, + 0x00, 0xE0, 0x30, 0x00, 0xC0, 0xC0, 0x01, 0x81, 0x00, 0x03, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x18, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x03, + 0x00, 0x00, 0x1C, 0x00, 0x00, 0x70, 0x00, 0x01, 0xC0, 0x00, 0x07, 0x00, + 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x03, 0x80, 0x00, 0x0E, 0x00, 0x00, + 0x70, 0x00, 0x01, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xE0, + 0x00, 0xC3, 0x80, 0x01, 0x87, 0xFF, 0xFF, 0x0F, 0xFF, 0xFC, 0x00, 0x00, + 0x0F, 0xC0, 0x01, 0xFF, 0xC0, 0x1E, 0x07, 0x80, 0xE0, 0x06, 0x03, 0x00, + 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, 0x0C, + 0x00, 0x00, 0x60, 0x00, 0x03, 0x80, 0x00, 0x1C, 0x00, 0x00, 0xE0, 0x00, + 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xE0, 0x00, 0x01, + 0x80, 0x00, 0x03, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, + 0x00, 0x03, 0x00, 0x00, 0x18, 0x00, 0x00, 0xE3, 0x00, 0x07, 0x0E, 0x00, + 0x38, 0x1E, 0x03, 0xC0, 0x3F, 0xFC, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x03, + 0xE0, 0x00, 0xF8, 0x00, 0x1B, 0x00, 0x06, 0x60, 0x01, 0x8C, 0x00, 0x63, + 0x00, 0x18, 0x60, 0x07, 0x0C, 0x00, 0xC1, 0x80, 0x30, 0x30, 0x0C, 0x0C, + 0x03, 0x01, 0x80, 0xC0, 0x30, 0x18, 0x06, 0x06, 0x00, 0xC1, 0x80, 0x30, + 0x60, 0x06, 0x18, 0x00, 0xC3, 0xFF, 0xFE, 0x7F, 0xFF, 0xC0, 0x00, 0xC0, + 0x00, 0x18, 0x00, 0x03, 0x00, 0x00, 0x60, 0x00, 0x18, 0x00, 0x03, 0x00, + 0x0F, 0xFC, 0x01, 0xFF, 0x80, 0x01, 0xFF, 0xF8, 0x0F, 0xFF, 0xC0, 0x40, + 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0x80, 0x00, 0x0C, 0x00, 0x00, + 0xC0, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0xBF, 0xC0, 0x0F, 0xFF, + 0x80, 0xF8, 0x1E, 0x02, 0x00, 0x30, 0x00, 0x01, 0xC0, 0x00, 0x06, 0x00, + 0x00, 0x30, 0x00, 0x01, 0x80, 0x00, 0x0C, 0x00, 0x00, 0x60, 0x00, 0x06, + 0x00, 0x00, 0x30, 0x00, 0x03, 0x80, 0x00, 0x18, 0xC0, 0x01, 0x87, 0x00, + 0x38, 0x1E, 0x07, 0x80, 0x7F, 0xF8, 0x00, 0x7E, 0x00, 0x00, 0x00, 0x03, + 0xF0, 0x00, 0xFF, 0xC0, 0x1F, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x01, + 0x80, 0x00, 0x18, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x00, 0xC0, 0x00, + 0x0E, 0x00, 0x00, 0x60, 0x00, 0x07, 0x0F, 0x80, 0x31, 0xFF, 0x01, 0x9C, + 0x3C, 0x0D, 0x80, 0x60, 0xD8, 0x03, 0x87, 0x80, 0x0C, 0x38, 0x00, 0x61, + 0xC0, 0x03, 0x0C, 0x00, 0x18, 0x60, 0x00, 0xC3, 0x00, 0x0C, 0x18, 0x00, + 0x60, 0xE0, 0x06, 0x03, 0x00, 0x30, 0x1C, 0x07, 0x00, 0x70, 0x70, 0x01, + 0xFF, 0x00, 0x07, 0xE0, 0x00, 0x7F, 0xFF, 0xDF, 0xFF, 0xFC, 0x00, 0x0F, + 0x00, 0x03, 0x00, 0x01, 0x80, 0x00, 0x60, 0x00, 0x30, 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, 0x60, 0x00, 0x18, 0x00, 0x0C, + 0x00, 0x03, 0x00, 0x01, 0x80, 0x00, 0x60, 0x00, 0x00, 0x3F, 0x00, 0x0F, + 0xFC, 0x01, 0xC1, 0xE0, 0x70, 0x06, 0x06, 0x00, 0x30, 0xC0, 0x03, 0x1C, + 0x00, 0x31, 0x80, 0x03, 0x18, 0x00, 0x31, 0x80, 0x06, 0x18, 0x00, 0xE0, + 0xC0, 0x1C, 0x0F, 0x07, 0x80, 0x3F, 0xE0, 0x03, 0xFE, 0x00, 0xE0, 0x70, + 0x18, 0x03, 0x83, 0x00, 0x1C, 0x60, 0x00, 0xC6, 0x00, 0x0C, 0xC0, 0x00, + 0xCC, 0x00, 0x0C, 0xC0, 0x00, 0xCC, 0x00, 0x18, 0xC0, 0x03, 0x8E, 0x00, + 0x70, 0x60, 0x0E, 0x07, 0x83, 0xC0, 0x3F, 0xF0, 0x00, 0xFC, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0xFF, 0x80, 0x0F, 0x07, 0x00, 0x70, 0x0E, 0x03, 0x80, + 0x18, 0x0C, 0x00, 0x70, 0x60, 0x00, 0xC1, 0x80, 0x03, 0x0C, 0x00, 0x0C, + 0x30, 0x00, 0x30, 0xC0, 0x01, 0xC3, 0x00, 0x0F, 0x0C, 0x00, 0x6C, 0x38, + 0x03, 0xF0, 0x60, 0x1D, 0x81, 0xE1, 0xE6, 0x03, 0xFE, 0x18, 0x03, 0xE0, + 0xC0, 0x00, 0x03, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x60, 0x00, 0x03, 0x00, + 0x00, 0x1C, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00, 0x38, 0x00, 0x03, + 0xC0, 0x00, 0x7C, 0x00, 0xFF, 0xC0, 0x01, 0xF8, 0x00, 0x00, 0x07, 0x83, + 0xF1, 0xFC, 0x7F, 0x1F, 0x83, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0xF0, 0x7E, 0x3F, 0x8F, 0xE3, 0xF0, 0x78, + 0x00, 0x00, 0x3C, 0x00, 0xFC, 0x03, 0xF8, 0x07, 0xF0, 0x0F, 0xC0, 0x0F, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x7E, 0x00, 0xFC, 0x03, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x3E, + 0x00, 0xF8, 0x01, 0xE0, 0x07, 0x80, 0x0F, 0x00, 0x3C, 0x00, 0x70, 0x01, + 0xC0, 0x01, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x3C, 0x00, 0x01, + 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, + 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x03, + 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, + 0x70, 0x00, 0x00, 0x78, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x0C, 0x00, 0x3F, 0xFF, 0xFF, 0x9F, + 0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, + 0x00, 0x06, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, 0xF0, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, + 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0x70, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x07, 0xF0, 0x3F, 0xFC, 0x78, + 0x1E, 0xC0, 0x07, 0xC0, 0x03, 0xC0, 0x03, 0x00, 0x03, 0x00, 0x03, 0x00, + 0x06, 0x00, 0x06, 0x00, 0x1C, 0x00, 0x38, 0x00, 0xE0, 0x07, 0xC0, 0x07, + 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x3C, 0x00, 0x7E, 0x00, 0xFE, 0x00, 0xFE, + 0x00, 0x7C, 0x00, 0x00, 0x3F, 0x00, 0x1F, 0xF0, 0x07, 0x07, 0x01, 0xC0, + 0x70, 0x60, 0x06, 0x1C, 0x00, 0xC3, 0x00, 0x18, 0xC0, 0x03, 0x18, 0x00, + 0x66, 0x00, 0xFC, 0xC0, 0x7F, 0x98, 0x1C, 0x66, 0x06, 0x0C, 0xC1, 0x81, + 0x98, 0x30, 0x33, 0x0C, 0x0E, 0x61, 0x81, 0x98, 0x30, 0x33, 0x06, 0x06, + 0x60, 0xF0, 0xCC, 0x0F, 0xF9, 0x80, 0x7F, 0x30, 0x00, 0x06, 0x00, 0x00, + 0xC0, 0x00, 0x18, 0x00, 0x03, 0x80, 0x00, 0x30, 0x00, 0x07, 0x00, 0x00, + 0x70, 0x18, 0x0F, 0xFE, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0xF0, 0x00, 0x0F, + 0xFE, 0x00, 0x00, 0x06, 0xC0, 0x00, 0x00, 0xCC, 0x00, 0x00, 0x31, 0x80, + 0x00, 0x06, 0x30, 0x00, 0x01, 0x86, 0x00, 0x00, 0x60, 0xC0, 0x00, 0x0C, + 0x1C, 0x00, 0x03, 0x01, 0x80, 0x00, 0x40, 0x30, 0x00, 0x18, 0x06, 0x00, + 0x06, 0x00, 0xC0, 0x00, 0xC0, 0x18, 0x00, 0x30, 0x01, 0x80, 0x07, 0xFF, + 0xF0, 0x01, 0xFF, 0xFE, 0x00, 0x60, 0x00, 0xC0, 0x0C, 0x00, 0x18, 0x03, + 0x00, 0x03, 0x00, 0x40, 0x00, 0x30, 0x18, 0x00, 0x06, 0x06, 0x00, 0x00, + 0xC0, 0xC0, 0x00, 0x18, 0xFF, 0x80, 0x7F, 0xFF, 0xF0, 0x0F, 0xFC, 0x03, + 0xFF, 0xFC, 0x01, 0xFF, 0xFF, 0xC0, 0x06, 0x00, 0x38, 0x01, 0x80, 0x07, + 0x00, 0xC0, 0x00, 0xC0, 0x30, 0x00, 0x30, 0x0C, 0x00, 0x0C, 0x03, 0x00, + 0x03, 0x00, 0xC0, 0x01, 0x80, 0x60, 0x00, 0xC0, 0x18, 0x01, 0xE0, 0x07, + 0xFF, 0xE0, 0x01, 0xFF, 0xFC, 0x00, 0xE0, 0x03, 0x80, 0x30, 0x00, 0x70, + 0x0C, 0x00, 0x0E, 0x03, 0x00, 0x01, 0x80, 0xC0, 0x00, 0x60, 0x60, 0x00, + 0x18, 0x18, 0x00, 0x06, 0x06, 0x00, 0x03, 0x01, 0x80, 0x01, 0xC0, 0x60, + 0x00, 0xE0, 0x30, 0x00, 0x70, 0xFF, 0xFF, 0xF8, 0x3F, 0xFF, 0xF8, 0x00, + 0x00, 0x0F, 0xE0, 0x00, 0x3F, 0xFC, 0xC0, 0x3C, 0x0F, 0x60, 0x78, 0x01, + 0xF0, 0x70, 0x00, 0x70, 0x70, 0x00, 0x18, 0x30, 0x00, 0x0C, 0x30, 0x00, + 0x06, 0x38, 0x00, 0x02, 0x18, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x0C, 0x00, + 0x00, 0x06, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, 0x80, 0x00, 0x01, 0x80, + 0x00, 0x00, 0xC0, 0x00, 0x00, 0x60, 0x00, 0x00, 0x30, 0x00, 0x00, 0x18, + 0x00, 0x00, 0x0C, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, 0x80, 0x00, 0x60, + 0x60, 0x00, 0x60, 0x38, 0x00, 0xE0, 0x0F, 0x01, 0xE0, 0x03, 0xFF, 0xC0, + 0x00, 0x3F, 0x00, 0x00, 0x03, 0xFF, 0xF0, 0x01, 0xFF, 0xFF, 0x00, 0x0C, + 0x00, 0xF0, 0x03, 0x00, 0x1C, 0x01, 0xC0, 0x03, 0x80, 0x60, 0x00, 0x60, + 0x18, 0x00, 0x1C, 0x06, 0x00, 0x03, 0x01, 0x80, 0x00, 0xC0, 0xC0, 0x00, + 0x30, 0x30, 0x00, 0x0C, 0x0C, 0x00, 0x03, 0x03, 0x00, 0x00, 0xC0, 0xC0, + 0x00, 0x60, 0x60, 0x00, 0x18, 0x18, 0x00, 0x06, 0x06, 0x00, 0x03, 0x01, + 0x80, 0x00, 0xC0, 0xE0, 0x00, 0x70, 0x30, 0x00, 0x18, 0x0C, 0x00, 0x0C, + 0x03, 0x00, 0x06, 0x00, 0xC0, 0x07, 0x00, 0x60, 0x07, 0x80, 0xFF, 0xFF, + 0xC0, 0x3F, 0xFF, 0x80, 0x00, 0x03, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFC, + 0x01, 0x80, 0x01, 0x80, 0x30, 0x00, 0x60, 0x0C, 0x00, 0x0C, 0x01, 0x80, + 0x01, 0x80, 0x30, 0x00, 0x30, 0x06, 0x00, 0x00, 0x00, 0xC0, 0xC0, 0x00, + 0x30, 0x18, 0x00, 0x06, 0x03, 0x00, 0x00, 0xFF, 0xE0, 0x00, 0x1F, 0xF8, + 0x00, 0x07, 0x03, 0x00, 0x00, 0xC0, 0x60, 0x00, 0x18, 0x0C, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x18, 0x00, 0x0C, 0x03, 0x00, 0x01, + 0x80, 0x60, 0x00, 0x30, 0x0C, 0x00, 0x0C, 0x01, 0x80, 0x01, 0x80, 0x60, + 0x00, 0x30, 0xFF, 0xFF, 0xFE, 0x1F, 0xFF, 0xFF, 0xC0, 0x03, 0xFF, 0xFF, + 0xF0, 0x7F, 0xFF, 0xFF, 0x00, 0x60, 0x00, 0x30, 0x06, 0x00, 0x06, 0x00, + 0xC0, 0x00, 0x60, 0x0C, 0x00, 0x06, 0x00, 0xC0, 0x00, 0x60, 0x0C, 0x00, + 0x00, 0x00, 0xC0, 0xC0, 0x00, 0x18, 0x0C, 0x00, 0x01, 0x80, 0xC0, 0x00, + 0x1F, 0xFC, 0x00, 0x01, 0xFF, 0x80, 0x00, 0x38, 0x18, 0x00, 0x03, 0x01, + 0x80, 0x00, 0x30, 0x18, 0x00, 0x03, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x60, + 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xFF, 0xFC, 0x00, + 0x0F, 0xFF, 0xC0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x3F, 0xFC, 0xC0, 0x3C, + 0x0F, 0xE0, 0x78, 0x01, 0xF0, 0x70, 0x00, 0x30, 0x70, 0x00, 0x18, 0x70, + 0x00, 0x0C, 0x30, 0x00, 0x00, 0x30, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18, + 0x00, 0x00, 0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, + 0x80, 0x00, 0x01, 0x80, 0x1F, 0xFE, 0xC0, 0x0F, 0xFF, 0x60, 0x00, 0x06, + 0x30, 0x00, 0x06, 0x18, 0x00, 0x03, 0x0C, 0x00, 0x01, 0x87, 0x00, 0x00, + 0xC1, 0x80, 0x00, 0xE0, 0xE0, 0x00, 0x60, 0x38, 0x00, 0x70, 0x0F, 0x00, + 0xF8, 0x03, 0xFF, 0xF0, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xFC, 0x1F, 0xE0, + 0x7F, 0x83, 0xFC, 0x03, 0x00, 0x06, 0x00, 0x60, 0x01, 0x80, 0x1C, 0x00, + 0x30, 0x03, 0x00, 0x06, 0x00, 0x60, 0x00, 0xC0, 0x0C, 0x00, 0x38, 0x01, + 0x80, 0x06, 0x00, 0x60, 0x00, 0xC0, 0x0C, 0x00, 0x18, 0x01, 0xFF, 0xFF, + 0x00, 0x3F, 0xFF, 0xC0, 0x06, 0x00, 0x18, 0x01, 0x80, 0x03, 0x00, 0x30, + 0x00, 0x60, 0x06, 0x00, 0x0C, 0x00, 0xC0, 0x03, 0x00, 0x38, 0x00, 0x60, + 0x06, 0x00, 0x0C, 0x00, 0xC0, 0x01, 0x80, 0x18, 0x00, 0x70, 0x03, 0x00, + 0x0C, 0x00, 0xE0, 0x01, 0x80, 0xFF, 0x83, 0xFE, 0x1F, 0xF0, 0x7F, 0xC0, + 0x07, 0xFF, 0xFC, 0x1F, 0xFF, 0xF0, 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, + 0x0C, 0x00, 0x00, 0x70, 0x00, 0x01, 0x80, 0x00, 0x06, 0x00, 0x00, 0x18, + 0x00, 0x00, 0x60, 0x00, 0x03, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x30, 0x00, + 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, 0x18, 0x00, 0x00, 0x60, 0x00, 0x01, + 0x80, 0x00, 0x06, 0x00, 0x00, 0x38, 0x00, 0x00, 0xC0, 0x00, 0x03, 0x00, + 0x00, 0x0C, 0x00, 0x00, 0x30, 0x00, 0xFF, 0xFF, 0x83, 0xFF, 0xFE, 0x00, + 0x00, 0x0F, 0xFF, 0xF0, 0x01, 0xFF, 0xFF, 0x00, 0x00, 0x0C, 0x00, 0x00, + 0x00, 0xC0, 0x00, 0x00, 0x18, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x18, + 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x38, 0x00, 0x00, 0x03, 0x00, 0x00, + 0x00, 0x30, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x07, + 0x00, 0x20, 0x00, 0x60, 0x06, 0x00, 0x06, 0x00, 0x60, 0x00, 0x60, 0x06, + 0x00, 0x06, 0x00, 0x60, 0x00, 0xC0, 0x0C, 0x00, 0x0C, 0x00, 0xC0, 0x00, + 0xC0, 0x0C, 0x00, 0x18, 0x00, 0xE0, 0x03, 0x00, 0x07, 0x00, 0x70, 0x00, + 0x3C, 0x1C, 0x00, 0x01, 0xFF, 0x80, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x03, + 0xFF, 0x07, 0xF8, 0x3F, 0xF8, 0x3F, 0xC0, 0x18, 0x00, 0x70, 0x00, 0xC0, + 0x07, 0x00, 0x0C, 0x00, 0x60, 0x00, 0x60, 0x0E, 0x00, 0x03, 0x00, 0xE0, + 0x00, 0x18, 0x0C, 0x00, 0x00, 0xC1, 0xC0, 0x00, 0x0C, 0x1C, 0x00, 0x00, + 0x61, 0x80, 0x00, 0x03, 0x3C, 0x00, 0x00, 0x1B, 0x78, 0x00, 0x01, 0xF0, + 0xE0, 0x00, 0x0F, 0x03, 0x80, 0x00, 0x60, 0x0C, 0x00, 0x03, 0x00, 0x70, + 0x00, 0x18, 0x01, 0x80, 0x01, 0x80, 0x0C, 0x00, 0x0C, 0x00, 0x60, 0x00, + 0x60, 0x01, 0x80, 0x03, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x60, 0x01, 0x80, + 0x03, 0x00, 0xFF, 0xE0, 0x1F, 0x87, 0xFF, 0x00, 0x7C, 0x00, 0x07, 0xFF, + 0xE0, 0x03, 0xFF, 0xF0, 0x00, 0x06, 0x00, 0x00, 0x03, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x60, 0x00, 0x00, + 0x70, 0x00, 0x00, 0x30, 0x00, 0x00, 0x18, 0x00, 0x00, 0x0C, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x06, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, 0x80, 0x00, + 0x00, 0xC0, 0x03, 0x00, 0x60, 0x01, 0x80, 0x60, 0x00, 0xC0, 0x30, 0x00, + 0x60, 0x18, 0x00, 0x30, 0x0C, 0x00, 0x30, 0x0E, 0x00, 0x18, 0x06, 0x00, + 0x0C, 0xFF, 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, 0x00, 0x07, 0xF0, 0x00, 0x3F, + 0x07, 0xF0, 0x00, 0x7F, 0x01, 0xB0, 0x00, 0xD8, 0x01, 0xB0, 0x00, 0xD8, + 0x01, 0x98, 0x01, 0x98, 0x01, 0x98, 0x03, 0x30, 0x01, 0x98, 0x03, 0x30, + 0x03, 0x18, 0x06, 0x30, 0x03, 0x1C, 0x0C, 0x30, 0x03, 0x0C, 0x0C, 0x30, + 0x03, 0x0C, 0x18, 0x60, 0x07, 0x0C, 0x30, 0x60, 0x06, 0x0C, 0x30, 0x60, + 0x06, 0x06, 0x60, 0x60, 0x06, 0x06, 0xC0, 0x60, 0x06, 0x06, 0xC0, 0xC0, + 0x0C, 0x07, 0x80, 0xC0, 0x0C, 0x03, 0x00, 0xC0, 0x0C, 0x00, 0x00, 0xC0, + 0x0C, 0x00, 0x01, 0xC0, 0x0C, 0x00, 0x01, 0x80, 0x18, 0x00, 0x01, 0x80, + 0x18, 0x00, 0x01, 0x80, 0x18, 0x00, 0x01, 0x80, 0xFF, 0x80, 0x3F, 0xE0, + 0xFF, 0x80, 0x3F, 0xE0, 0x07, 0xE0, 0x0F, 0xFC, 0x3F, 0x80, 0x3F, 0xF0, + 0x0F, 0x00, 0x06, 0x00, 0x3C, 0x00, 0x10, 0x01, 0x98, 0x00, 0xC0, 0x06, + 0x60, 0x03, 0x00, 0x19, 0xC0, 0x0C, 0x00, 0x63, 0x00, 0x30, 0x01, 0x0C, + 0x01, 0x80, 0x0C, 0x18, 0x06, 0x00, 0x30, 0x60, 0x18, 0x00, 0xC1, 0xC0, + 0x60, 0x03, 0x03, 0x01, 0x00, 0x08, 0x0C, 0x0C, 0x00, 0x60, 0x18, 0x30, + 0x01, 0x80, 0x60, 0xC0, 0x06, 0x01, 0xC3, 0x00, 0x18, 0x03, 0x18, 0x00, + 0xC0, 0x0C, 0x60, 0x03, 0x00, 0x19, 0x80, 0x0C, 0x00, 0x66, 0x00, 0x30, + 0x01, 0xD8, 0x00, 0x80, 0x03, 0xC0, 0x06, 0x00, 0x0F, 0x00, 0xFF, 0xC0, + 0x1C, 0x03, 0xFE, 0x00, 0x70, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x7F, 0xF0, + 0x00, 0xF0, 0x78, 0x03, 0x80, 0x1C, 0x07, 0x00, 0x0E, 0x0E, 0x00, 0x06, + 0x0C, 0x00, 0x06, 0x18, 0x00, 0x07, 0x38, 0x00, 0x03, 0x30, 0x00, 0x03, + 0x60, 0x00, 0x03, 0x60, 0x00, 0x03, 0x60, 0x00, 0x03, 0xC0, 0x00, 0x03, + 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x06, 0xC0, 0x00, 0x06, 0xC0, 0x00, 0x06, + 0xC0, 0x00, 0x0C, 0xC0, 0x00, 0x1C, 0xC0, 0x00, 0x18, 0x60, 0x00, 0x30, + 0x60, 0x00, 0x70, 0x70, 0x00, 0xE0, 0x38, 0x01, 0xC0, 0x1E, 0x0F, 0x00, + 0x0F, 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xFF, 0xFC, 0x01, 0xFF, 0xFF, + 0xC0, 0x06, 0x00, 0x78, 0x01, 0x80, 0x06, 0x00, 0xC0, 0x01, 0xC0, 0x30, + 0x00, 0x30, 0x0C, 0x00, 0x0C, 0x03, 0x00, 0x03, 0x00, 0xC0, 0x01, 0xC0, + 0x60, 0x00, 0x60, 0x18, 0x00, 0x30, 0x06, 0x00, 0x18, 0x01, 0x80, 0x3C, + 0x00, 0xFF, 0xFE, 0x00, 0x3F, 0xFC, 0x00, 0x0C, 0x00, 0x00, 0x03, 0x00, + 0x00, 0x00, 0xC0, 0x00, 0x00, 0x60, 0x00, 0x00, 0x18, 0x00, 0x00, 0x06, + 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x60, 0x00, 0x00, 0x30, 0x00, 0x00, + 0xFF, 0xFC, 0x00, 0x3F, 0xFF, 0x00, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x7F, + 0xF0, 0x00, 0xF0, 0x78, 0x03, 0x80, 0x1C, 0x07, 0x00, 0x0E, 0x0E, 0x00, + 0x06, 0x0C, 0x00, 0x06, 0x18, 0x00, 0x03, 0x38, 0x00, 0x03, 0x30, 0x00, + 0x03, 0x60, 0x00, 0x03, 0x60, 0x00, 0x03, 0x60, 0x00, 0x03, 0xC0, 0x00, + 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x06, 0xC0, 0x00, 0x06, 0xC0, 0x00, + 0x06, 0xC0, 0x00, 0x0C, 0xC0, 0x00, 0x1C, 0xC0, 0x00, 0x18, 0x60, 0x00, + 0x30, 0x60, 0x00, 0x70, 0x30, 0x00, 0xE0, 0x38, 0x01, 0xC0, 0x0E, 0x0F, + 0x00, 0x07, 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0x1F, 0xF8, + 0x30, 0x3F, 0xFF, 0xF0, 0x78, 0x0F, 0x80, 0x07, 0xFF, 0xFC, 0x01, 0xFF, + 0xFF, 0xC0, 0x06, 0x00, 0x78, 0x01, 0x80, 0x0E, 0x00, 0xC0, 0x01, 0xC0, + 0x30, 0x00, 0x30, 0x0C, 0x00, 0x0C, 0x03, 0x00, 0x03, 0x00, 0xC0, 0x00, + 0xC0, 0x60, 0x00, 0x60, 0x18, 0x00, 0x30, 0x06, 0x00, 0x38, 0x01, 0x80, + 0x3C, 0x00, 0xFF, 0xFC, 0x00, 0x3F, 0xFC, 0x00, 0x0C, 0x07, 0x80, 0x03, + 0x00, 0x70, 0x00, 0xC0, 0x0E, 0x00, 0x60, 0x01, 0x80, 0x18, 0x00, 0x70, + 0x06, 0x00, 0x0C, 0x01, 0x80, 0x03, 0x80, 0x60, 0x00, 0x60, 0x30, 0x00, + 0x1C, 0xFF, 0xE0, 0x07, 0xFF, 0xF8, 0x00, 0xF0, 0x00, 0x1F, 0xC0, 0x00, + 0x7F, 0xF3, 0x00, 0xE0, 0x3B, 0x03, 0x80, 0x0F, 0x07, 0x00, 0x0E, 0x06, + 0x00, 0x06, 0x0C, 0x00, 0x06, 0x0C, 0x00, 0x06, 0x0C, 0x00, 0x00, 0x0C, + 0x00, 0x00, 0x0E, 0x00, 0x00, 0x07, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, + 0x7F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x70, 0x00, 0x00, 0x38, 0x00, + 0x00, 0x18, 0x00, 0x00, 0x18, 0x20, 0x00, 0x18, 0x60, 0x00, 0x18, 0x60, + 0x00, 0x30, 0x60, 0x00, 0x70, 0xF0, 0x00, 0xE0, 0xF8, 0x01, 0xC0, 0xDC, + 0x07, 0x80, 0x8F, 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0xFF, 0xFE, 0x3F, + 0xFF, 0xFE, 0x30, 0x18, 0x06, 0x60, 0x18, 0x06, 0x60, 0x18, 0x06, 0x60, + 0x38, 0x0C, 0x60, 0x30, 0x04, 0x00, 0x30, 0x00, 0x00, 0x30, 0x00, 0x00, + 0x30, 0x00, 0x00, 0x70, 0x00, 0x00, 0x60, 0x00, 0x00, 0x60, 0x00, 0x00, + 0x60, 0x00, 0x00, 0x60, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, + 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x01, 0x80, 0x00, 0x01, + 0x80, 0x00, 0x01, 0x80, 0x00, 0x01, 0x80, 0x00, 0xFF, 0xFE, 0x00, 0xFF, + 0xFC, 0x00, 0x7F, 0xC0, 0xFF, 0xDF, 0xF0, 0x3F, 0xF1, 0x80, 0x00, 0x60, + 0x60, 0x00, 0x30, 0x18, 0x00, 0x0C, 0x06, 0x00, 0x03, 0x03, 0x80, 0x00, + 0xC0, 0xC0, 0x00, 0x30, 0x30, 0x00, 0x18, 0x0C, 0x00, 0x06, 0x03, 0x00, + 0x01, 0x81, 0xC0, 0x00, 0x60, 0x60, 0x00, 0x18, 0x18, 0x00, 0x0C, 0x06, + 0x00, 0x03, 0x01, 0x80, 0x00, 0xC0, 0xC0, 0x00, 0x30, 0x30, 0x00, 0x1C, + 0x0C, 0x00, 0x06, 0x03, 0x00, 0x01, 0x80, 0xC0, 0x00, 0xC0, 0x30, 0x00, + 0x70, 0x0E, 0x00, 0x38, 0x01, 0xC0, 0x1C, 0x00, 0x38, 0x1E, 0x00, 0x07, + 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFF, 0x80, 0x3F, 0xFF, 0xF0, 0x07, + 0xFC, 0xE0, 0x00, 0x0C, 0x0C, 0x00, 0x03, 0x01, 0x80, 0x00, 0x60, 0x30, + 0x00, 0x18, 0x06, 0x00, 0x02, 0x00, 0xC0, 0x00, 0xC0, 0x0C, 0x00, 0x30, + 0x01, 0x80, 0x06, 0x00, 0x30, 0x01, 0x80, 0x06, 0x00, 0x60, 0x00, 0xC0, + 0x0C, 0x00, 0x18, 0x03, 0x00, 0x01, 0x80, 0xC0, 0x00, 0x30, 0x18, 0x00, + 0x06, 0x06, 0x00, 0x00, 0xC0, 0xC0, 0x00, 0x18, 0x30, 0x00, 0x03, 0x8C, + 0x00, 0x00, 0x31, 0x80, 0x00, 0x06, 0x60, 0x00, 0x00, 0xD8, 0x00, 0x00, + 0x1B, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x38, 0x00, 0x00, 0xFF, 0xC0, + 0x7F, 0xFF, 0xF8, 0x0F, 0xF8, 0xC0, 0x00, 0x0C, 0x18, 0x00, 0x01, 0x83, + 0x00, 0x00, 0x30, 0x60, 0x08, 0x0C, 0x0C, 0x07, 0x01, 0x81, 0x81, 0xE0, + 0x30, 0x60, 0x2C, 0x0C, 0x0C, 0x0D, 0x81, 0x81, 0x81, 0x30, 0x30, 0x30, + 0x66, 0x0C, 0x06, 0x08, 0xC1, 0x80, 0xC3, 0x0C, 0x30, 0x18, 0x41, 0x8C, + 0x03, 0x18, 0x31, 0x80, 0x62, 0x06, 0x30, 0x0C, 0xC0, 0xCC, 0x03, 0x10, + 0x19, 0x80, 0x66, 0x03, 0x30, 0x0C, 0x80, 0x6C, 0x01, 0xB0, 0x0D, 0x80, + 0x34, 0x01, 0xB0, 0x07, 0x80, 0x3C, 0x00, 0xE0, 0x07, 0x80, 0x1C, 0x00, + 0xF0, 0x00, 0x03, 0xF8, 0x03, 0xF8, 0x1F, 0xC0, 0x3F, 0xC0, 0x30, 0x00, + 0x30, 0x01, 0xC0, 0x03, 0x00, 0x06, 0x00, 0x30, 0x00, 0x18, 0x03, 0x00, + 0x00, 0xE0, 0x30, 0x00, 0x03, 0x03, 0x00, 0x00, 0x1C, 0x30, 0x00, 0x00, + 0x63, 0x00, 0x00, 0x03, 0xB0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x30, + 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x36, 0x00, 0x00, 0x03, 0x38, 0x00, + 0x00, 0x30, 0xC0, 0x00, 0x03, 0x07, 0x00, 0x00, 0x30, 0x18, 0x00, 0x03, + 0x00, 0x60, 0x00, 0x30, 0x03, 0x80, 0x03, 0x00, 0x0C, 0x00, 0x30, 0x00, + 0x70, 0x03, 0x00, 0x01, 0x80, 0xFF, 0x80, 0xFF, 0x07, 0xFC, 0x07, 0xF8, + 0x00, 0x7F, 0x80, 0x7F, 0x7F, 0x00, 0x7F, 0x1C, 0x00, 0x18, 0x0C, 0x00, + 0x30, 0x0C, 0x00, 0x70, 0x06, 0x00, 0xE0, 0x06, 0x00, 0xC0, 0x03, 0x01, + 0x80, 0x03, 0x03, 0x00, 0x01, 0x86, 0x00, 0x01, 0x8C, 0x00, 0x00, 0xD8, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x60, 0x00, 0x00, 0xC0, + 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, + 0x00, 0x01, 0x80, 0x00, 0x01, 0x80, 0x00, 0x01, 0x80, 0x00, 0x01, 0x80, + 0x00, 0xFF, 0xFE, 0x00, 0xFF, 0xFC, 0x00, 0x03, 0xFF, 0xFE, 0x07, 0xFF, + 0xF8, 0x0C, 0x00, 0x30, 0x10, 0x00, 0xC0, 0x60, 0x03, 0x80, 0xC0, 0x0E, + 0x01, 0x80, 0x38, 0x03, 0x00, 0xE0, 0x00, 0x03, 0x80, 0x00, 0x0E, 0x00, + 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x01, 0x80, 0x00, 0x06, 0x00, 0x00, + 0x18, 0x00, 0x00, 0x60, 0x00, 0x01, 0x80, 0x00, 0x06, 0x00, 0x60, 0x18, + 0x00, 0xC0, 0x60, 0x01, 0x81, 0x80, 0x02, 0x06, 0x00, 0x0C, 0x18, 0x00, + 0x18, 0x60, 0x00, 0x30, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0x80, 0x01, 0xFE, + 0x03, 0xFC, 0x06, 0x00, 0x08, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x01, + 0x80, 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0x40, 0x01, 0x80, + 0x03, 0x00, 0x06, 0x00, 0x0C, 0x00, 0x10, 0x00, 0x60, 0x00, 0xC0, 0x01, + 0x80, 0x03, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, 0x00, 0x80, + 0x03, 0x00, 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x20, 0x00, 0xFF, 0x01, + 0xFE, 0x00, 0xC0, 0x30, 0x0E, 0x01, 0x80, 0x60, 0x18, 0x07, 0x00, 0xC0, + 0x30, 0x0C, 0x03, 0x80, 0x60, 0x18, 0x06, 0x00, 0xC0, 0x30, 0x0C, 0x03, + 0x00, 0x60, 0x18, 0x06, 0x01, 0x80, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x18, + 0x06, 0x01, 0x80, 0x60, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x04, 0x01, 0xFE, + 0x03, 0xFC, 0x00, 0x10, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, + 0x04, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x03, 0x00, 0x06, + 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, + 0x06, 0x00, 0x08, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x06, + 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, 0x01, 0x80, 0xFF, 0x01, + 0xFE, 0x00, 0x00, 0x10, 0x00, 0x0C, 0x00, 0x07, 0x80, 0x03, 0x60, 0x01, + 0x8C, 0x00, 0xC3, 0x80, 0xE0, 0x60, 0x70, 0x1C, 0x38, 0x03, 0x1C, 0x00, + 0x6E, 0x00, 0x1F, 0x00, 0x02, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xC3, 0x86, 0x0C, 0x18, 0x70, 0xC0, 0x00, 0x3F, 0x80, 0x0F, 0xFF, 0x80, + 0x78, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x18, 0x00, 0x00, 0x60, 0x00, + 0x01, 0x80, 0x00, 0x06, 0x00, 0x00, 0x38, 0x03, 0xFC, 0xC0, 0x7F, 0xFF, + 0x07, 0xC0, 0x0C, 0x38, 0x00, 0x31, 0xC0, 0x01, 0xCE, 0x00, 0x06, 0x30, + 0x00, 0x18, 0xC0, 0x00, 0xE3, 0x00, 0x07, 0x8E, 0x00, 0x7C, 0x1C, 0x0F, + 0x3F, 0x3F, 0xF0, 0xFC, 0x7F, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x30, 0x00, 0x00, 0x06, 0x00, 0x00, + 0x00, 0xC0, 0x00, 0x00, 0x10, 0x00, 0x00, 0x06, 0x07, 0xE0, 0x00, 0xC3, + 0xFF, 0x00, 0x19, 0xC0, 0xF0, 0x03, 0x60, 0x07, 0x00, 0xD8, 0x00, 0x60, + 0x1E, 0x00, 0x0E, 0x03, 0x80, 0x00, 0xC0, 0x60, 0x00, 0x18, 0x0C, 0x00, + 0x03, 0x03, 0x00, 0x00, 0x60, 0x60, 0x00, 0x0C, 0x0C, 0x00, 0x01, 0x81, + 0x80, 0x00, 0x60, 0x70, 0x00, 0x0C, 0x0E, 0x00, 0x03, 0x01, 0xC0, 0x00, + 0x60, 0x3C, 0x00, 0x18, 0x05, 0x80, 0x06, 0x01, 0xB8, 0x01, 0x83, 0xF3, + 0xC1, 0xE0, 0x7E, 0x3F, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x3F, 0x00, + 0x07, 0xFF, 0x30, 0x38, 0x0F, 0xC1, 0x80, 0x1F, 0x0C, 0x00, 0x18, 0x60, + 0x00, 0x63, 0x00, 0x01, 0x9C, 0x00, 0x06, 0x60, 0x00, 0x01, 0x80, 0x00, + 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, 0x0C, + 0x00, 0x00, 0x30, 0x00, 0x00, 0xE0, 0x00, 0x01, 0x80, 0x00, 0xC7, 0x00, + 0x0E, 0x0F, 0x01, 0xF0, 0x1F, 0xFF, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x00, + 0x1F, 0x80, 0x00, 0x0F, 0x80, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x60, 0x00, + 0x00, 0x30, 0x00, 0x00, 0x10, 0x00, 0x00, 0x18, 0x00, 0xFC, 0x0C, 0x01, + 0xFF, 0x86, 0x01, 0xC0, 0xE3, 0x03, 0x80, 0x1B, 0x03, 0x80, 0x05, 0x81, + 0x80, 0x03, 0xC1, 0x80, 0x00, 0xE1, 0x80, 0x00, 0x60, 0xC0, 0x00, 0x30, + 0x60, 0x00, 0x18, 0x60, 0x00, 0x0C, 0x30, 0x00, 0x06, 0x18, 0x00, 0x02, + 0x0C, 0x00, 0x03, 0x06, 0x00, 0x01, 0x83, 0x00, 0x01, 0xC1, 0xC0, 0x01, + 0xE0, 0x60, 0x01, 0xE0, 0x38, 0x01, 0xB0, 0x0F, 0x03, 0x9F, 0x03, 0xFF, + 0x0F, 0x80, 0x7E, 0x00, 0x00, 0x00, 0x3F, 0x00, 0x07, 0xFF, 0x80, 0x78, + 0x0F, 0x03, 0x80, 0x0E, 0x1C, 0x00, 0x18, 0xE0, 0x00, 0x73, 0x00, 0x00, + 0xD8, 0x00, 0x03, 0x60, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, + 0x00, 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x38, 0x00, + 0x00, 0x60, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x03, 0x07, 0x80, 0xF8, + 0x0F, 0xFF, 0x80, 0x0F, 0xF0, 0x00, 0x00, 0x00, 0xFF, 0x80, 0x00, 0xFF, + 0xF0, 0x00, 0xF0, 0x00, 0x00, 0x70, 0x00, 0x00, 0x18, 0x00, 0x00, 0x06, + 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0xC0, 0x00, 0x07, 0xFF, 0xFC, 0x03, + 0xFF, 0xFF, 0x00, 0x03, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x60, 0x00, + 0x00, 0x18, 0x00, 0x00, 0x06, 0x00, 0x00, 0x03, 0x80, 0x00, 0x00, 0xC0, + 0x00, 0x00, 0x30, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, + 0x80, 0x00, 0x00, 0x60, 0x00, 0x00, 0x18, 0x00, 0x00, 0x06, 0x00, 0x00, + 0x01, 0x80, 0x00, 0x00, 0xC0, 0x00, 0x0F, 0xFF, 0xFC, 0x03, 0xFF, 0xFE, + 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFF, 0x87, 0xC1, 0xE0, 0xF3, 0xE1, 0xC0, + 0x1B, 0x01, 0xC0, 0x07, 0x81, 0xC0, 0x03, 0xC0, 0xC0, 0x00, 0xE0, 0xC0, + 0x00, 0x60, 0x60, 0x00, 0x30, 0x60, 0x00, 0x18, 0x30, 0x00, 0x0C, 0x18, + 0x00, 0x06, 0x0C, 0x00, 0x06, 0x06, 0x00, 0x03, 0x03, 0x00, 0x03, 0x81, + 0xC0, 0x01, 0xC0, 0x60, 0x01, 0xC0, 0x38, 0x03, 0x60, 0x0F, 0x07, 0x30, + 0x03, 0xFF, 0x18, 0x00, 0x7E, 0x0C, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x06, + 0x00, 0x00, 0x03, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, 0x80, 0x00, 0x01, + 0x80, 0x00, 0x03, 0x80, 0x03, 0xFF, 0x80, 0x01, 0xFF, 0x00, 0x00, 0x07, + 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, + 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x01, 0x80, 0x00, 0x01, 0x83, 0xF0, 0x01, + 0x8F, 0xF8, 0x01, 0x98, 0x1C, 0x03, 0xB0, 0x0E, 0x03, 0x40, 0x06, 0x03, + 0x80, 0x06, 0x03, 0x00, 0x06, 0x03, 0x00, 0x06, 0x07, 0x00, 0x06, 0x06, + 0x00, 0x0E, 0x06, 0x00, 0x0E, 0x06, 0x00, 0x0E, 0x06, 0x00, 0x0C, 0x0C, + 0x00, 0x0C, 0x0C, 0x00, 0x1C, 0x0C, 0x00, 0x1C, 0x0C, 0x00, 0x18, 0x0C, + 0x00, 0x18, 0x18, 0x00, 0x18, 0xFF, 0x01, 0xFF, 0xFF, 0x01, 0xFF, 0x00, + 0x07, 0x00, 0x00, 0xC0, 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0x80, 0x1F, + 0xF0, 0x00, 0x06, 0x00, 0x01, 0xC0, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, + 0xC0, 0x00, 0x18, 0x00, 0x07, 0x00, 0x00, 0xC0, 0x00, 0x18, 0x00, 0x03, + 0x00, 0x00, 0x60, 0x00, 0x1C, 0x00, 0x03, 0x00, 0x00, 0x60, 0x00, 0x0C, + 0x00, 0x01, 0x80, 0x7F, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x00, 0x70, 0x00, + 0x07, 0x00, 0x00, 0x70, 0x00, 0x06, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xFF, 0x03, 0xFF, 0xF0, + 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, 0x60, 0x00, 0x06, + 0x00, 0x00, 0x60, 0x00, 0x06, 0x00, 0x00, 0xC0, 0x00, 0x0C, 0x00, 0x00, + 0xC0, 0x00, 0x0C, 0x00, 0x01, 0xC0, 0x00, 0x18, 0x00, 0x01, 0x80, 0x00, + 0x18, 0x00, 0x01, 0x80, 0x00, 0x38, 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, + 0x03, 0x00, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, + 0x03, 0x80, 0xFF, 0xF0, 0x0F, 0xFC, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0x60, 0x00, 0x00, 0x60, 0x00, 0x00, 0x60, 0x00, 0x00, 0x60, + 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0xFF, 0x00, 0xC1, + 0xFF, 0x00, 0x80, 0x70, 0x01, 0x80, 0xC0, 0x01, 0x83, 0x80, 0x01, 0x87, + 0x00, 0x01, 0x8C, 0x00, 0x03, 0x38, 0x00, 0x03, 0x70, 0x00, 0x03, 0xF8, + 0x00, 0x03, 0x9C, 0x00, 0x03, 0x0C, 0x00, 0x06, 0x0E, 0x00, 0x06, 0x07, + 0x00, 0x06, 0x03, 0x80, 0x06, 0x01, 0x80, 0x04, 0x00, 0xC0, 0x0C, 0x00, + 0xE0, 0xFC, 0x03, 0xFE, 0xFC, 0x03, 0xFC, 0x01, 0xFF, 0x00, 0x3F, 0xE0, + 0x00, 0x0C, 0x00, 0x03, 0x00, 0x00, 0x60, 0x00, 0x0C, 0x00, 0x01, 0x80, + 0x00, 0x70, 0x00, 0x0C, 0x00, 0x01, 0x80, 0x00, 0x30, 0x00, 0x06, 0x00, + 0x01, 0x80, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, 0xC0, 0x00, 0x18, 0x00, + 0x06, 0x00, 0x00, 0xC0, 0x00, 0x18, 0x00, 0x03, 0x00, 0x00, 0xE0, 0x00, + 0x18, 0x00, 0x03, 0x00, 0x00, 0x60, 0x00, 0x0C, 0x03, 0xFF, 0xFF, 0xFF, + 0xFF, 0xF0, 0x00, 0x1E, 0x07, 0x81, 0xE7, 0xE1, 0xF8, 0x3D, 0x8E, 0xE3, + 0x81, 0xE0, 0xF8, 0x30, 0x38, 0x1E, 0x06, 0x06, 0x03, 0x80, 0xC1, 0x80, + 0x60, 0x18, 0x30, 0x0C, 0x03, 0x06, 0x01, 0x80, 0x60, 0xC0, 0x30, 0x08, + 0x18, 0x0C, 0x03, 0x06, 0x01, 0x80, 0x60, 0xC0, 0x30, 0x0C, 0x18, 0x06, + 0x01, 0x83, 0x00, 0x80, 0x60, 0x40, 0x30, 0x0C, 0x18, 0x06, 0x01, 0x83, + 0x00, 0xC0, 0x30, 0x60, 0x18, 0x06, 0x7F, 0x03, 0xC1, 0xFF, 0xE0, 0xF8, + 0x3E, 0x00, 0x03, 0xE0, 0x1F, 0x1F, 0xF0, 0x3E, 0x60, 0x70, 0x0F, 0x80, + 0x70, 0x3C, 0x00, 0x60, 0x70, 0x00, 0xC0, 0xC0, 0x01, 0x81, 0x80, 0x03, + 0x07, 0x00, 0x06, 0x0C, 0x00, 0x1C, 0x18, 0x00, 0x30, 0x30, 0x00, 0x60, + 0x60, 0x00, 0xC1, 0xC0, 0x01, 0x83, 0x00, 0x06, 0x06, 0x00, 0x0C, 0x0C, + 0x00, 0x18, 0x18, 0x00, 0x30, 0x70, 0x00, 0x67, 0xFC, 0x07, 0xFF, 0xF0, + 0x0F, 0xE0, 0x00, 0x3F, 0x00, 0x07, 0xFF, 0x00, 0x3C, 0x0F, 0x01, 0xC0, + 0x1C, 0x0C, 0x00, 0x38, 0x60, 0x00, 0x63, 0x00, 0x00, 0xDC, 0x00, 0x03, + 0x60, 0x00, 0x0D, 0x80, 0x00, 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, + 0x00, 0x1B, 0x00, 0x00, 0x6C, 0x00, 0x03, 0xB0, 0x00, 0x0C, 0x60, 0x00, + 0x61, 0xC0, 0x03, 0x03, 0x80, 0x38, 0x0F, 0x03, 0xC0, 0x0F, 0xFE, 0x00, + 0x0F, 0xC0, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x1F, 0x8F, 0xFE, 0x00, 0xFC, + 0xE0, 0x78, 0x00, 0xCC, 0x00, 0xE0, 0x06, 0xC0, 0x03, 0x00, 0x3C, 0x00, + 0x1C, 0x01, 0xC0, 0x00, 0x60, 0x0C, 0x00, 0x03, 0x00, 0xE0, 0x00, 0x18, + 0x06, 0x00, 0x00, 0xC0, 0x30, 0x00, 0x06, 0x01, 0x80, 0x00, 0x30, 0x0C, + 0x00, 0x03, 0x00, 0xE0, 0x00, 0x18, 0x07, 0x00, 0x01, 0x80, 0x3C, 0x00, + 0x1C, 0x01, 0xE0, 0x01, 0xC0, 0x0D, 0x80, 0x1C, 0x00, 0xCF, 0x03, 0xC0, + 0x06, 0x3F, 0xF8, 0x00, 0x30, 0x7F, 0x00, 0x01, 0x80, 0x00, 0x00, 0x0C, + 0x00, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x30, 0x00, + 0x00, 0x01, 0x80, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x07, 0xFF, 0x00, 0x00, + 0x7F, 0xF8, 0x00, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7F, 0xE1, 0xF0, 0x78, + 0x1C, 0xFC, 0x38, 0x01, 0xB0, 0x1C, 0x00, 0x2C, 0x0E, 0x00, 0x0F, 0x03, + 0x00, 0x01, 0xC1, 0x80, 0x00, 0x60, 0x60, 0x00, 0x18, 0x30, 0x00, 0x06, + 0x0C, 0x00, 0x01, 0x83, 0x00, 0x00, 0x60, 0xC0, 0x00, 0x30, 0x30, 0x00, + 0x0C, 0x0C, 0x00, 0x07, 0x03, 0x80, 0x03, 0xC0, 0x60, 0x01, 0xB0, 0x1C, + 0x00, 0xD8, 0x03, 0xC0, 0xE6, 0x00, 0x7F, 0xF1, 0x80, 0x07, 0xE0, 0x60, + 0x00, 0x00, 0x18, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, + 0xC0, 0x00, 0x00, 0x30, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, + 0x7F, 0xF8, 0x00, 0x1F, 0xFE, 0x00, 0x07, 0xF0, 0x3E, 0x03, 0xF8, 0x7F, + 0xC0, 0x18, 0xF0, 0x60, 0x0C, 0xE0, 0x00, 0x07, 0xE0, 0x00, 0x03, 0xC0, + 0x00, 0x03, 0xC0, 0x00, 0x01, 0x80, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x60, + 0x00, 0x00, 0x30, 0x00, 0x00, 0x38, 0x00, 0x00, 0x18, 0x00, 0x00, 0x0C, + 0x00, 0x00, 0x06, 0x00, 0x00, 0x03, 0x00, 0x00, 0x03, 0x80, 0x00, 0x01, + 0x80, 0x00, 0x3F, 0xFF, 0xF0, 0x1F, 0xFF, 0xF0, 0x00, 0x00, 0x3F, 0x00, + 0x0F, 0xFE, 0xC0, 0xF0, 0x3E, 0x0E, 0x00, 0x70, 0xE0, 0x01, 0x06, 0x00, + 0x08, 0x30, 0x00, 0x41, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x3F, 0xF0, 0x00, + 0x3F, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x18, 0x00, 0x00, + 0xCC, 0x00, 0x06, 0x60, 0x00, 0x33, 0x00, 0x03, 0x3C, 0x00, 0x71, 0xF8, + 0x0F, 0x0D, 0xFF, 0xF0, 0x01, 0xFC, 0x00, 0x03, 0x00, 0x03, 0x00, 0x01, + 0x80, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x70, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, + 0x0C, 0x00, 0x06, 0x00, 0x06, 0x00, 0x03, 0x00, 0x01, 0x80, 0x00, 0xC0, + 0x00, 0xE0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x18, 0x00, 0x0C, 0x00, 0x0E, + 0x00, 0x06, 0x00, 0x03, 0x00, 0x01, 0x80, 0x00, 0xC0, 0x03, 0x38, 0x0F, + 0x9F, 0xFF, 0x03, 0xF8, 0x00, 0xFC, 0x03, 0xFF, 0xE0, 0x1F, 0xC6, 0x00, + 0x0C, 0x30, 0x00, 0x61, 0x80, 0x03, 0x0C, 0x00, 0x18, 0x60, 0x01, 0x86, + 0x00, 0x0C, 0x30, 0x00, 0x61, 0x80, 0x03, 0x0C, 0x00, 0x18, 0x60, 0x01, + 0x86, 0x00, 0x0C, 0x30, 0x00, 0x61, 0x80, 0x03, 0x0C, 0x00, 0x38, 0x60, + 0x07, 0x83, 0x80, 0x6C, 0x1E, 0x1E, 0x7C, 0x7F, 0xE3, 0xE0, 0xF8, 0x00, + 0x00, 0x7F, 0xC0, 0xFF, 0xFF, 0xF0, 0x3F, 0xF1, 0xC0, 0x00, 0xC0, 0x30, + 0x00, 0x60, 0x0C, 0x00, 0x18, 0x03, 0x00, 0x0C, 0x00, 0xE0, 0x06, 0x00, + 0x18, 0x01, 0x80, 0x06, 0x00, 0xC0, 0x01, 0x80, 0x30, 0x00, 0x60, 0x18, + 0x00, 0x0C, 0x0C, 0x00, 0x03, 0x03, 0x00, 0x00, 0xC1, 0x80, 0x00, 0x30, + 0xC0, 0x00, 0x06, 0x30, 0x00, 0x01, 0x98, 0x00, 0x00, 0x6C, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x07, 0x80, 0x00, 0xFE, 0x00, 0x7F, 0xFF, 0x00, 0x3F, + 0xCC, 0x00, 0x03, 0x06, 0x00, 0x01, 0x83, 0x00, 0x01, 0x81, 0x81, 0x80, + 0xC0, 0xC1, 0xE0, 0x60, 0x60, 0xF0, 0x60, 0x30, 0xD8, 0x30, 0x18, 0x6C, + 0x30, 0x0C, 0x66, 0x18, 0x06, 0x33, 0x18, 0x03, 0x31, 0x8C, 0x01, 0x98, + 0x66, 0x00, 0xD8, 0x36, 0x00, 0x6C, 0x1B, 0x00, 0x3C, 0x0F, 0x00, 0x1E, + 0x07, 0x80, 0x0E, 0x03, 0x80, 0x07, 0x01, 0xC0, 0x00, 0x07, 0xF0, 0x3F, + 0xC3, 0xFC, 0x0F, 0xF0, 0x38, 0x00, 0x60, 0x07, 0x00, 0x70, 0x00, 0xE0, + 0x38, 0x00, 0x18, 0x1C, 0x00, 0x03, 0x0C, 0x00, 0x00, 0xEE, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x03, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xDC, 0x00, + 0x00, 0xE3, 0x80, 0x00, 0x70, 0x70, 0x00, 0x38, 0x0E, 0x00, 0x18, 0x01, + 0x80, 0x1C, 0x00, 0x30, 0x0E, 0x00, 0x0E, 0x0F, 0xF0, 0x3F, 0xE3, 0xFC, + 0x0F, 0xF8, 0x03, 0xF8, 0x07, 0xF8, 0x3F, 0xC0, 0x3F, 0xC0, 0x60, 0x00, + 0x30, 0x01, 0x80, 0x01, 0x80, 0x0C, 0x00, 0x18, 0x00, 0x60, 0x01, 0x80, + 0x03, 0x80, 0x0C, 0x00, 0x0C, 0x00, 0xC0, 0x00, 0x60, 0x0C, 0x00, 0x03, + 0x00, 0x60, 0x00, 0x0C, 0x06, 0x00, 0x00, 0x60, 0x60, 0x00, 0x03, 0x06, + 0x00, 0x00, 0x1C, 0x30, 0x00, 0x00, 0x63, 0x00, 0x00, 0x03, 0x30, 0x00, + 0x00, 0x19, 0x80, 0x00, 0x00, 0x78, 0x00, 0x00, 0x03, 0x80, 0x00, 0x00, + 0x1C, 0x00, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x60, + 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x03, 0x00, 0x00, + 0x00, 0x30, 0x00, 0x01, 0xFF, 0xF8, 0x00, 0x0F, 0xFF, 0x80, 0x00, 0x00, + 0x07, 0xFF, 0xF8, 0x3F, 0xFF, 0xC3, 0x00, 0x0C, 0x18, 0x00, 0xC0, 0xC0, + 0x0C, 0x00, 0x00, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, + 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x18, 0x00, 0x01, 0x80, + 0x00, 0x18, 0x00, 0x01, 0x80, 0x0C, 0x18, 0x00, 0x61, 0x80, 0x02, 0x1F, + 0xFF, 0xF0, 0xFF, 0xFF, 0x80, 0x00, 0x0E, 0x00, 0x7C, 0x01, 0xC0, 0x03, + 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, 0x01, 0xC0, 0x03, 0x00, + 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x60, 0x01, 0xC0, 0x0F, 0x00, 0xF8, + 0x01, 0xF0, 0x00, 0x30, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x03, 0x80, + 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0xE0, 0x01, 0x80, 0x03, + 0x00, 0x06, 0x00, 0x0E, 0x00, 0x0F, 0x00, 0x0E, 0x00, 0x01, 0x80, 0xC0, + 0x60, 0x60, 0x30, 0x18, 0x0C, 0x06, 0x06, 0x03, 0x01, 0x80, 0xC0, 0x40, + 0x60, 0x30, 0x18, 0x0C, 0x0C, 0x06, 0x03, 0x01, 0x80, 0xC0, 0xC0, 0x60, + 0x30, 0x18, 0x08, 0x0C, 0x06, 0x03, 0x01, 0x80, 0x80, 0xC0, 0x60, 0x30, + 0x00, 0x01, 0xC0, 0x03, 0xC0, 0x01, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x06, + 0x00, 0x0C, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, + 0x0C, 0x00, 0x18, 0x00, 0x38, 0x00, 0x38, 0x00, 0x3E, 0x00, 0x7C, 0x03, + 0xC0, 0x0E, 0x00, 0x18, 0x00, 0x70, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, + 0x06, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x03, 0x00, 0x0E, + 0x00, 0xF8, 0x01, 0xC0, 0x00, 0x0F, 0x00, 0x01, 0xFC, 0x03, 0x70, 0xE0, + 0x7E, 0x07, 0x1E, 0xC0, 0x3F, 0x80, 0x01, 0xE0 }; + +const GFXglyph FreeMonoOblique24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 28, 0, 1 }, // 0x20 ' ' + { 0, 10, 30, 28, 12, -28 }, // 0x21 '!' + { 38, 16, 14, 28, 10, -28 }, // 0x22 '"' + { 66, 22, 32, 28, 6, -29 }, // 0x23 '#' + { 154, 21, 33, 28, 6, -29 }, // 0x24 '$' + { 241, 22, 29, 28, 6, -27 }, // 0x25 '%' + { 321, 19, 25, 28, 6, -23 }, // 0x26 '&' + { 381, 7, 14, 28, 16, -28 }, // 0x27 ''' + { 394, 11, 34, 28, 16, -27 }, // 0x28 '(' + { 441, 11, 34, 28, 7, -27 }, // 0x29 ')' + { 488, 18, 17, 28, 10, -28 }, // 0x2A '*' + { 527, 22, 22, 28, 6, -23 }, // 0x2B '+' + { 588, 12, 14, 28, 5, -6 }, // 0x2C ',' + { 609, 22, 2, 28, 6, -13 }, // 0x2D '-' + { 615, 7, 6, 28, 11, -4 }, // 0x2E '.' + { 621, 24, 35, 28, 5, -30 }, // 0x2F '/' + { 726, 20, 30, 28, 7, -28 }, // 0x30 '0' + { 801, 17, 29, 28, 6, -28 }, // 0x31 '1' + { 863, 23, 29, 28, 4, -28 }, // 0x32 '2' + { 947, 22, 30, 28, 5, -28 }, // 0x33 '3' + { 1030, 19, 28, 28, 7, -27 }, // 0x34 '4' + { 1097, 21, 29, 28, 6, -27 }, // 0x35 '5' + { 1174, 21, 30, 28, 9, -28 }, // 0x36 '6' + { 1253, 18, 28, 28, 10, -27 }, // 0x37 '7' + { 1316, 20, 30, 28, 7, -28 }, // 0x38 '8' + { 1391, 22, 30, 28, 6, -28 }, // 0x39 '9' + { 1474, 10, 21, 28, 11, -19 }, // 0x3A ':' + { 1501, 15, 27, 28, 5, -19 }, // 0x3B ';' + { 1552, 23, 22, 28, 6, -23 }, // 0x3C '<' + { 1616, 25, 9, 28, 4, -17 }, // 0x3D '=' + { 1645, 24, 22, 28, 4, -23 }, // 0x3E '>' + { 1711, 16, 28, 28, 11, -26 }, // 0x3F '?' + { 1767, 19, 32, 28, 7, -28 }, // 0x40 '@' + { 1843, 27, 26, 28, 1, -25 }, // 0x41 'A' + { 1931, 26, 26, 28, 2, -25 }, // 0x42 'B' + { 2016, 25, 28, 28, 5, -26 }, // 0x43 'C' + { 2104, 26, 26, 28, 2, -25 }, // 0x44 'D' + { 2189, 27, 26, 28, 2, -25 }, // 0x45 'E' + { 2277, 28, 26, 28, 2, -25 }, // 0x46 'F' + { 2368, 25, 28, 28, 5, -26 }, // 0x47 'G' + { 2456, 27, 26, 28, 3, -25 }, // 0x48 'H' + { 2544, 22, 26, 28, 6, -25 }, // 0x49 'I' + { 2616, 28, 27, 28, 5, -25 }, // 0x4A 'J' + { 2711, 29, 26, 28, 2, -25 }, // 0x4B 'K' + { 2806, 25, 26, 28, 3, -25 }, // 0x4C 'L' + { 2888, 32, 26, 28, 1, -25 }, // 0x4D 'M' + { 2992, 30, 26, 28, 2, -25 }, // 0x4E 'N' + { 3090, 24, 28, 28, 5, -26 }, // 0x4F 'O' + { 3174, 26, 26, 28, 2, -25 }, // 0x50 'P' + { 3259, 24, 32, 28, 5, -26 }, // 0x51 'Q' + { 3355, 26, 26, 28, 2, -25 }, // 0x52 'R' + { 3440, 24, 28, 28, 5, -26 }, // 0x53 'S' + { 3524, 24, 26, 28, 7, -25 }, // 0x54 'T' + { 3602, 26, 27, 28, 6, -25 }, // 0x55 'U' + { 3690, 27, 26, 28, 6, -25 }, // 0x56 'V' + { 3778, 27, 26, 28, 6, -25 }, // 0x57 'W' + { 3866, 29, 26, 28, 2, -25 }, // 0x58 'X' + { 3961, 24, 26, 28, 7, -25 }, // 0x59 'Y' + { 4039, 23, 26, 28, 5, -25 }, // 0x5A 'Z' + { 4114, 15, 34, 28, 12, -27 }, // 0x5B '[' + { 4178, 10, 35, 28, 12, -30 }, // 0x5C '\' + { 4222, 15, 34, 28, 6, -27 }, // 0x5D ']' + { 4286, 18, 12, 28, 9, -28 }, // 0x5E '^' + { 4313, 28, 2, 28, -1, 5 }, // 0x5F '_' + { 4320, 6, 7, 28, 13, -29 }, // 0x60 '`' + { 4326, 22, 22, 28, 4, -20 }, // 0x61 'a' + { 4387, 27, 29, 28, 1, -27 }, // 0x62 'b' + { 4485, 22, 22, 28, 6, -20 }, // 0x63 'c' + { 4546, 25, 29, 28, 5, -27 }, // 0x64 'd' + { 4637, 22, 22, 28, 5, -20 }, // 0x65 'e' + { 4698, 26, 28, 28, 5, -27 }, // 0x66 'f' + { 4789, 25, 30, 28, 5, -20 }, // 0x67 'g' + { 4883, 24, 28, 28, 3, -27 }, // 0x68 'h' + { 4967, 19, 29, 28, 5, -28 }, // 0x69 'i' + { 5036, 20, 38, 28, 4, -28 }, // 0x6A 'j' + { 5131, 24, 28, 28, 3, -27 }, // 0x6B 'k' + { 5215, 19, 28, 28, 5, -27 }, // 0x6C 'l' + { 5282, 27, 21, 28, 1, -20 }, // 0x6D 'm' + { 5353, 23, 21, 28, 3, -20 }, // 0x6E 'n' + { 5414, 22, 22, 28, 5, -20 }, // 0x6F 'o' + { 5475, 29, 30, 28, -1, -20 }, // 0x70 'p' + { 5584, 26, 30, 28, 5, -20 }, // 0x71 'q' + { 5682, 25, 20, 28, 4, -19 }, // 0x72 'r' + { 5745, 21, 22, 28, 5, -20 }, // 0x73 's' + { 5803, 17, 27, 28, 7, -25 }, // 0x74 't' + { 5861, 21, 21, 28, 6, -19 }, // 0x75 'u' + { 5917, 26, 20, 28, 5, -19 }, // 0x76 'v' + { 5982, 25, 20, 28, 6, -19 }, // 0x77 'w' + { 6045, 26, 20, 28, 3, -19 }, // 0x78 'x' + { 6110, 29, 29, 28, 1, -19 }, // 0x79 'y' + { 6216, 21, 20, 28, 5, -19 }, // 0x7A 'z' + { 6269, 15, 34, 28, 10, -27 }, // 0x7B '{' + { 6333, 9, 35, 28, 12, -28 }, // 0x7C '|' + { 6373, 15, 34, 28, 8, -27 }, // 0x7D '}' + { 6437, 20, 6, 28, 7, -15 } }; // 0x7E '~' + +const GFXfont FreeMonoOblique24pt7b PROGMEM = { + (uint8_t *)FreeMonoOblique24pt7bBitmaps, + (GFXglyph *)FreeMonoOblique24pt7bGlyphs, + 0x20, 0x7E, 47 }; + +// Approx. 7124 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique9pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique9pt7b.h new file mode 100644 index 0000000..a00ca82 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique9pt7b.h @@ -0,0 +1,187 @@ +const uint8_t FreeMonoOblique9pt7bBitmaps[] PROGMEM = { + 0x11, 0x22, 0x24, 0x40, 0x00, 0xC0, 0xDE, 0xE5, 0x29, 0x00, 0x09, 0x05, + 0x02, 0x82, 0x47, 0xF8, 0xA0, 0x51, 0xFE, 0x28, 0x14, 0x0A, 0x09, 0x00, + 0x08, 0x1D, 0x23, 0x40, 0x70, 0x1C, 0x02, 0x82, 0x84, 0x78, 0x20, 0x20, + 0x1C, 0x11, 0x08, 0x83, 0x80, 0x18, 0x71, 0xC0, 0x1C, 0x11, 0x08, 0x83, + 0x80, 0x1E, 0x60, 0x81, 0x03, 0x0A, 0x65, 0x46, 0x88, 0xE8, 0xFA, 0x80, + 0x12, 0x24, 0x48, 0x88, 0x88, 0x88, 0x80, 0x01, 0x11, 0x11, 0x11, 0x22, + 0x44, 0x80, 0x10, 0x22, 0x5B, 0xC3, 0x0A, 0x22, 0x00, 0x04, 0x02, 0x02, + 0x1F, 0xF0, 0x80, 0x40, 0x20, 0x00, 0x36, 0x4C, 0x80, 0xFF, 0x80, 0xF0, + 0x00, 0x80, 0x80, 0x40, 0x40, 0x40, 0x20, 0x20, 0x20, 0x10, 0x10, 0x10, + 0x08, 0x08, 0x00, 0x1C, 0x45, 0x0A, 0x18, 0x30, 0x61, 0x42, 0x85, 0x11, + 0xC0, 0x04, 0x38, 0x90, 0x20, 0x81, 0x02, 0x04, 0x08, 0x23, 0xF8, 0x07, + 0x04, 0xC4, 0x20, 0x10, 0x10, 0x30, 0x20, 0x20, 0x60, 0x40, 0x3F, 0x80, + 0x0F, 0x00, 0x40, 0x20, 0x20, 0x60, 0x18, 0x04, 0x02, 0x01, 0x43, 0x1E, + 0x00, 0x03, 0x05, 0x0A, 0x12, 0x22, 0x22, 0x42, 0x7F, 0x04, 0x04, 0x1E, + 0x1F, 0x88, 0x08, 0x05, 0xC3, 0x30, 0x08, 0x04, 0x02, 0x02, 0x42, 0x1E, + 0x00, 0x07, 0x18, 0x20, 0x40, 0x5C, 0xA6, 0xC2, 0x82, 0x82, 0xC4, 0x78, + 0xFF, 0x04, 0x10, 0x20, 0x82, 0x04, 0x10, 0x20, 0x81, 0x00, 0x1E, 0x23, + 0x41, 0x41, 0x62, 0x1C, 0x66, 0x82, 0x82, 0x84, 0x78, 0x1E, 0x23, 0x41, + 0x41, 0x43, 0x65, 0x3A, 0x02, 0x04, 0x18, 0xE0, 0x6C, 0x00, 0x36, 0x18, + 0xC0, 0x00, 0x19, 0x8C, 0xC4, 0x00, 0x01, 0x83, 0x06, 0x0C, 0x06, 0x00, + 0x80, 0x30, 0x04, 0xFF, 0x80, 0x00, 0x1F, 0xF0, 0x20, 0x0C, 0x01, 0x00, + 0x60, 0x20, 0x60, 0xC1, 0x80, 0x3D, 0x8E, 0x08, 0x10, 0xC6, 0x08, 0x00, + 0x01, 0x80, 0x1C, 0x45, 0x0A, 0x79, 0x34, 0x69, 0x4E, 0x81, 0x03, 0x03, + 0xC0, 0x0F, 0x00, 0x60, 0x12, 0x02, 0x40, 0x88, 0x21, 0x07, 0xE1, 0x04, + 0x20, 0x5E, 0x3C, 0x3F, 0x84, 0x11, 0x04, 0x82, 0x3F, 0x88, 0x32, 0x04, + 0x81, 0x60, 0xBF, 0xC0, 0x1E, 0x98, 0xD0, 0x28, 0x08, 0x04, 0x02, 0x01, + 0x00, 0x41, 0x1F, 0x00, 0x3F, 0x0C, 0x22, 0x04, 0x81, 0x20, 0x48, 0x12, + 0x09, 0x02, 0x43, 0x3F, 0x00, 0x3F, 0xC4, 0x11, 0x00, 0x88, 0x3E, 0x08, + 0x82, 0x00, 0x82, 0x60, 0xBF, 0xE0, 0x3F, 0xE2, 0x08, 0x40, 0x11, 0x03, + 0xE0, 0x44, 0x08, 0x01, 0x00, 0x60, 0x1F, 0x00, 0x1E, 0x98, 0xD0, 0x08, + 0x08, 0x04, 0x7A, 0x05, 0x02, 0x41, 0x1F, 0x00, 0x3D, 0xE2, 0x18, 0x42, + 0x08, 0x43, 0xF8, 0x41, 0x08, 0x21, 0x08, 0x21, 0x1E, 0xF0, 0x3F, 0x82, + 0x02, 0x01, 0x00, 0x80, 0x40, 0x20, 0x20, 0x10, 0x7F, 0x00, 0x0F, 0xE0, + 0x20, 0x04, 0x00, 0x80, 0x10, 0x02, 0x20, 0x84, 0x10, 0x84, 0x0F, 0x00, + 0x3C, 0xE2, 0x10, 0x44, 0x11, 0x02, 0xC0, 0x64, 0x08, 0x81, 0x08, 0x61, + 0x1E, 0x38, 0x3E, 0x02, 0x00, 0x80, 0x20, 0x10, 0x04, 0x01, 0x04, 0x42, + 0x10, 0xBF, 0xE0, 0x38, 0x38, 0xC3, 0x05, 0x28, 0x29, 0x42, 0x52, 0x13, + 0x10, 0x99, 0x84, 0x08, 0x20, 0x47, 0x8F, 0x00, 0x70, 0xE6, 0x08, 0xA1, + 0x14, 0x22, 0x48, 0x49, 0x11, 0x22, 0x14, 0x43, 0x1E, 0x20, 0x1E, 0x18, + 0x90, 0x28, 0x18, 0x0C, 0x06, 0x05, 0x02, 0x46, 0x1E, 0x00, 0x3F, 0x84, + 0x31, 0x04, 0x81, 0x20, 0x8F, 0xC2, 0x00, 0x80, 0x60, 0x3E, 0x00, 0x1E, + 0x18, 0x90, 0x28, 0x18, 0x0C, 0x06, 0x05, 0x02, 0x46, 0x1E, 0x08, 0x0F, + 0x44, 0x60, 0x3F, 0x84, 0x31, 0x04, 0x81, 0x20, 0x8F, 0xC2, 0x10, 0x84, + 0x60, 0xBC, 0x10, 0x0F, 0x88, 0xC8, 0x24, 0x01, 0x80, 0x38, 0x05, 0x02, + 0xC2, 0x5E, 0x00, 0xFF, 0xC4, 0x44, 0x02, 0x01, 0x00, 0x80, 0x40, 0x60, + 0x20, 0x7E, 0x00, 0xF1, 0xD0, 0x24, 0x09, 0x02, 0x41, 0xA0, 0x48, 0x12, + 0x04, 0xC6, 0x1F, 0x00, 0xF1, 0xE8, 0x11, 0x02, 0x20, 0x82, 0x20, 0x44, + 0x09, 0x01, 0x40, 0x28, 0x02, 0x00, 0xF1, 0xE8, 0x09, 0x12, 0x26, 0x45, + 0x48, 0xAA, 0x29, 0x45, 0x28, 0xC6, 0x18, 0xC0, 0x38, 0xE2, 0x08, 0x26, + 0x05, 0x00, 0x40, 0x18, 0x04, 0x81, 0x08, 0x41, 0x1C, 0x70, 0xE3, 0xA0, + 0x90, 0x84, 0x81, 0x80, 0x80, 0x40, 0x20, 0x20, 0x7E, 0x00, 0x3F, 0x90, + 0x88, 0x80, 0x80, 0x80, 0x80, 0x80, 0x82, 0x82, 0x7F, 0x00, 0x39, 0x08, + 0x44, 0x21, 0x08, 0x42, 0x21, 0x0E, 0x00, 0x88, 0x44, 0x44, 0x22, 0x22, + 0x11, 0x11, 0x38, 0x42, 0x11, 0x08, 0x42, 0x10, 0x84, 0x2E, 0x00, 0x08, + 0x28, 0x92, 0x18, 0x20, 0xFF, 0xC0, 0xA4, 0x3E, 0x00, 0x80, 0x47, 0xA4, + 0x34, 0x12, 0x18, 0xF7, 0x38, 0x01, 0x00, 0x40, 0x09, 0xE1, 0xC6, 0x20, + 0x44, 0x09, 0x01, 0x30, 0x46, 0x13, 0xBC, 0x00, 0x1F, 0x48, 0x74, 0x0A, + 0x00, 0x80, 0x20, 0x0C, 0x18, 0xF8, 0x01, 0x80, 0x40, 0x23, 0x96, 0x32, + 0x0A, 0x05, 0x02, 0x81, 0x61, 0x1F, 0xE0, 0x1F, 0x30, 0xD0, 0x3F, 0xF8, + 0x04, 0x01, 0x00, 0x7C, 0x07, 0xC3, 0x00, 0x80, 0xFE, 0x10, 0x04, 0x01, + 0x00, 0x40, 0x10, 0x08, 0x0F, 0xE0, 0x1D, 0xD8, 0xC4, 0x12, 0x04, 0x82, + 0x20, 0x8C, 0x61, 0xE8, 0x02, 0x01, 0x07, 0x80, 0x30, 0x04, 0x01, 0x00, + 0x5C, 0x38, 0x88, 0x22, 0x08, 0x82, 0x21, 0x18, 0x4F, 0x3C, 0x04, 0x04, + 0x00, 0x38, 0x08, 0x08, 0x08, 0x08, 0x10, 0x10, 0xFF, 0x01, 0x00, 0x80, + 0x03, 0xF0, 0x10, 0x08, 0x04, 0x02, 0x02, 0x01, 0x00, 0x80, 0x40, 0x47, + 0xC0, 0x38, 0x08, 0x04, 0x02, 0x71, 0x20, 0xA0, 0xA0, 0x68, 0x24, 0x11, + 0x38, 0xE0, 0x3C, 0x04, 0x04, 0x08, 0x08, 0x08, 0x08, 0x08, 0x10, 0x10, + 0xFF, 0x3E, 0xE2, 0x64, 0x88, 0x91, 0x12, 0x24, 0x48, 0x91, 0x17, 0x33, + 0x37, 0x14, 0x4C, 0x24, 0x12, 0x09, 0x08, 0x85, 0xE3, 0x1E, 0x10, 0x90, + 0x30, 0x18, 0x0C, 0x0B, 0x08, 0x78, 0x33, 0xC3, 0x8C, 0x40, 0x88, 0x12, + 0x02, 0x60, 0x8C, 0x31, 0x78, 0x20, 0x08, 0x03, 0xE0, 0x00, 0x1C, 0xD8, + 0xC4, 0x12, 0x04, 0x81, 0x20, 0x4C, 0x21, 0xF8, 0x02, 0x00, 0x81, 0xF0, + 0x73, 0x8E, 0x04, 0x04, 0x02, 0x01, 0x00, 0x81, 0xFC, 0x1F, 0x61, 0x40, + 0x3C, 0x03, 0x81, 0x82, 0xFC, 0x10, 0x63, 0xF9, 0x02, 0x04, 0x10, 0x20, + 0x40, 0x7C, 0xE3, 0x10, 0x90, 0x48, 0x24, 0x22, 0x11, 0x18, 0xF6, 0xF3, + 0xD0, 0x44, 0x10, 0x88, 0x24, 0x09, 0x02, 0x80, 0x40, 0xE1, 0xD0, 0x24, + 0x91, 0x24, 0x55, 0x19, 0x86, 0x61, 0x10, 0x39, 0xC4, 0x20, 0xB0, 0x30, + 0x0C, 0x04, 0x86, 0x13, 0x8E, 0x3C, 0x71, 0x04, 0x10, 0x40, 0x88, 0x09, + 0x00, 0xA0, 0x06, 0x00, 0x40, 0x08, 0x01, 0x00, 0xFC, 0x00, 0x7F, 0x42, + 0x04, 0x08, 0x10, 0x20, 0x42, 0xFE, 0x0C, 0x41, 0x04, 0x30, 0x8C, 0x08, + 0x21, 0x04, 0x10, 0x60, 0x24, 0x94, 0x92, 0x52, 0x40, 0x18, 0x20, 0x82, + 0x10, 0x40, 0xC4, 0x10, 0x82, 0x08, 0xC0, 0x61, 0x24, 0x30 }; + +const GFXglyph FreeMonoOblique9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 11, 0, 1 }, // 0x20 ' ' + { 0, 4, 11, 11, 4, -10 }, // 0x21 '!' + { 6, 5, 5, 11, 4, -10 }, // 0x22 '"' + { 10, 9, 12, 11, 2, -10 }, // 0x23 '#' + { 24, 8, 12, 11, 3, -10 }, // 0x24 '$' + { 36, 9, 11, 11, 2, -10 }, // 0x25 '%' + { 49, 7, 10, 11, 2, -9 }, // 0x26 '&' + { 58, 2, 5, 11, 6, -10 }, // 0x27 ''' + { 60, 4, 13, 11, 6, -10 }, // 0x28 '(' + { 67, 4, 13, 11, 3, -10 }, // 0x29 ')' + { 74, 7, 7, 11, 4, -10 }, // 0x2A '*' + { 81, 9, 8, 11, 2, -8 }, // 0x2B '+' + { 90, 4, 5, 11, 2, -1 }, // 0x2C ',' + { 93, 9, 1, 11, 2, -5 }, // 0x2D '-' + { 95, 2, 2, 11, 4, -1 }, // 0x2E '.' + { 96, 9, 13, 11, 2, -11 }, // 0x2F '/' + { 111, 7, 11, 11, 3, -10 }, // 0x30 '0' + { 121, 7, 11, 11, 2, -10 }, // 0x31 '1' + { 131, 9, 11, 11, 2, -10 }, // 0x32 '2' + { 144, 9, 11, 11, 2, -10 }, // 0x33 '3' + { 157, 8, 11, 11, 2, -10 }, // 0x34 '4' + { 168, 9, 11, 11, 2, -10 }, // 0x35 '5' + { 181, 8, 11, 11, 3, -10 }, // 0x36 '6' + { 192, 7, 11, 11, 4, -10 }, // 0x37 '7' + { 202, 8, 11, 11, 3, -10 }, // 0x38 '8' + { 213, 8, 11, 11, 3, -10 }, // 0x39 '9' + { 224, 3, 8, 11, 4, -7 }, // 0x3A ':' + { 227, 5, 11, 11, 2, -7 }, // 0x3B ';' + { 234, 9, 8, 11, 2, -8 }, // 0x3C '<' + { 243, 9, 4, 11, 2, -6 }, // 0x3D '=' + { 248, 9, 8, 11, 2, -8 }, // 0x3E '>' + { 257, 7, 10, 11, 4, -9 }, // 0x3F '?' + { 266, 7, 12, 11, 3, -10 }, // 0x40 '@' + { 277, 11, 10, 11, 0, -9 }, // 0x41 'A' + { 291, 10, 10, 11, 1, -9 }, // 0x42 'B' + { 304, 9, 10, 11, 2, -9 }, // 0x43 'C' + { 316, 10, 10, 11, 1, -9 }, // 0x44 'D' + { 329, 10, 10, 11, 1, -9 }, // 0x45 'E' + { 342, 11, 10, 11, 1, -9 }, // 0x46 'F' + { 356, 9, 10, 11, 2, -9 }, // 0x47 'G' + { 368, 11, 10, 11, 1, -9 }, // 0x48 'H' + { 382, 9, 10, 11, 2, -9 }, // 0x49 'I' + { 394, 11, 10, 11, 2, -9 }, // 0x4A 'J' + { 408, 11, 10, 11, 1, -9 }, // 0x4B 'K' + { 422, 10, 10, 11, 1, -9 }, // 0x4C 'L' + { 435, 13, 10, 11, 0, -9 }, // 0x4D 'M' + { 452, 11, 10, 11, 1, -9 }, // 0x4E 'N' + { 466, 9, 10, 11, 2, -9 }, // 0x4F 'O' + { 478, 10, 10, 11, 1, -9 }, // 0x50 'P' + { 491, 9, 13, 11, 2, -9 }, // 0x51 'Q' + { 506, 10, 10, 11, 1, -9 }, // 0x52 'R' + { 519, 9, 10, 11, 2, -9 }, // 0x53 'S' + { 531, 9, 10, 11, 3, -9 }, // 0x54 'T' + { 543, 10, 10, 11, 2, -9 }, // 0x55 'U' + { 556, 11, 10, 11, 2, -9 }, // 0x56 'V' + { 570, 11, 10, 11, 2, -9 }, // 0x57 'W' + { 584, 11, 10, 11, 1, -9 }, // 0x58 'X' + { 598, 9, 10, 11, 3, -9 }, // 0x59 'Y' + { 610, 9, 10, 11, 2, -9 }, // 0x5A 'Z' + { 622, 5, 13, 11, 5, -10 }, // 0x5B '[' + { 631, 4, 14, 11, 4, -11 }, // 0x5C '\' + { 638, 5, 13, 11, 2, -10 }, // 0x5D ']' + { 647, 7, 5, 11, 3, -10 }, // 0x5E '^' + { 652, 11, 1, 11, 0, 2 }, // 0x5F '_' + { 654, 2, 3, 11, 5, -11 }, // 0x60 '`' + { 655, 9, 8, 11, 2, -7 }, // 0x61 'a' + { 664, 11, 11, 11, 0, -10 }, // 0x62 'b' + { 680, 10, 8, 11, 2, -7 }, // 0x63 'c' + { 690, 9, 11, 11, 2, -10 }, // 0x64 'd' + { 703, 9, 8, 11, 2, -7 }, // 0x65 'e' + { 712, 10, 11, 11, 2, -10 }, // 0x66 'f' + { 726, 10, 11, 11, 2, -7 }, // 0x67 'g' + { 740, 10, 11, 11, 1, -10 }, // 0x68 'h' + { 754, 8, 11, 11, 2, -10 }, // 0x69 'i' + { 765, 9, 14, 11, 1, -10 }, // 0x6A 'j' + { 781, 9, 11, 11, 1, -10 }, // 0x6B 'k' + { 794, 8, 11, 11, 2, -10 }, // 0x6C 'l' + { 805, 11, 8, 11, 0, -7 }, // 0x6D 'm' + { 816, 9, 8, 11, 1, -7 }, // 0x6E 'n' + { 825, 9, 8, 11, 2, -7 }, // 0x6F 'o' + { 834, 11, 11, 11, 0, -7 }, // 0x70 'p' + { 850, 10, 11, 11, 2, -7 }, // 0x71 'q' + { 864, 9, 8, 11, 2, -7 }, // 0x72 'r' + { 873, 8, 8, 11, 2, -7 }, // 0x73 's' + { 881, 7, 10, 11, 2, -9 }, // 0x74 't' + { 890, 9, 8, 11, 2, -7 }, // 0x75 'u' + { 899, 10, 8, 11, 2, -7 }, // 0x76 'v' + { 909, 10, 8, 11, 2, -7 }, // 0x77 'w' + { 919, 10, 8, 11, 1, -7 }, // 0x78 'x' + { 929, 12, 11, 11, 0, -7 }, // 0x79 'y' + { 946, 8, 8, 11, 2, -7 }, // 0x7A 'z' + { 954, 6, 13, 11, 4, -10 }, // 0x7B '{' + { 964, 3, 12, 11, 5, -9 }, // 0x7C '|' + { 969, 6, 13, 11, 3, -10 }, // 0x7D '}' + { 979, 7, 3, 11, 3, -6 } }; // 0x7E '~' + +const GFXfont FreeMonoOblique9pt7b PROGMEM = { + (uint8_t *)FreeMonoOblique9pt7bBitmaps, + (GFXglyph *)FreeMonoOblique9pt7bGlyphs, + 0x20, 0x7E, 18 }; + +// Approx. 1654 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSans12pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSans12pt7b.h new file mode 100644 index 0000000..9ecbb8f --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSans12pt7b.h @@ -0,0 +1,270 @@ +const uint8_t FreeSans12pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xF0, 0xF0, 0xCF, 0x3C, 0xF3, 0x8A, 0x20, 0x06, 0x30, + 0x31, 0x03, 0x18, 0x18, 0xC7, 0xFF, 0xBF, 0xFC, 0x31, 0x03, 0x18, 0x18, + 0xC7, 0xFF, 0xBF, 0xFC, 0x31, 0x01, 0x18, 0x18, 0xC0, 0xC6, 0x06, 0x30, + 0x04, 0x03, 0xE1, 0xFF, 0x72, 0x6C, 0x47, 0x88, 0xF1, 0x07, 0x20, 0x7E, + 0x03, 0xF0, 0x17, 0x02, 0x3C, 0x47, 0x88, 0xF1, 0x1B, 0x26, 0x7F, 0xC3, + 0xE0, 0x10, 0x02, 0x00, 0x00, 0x06, 0x03, 0xC0, 0x40, 0x7E, 0x0C, 0x0E, + 0x70, 0x80, 0xC3, 0x18, 0x0C, 0x31, 0x00, 0xE7, 0x30, 0x07, 0xE6, 0x00, + 0x3C, 0x40, 0x00, 0x0C, 0x7C, 0x00, 0x8F, 0xE0, 0x19, 0xC7, 0x01, 0x18, + 0x30, 0x31, 0x83, 0x02, 0x1C, 0x70, 0x40, 0xFE, 0x04, 0x07, 0xC0, 0x0F, + 0x00, 0x7E, 0x03, 0x9C, 0x0C, 0x30, 0x30, 0xC0, 0xE7, 0x01, 0xF8, 0x03, + 0x80, 0x3E, 0x01, 0xCC, 0x6E, 0x19, 0xB0, 0x7C, 0xC0, 0xF3, 0x03, 0xCE, + 0x1F, 0x9F, 0xE6, 0x1E, 0x1C, 0xFF, 0xA0, 0x08, 0x8C, 0x66, 0x31, 0x98, + 0xC6, 0x31, 0x8C, 0x63, 0x08, 0x63, 0x08, 0x61, 0x0C, 0x20, 0x82, 0x18, + 0xC3, 0x18, 0xC3, 0x18, 0xC6, 0x31, 0x8C, 0x62, 0x31, 0x88, 0xC4, 0x62, + 0x00, 0x10, 0x23, 0x5B, 0xE3, 0x8D, 0x91, 0x00, 0x0C, 0x03, 0x00, 0xC0, + 0x30, 0xFF, 0xFF, 0xF0, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0xF5, 0x60, + 0xFF, 0xF0, 0xF0, 0x02, 0x0C, 0x10, 0x20, 0xC1, 0x02, 0x0C, 0x10, 0x20, + 0xC1, 0x02, 0x0C, 0x10, 0x20, 0xC1, 0x00, 0x1F, 0x07, 0xF1, 0xC7, 0x30, + 0x6E, 0x0F, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, + 0x0E, 0xC1, 0x9C, 0x71, 0xFC, 0x1F, 0x00, 0x08, 0xCF, 0xFF, 0x8C, 0x63, + 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0x1F, 0x0F, 0xF9, 0x87, 0x60, 0x7C, + 0x06, 0x00, 0xC0, 0x18, 0x07, 0x01, 0xC0, 0xF0, 0x78, 0x1C, 0x06, 0x00, + 0x80, 0x30, 0x07, 0xFF, 0xFF, 0xE0, 0x3F, 0x0F, 0xF3, 0x87, 0x60, 0x6C, + 0x0C, 0x01, 0x80, 0x70, 0x7C, 0x0F, 0x80, 0x18, 0x01, 0x80, 0x3C, 0x07, + 0x80, 0xD8, 0x73, 0xFC, 0x1F, 0x00, 0x01, 0x80, 0x70, 0x0E, 0x03, 0xC0, + 0xD8, 0x1B, 0x06, 0x61, 0x8C, 0x21, 0x8C, 0x33, 0x06, 0x7F, 0xFF, 0xFE, + 0x03, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x3F, 0xCF, 0xF9, 0x80, 0x30, 0x06, + 0x00, 0xDE, 0x1F, 0xE7, 0x0E, 0x00, 0xE0, 0x0C, 0x01, 0x80, 0x30, 0x07, + 0x81, 0xF8, 0x73, 0xFC, 0x1F, 0x00, 0x0F, 0x07, 0xF9, 0xC3, 0x30, 0x74, + 0x01, 0x80, 0x33, 0xC7, 0xFE, 0xF0, 0xDC, 0x1F, 0x01, 0xE0, 0x3C, 0x06, + 0xC1, 0xDC, 0x71, 0xFC, 0x1F, 0x00, 0xFF, 0xFF, 0xFC, 0x01, 0x00, 0x60, + 0x18, 0x02, 0x00, 0xC0, 0x30, 0x06, 0x01, 0x80, 0x30, 0x04, 0x01, 0x80, + 0x30, 0x06, 0x01, 0x80, 0x30, 0x00, 0x1F, 0x07, 0xF1, 0xC7, 0x30, 0x66, + 0x0C, 0xC1, 0x8C, 0x61, 0xFC, 0x3F, 0x8E, 0x3B, 0x01, 0xE0, 0x3C, 0x07, + 0x80, 0xD8, 0x31, 0xFC, 0x1F, 0x00, 0x1F, 0x07, 0xF1, 0xC7, 0x70, 0x6C, + 0x07, 0x80, 0xF0, 0x1E, 0x07, 0x61, 0xEF, 0xFC, 0x79, 0x80, 0x30, 0x05, + 0x81, 0x98, 0x73, 0xFC, 0x1E, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0xF0, 0x00, + 0x0F, 0x56, 0x00, 0x00, 0x07, 0x01, 0xE0, 0xF8, 0x3C, 0x0F, 0x00, 0xE0, + 0x07, 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xF0, 0x01, 0xFF, 0xFF, 0xFF, 0x00, + 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0x00, 0x0E, 0x00, 0x78, 0x01, 0xF0, 0x07, + 0xC0, 0x0F, 0x00, 0x70, 0x1E, 0x0F, 0x03, 0xC0, 0xF0, 0x08, 0x00, 0x1F, + 0x1F, 0xEE, 0x1B, 0x03, 0xC0, 0xC0, 0x30, 0x0C, 0x06, 0x03, 0x81, 0xC0, + 0xE0, 0x30, 0x0C, 0x03, 0x00, 0x00, 0x00, 0x0C, 0x03, 0x00, 0x00, 0xFE, + 0x00, 0x0F, 0xFE, 0x00, 0xF0, 0x3E, 0x07, 0x00, 0x3C, 0x38, 0x00, 0x30, + 0xC1, 0xE0, 0x66, 0x0F, 0xD9, 0xD8, 0x61, 0xC3, 0xC3, 0x07, 0x0F, 0x1C, + 0x1C, 0x3C, 0x60, 0x60, 0xF1, 0x81, 0x83, 0xC6, 0x06, 0x1B, 0x18, 0x38, + 0xEE, 0x71, 0xE7, 0x18, 0xFD, 0xF8, 0x71, 0xE7, 0xC0, 0xE0, 0x00, 0x01, + 0xE0, 0x00, 0x01, 0xFF, 0xC0, 0x01, 0xFC, 0x00, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x07, 0xE0, 0x06, 0x60, 0x06, 0x60, 0x0E, 0x70, 0x0C, 0x30, + 0x0C, 0x30, 0x1C, 0x38, 0x18, 0x18, 0x1F, 0xF8, 0x3F, 0xFC, 0x30, 0x1C, + 0x30, 0x0C, 0x70, 0x0E, 0x60, 0x06, 0x60, 0x06, 0xFF, 0xC7, 0xFF, 0x30, + 0x19, 0x80, 0x6C, 0x03, 0x60, 0x1B, 0x00, 0xD8, 0x0C, 0xFF, 0xC7, 0xFF, + 0x30, 0x0D, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x06, 0xFF, 0xF7, + 0xFE, 0x00, 0x07, 0xE0, 0x3F, 0xF0, 0xE0, 0x73, 0x80, 0x66, 0x00, 0x6C, + 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x06, 0x00, + 0x06, 0x00, 0x6C, 0x00, 0xDC, 0x03, 0x1E, 0x0E, 0x1F, 0xF8, 0x0F, 0xC0, + 0xFF, 0x83, 0xFF, 0x8C, 0x07, 0x30, 0x0E, 0xC0, 0x1B, 0x00, 0x7C, 0x00, + 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x1F, 0x00, + 0x6C, 0x03, 0xB0, 0x1C, 0xFF, 0xE3, 0xFF, 0x00, 0xFF, 0xFF, 0xFF, 0xC0, + 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0xFF, 0xEF, 0xFE, 0xC0, + 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xFF, 0xDF, + 0xFB, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, 0x18, 0x00, + 0x07, 0xF0, 0x1F, 0xFC, 0x3C, 0x1E, 0x70, 0x06, 0x60, 0x03, 0xE0, 0x00, + 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x7F, 0xC0, 0x7F, 0xC0, 0x03, 0xC0, 0x03, + 0x60, 0x03, 0x60, 0x07, 0x30, 0x0F, 0x3C, 0x1F, 0x1F, 0xFB, 0x07, 0xE1, + 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, + 0x03, 0xFF, 0xFF, 0xFF, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, + 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x01, + 0x80, 0xC0, 0x60, 0x30, 0x18, 0x0C, 0x06, 0x03, 0x01, 0x80, 0xC0, 0x60, + 0x3C, 0x1E, 0x0F, 0x07, 0xC7, 0x7F, 0x1F, 0x00, 0xC0, 0x3B, 0x01, 0xCC, + 0x0E, 0x30, 0x70, 0xC3, 0x83, 0x1C, 0x0C, 0xE0, 0x33, 0x80, 0xDE, 0x03, + 0xDC, 0x0E, 0x38, 0x30, 0x60, 0xC1, 0xC3, 0x03, 0x8C, 0x06, 0x30, 0x1C, + 0xC0, 0x3B, 0x00, 0x60, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x0C, + 0x03, 0x00, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x0C, 0x03, 0x00, + 0xFF, 0xFF, 0xF0, 0xE0, 0x07, 0xE0, 0x07, 0xF0, 0x0F, 0xF0, 0x0F, 0xD0, + 0x0F, 0xD8, 0x1B, 0xD8, 0x1B, 0xD8, 0x1B, 0xCC, 0x33, 0xCC, 0x33, 0xCC, + 0x33, 0xC6, 0x63, 0xC6, 0x63, 0xC6, 0x63, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, + 0xC3, 0xC1, 0x83, 0xE0, 0x1F, 0x00, 0xFC, 0x07, 0xE0, 0x3D, 0x81, 0xEE, + 0x0F, 0x30, 0x79, 0xC3, 0xC6, 0x1E, 0x18, 0xF0, 0xE7, 0x83, 0x3C, 0x1D, + 0xE0, 0x6F, 0x01, 0xF8, 0x0F, 0xC0, 0x3E, 0x01, 0xC0, 0x03, 0xE0, 0x0F, + 0xFC, 0x0F, 0x07, 0x86, 0x00, 0xC6, 0x00, 0x33, 0x00, 0x1B, 0x00, 0x07, + 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x36, 0x00, + 0x33, 0x00, 0x18, 0xC0, 0x18, 0x78, 0x3C, 0x1F, 0xFC, 0x03, 0xF8, 0x00, + 0xFF, 0x8F, 0xFE, 0xC0, 0x6C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x07, + 0xFF, 0xEF, 0xFC, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, + 0xC0, 0x0C, 0x00, 0x03, 0xE0, 0x0F, 0xFC, 0x0F, 0x07, 0x86, 0x00, 0xC6, + 0x00, 0x33, 0x00, 0x1B, 0x00, 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x00, + 0xF0, 0x00, 0x78, 0x00, 0x36, 0x00, 0x33, 0x01, 0x98, 0xC0, 0xFC, 0x78, + 0x3C, 0x1F, 0xFF, 0x03, 0xF9, 0x80, 0x00, 0x40, 0xFF, 0xC3, 0xFF, 0xCC, + 0x03, 0xB0, 0x06, 0xC0, 0x1B, 0x00, 0x6C, 0x01, 0xB0, 0x0C, 0xFF, 0xE3, + 0xFF, 0xCC, 0x03, 0xB0, 0x06, 0xC0, 0x1B, 0x00, 0x6C, 0x01, 0xB0, 0x06, + 0xC0, 0x1B, 0x00, 0x70, 0x0F, 0xE0, 0x7F, 0xC3, 0x83, 0x9C, 0x07, 0x60, + 0x0D, 0x80, 0x06, 0x00, 0x1E, 0x00, 0x3F, 0x80, 0x3F, 0xC0, 0x0F, 0x80, + 0x07, 0xC0, 0x0F, 0x00, 0x3E, 0x00, 0xDE, 0x0E, 0x3F, 0xF0, 0x3F, 0x80, + 0xFF, 0xFF, 0xFF, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x06, 0x00, 0x60, 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xE0, + 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, + 0xE0, 0x0F, 0x80, 0xEE, 0x0E, 0x3F, 0xE0, 0x7C, 0x00, 0x60, 0x06, 0xC0, + 0x1D, 0xC0, 0x31, 0x80, 0x63, 0x01, 0xC7, 0x03, 0x06, 0x06, 0x0C, 0x1C, + 0x1C, 0x30, 0x18, 0x60, 0x31, 0xC0, 0x73, 0x00, 0x66, 0x00, 0xDC, 0x01, + 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0xE0, 0x30, 0x1D, 0x80, 0xE0, + 0x76, 0x07, 0x81, 0xD8, 0x1E, 0x06, 0x70, 0x7C, 0x18, 0xC1, 0xB0, 0xE3, + 0x0C, 0xC3, 0x8C, 0x33, 0x0C, 0x38, 0xC6, 0x30, 0x67, 0x18, 0xC1, 0x98, + 0x67, 0x06, 0x61, 0xD8, 0x1D, 0x83, 0x60, 0x3C, 0x0D, 0x80, 0xF0, 0x3E, + 0x03, 0xC0, 0x70, 0x0F, 0x01, 0xC0, 0x18, 0x07, 0x00, 0x70, 0x0E, 0x60, + 0x38, 0xE0, 0x60, 0xE1, 0xC0, 0xC3, 0x01, 0xCC, 0x01, 0xF8, 0x01, 0xE0, + 0x03, 0x80, 0x07, 0x80, 0x1F, 0x00, 0x33, 0x00, 0xE7, 0x03, 0x86, 0x06, + 0x0E, 0x1C, 0x0E, 0x70, 0x0C, 0xC0, 0x1C, 0x60, 0x06, 0x70, 0x0E, 0x30, + 0x1C, 0x38, 0x18, 0x1C, 0x38, 0x0C, 0x30, 0x0E, 0x70, 0x06, 0x60, 0x03, + 0xC0, 0x03, 0xC0, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, + 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xC0, 0x0E, + 0x00, 0xE0, 0x0E, 0x00, 0x60, 0x07, 0x00, 0x70, 0x07, 0x00, 0x30, 0x03, + 0x80, 0x38, 0x03, 0x80, 0x18, 0x01, 0xC0, 0x1C, 0x00, 0xFF, 0xFF, 0xFF, + 0xC0, 0xFF, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCF, + 0xF0, 0x81, 0x81, 0x02, 0x06, 0x04, 0x08, 0x18, 0x10, 0x20, 0x60, 0x40, + 0x81, 0x81, 0x02, 0x06, 0x04, 0xFF, 0x33, 0x33, 0x33, 0x33, 0x33, 0x33, + 0x33, 0x33, 0x33, 0x3F, 0xF0, 0x0C, 0x0E, 0x05, 0x86, 0xC3, 0x21, 0x19, + 0x8C, 0x83, 0xC1, 0x80, 0xFF, 0xFE, 0xE3, 0x8C, 0x30, 0x3F, 0x07, 0xF8, + 0xE1, 0xCC, 0x0C, 0x00, 0xC0, 0x1C, 0x3F, 0xCF, 0x8C, 0xC0, 0xCC, 0x0C, + 0xE3, 0xC7, 0xEF, 0x3C, 0x70, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0xC0, + 0x0C, 0xF8, 0xDF, 0xCF, 0x0E, 0xE0, 0x7C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, + 0x3C, 0x03, 0xE0, 0x6F, 0x0E, 0xDF, 0xCC, 0xF8, 0x1F, 0x0F, 0xE7, 0x1B, + 0x83, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x38, 0x37, 0x1C, 0xFE, 0x1F, + 0x00, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x3C, 0xCF, 0xFB, 0x8F, + 0xE0, 0xF8, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF8, 0x3B, 0x8F, 0x3F, + 0x63, 0xCC, 0x1F, 0x07, 0xF1, 0xC7, 0x70, 0x3C, 0x07, 0xFF, 0xFF, 0xFE, + 0x00, 0xC0, 0x1C, 0x0D, 0xC3, 0x1F, 0xE1, 0xF0, 0x3B, 0xD8, 0xC6, 0x7F, + 0xEC, 0x63, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x00, 0x1E, 0x67, 0xFD, 0xC7, + 0xF0, 0x7C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x7C, 0x1D, 0xC7, 0x9F, + 0xB1, 0xE6, 0x00, 0xC0, 0x3E, 0x0E, 0x7F, 0xC7, 0xE0, 0xC0, 0x30, 0x0C, + 0x03, 0x00, 0xC0, 0x33, 0xCD, 0xFB, 0xC7, 0xE0, 0xF0, 0x3C, 0x0F, 0x03, + 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x30, 0xF0, 0x3F, 0xFF, 0xFF, + 0xF0, 0x33, 0x00, 0x03, 0x33, 0x33, 0x33, 0x33, 0x33, 0x33, 0x33, 0x3F, + 0xE0, 0xC0, 0x18, 0x03, 0x00, 0x60, 0x0C, 0x01, 0x83, 0x30, 0xC6, 0x30, + 0xCC, 0x1B, 0x83, 0xF0, 0x77, 0x0C, 0x61, 0x8E, 0x30, 0xE6, 0x0C, 0xC1, + 0xD8, 0x18, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xCF, 0x1F, 0x6F, 0xDF, 0xFC, + 0x78, 0xFC, 0x18, 0x3C, 0x0C, 0x1E, 0x06, 0x0F, 0x03, 0x07, 0x81, 0x83, + 0xC0, 0xC1, 0xE0, 0x60, 0xF0, 0x30, 0x78, 0x18, 0x3C, 0x0C, 0x18, 0xCF, + 0x37, 0xEF, 0x1F, 0x83, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3C, + 0x0F, 0x03, 0xC0, 0xC0, 0x1F, 0x07, 0xF1, 0xC7, 0x70, 0x7C, 0x07, 0x80, + 0xF0, 0x1E, 0x03, 0xC0, 0x7C, 0x1D, 0xC7, 0x1F, 0xC1, 0xF0, 0xCF, 0x8D, + 0xFC, 0xF0, 0xEE, 0x06, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3E, + 0x07, 0xF0, 0xEF, 0xFC, 0xCF, 0x8C, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x00, + 0x1E, 0x67, 0xFD, 0xC7, 0xF0, 0x7C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, + 0x7C, 0x1D, 0xC7, 0x9F, 0xF1, 0xE6, 0x00, 0xC0, 0x18, 0x03, 0x00, 0x60, + 0xCF, 0x7F, 0x38, 0xC3, 0x0C, 0x30, 0xC3, 0x0C, 0x30, 0xC0, 0x3E, 0x1F, + 0xEE, 0x1B, 0x00, 0xC0, 0x3C, 0x07, 0xF0, 0x3E, 0x01, 0xF0, 0x3E, 0x1D, + 0xFE, 0x3E, 0x00, 0x63, 0x19, 0xFF, 0xB1, 0x8C, 0x63, 0x18, 0xC6, 0x31, + 0xE7, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, + 0xF0, 0x7E, 0x3D, 0xFB, 0x3C, 0xC0, 0xE0, 0x66, 0x06, 0x60, 0x67, 0x0C, + 0x30, 0xC3, 0x0C, 0x39, 0x81, 0x98, 0x19, 0x81, 0xF0, 0x0F, 0x00, 0xE0, + 0x0E, 0x00, 0xC1, 0xC1, 0xB0, 0xE1, 0xD8, 0x70, 0xCC, 0x2C, 0x66, 0x36, + 0x31, 0x9B, 0x18, 0xCD, 0x98, 0x64, 0x6C, 0x16, 0x36, 0x0F, 0x1A, 0x07, + 0x8F, 0x03, 0x83, 0x80, 0xC1, 0xC0, 0x60, 0xEE, 0x18, 0xC6, 0x0C, 0xC1, + 0xF0, 0x1C, 0x01, 0x80, 0x78, 0x1B, 0x03, 0x30, 0xC7, 0x30, 0x66, 0x06, + 0xE0, 0x6C, 0x0D, 0x83, 0x38, 0x63, 0x0C, 0x63, 0x0E, 0x60, 0xCC, 0x1B, + 0x03, 0x60, 0x3C, 0x07, 0x00, 0xE0, 0x18, 0x03, 0x00, 0xE0, 0x78, 0x0E, + 0x00, 0xFF, 0xFF, 0xF0, 0x18, 0x0C, 0x07, 0x03, 0x81, 0xC0, 0x60, 0x30, + 0x18, 0x0E, 0x03, 0xFF, 0xFF, 0xC0, 0x19, 0xCC, 0x63, 0x18, 0xC6, 0x31, + 0x99, 0x86, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x1C, 0x60, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFC, 0xC7, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x0C, 0x33, 0x31, + 0x8C, 0x63, 0x18, 0xC6, 0x73, 0x00, 0x70, 0x3E, 0x09, 0xE4, 0x1F, 0x03, + 0x80 }; + +const GFXglyph FreeSans12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 6, 0, 1 }, // 0x20 ' ' + { 0, 2, 18, 8, 3, -17 }, // 0x21 '!' + { 5, 6, 6, 8, 1, -16 }, // 0x22 '"' + { 10, 13, 16, 13, 0, -15 }, // 0x23 '#' + { 36, 11, 20, 13, 1, -17 }, // 0x24 '$' + { 64, 20, 17, 21, 1, -16 }, // 0x25 '%' + { 107, 14, 17, 16, 1, -16 }, // 0x26 '&' + { 137, 2, 6, 5, 1, -16 }, // 0x27 ''' + { 139, 5, 23, 8, 2, -17 }, // 0x28 '(' + { 154, 5, 23, 8, 1, -17 }, // 0x29 ')' + { 169, 7, 7, 9, 1, -17 }, // 0x2A '*' + { 176, 10, 11, 14, 2, -10 }, // 0x2B '+' + { 190, 2, 6, 7, 2, -1 }, // 0x2C ',' + { 192, 6, 2, 8, 1, -7 }, // 0x2D '-' + { 194, 2, 2, 6, 2, -1 }, // 0x2E '.' + { 195, 7, 18, 7, 0, -17 }, // 0x2F '/' + { 211, 11, 17, 13, 1, -16 }, // 0x30 '0' + { 235, 5, 17, 13, 3, -16 }, // 0x31 '1' + { 246, 11, 17, 13, 1, -16 }, // 0x32 '2' + { 270, 11, 17, 13, 1, -16 }, // 0x33 '3' + { 294, 11, 17, 13, 1, -16 }, // 0x34 '4' + { 318, 11, 17, 13, 1, -16 }, // 0x35 '5' + { 342, 11, 17, 13, 1, -16 }, // 0x36 '6' + { 366, 11, 17, 13, 1, -16 }, // 0x37 '7' + { 390, 11, 17, 13, 1, -16 }, // 0x38 '8' + { 414, 11, 17, 13, 1, -16 }, // 0x39 '9' + { 438, 2, 13, 6, 2, -12 }, // 0x3A ':' + { 442, 2, 16, 6, 2, -11 }, // 0x3B ';' + { 446, 12, 12, 14, 1, -11 }, // 0x3C '<' + { 464, 12, 6, 14, 1, -8 }, // 0x3D '=' + { 473, 12, 12, 14, 1, -11 }, // 0x3E '>' + { 491, 10, 18, 13, 2, -17 }, // 0x3F '?' + { 514, 22, 21, 24, 1, -17 }, // 0x40 '@' + { 572, 16, 18, 16, 0, -17 }, // 0x41 'A' + { 608, 13, 18, 16, 2, -17 }, // 0x42 'B' + { 638, 15, 18, 17, 1, -17 }, // 0x43 'C' + { 672, 14, 18, 17, 2, -17 }, // 0x44 'D' + { 704, 12, 18, 15, 2, -17 }, // 0x45 'E' + { 731, 11, 18, 14, 2, -17 }, // 0x46 'F' + { 756, 16, 18, 18, 1, -17 }, // 0x47 'G' + { 792, 13, 18, 17, 2, -17 }, // 0x48 'H' + { 822, 2, 18, 7, 2, -17 }, // 0x49 'I' + { 827, 9, 18, 13, 1, -17 }, // 0x4A 'J' + { 848, 14, 18, 16, 2, -17 }, // 0x4B 'K' + { 880, 10, 18, 14, 2, -17 }, // 0x4C 'L' + { 903, 16, 18, 20, 2, -17 }, // 0x4D 'M' + { 939, 13, 18, 18, 2, -17 }, // 0x4E 'N' + { 969, 17, 18, 19, 1, -17 }, // 0x4F 'O' + { 1008, 12, 18, 16, 2, -17 }, // 0x50 'P' + { 1035, 17, 19, 19, 1, -17 }, // 0x51 'Q' + { 1076, 14, 18, 17, 2, -17 }, // 0x52 'R' + { 1108, 14, 18, 16, 1, -17 }, // 0x53 'S' + { 1140, 12, 18, 15, 1, -17 }, // 0x54 'T' + { 1167, 13, 18, 17, 2, -17 }, // 0x55 'U' + { 1197, 15, 18, 15, 0, -17 }, // 0x56 'V' + { 1231, 22, 18, 22, 0, -17 }, // 0x57 'W' + { 1281, 15, 18, 16, 0, -17 }, // 0x58 'X' + { 1315, 16, 18, 16, 0, -17 }, // 0x59 'Y' + { 1351, 13, 18, 15, 1, -17 }, // 0x5A 'Z' + { 1381, 4, 23, 7, 2, -17 }, // 0x5B '[' + { 1393, 7, 18, 7, 0, -17 }, // 0x5C '\' + { 1409, 4, 23, 7, 1, -17 }, // 0x5D ']' + { 1421, 9, 9, 11, 1, -16 }, // 0x5E '^' + { 1432, 15, 1, 13, -1, 4 }, // 0x5F '_' + { 1434, 5, 4, 6, 1, -17 }, // 0x60 '`' + { 1437, 12, 13, 13, 1, -12 }, // 0x61 'a' + { 1457, 12, 18, 13, 1, -17 }, // 0x62 'b' + { 1484, 10, 13, 12, 1, -12 }, // 0x63 'c' + { 1501, 11, 18, 13, 1, -17 }, // 0x64 'd' + { 1526, 11, 13, 13, 1, -12 }, // 0x65 'e' + { 1544, 5, 18, 7, 1, -17 }, // 0x66 'f' + { 1556, 11, 18, 13, 1, -12 }, // 0x67 'g' + { 1581, 10, 18, 13, 1, -17 }, // 0x68 'h' + { 1604, 2, 18, 5, 2, -17 }, // 0x69 'i' + { 1609, 4, 23, 6, 0, -17 }, // 0x6A 'j' + { 1621, 11, 18, 12, 1, -17 }, // 0x6B 'k' + { 1646, 2, 18, 5, 1, -17 }, // 0x6C 'l' + { 1651, 17, 13, 19, 1, -12 }, // 0x6D 'm' + { 1679, 10, 13, 13, 1, -12 }, // 0x6E 'n' + { 1696, 11, 13, 13, 1, -12 }, // 0x6F 'o' + { 1714, 12, 17, 13, 1, -12 }, // 0x70 'p' + { 1740, 11, 17, 13, 1, -12 }, // 0x71 'q' + { 1764, 6, 13, 8, 1, -12 }, // 0x72 'r' + { 1774, 10, 13, 12, 1, -12 }, // 0x73 's' + { 1791, 5, 16, 7, 1, -15 }, // 0x74 't' + { 1801, 10, 13, 13, 1, -12 }, // 0x75 'u' + { 1818, 12, 13, 12, 0, -12 }, // 0x76 'v' + { 1838, 17, 13, 17, 0, -12 }, // 0x77 'w' + { 1866, 11, 13, 11, 0, -12 }, // 0x78 'x' + { 1884, 11, 18, 11, 0, -12 }, // 0x79 'y' + { 1909, 10, 13, 12, 1, -12 }, // 0x7A 'z' + { 1926, 5, 23, 8, 1, -17 }, // 0x7B '{' + { 1941, 2, 23, 6, 2, -17 }, // 0x7C '|' + { 1947, 5, 23, 8, 2, -17 }, // 0x7D '}' + { 1962, 10, 5, 12, 1, -10 } }; // 0x7E '~' + +const GFXfont FreeSans12pt7b PROGMEM = { + (uint8_t *)FreeSans12pt7bBitmaps, + (GFXglyph *)FreeSans12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 2641 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSans18pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSans18pt7b.h new file mode 100644 index 0000000..3fdc591 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSans18pt7b.h @@ -0,0 +1,452 @@ +const uint8_t FreeSans18pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE9, 0x20, 0x3F, 0xFC, 0xE3, 0xF1, + 0xF8, 0xFC, 0x7E, 0x3F, 0x1F, 0x8E, 0x82, 0x41, 0x00, 0x01, 0xC3, 0x80, + 0x38, 0x70, 0x06, 0x0E, 0x00, 0xC1, 0x80, 0x38, 0x70, 0x07, 0x0E, 0x0F, + 0xFF, 0xF9, 0xFF, 0xFF, 0x3F, 0xFF, 0xE0, 0xE1, 0xC0, 0x1C, 0x38, 0x03, + 0x87, 0x00, 0x70, 0xE0, 0x0C, 0x18, 0x3F, 0xFF, 0xF7, 0xFF, 0xFE, 0xFF, + 0xFF, 0xC1, 0xC3, 0x80, 0x30, 0x60, 0x06, 0x0C, 0x01, 0xC3, 0x80, 0x38, + 0x70, 0x07, 0x0E, 0x00, 0xC1, 0x80, 0x03, 0x00, 0x0F, 0xC0, 0x3F, 0xF0, + 0x3F, 0xF8, 0x7B, 0x3C, 0xF3, 0x1C, 0xE3, 0x0E, 0xE3, 0x0E, 0xE3, 0x0E, + 0xE3, 0x00, 0xE3, 0x00, 0xF3, 0x00, 0x7B, 0x00, 0x7F, 0x80, 0x1F, 0xF0, + 0x07, 0xFC, 0x03, 0x7E, 0x03, 0x0F, 0x03, 0x07, 0xE3, 0x07, 0xE3, 0x07, + 0xE3, 0x07, 0xE3, 0x0F, 0x73, 0x3E, 0x7F, 0xFC, 0x3F, 0xF8, 0x0F, 0xE0, + 0x03, 0x00, 0x03, 0x00, 0x03, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x78, 0x00, + 0xE0, 0x0F, 0xF0, 0x06, 0x00, 0xFF, 0xC0, 0x70, 0x07, 0x0E, 0x07, 0x00, + 0x70, 0x38, 0x38, 0x03, 0x00, 0xC3, 0x80, 0x18, 0x06, 0x1C, 0x00, 0xE0, + 0x71, 0xC0, 0x03, 0x87, 0x8C, 0x00, 0x1F, 0xF8, 0xE0, 0x00, 0x7F, 0x86, + 0x00, 0x01, 0xF8, 0x70, 0x00, 0x00, 0x03, 0x03, 0xC0, 0x00, 0x38, 0x7F, + 0x80, 0x01, 0x87, 0xFE, 0x00, 0x1C, 0x38, 0x70, 0x00, 0xC3, 0x81, 0xC0, + 0x0E, 0x18, 0x06, 0x00, 0xE0, 0xC0, 0x30, 0x07, 0x07, 0x03, 0x80, 0x70, + 0x1C, 0x38, 0x03, 0x80, 0xFF, 0xC0, 0x38, 0x03, 0xFC, 0x01, 0x80, 0x07, + 0x80, 0x01, 0xF0, 0x00, 0x7F, 0x80, 0x0F, 0xFC, 0x01, 0xE1, 0xE0, 0x1C, + 0x0E, 0x01, 0xC0, 0xE0, 0x1C, 0x0E, 0x01, 0xE1, 0xE0, 0x0E, 0x3C, 0x00, + 0x77, 0x80, 0x07, 0xF0, 0x00, 0x7C, 0x00, 0x0F, 0xE0, 0x03, 0xCF, 0x1C, + 0x78, 0x79, 0xC7, 0x03, 0xDC, 0xE0, 0x1F, 0x8E, 0x00, 0xF8, 0xE0, 0x0F, + 0x0E, 0x00, 0x70, 0xF0, 0x0F, 0x87, 0xC3, 0xFC, 0x7F, 0xFD, 0xC3, 0xFF, + 0x0E, 0x0F, 0xC0, 0xF0, 0xFF, 0xFF, 0xFA, 0x40, 0x06, 0x06, 0x0C, 0x0C, + 0x18, 0x18, 0x38, 0x30, 0x70, 0x70, 0x70, 0x60, 0xE0, 0xE0, 0xE0, 0xE0, + 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0x60, 0x70, 0x70, 0x70, 0x30, 0x38, 0x18, + 0x18, 0x0C, 0x0C, 0x06, 0x03, 0xC0, 0x60, 0x30, 0x30, 0x38, 0x18, 0x1C, + 0x0C, 0x0E, 0x0E, 0x0E, 0x06, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, + 0x07, 0x07, 0x06, 0x0E, 0x0E, 0x0E, 0x0C, 0x1C, 0x18, 0x38, 0x30, 0x30, + 0x60, 0xC0, 0x0C, 0x03, 0x00, 0xC3, 0xB7, 0xFF, 0xC7, 0x81, 0xE0, 0xEC, + 0x73, 0x88, 0x40, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, + 0x80, 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x01, 0x80, 0x01, + 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0xFF, + 0xF6, 0xDA, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0xC0, 0x30, 0x18, + 0x06, 0x01, 0x80, 0xC0, 0x30, 0x0C, 0x06, 0x01, 0x80, 0x60, 0x30, 0x0C, + 0x03, 0x00, 0xC0, 0x60, 0x18, 0x06, 0x03, 0x00, 0xC0, 0x30, 0x18, 0x06, + 0x01, 0x80, 0xC0, 0x30, 0x00, 0x07, 0xE0, 0x0F, 0xF8, 0x1F, 0xFC, 0x3C, + 0x3C, 0x78, 0x1E, 0x70, 0x0E, 0x70, 0x0E, 0xE0, 0x07, 0xE0, 0x07, 0xE0, + 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, + 0x07, 0xE0, 0x07, 0xE0, 0x0F, 0x70, 0x0E, 0x70, 0x0E, 0x78, 0x1E, 0x3C, + 0x3C, 0x1F, 0xF8, 0x1F, 0xF0, 0x07, 0xE0, 0x03, 0x03, 0x07, 0x0F, 0x3F, + 0xFF, 0xFF, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, + 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0xE0, 0x1F, 0xF8, + 0x3F, 0xFC, 0x7C, 0x3E, 0x70, 0x0F, 0xF0, 0x0F, 0xE0, 0x07, 0xE0, 0x07, + 0x00, 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0xF8, + 0x03, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x3C, 0x00, 0x38, 0x00, 0x70, 0x00, + 0x60, 0x00, 0xE0, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x07, 0xF0, + 0x07, 0xFE, 0x07, 0xFF, 0x87, 0x83, 0xC3, 0x80, 0xF3, 0x80, 0x39, 0xC0, + 0x1C, 0xE0, 0x0E, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x7F, 0x00, 0x3F, 0x00, + 0x1F, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x03, 0xF0, 0x01, + 0xF8, 0x00, 0xFE, 0x00, 0x77, 0x00, 0x73, 0xE0, 0xF8, 0xFF, 0xF8, 0x3F, + 0xF8, 0x07, 0xF0, 0x00, 0x00, 0x38, 0x00, 0x38, 0x00, 0x78, 0x00, 0xF8, + 0x00, 0xF8, 0x01, 0xF8, 0x03, 0xB8, 0x03, 0x38, 0x07, 0x38, 0x0E, 0x38, + 0x1C, 0x38, 0x18, 0x38, 0x38, 0x38, 0x70, 0x38, 0x60, 0x38, 0xE0, 0x38, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, + 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x1F, 0xFF, 0x0F, 0xFF, 0x8F, 0xFF, + 0xC7, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x39, + 0xF0, 0x3F, 0xFE, 0x1F, 0xFF, 0x8F, 0x83, 0xE7, 0x00, 0xF0, 0x00, 0x3C, + 0x00, 0x0E, 0x00, 0x07, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xFC, 0x00, + 0xEF, 0x00, 0x73, 0xC0, 0xF0, 0xFF, 0xF8, 0x3F, 0xF8, 0x07, 0xE0, 0x00, + 0x03, 0xE0, 0x0F, 0xF8, 0x1F, 0xFC, 0x3C, 0x1E, 0x38, 0x0E, 0x70, 0x0E, + 0x70, 0x00, 0x60, 0x00, 0xE0, 0x00, 0xE3, 0xE0, 0xEF, 0xF8, 0xFF, 0xFC, + 0xFC, 0x3E, 0xF0, 0x0E, 0xF0, 0x0F, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, + 0x60, 0x07, 0x70, 0x0F, 0x70, 0x0E, 0x3C, 0x3E, 0x3F, 0xFC, 0x1F, 0xF8, + 0x07, 0xE0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x06, 0x00, 0x0E, + 0x00, 0x1C, 0x00, 0x18, 0x00, 0x38, 0x00, 0x70, 0x00, 0x60, 0x00, 0xE0, + 0x00, 0xC0, 0x01, 0xC0, 0x01, 0x80, 0x03, 0x80, 0x03, 0x80, 0x07, 0x00, + 0x07, 0x00, 0x07, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0C, 0x00, + 0x1C, 0x00, 0x1C, 0x00, 0x07, 0xF0, 0x0F, 0xFE, 0x0F, 0xFF, 0x87, 0x83, + 0xC7, 0x80, 0xF3, 0x80, 0x39, 0xC0, 0x1C, 0xE0, 0x0E, 0x78, 0x0F, 0x1E, + 0x0F, 0x07, 0xFF, 0x01, 0xFF, 0x03, 0xFF, 0xE3, 0xE0, 0xF9, 0xC0, 0x1D, + 0xC0, 0x0F, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0xF7, 0x00, + 0x73, 0xE0, 0xF8, 0xFF, 0xF8, 0x3F, 0xF8, 0x07, 0xF0, 0x00, 0x07, 0xE0, + 0x1F, 0xF8, 0x3F, 0xFC, 0x7C, 0x3C, 0x70, 0x0E, 0xF0, 0x0E, 0xE0, 0x06, + 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x0F, 0x70, 0x0F, 0x78, 0x3F, + 0x3F, 0xFF, 0x1F, 0xF7, 0x07, 0xC7, 0x00, 0x07, 0x00, 0x06, 0x00, 0x0E, + 0x70, 0x0E, 0x70, 0x1C, 0x78, 0x3C, 0x3F, 0xF8, 0x1F, 0xF0, 0x07, 0xC0, + 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x07, 0xFF, 0x80, 0xFF, 0xF0, 0x00, 0x00, + 0x00, 0x07, 0xFF, 0xB6, 0xD6, 0x00, 0x00, 0x80, 0x03, 0xC0, 0x07, 0xE0, + 0x0F, 0xC0, 0x3F, 0x80, 0x7E, 0x00, 0xFC, 0x01, 0xF0, 0x00, 0xE0, 0x00, + 0x7C, 0x00, 0x1F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x80, 0x07, 0xF0, 0x00, + 0x7E, 0x00, 0x0F, 0x00, 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0x80, 0x80, 0x00, 0x70, 0x00, 0x3E, 0x00, 0x0F, 0xE0, 0x00, 0xFC, + 0x00, 0x1F, 0xC0, 0x03, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0x80, 0x0F, 0xC0, + 0x1F, 0x80, 0x7F, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x01, 0xC0, 0x00, + 0x80, 0x00, 0x00, 0x0F, 0xC0, 0x7F, 0xE1, 0xFF, 0xE3, 0xC3, 0xEF, 0x01, + 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, 0x00, 0x0E, 0x00, 0x38, 0x00, 0xF0, + 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x00, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x0E, + 0x00, 0x1C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xC0, 0x03, 0x80, + 0x07, 0x00, 0x0E, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x3F, 0xFF, 0x00, + 0x00, 0xFF, 0xFF, 0xC0, 0x01, 0xF8, 0x0F, 0xE0, 0x03, 0xE0, 0x01, 0xF0, + 0x07, 0x80, 0x00, 0xF8, 0x0F, 0x00, 0x00, 0x3C, 0x1E, 0x00, 0x00, 0x1E, + 0x3C, 0x03, 0xE0, 0x1E, 0x38, 0x0F, 0xF3, 0x8E, 0x78, 0x1E, 0x3F, 0x0F, + 0x70, 0x38, 0x1F, 0x07, 0x70, 0x78, 0x0F, 0x07, 0xE0, 0x70, 0x0E, 0x07, + 0xE0, 0x70, 0x0E, 0x07, 0xE0, 0xE0, 0x0E, 0x07, 0xE0, 0xE0, 0x1C, 0x07, + 0xE0, 0xE0, 0x1C, 0x0E, 0xE0, 0xE0, 0x1C, 0x0E, 0xE0, 0xE0, 0x38, 0x1C, + 0xF0, 0x70, 0x78, 0x3C, 0x70, 0x78, 0xFC, 0x78, 0x78, 0x3F, 0xDF, 0xF0, + 0x38, 0x1F, 0x0F, 0xC0, 0x3C, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x00, 0x07, 0xF0, 0x0E, 0x00, 0x01, 0xFF, 0xFE, 0x00, + 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x03, + 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xDC, 0x00, 0x07, 0x78, + 0x00, 0x3C, 0xE0, 0x00, 0xE3, 0x80, 0x03, 0x8F, 0x00, 0x1E, 0x1C, 0x00, + 0x70, 0x70, 0x01, 0xC1, 0xE0, 0x0E, 0x03, 0x80, 0x38, 0x0E, 0x00, 0xE0, + 0x3C, 0x07, 0xFF, 0xF0, 0x1F, 0xFF, 0xE0, 0xFF, 0xFF, 0x83, 0xC0, 0x0E, + 0x0E, 0x00, 0x3C, 0x78, 0x00, 0xF1, 0xE0, 0x01, 0xC7, 0x00, 0x07, 0xBC, + 0x00, 0x1E, 0xF0, 0x00, 0x3B, 0x80, 0x00, 0xF0, 0xFF, 0xFC, 0x1F, 0xFF, + 0xE3, 0xFF, 0xFE, 0x70, 0x03, 0xCE, 0x00, 0x3D, 0xC0, 0x03, 0xB8, 0x00, + 0x77, 0x00, 0x0E, 0xE0, 0x01, 0xDC, 0x00, 0x73, 0x80, 0x1E, 0x7F, 0xFF, + 0x8F, 0xFF, 0xF1, 0xFF, 0xFF, 0x38, 0x00, 0xF7, 0x00, 0x0E, 0xE0, 0x00, + 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x03, + 0xF8, 0x00, 0xF7, 0xFF, 0xFC, 0xFF, 0xFF, 0x1F, 0xFF, 0x80, 0x00, 0xFF, + 0x00, 0x0F, 0xFF, 0x00, 0xFF, 0xFE, 0x07, 0xE0, 0x7C, 0x3E, 0x00, 0x78, + 0xF0, 0x00, 0xE7, 0x80, 0x03, 0xDC, 0x00, 0x07, 0x70, 0x00, 0x03, 0x80, + 0x00, 0x0E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x03, 0x80, 0x00, + 0x0E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x1D, 0xC0, 0x00, 0x77, + 0x00, 0x03, 0xDE, 0x00, 0x0E, 0x3C, 0x00, 0x78, 0xF8, 0x03, 0xC1, 0xF8, + 0x1F, 0x03, 0xFF, 0xF8, 0x03, 0xFF, 0xC0, 0x03, 0xF8, 0x00, 0xFF, 0xF8, + 0x0F, 0xFF, 0xE0, 0xFF, 0xFF, 0x0E, 0x00, 0xF8, 0xE0, 0x03, 0xCE, 0x00, + 0x1C, 0xE0, 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xFE, 0x00, 0x07, 0xE0, + 0x00, 0x7E, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x07, 0xE0, 0x00, 0x7E, + 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x0F, 0xE0, 0x00, 0xEE, 0x00, 0x0E, + 0xE0, 0x01, 0xEE, 0x00, 0x3C, 0xE0, 0x0F, 0x8F, 0xFF, 0xF0, 0xFF, 0xFE, + 0x0F, 0xFF, 0x80, 0xFF, 0xFF, 0xBF, 0xFF, 0xEF, 0xFF, 0xFB, 0x80, 0x00, + 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, 0x00, 0x38, + 0x00, 0x0E, 0x00, 0x03, 0xFF, 0xFE, 0xFF, 0xFF, 0xBF, 0xFF, 0xEE, 0x00, + 0x03, 0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, + 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x0E, 0x00, + 0x07, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x38, + 0x00, 0x1F, 0xFF, 0xCF, 0xFF, 0xE7, 0xFF, 0xF3, 0x80, 0x01, 0xC0, 0x00, + 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, 0x00, + 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x00, 0x00, 0x7F, + 0x80, 0x03, 0xFF, 0xE0, 0x07, 0xFF, 0xF8, 0x0F, 0x80, 0xFC, 0x1E, 0x00, + 0x3E, 0x3C, 0x00, 0x0E, 0x78, 0x00, 0x0F, 0x70, 0x00, 0x07, 0x70, 0x00, + 0x00, 0xE0, 0x00, 0x00, 0xE0, 0x00, 0x00, 0xE0, 0x00, 0x00, 0xE0, 0x03, + 0xFF, 0xE0, 0x03, 0xFF, 0xE0, 0x03, 0xFF, 0xE0, 0x00, 0x07, 0xF0, 0x00, + 0x07, 0x70, 0x00, 0x07, 0x70, 0x00, 0x0F, 0x78, 0x00, 0x0F, 0x3C, 0x00, + 0x1F, 0x1E, 0x00, 0x3F, 0x0F, 0xC0, 0xF7, 0x07, 0xFF, 0xE7, 0x03, 0xFF, + 0xC3, 0x00, 0xFF, 0x03, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, + 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0, + 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, + 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00, + 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1C, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, + 0x1C, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xC0, + 0x07, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, 0x1F, 0x80, 0x7E, + 0x01, 0xF8, 0x07, 0xE0, 0x1F, 0xC0, 0xF7, 0x87, 0x9F, 0xFE, 0x3F, 0xF0, + 0x3F, 0x00, 0xE0, 0x01, 0xEE, 0x00, 0x3C, 0xE0, 0x07, 0x8E, 0x00, 0xF0, + 0xE0, 0x1E, 0x0E, 0x03, 0xE0, 0xE0, 0x7C, 0x0E, 0x0F, 0x80, 0xE1, 0xF0, + 0x0E, 0x1E, 0x00, 0xE3, 0xC0, 0x0E, 0x7C, 0x00, 0xEF, 0xE0, 0x0F, 0xCE, + 0x00, 0xF8, 0xF0, 0x0F, 0x07, 0x80, 0xE0, 0x3C, 0x0E, 0x03, 0xC0, 0xE0, + 0x1E, 0x0E, 0x00, 0xF0, 0xE0, 0x0F, 0x0E, 0x00, 0x78, 0xE0, 0x03, 0xCE, + 0x00, 0x3C, 0xE0, 0x01, 0xEE, 0x00, 0x0F, 0xE0, 0x01, 0xC0, 0x03, 0x80, + 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x01, + 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x70, + 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00, + 0x38, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xF8, 0x00, 0x1F, 0xF8, + 0x00, 0x1F, 0xF8, 0x00, 0x1F, 0xFC, 0x00, 0x3F, 0xFC, 0x00, 0x3F, 0xFC, + 0x00, 0x3F, 0xEE, 0x00, 0x77, 0xEE, 0x00, 0x77, 0xEE, 0x00, 0x77, 0xE7, + 0x00, 0xE7, 0xE7, 0x00, 0xE7, 0xE7, 0x00, 0xE7, 0xE3, 0x81, 0xC7, 0xE3, + 0x81, 0xC7, 0xE3, 0x81, 0xC7, 0xE1, 0xC3, 0x87, 0xE1, 0xC3, 0x87, 0xE1, + 0xC3, 0x87, 0xE0, 0xE7, 0x07, 0xE0, 0xE7, 0x07, 0xE0, 0xE7, 0x07, 0xE0, + 0x7E, 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0x3C, 0x07, 0xE0, + 0x3C, 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xF8, 0x00, 0x7F, 0xC0, 0x07, + 0xFC, 0x00, 0x7F, 0xE0, 0x07, 0xEF, 0x00, 0x7E, 0x70, 0x07, 0xE7, 0x80, + 0x7E, 0x3C, 0x07, 0xE1, 0xC0, 0x7E, 0x1E, 0x07, 0xE0, 0xE0, 0x7E, 0x0F, + 0x07, 0xE0, 0x78, 0x7E, 0x03, 0x87, 0xE0, 0x3C, 0x7E, 0x01, 0xE7, 0xE0, + 0x0E, 0x7E, 0x00, 0xF7, 0xE0, 0x07, 0xFE, 0x00, 0x3F, 0xE0, 0x03, 0xFE, + 0x00, 0x1F, 0xE0, 0x01, 0xFE, 0x00, 0x0F, 0x00, 0x7F, 0x00, 0x01, 0xFF, + 0xF0, 0x01, 0xFF, 0xFC, 0x01, 0xF0, 0x1F, 0x01, 0xE0, 0x03, 0xC1, 0xE0, + 0x00, 0xF1, 0xE0, 0x00, 0x3C, 0xE0, 0x00, 0x0E, 0x70, 0x00, 0x07, 0x70, + 0x00, 0x03, 0xF8, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, + 0x00, 0x00, 0x1F, 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03, + 0xB8, 0x00, 0x03, 0x9C, 0x00, 0x01, 0xCF, 0x00, 0x01, 0xE3, 0xC0, 0x01, + 0xE0, 0xF0, 0x01, 0xE0, 0x3E, 0x03, 0xE0, 0x0F, 0xFF, 0xE0, 0x03, 0xFF, + 0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFF, 0xFC, 0x3F, 0xFF, 0x8F, 0xFF, 0xF3, + 0x80, 0x3E, 0xE0, 0x03, 0xF8, 0x00, 0x7E, 0x00, 0x1F, 0x80, 0x07, 0xE0, + 0x01, 0xF8, 0x00, 0x7E, 0x00, 0x3F, 0x80, 0x1E, 0xFF, 0xFF, 0x3F, 0xFF, + 0x8F, 0xFF, 0xC3, 0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, + 0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, + 0x00, 0x38, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x01, 0xFF, 0xF0, 0x01, 0xFF, + 0xFC, 0x01, 0xF0, 0x1F, 0x01, 0xE0, 0x03, 0xC1, 0xE0, 0x00, 0xF1, 0xE0, + 0x00, 0x3C, 0xE0, 0x00, 0x0E, 0x70, 0x00, 0x07, 0x70, 0x00, 0x01, 0xF8, + 0x00, 0x00, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, + 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x07, 0xB8, 0x00, 0x03, + 0x9C, 0x00, 0x01, 0xCF, 0x00, 0x39, 0xE3, 0xC0, 0x1F, 0xE0, 0xF0, 0x07, + 0xE0, 0x3E, 0x03, 0xF0, 0x0F, 0xFF, 0xFC, 0x03, 0xFF, 0xEE, 0x00, 0x3F, + 0x83, 0x80, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x20, 0xFF, 0xFE, 0x0F, 0xFF, + 0xF8, 0xFF, 0xFF, 0xCE, 0x00, 0x3C, 0xE0, 0x01, 0xEE, 0x00, 0x0E, 0xE0, + 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x01, 0xCE, + 0x00, 0x3C, 0xFF, 0xFF, 0x8F, 0xFF, 0xF0, 0xFF, 0xFF, 0x8E, 0x00, 0x3C, + 0xE0, 0x01, 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x00, + 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xFE, 0x00, + 0x0F, 0x03, 0xFC, 0x00, 0xFF, 0xF0, 0x1F, 0xFF, 0x83, 0xE0, 0x7C, 0x38, + 0x01, 0xE7, 0x00, 0x0E, 0x70, 0x00, 0xE7, 0x00, 0x00, 0x70, 0x00, 0x07, + 0x80, 0x00, 0x3E, 0x00, 0x01, 0xFE, 0x00, 0x0F, 0xFE, 0x00, 0x3F, 0xF8, + 0x00, 0x3F, 0xE0, 0x00, 0x3E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0xE0, 0x00, + 0x7E, 0x00, 0x07, 0xF0, 0x00, 0x77, 0x80, 0x0E, 0x7C, 0x03, 0xE3, 0xFF, + 0xFC, 0x1F, 0xFF, 0x80, 0x3F, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0x80, 0x70, 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x07, + 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x0E, + 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x1C, + 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x38, + 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0xE0, 0x00, 0xFC, 0x00, + 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, + 0x3F, 0x00, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, + 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0, 0x00, + 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7F, 0x00, 0x1E, 0xF0, 0x07, + 0x9F, 0x01, 0xF1, 0xFF, 0xFC, 0x1F, 0xFE, 0x00, 0x7F, 0x00, 0xE0, 0x00, + 0x7F, 0x80, 0x03, 0xFC, 0x00, 0x1C, 0xE0, 0x01, 0xE7, 0x80, 0x0F, 0x3C, + 0x00, 0x70, 0xE0, 0x07, 0x87, 0x80, 0x3C, 0x1C, 0x01, 0xC0, 0xE0, 0x0E, + 0x07, 0x80, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x38, 0x07, 0x83, 0x80, 0x1C, + 0x1C, 0x00, 0xE0, 0xE0, 0x07, 0x8E, 0x00, 0x1C, 0x70, 0x00, 0xE3, 0x80, + 0x07, 0xB8, 0x00, 0x1D, 0xC0, 0x00, 0xEE, 0x00, 0x07, 0xE0, 0x00, 0x1F, + 0x00, 0x00, 0xF8, 0x00, 0x03, 0x80, 0x00, 0x70, 0x03, 0xC0, 0x0F, 0x70, + 0x03, 0xC0, 0x0F, 0x78, 0x03, 0xE0, 0x0F, 0x78, 0x03, 0xE0, 0x0E, 0x38, + 0x07, 0xE0, 0x0E, 0x38, 0x07, 0xF0, 0x1E, 0x3C, 0x07, 0x70, 0x1E, 0x3C, + 0x07, 0x70, 0x1C, 0x1C, 0x0E, 0x70, 0x1C, 0x1C, 0x0E, 0x38, 0x3C, 0x1C, + 0x0E, 0x38, 0x3C, 0x1E, 0x1E, 0x38, 0x38, 0x0E, 0x1C, 0x38, 0x38, 0x0E, + 0x1C, 0x1C, 0x38, 0x0E, 0x1C, 0x1C, 0x78, 0x0F, 0x3C, 0x1C, 0x70, 0x07, + 0x38, 0x0E, 0x70, 0x07, 0x38, 0x0E, 0x70, 0x07, 0x38, 0x0E, 0x70, 0x07, + 0x70, 0x0E, 0xE0, 0x03, 0xF0, 0x07, 0xE0, 0x03, 0xF0, 0x07, 0xE0, 0x03, + 0xF0, 0x07, 0xE0, 0x03, 0xE0, 0x03, 0xC0, 0x01, 0xE0, 0x03, 0xC0, 0x01, + 0xE0, 0x03, 0xC0, 0xF0, 0x00, 0x7B, 0xC0, 0x07, 0x8F, 0x00, 0x38, 0x78, + 0x03, 0xC1, 0xE0, 0x3C, 0x07, 0x81, 0xC0, 0x3C, 0x1E, 0x00, 0xF1, 0xE0, + 0x03, 0x8E, 0x00, 0x1E, 0xF0, 0x00, 0x7F, 0x00, 0x01, 0xF0, 0x00, 0x0F, + 0x80, 0x00, 0x7C, 0x00, 0x07, 0xF0, 0x00, 0x3B, 0x80, 0x03, 0xDE, 0x00, + 0x3C, 0x78, 0x01, 0xC1, 0xC0, 0x1E, 0x0F, 0x01, 0xE0, 0x3C, 0x0E, 0x00, + 0xE0, 0xF0, 0x07, 0x8F, 0x00, 0x1E, 0x70, 0x00, 0xF7, 0x80, 0x03, 0xC0, + 0xF0, 0x00, 0x3C, 0xF0, 0x00, 0x78, 0xF0, 0x01, 0xE1, 0xE0, 0x03, 0x81, + 0xE0, 0x0F, 0x01, 0xC0, 0x1C, 0x03, 0xC0, 0x78, 0x03, 0xC1, 0xE0, 0x07, + 0x83, 0x80, 0x07, 0x8F, 0x00, 0x07, 0x1C, 0x00, 0x0F, 0x78, 0x00, 0x0E, + 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, + 0x00, 0x00, 0x70, 0x00, 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, + 0x00, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, + 0x00, 0x70, 0x00, 0x7F, 0xFF, 0xEF, 0xFF, 0xFD, 0xFF, 0xFF, 0x80, 0x00, + 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, + 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, + 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x7C, 0x00, + 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xF8, 0xE3, 0x8E, 0x38, 0xE3, + 0x8E, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x8E, 0x38, 0xE3, + 0x8E, 0x38, 0xE3, 0x8F, 0xFF, 0xFC, 0xC0, 0x30, 0x06, 0x01, 0x80, 0x60, + 0x0C, 0x03, 0x00, 0xC0, 0x18, 0x06, 0x01, 0x80, 0x20, 0x0C, 0x03, 0x00, + 0x40, 0x18, 0x06, 0x01, 0x80, 0x30, 0x0C, 0x03, 0x00, 0x60, 0x18, 0x06, + 0x00, 0xC0, 0x30, 0xFF, 0xFF, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, + 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, + 0x1C, 0x7F, 0xFF, 0xFC, 0x07, 0x00, 0x78, 0x03, 0xC0, 0x3F, 0x01, 0xD8, + 0x0C, 0xE0, 0xE3, 0x06, 0x1C, 0x70, 0xE3, 0x83, 0x18, 0x1D, 0xC0, 0x6C, + 0x03, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xF0, 0xF0, 0xE0, 0xE0, + 0xE0, 0x07, 0xF0, 0x0F, 0xFC, 0x0F, 0xFF, 0x0F, 0x03, 0xC7, 0x00, 0xE0, + 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0xFE, 0x0F, 0xFF, 0x1F, 0xF3, + 0x9F, 0x01, 0xCF, 0x00, 0xE7, 0x00, 0x73, 0x80, 0x79, 0xE0, 0xFC, 0x7F, + 0xEF, 0x9F, 0xE3, 0xC7, 0xE1, 0xE0, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, + 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE3, 0xE0, 0xEF, 0xF8, + 0xFF, 0xFC, 0xFC, 0x3E, 0xF8, 0x1E, 0xF0, 0x0E, 0xE0, 0x0F, 0xE0, 0x07, + 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xF0, 0x0E, + 0xF8, 0x1E, 0xFC, 0x3C, 0xEF, 0xFC, 0xEF, 0xF8, 0xE3, 0xE0, 0x07, 0xF0, + 0x1F, 0xF8, 0x3F, 0xFC, 0x3C, 0x1E, 0x78, 0x0E, 0x70, 0x07, 0xE0, 0x00, + 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x07, + 0x70, 0x07, 0x78, 0x0E, 0x7C, 0x1E, 0x3F, 0xFC, 0x1F, 0xF8, 0x07, 0xE0, + 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, + 0x1C, 0x00, 0x0E, 0x0F, 0xC7, 0x1F, 0xFB, 0x9F, 0xFF, 0xDF, 0x07, 0xEF, + 0x01, 0xF7, 0x00, 0x7F, 0x80, 0x3F, 0x80, 0x0F, 0xC0, 0x07, 0xE0, 0x03, + 0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0x77, 0x00, 0x7B, 0xC0, 0x7D, 0xF0, + 0x7E, 0x7F, 0xFB, 0x1F, 0xF9, 0x83, 0xF0, 0xC0, 0x07, 0xE0, 0x1F, 0xF8, + 0x3F, 0xFC, 0x7C, 0x1E, 0x70, 0x0E, 0x60, 0x06, 0xE0, 0x07, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0x70, 0x07, + 0x78, 0x0E, 0x3C, 0x1E, 0x3F, 0xFC, 0x1F, 0xF8, 0x07, 0xE0, 0x0E, 0x3C, + 0xF9, 0xC3, 0x87, 0x0E, 0x7F, 0xFF, 0xFC, 0xE1, 0xC3, 0x87, 0x0E, 0x1C, + 0x38, 0x70, 0xE1, 0xC3, 0x87, 0x0E, 0x1C, 0x38, 0x70, 0x07, 0xC7, 0x1F, + 0xF7, 0x3F, 0xFF, 0x3C, 0x3F, 0x78, 0x0F, 0x70, 0x0F, 0xE0, 0x07, 0xE0, + 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0x70, + 0x0F, 0x78, 0x0F, 0x7C, 0x3F, 0x3F, 0xF7, 0x1F, 0xE7, 0x07, 0xC7, 0x00, + 0x07, 0x00, 0x07, 0x00, 0x0E, 0x70, 0x0E, 0x78, 0x1E, 0x3F, 0xFC, 0x1F, + 0xF8, 0x07, 0xE0, 0xE0, 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, + 0x1C, 0x00, 0x38, 0x00, 0x71, 0xF8, 0xE7, 0xFD, 0xDF, 0xFB, 0xF0, 0xFF, + 0xC0, 0xFF, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, 0xE0, 0x0F, 0xC0, + 0x1F, 0x80, 0x3F, 0x00, 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, + 0xE0, 0x0F, 0xC0, 0x1C, 0xFF, 0xF0, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFC, 0x1C, 0x71, 0xC7, 0x00, 0x00, 0x07, 0x1C, 0x71, 0xC7, 0x1C, + 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, + 0x73, 0xFF, 0xFB, 0xC0, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, + 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x3C, 0xE0, 0x78, 0xE0, 0xF0, + 0xE1, 0xE0, 0xE3, 0xC0, 0xE7, 0x80, 0xEF, 0x00, 0xEF, 0x80, 0xFF, 0x80, + 0xFB, 0xC0, 0xF1, 0xE0, 0xE0, 0xE0, 0xE0, 0xF0, 0xE0, 0x70, 0xE0, 0x78, + 0xE0, 0x3C, 0xE0, 0x1C, 0xE0, 0x1E, 0xE0, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xE3, 0xE0, 0xF8, 0xE7, 0xF1, 0xFE, + 0xEF, 0xFB, 0xFE, 0xF8, 0x7F, 0x0F, 0xF0, 0x3E, 0x07, 0xF0, 0x1C, 0x07, + 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, + 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, + 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, + 0xE0, 0x1C, 0x07, 0xE3, 0xF1, 0xCF, 0xFB, 0xBF, 0xF7, 0xE1, 0xFF, 0x81, + 0xFE, 0x01, 0xF8, 0x03, 0xF0, 0x07, 0xE0, 0x0F, 0xC0, 0x1F, 0x80, 0x3F, + 0x00, 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, 0xE0, 0x0F, 0xC0, + 0x1F, 0x80, 0x38, 0x07, 0xF0, 0x0F, 0xFE, 0x0F, 0xFF, 0x87, 0x83, 0xC7, + 0x80, 0xF3, 0x80, 0x3B, 0x80, 0x1F, 0xC0, 0x07, 0xE0, 0x03, 0xF0, 0x01, + 0xF8, 0x00, 0xFC, 0x00, 0x7E, 0x00, 0x3B, 0x80, 0x39, 0xE0, 0x3C, 0x78, + 0x3C, 0x3F, 0xFE, 0x0F, 0xFE, 0x01, 0xFC, 0x00, 0xE3, 0xE0, 0xE7, 0xF8, + 0xEF, 0xFC, 0xFC, 0x3E, 0xF8, 0x1E, 0xF0, 0x0E, 0xE0, 0x0F, 0xE0, 0x07, + 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xF0, 0x0E, + 0xF8, 0x1E, 0xFC, 0x3E, 0xFF, 0xFC, 0xEF, 0xF8, 0xE3, 0xE0, 0xE0, 0x00, + 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0x07, 0xE1, + 0x8F, 0xFC, 0xCF, 0xFF, 0x67, 0x83, 0xF7, 0x80, 0xFB, 0x80, 0x3F, 0xC0, + 0x1F, 0xC0, 0x07, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0x7E, + 0x00, 0x3B, 0x80, 0x3D, 0xE0, 0x3E, 0xF8, 0x3F, 0x3F, 0xFF, 0x8F, 0xFD, + 0xC1, 0xF8, 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, + 0x07, 0x00, 0x03, 0x80, 0xE3, 0xF7, 0xFB, 0xFF, 0x8F, 0x07, 0x83, 0x81, + 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, + 0x38, 0x00, 0x0F, 0xC0, 0xFF, 0x87, 0xFF, 0x3C, 0x1E, 0xE0, 0x3B, 0x80, + 0x0E, 0x00, 0x3C, 0x00, 0x7F, 0x00, 0xFF, 0x80, 0xFF, 0x80, 0x7F, 0x00, + 0x3F, 0x80, 0x7E, 0x01, 0xFC, 0x1F, 0x7F, 0xF8, 0xFF, 0xC1, 0xFC, 0x00, + 0x38, 0x70, 0xE1, 0xCF, 0xFF, 0xFF, 0x9C, 0x38, 0x70, 0xE1, 0xC3, 0x87, + 0x0E, 0x1C, 0x38, 0x70, 0xE1, 0xC3, 0xE7, 0xC7, 0x80, 0xE0, 0x0F, 0xC0, + 0x1F, 0x80, 0x3F, 0x00, 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, + 0xE0, 0x0F, 0xC0, 0x1F, 0x80, 0x3F, 0x00, 0x7E, 0x00, 0xFC, 0x03, 0xFC, + 0x0F, 0xFC, 0x3F, 0x7F, 0xEE, 0xFF, 0x9C, 0x7E, 0x38, 0x70, 0x03, 0xB8, + 0x03, 0x9C, 0x01, 0xC7, 0x00, 0xE3, 0x80, 0xE1, 0xC0, 0x70, 0x70, 0x38, + 0x38, 0x38, 0x1C, 0x1C, 0x07, 0x0E, 0x03, 0x8E, 0x01, 0xC7, 0x00, 0x77, + 0x00, 0x3B, 0x80, 0x1D, 0xC0, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, + 0x70, 0x00, 0xF0, 0x1C, 0x03, 0xB8, 0x1F, 0x03, 0xDC, 0x0F, 0x81, 0xCE, + 0x07, 0xC0, 0xE7, 0x83, 0xE0, 0x71, 0xC3, 0xB8, 0x70, 0xE1, 0xDC, 0x38, + 0x70, 0xEE, 0x1C, 0x1C, 0x63, 0x0E, 0x0E, 0x71, 0xCE, 0x07, 0x38, 0xE7, + 0x03, 0x9C, 0x73, 0x80, 0xEC, 0x19, 0x80, 0x7E, 0x0F, 0xC0, 0x3F, 0x07, + 0xE0, 0x0F, 0x83, 0xF0, 0x07, 0x80, 0xF0, 0x03, 0xC0, 0x78, 0x01, 0xE0, + 0x3C, 0x00, 0x70, 0x07, 0x38, 0x0E, 0x3C, 0x1C, 0x1C, 0x1C, 0x0E, 0x38, + 0x0F, 0x70, 0x07, 0x70, 0x03, 0xE0, 0x03, 0xC0, 0x01, 0xC0, 0x03, 0xE0, + 0x07, 0xE0, 0x07, 0x70, 0x0E, 0x78, 0x1E, 0x38, 0x1C, 0x1C, 0x38, 0x1E, + 0x78, 0x0E, 0x70, 0x07, 0x70, 0x07, 0x38, 0x03, 0x9C, 0x01, 0xC7, 0x01, + 0xC3, 0x80, 0xE1, 0xC0, 0x70, 0x70, 0x70, 0x38, 0x38, 0x1C, 0x3C, 0x07, + 0x1C, 0x03, 0x8E, 0x01, 0xCE, 0x00, 0x77, 0x00, 0x3B, 0x80, 0x1F, 0x80, + 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x38, + 0x00, 0x1C, 0x00, 0x1E, 0x00, 0x0E, 0x00, 0x3F, 0x00, 0x1F, 0x00, 0x0F, + 0x00, 0x00, 0x7F, 0xFC, 0xFF, 0xF9, 0xFF, 0xF0, 0x00, 0xE0, 0x03, 0x80, + 0x0E, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x1C, 0x00, 0x70, + 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xF8, 0x07, 0x0F, 0x1F, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1C, 0x1C, 0x1C, 0x38, 0xF8, 0xE0, 0xF8, 0x38, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1F, 0x0F, 0x07, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xE0, 0xF0, 0xF8, 0x38, + 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x1C, 0x1F, + 0x07, 0x1F, 0x1C, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, + 0x38, 0x38, 0xF8, 0xF0, 0xE0, 0x38, 0x00, 0xFC, 0x03, 0xFC, 0x1F, 0x3E, + 0x3C, 0x1F, 0xE0, 0x1F, 0x80, 0x1E, 0x00 }; + +const GFXglyph FreeSans18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 9, 0, 1 }, // 0x20 ' ' + { 0, 3, 26, 12, 4, -25 }, // 0x21 '!' + { 10, 9, 9, 12, 1, -24 }, // 0x22 '"' + { 21, 19, 24, 19, 0, -23 }, // 0x23 '#' + { 78, 16, 30, 19, 2, -26 }, // 0x24 '$' + { 138, 29, 25, 31, 1, -24 }, // 0x25 '%' + { 229, 20, 25, 23, 2, -24 }, // 0x26 '&' + { 292, 3, 9, 7, 2, -24 }, // 0x27 ''' + { 296, 8, 33, 12, 3, -25 }, // 0x28 '(' + { 329, 8, 33, 12, 1, -25 }, // 0x29 ')' + { 362, 10, 10, 14, 2, -25 }, // 0x2A '*' + { 375, 16, 16, 20, 2, -15 }, // 0x2B '+' + { 407, 3, 9, 10, 3, -3 }, // 0x2C ',' + { 411, 8, 3, 12, 2, -10 }, // 0x2D '-' + { 414, 3, 4, 9, 3, -3 }, // 0x2E '.' + { 416, 10, 26, 10, 0, -25 }, // 0x2F '/' + { 449, 16, 25, 19, 2, -24 }, // 0x30 '0' + { 499, 8, 25, 19, 4, -24 }, // 0x31 '1' + { 524, 16, 25, 19, 2, -24 }, // 0x32 '2' + { 574, 17, 25, 19, 1, -24 }, // 0x33 '3' + { 628, 16, 25, 19, 1, -24 }, // 0x34 '4' + { 678, 17, 25, 19, 1, -24 }, // 0x35 '5' + { 732, 16, 25, 19, 2, -24 }, // 0x36 '6' + { 782, 16, 25, 19, 2, -24 }, // 0x37 '7' + { 832, 17, 25, 19, 1, -24 }, // 0x38 '8' + { 886, 16, 25, 19, 1, -24 }, // 0x39 '9' + { 936, 3, 19, 9, 3, -18 }, // 0x3A ':' + { 944, 3, 24, 9, 3, -18 }, // 0x3B ';' + { 953, 17, 17, 20, 2, -16 }, // 0x3C '<' + { 990, 17, 9, 20, 2, -12 }, // 0x3D '=' + { 1010, 17, 17, 20, 2, -16 }, // 0x3E '>' + { 1047, 15, 26, 19, 3, -25 }, // 0x3F '?' + { 1096, 32, 31, 36, 1, -25 }, // 0x40 '@' + { 1220, 22, 26, 23, 1, -25 }, // 0x41 'A' + { 1292, 19, 26, 23, 3, -25 }, // 0x42 'B' + { 1354, 22, 26, 25, 1, -25 }, // 0x43 'C' + { 1426, 20, 26, 24, 3, -25 }, // 0x44 'D' + { 1491, 18, 26, 22, 3, -25 }, // 0x45 'E' + { 1550, 17, 26, 21, 3, -25 }, // 0x46 'F' + { 1606, 24, 26, 27, 1, -25 }, // 0x47 'G' + { 1684, 19, 26, 25, 3, -25 }, // 0x48 'H' + { 1746, 3, 26, 10, 4, -25 }, // 0x49 'I' + { 1756, 14, 26, 18, 1, -25 }, // 0x4A 'J' + { 1802, 20, 26, 24, 3, -25 }, // 0x4B 'K' + { 1867, 15, 26, 20, 3, -25 }, // 0x4C 'L' + { 1916, 24, 26, 30, 3, -25 }, // 0x4D 'M' + { 1994, 20, 26, 26, 3, -25 }, // 0x4E 'N' + { 2059, 25, 26, 27, 1, -25 }, // 0x4F 'O' + { 2141, 18, 26, 23, 3, -25 }, // 0x50 'P' + { 2200, 25, 28, 27, 1, -25 }, // 0x51 'Q' + { 2288, 20, 26, 25, 3, -25 }, // 0x52 'R' + { 2353, 20, 26, 23, 1, -25 }, // 0x53 'S' + { 2418, 19, 26, 22, 1, -25 }, // 0x54 'T' + { 2480, 19, 26, 25, 3, -25 }, // 0x55 'U' + { 2542, 21, 26, 23, 1, -25 }, // 0x56 'V' + { 2611, 32, 26, 33, 0, -25 }, // 0x57 'W' + { 2715, 21, 26, 23, 1, -25 }, // 0x58 'X' + { 2784, 23, 26, 24, 0, -25 }, // 0x59 'Y' + { 2859, 19, 26, 22, 1, -25 }, // 0x5A 'Z' + { 2921, 6, 33, 10, 2, -25 }, // 0x5B '[' + { 2946, 10, 26, 10, 0, -25 }, // 0x5C '\' + { 2979, 6, 33, 10, 1, -25 }, // 0x5D ']' + { 3004, 13, 13, 16, 2, -24 }, // 0x5E '^' + { 3026, 21, 2, 19, -1, 5 }, // 0x5F '_' + { 3032, 7, 5, 9, 1, -25 }, // 0x60 '`' + { 3037, 17, 19, 19, 1, -18 }, // 0x61 'a' + { 3078, 16, 26, 20, 2, -25 }, // 0x62 'b' + { 3130, 16, 19, 18, 1, -18 }, // 0x63 'c' + { 3168, 17, 26, 20, 1, -25 }, // 0x64 'd' + { 3224, 16, 19, 19, 1, -18 }, // 0x65 'e' + { 3262, 7, 26, 10, 1, -25 }, // 0x66 'f' + { 3285, 16, 27, 19, 1, -18 }, // 0x67 'g' + { 3339, 15, 26, 19, 2, -25 }, // 0x68 'h' + { 3388, 3, 26, 8, 2, -25 }, // 0x69 'i' + { 3398, 6, 34, 9, 0, -25 }, // 0x6A 'j' + { 3424, 16, 26, 18, 2, -25 }, // 0x6B 'k' + { 3476, 3, 26, 7, 2, -25 }, // 0x6C 'l' + { 3486, 24, 19, 28, 2, -18 }, // 0x6D 'm' + { 3543, 15, 19, 19, 2, -18 }, // 0x6E 'n' + { 3579, 17, 19, 19, 1, -18 }, // 0x6F 'o' + { 3620, 16, 25, 20, 2, -18 }, // 0x70 'p' + { 3670, 17, 25, 20, 1, -18 }, // 0x71 'q' + { 3724, 9, 19, 12, 2, -18 }, // 0x72 'r' + { 3746, 14, 19, 17, 2, -18 }, // 0x73 's' + { 3780, 7, 23, 10, 1, -22 }, // 0x74 't' + { 3801, 15, 19, 19, 2, -18 }, // 0x75 'u' + { 3837, 17, 19, 17, 0, -18 }, // 0x76 'v' + { 3878, 25, 19, 25, 0, -18 }, // 0x77 'w' + { 3938, 16, 19, 17, 0, -18 }, // 0x78 'x' + { 3976, 17, 27, 17, 0, -18 }, // 0x79 'y' + { 4034, 15, 19, 17, 1, -18 }, // 0x7A 'z' + { 4070, 8, 33, 12, 1, -25 }, // 0x7B '{' + { 4103, 2, 33, 9, 3, -25 }, // 0x7C '|' + { 4112, 8, 33, 12, 3, -25 }, // 0x7D '}' + { 4145, 15, 7, 18, 1, -15 } }; // 0x7E '~' + +const GFXfont FreeSans18pt7b PROGMEM = { + (uint8_t *)FreeSans18pt7bBitmaps, + (GFXglyph *)FreeSans18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 4831 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSans24pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSans24pt7b.h new file mode 100644 index 0000000..ff2d174 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSans24pt7b.h @@ -0,0 +1,727 @@ +const uint8_t FreeSans24pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x76, 0x66, + 0x66, 0x00, 0x0F, 0xFF, 0xFF, 0xF1, 0xFE, 0x3F, 0xC7, 0xF8, 0xFF, 0x1F, + 0xE3, 0xFC, 0x7F, 0x8F, 0xF1, 0xEC, 0x19, 0x83, 0x30, 0x60, 0x00, 0x70, + 0x3C, 0x00, 0x70, 0x3C, 0x00, 0xF0, 0x38, 0x00, 0xF0, 0x38, 0x00, 0xF0, + 0x78, 0x00, 0xE0, 0x78, 0x00, 0xE0, 0x78, 0x01, 0xE0, 0x70, 0x01, 0xE0, + 0x70, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x03, 0xC0, + 0xE0, 0x03, 0xC0, 0xE0, 0x03, 0xC0, 0xE0, 0x03, 0x81, 0xE0, 0x03, 0x81, + 0xE0, 0x03, 0x81, 0xE0, 0x07, 0x81, 0xC0, 0x07, 0x81, 0xC0, 0xFF, 0xFF, + 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0x0F, 0x03, 0x80, 0x0F, 0x03, + 0x80, 0x0F, 0x07, 0x80, 0x0E, 0x07, 0x80, 0x0E, 0x07, 0x80, 0x1E, 0x07, + 0x00, 0x1E, 0x07, 0x00, 0x1E, 0x07, 0x00, 0x1C, 0x0F, 0x00, 0x1C, 0x0F, + 0x00, 0x00, 0x38, 0x00, 0x01, 0xFC, 0x00, 0x1F, 0xFE, 0x00, 0x7F, 0xFE, + 0x01, 0xFF, 0xFE, 0x07, 0xE7, 0x3E, 0x0F, 0x8E, 0x3C, 0x3E, 0x1C, 0x3C, + 0x78, 0x38, 0x38, 0xF0, 0x70, 0x71, 0xE0, 0xE0, 0xE3, 0xC1, 0xC0, 0x07, + 0x83, 0x80, 0x0F, 0x87, 0x00, 0x0F, 0x8E, 0x00, 0x1F, 0xDC, 0x00, 0x1F, + 0xF8, 0x00, 0x1F, 0xFF, 0x00, 0x0F, 0xFF, 0x80, 0x07, 0xFF, 0x80, 0x03, + 0xFF, 0x80, 0x07, 0x1F, 0x80, 0x0E, 0x1F, 0x00, 0x1C, 0x1F, 0x00, 0x38, + 0x1F, 0xC0, 0x70, 0x3F, 0x80, 0xE0, 0x7F, 0x81, 0xC0, 0xFF, 0x03, 0x81, + 0xEF, 0x07, 0x07, 0x9F, 0x0E, 0x0F, 0x3E, 0x1C, 0x3E, 0x3F, 0x39, 0xF8, + 0x3F, 0xFF, 0xE0, 0x3F, 0xFF, 0x00, 0x0F, 0xF8, 0x00, 0x03, 0x80, 0x00, + 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, 0x00, + 0x00, 0x00, 0x1C, 0x00, 0x0F, 0xC0, 0x00, 0x78, 0x00, 0x3F, 0xE0, 0x00, + 0xE0, 0x01, 0xFF, 0xE0, 0x03, 0x80, 0x03, 0xFF, 0xE0, 0x07, 0x00, 0x0F, + 0x87, 0xC0, 0x1C, 0x00, 0x3C, 0x03, 0xC0, 0x38, 0x00, 0x70, 0x03, 0x80, + 0xE0, 0x00, 0xE0, 0x07, 0x03, 0xC0, 0x01, 0xC0, 0x0E, 0x07, 0x00, 0x03, + 0x80, 0x1C, 0x1E, 0x00, 0x07, 0x80, 0x78, 0x38, 0x00, 0x07, 0xC3, 0xE0, + 0xF0, 0x00, 0x07, 0xFF, 0xC1, 0xC0, 0x00, 0x0F, 0xFF, 0x07, 0x80, 0x00, + 0x0F, 0xFC, 0x0E, 0x00, 0x00, 0x07, 0xE0, 0x38, 0x00, 0x00, 0x00, 0x00, + 0x70, 0x00, 0x00, 0x00, 0x01, 0xC0, 0x3F, 0x00, 0x00, 0x03, 0x80, 0xFF, + 0x80, 0x00, 0x0E, 0x07, 0xFF, 0x80, 0x00, 0x3C, 0x0F, 0xFF, 0x80, 0x00, + 0x70, 0x3E, 0x1F, 0x00, 0x01, 0xE0, 0xF0, 0x0F, 0x00, 0x03, 0x81, 0xC0, + 0x0E, 0x00, 0x0F, 0x03, 0x80, 0x1C, 0x00, 0x1C, 0x07, 0x00, 0x38, 0x00, + 0x78, 0x0E, 0x00, 0x70, 0x00, 0xE0, 0x1E, 0x01, 0xE0, 0x03, 0x80, 0x1F, + 0x0F, 0x80, 0x07, 0x00, 0x1F, 0xFF, 0x00, 0x1C, 0x00, 0x3F, 0xFC, 0x00, + 0x38, 0x00, 0x1F, 0xF0, 0x00, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x7E, 0x00, + 0x00, 0x1F, 0xF0, 0x00, 0x03, 0xFF, 0x80, 0x00, 0x7F, 0xFC, 0x00, 0x07, + 0xC3, 0xC0, 0x00, 0xF8, 0x1E, 0x00, 0x0F, 0x00, 0xE0, 0x00, 0xF0, 0x0E, + 0x00, 0x0F, 0x00, 0xE0, 0x00, 0xF0, 0x0E, 0x00, 0x07, 0x81, 0xE0, 0x00, + 0x7C, 0x3C, 0x00, 0x03, 0xEF, 0x80, 0x00, 0x1F, 0xF0, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x1F, 0x80, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0xE0, 0x00, + 0x1F, 0x1E, 0x07, 0x83, 0xE0, 0xF0, 0x78, 0x7C, 0x0F, 0x8F, 0x87, 0x80, + 0x7C, 0xF0, 0xF0, 0x03, 0xFF, 0x0F, 0x00, 0x1F, 0xE0, 0xF0, 0x00, 0xFE, + 0x0F, 0x00, 0x0F, 0xC0, 0xF0, 0x00, 0x7E, 0x0F, 0x80, 0x0F, 0xF0, 0x7C, + 0x01, 0xFF, 0x07, 0xF0, 0x7D, 0xF8, 0x3F, 0xFF, 0x8F, 0xC1, 0xFF, 0xF0, + 0x7E, 0x0F, 0xFE, 0x03, 0xE0, 0x3F, 0x80, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF6, 0x66, 0x01, 0xC0, 0x70, 0x38, 0x1C, 0x07, 0x03, 0xC0, 0xE0, 0x78, + 0x1C, 0x07, 0x03, 0xC0, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x70, 0x3C, + 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, + 0xC0, 0x70, 0x1E, 0x07, 0x81, 0xE0, 0x38, 0x0F, 0x03, 0xC0, 0x70, 0x1E, + 0x03, 0x80, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x18, 0x07, 0xE0, 0x38, 0x07, + 0x01, 0xC0, 0x38, 0x0F, 0x01, 0xC0, 0x78, 0x0E, 0x03, 0x80, 0xF0, 0x1C, + 0x07, 0x01, 0xE0, 0x78, 0x1E, 0x03, 0x80, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, + 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x07, 0x81, 0xE0, 0x78, + 0x1E, 0x07, 0x03, 0xC0, 0xF0, 0x38, 0x1E, 0x07, 0x01, 0xC0, 0xE0, 0x38, + 0x1C, 0x06, 0x03, 0x80, 0x03, 0x00, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x63, + 0x1B, 0xFF, 0xFF, 0xFF, 0xC3, 0xF0, 0x07, 0x80, 0x3F, 0x01, 0xCE, 0x07, + 0x3C, 0x38, 0x70, 0x21, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, 0x00, + 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, 0x0E, + 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x07, 0x00, 0x00, 0x0E, 0x00, + 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, 0x00, 0xE0, 0x00, + 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, 0xFF, 0xFF, 0xF3, + 0x33, 0x36, 0xEC, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xF0, + 0x00, 0x38, 0x01, 0xC0, 0x0C, 0x00, 0xE0, 0x07, 0x00, 0x30, 0x03, 0x80, + 0x1C, 0x00, 0xC0, 0x06, 0x00, 0x70, 0x03, 0x80, 0x18, 0x01, 0xC0, 0x0E, + 0x00, 0x60, 0x03, 0x00, 0x38, 0x01, 0x80, 0x0C, 0x00, 0xE0, 0x07, 0x00, + 0x30, 0x03, 0x80, 0x1C, 0x00, 0xC0, 0x06, 0x00, 0x70, 0x03, 0x80, 0x18, + 0x01, 0xC0, 0x0E, 0x00, 0x60, 0x07, 0x00, 0x38, 0x00, 0x00, 0xFC, 0x00, + 0x0F, 0xFC, 0x00, 0xFF, 0xFC, 0x07, 0xFF, 0xF8, 0x1F, 0x87, 0xE0, 0xF8, + 0x07, 0xC3, 0xC0, 0x0F, 0x1F, 0x00, 0x3E, 0x78, 0x00, 0x79, 0xE0, 0x01, + 0xE7, 0x80, 0x07, 0xBC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, + 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x00, + 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x00, 0x03, + 0xDE, 0x00, 0x1E, 0x78, 0x00, 0x79, 0xE0, 0x01, 0xE7, 0xC0, 0x0F, 0x8F, + 0x00, 0x3C, 0x3E, 0x01, 0xF0, 0x7C, 0x1F, 0x81, 0xFF, 0xFE, 0x03, 0xFF, + 0xF0, 0x03, 0xFF, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x60, 0x1C, 0x03, 0x80, + 0xF0, 0x3E, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x3C, 0x07, 0x80, 0xF0, + 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, + 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, + 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x01, 0xFE, 0x00, 0x1F, 0xFE, 0x01, 0xFF, + 0xFE, 0x0F, 0xFF, 0xFC, 0x3F, 0x03, 0xF9, 0xF0, 0x03, 0xE7, 0x80, 0x07, + 0xFE, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x00, 0x03, 0xC0, + 0x00, 0x0F, 0x00, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, + 0x7C, 0x00, 0x07, 0xF0, 0x00, 0x7F, 0x80, 0x07, 0xF8, 0x00, 0x3F, 0xC0, + 0x03, 0xFC, 0x00, 0x1F, 0xC0, 0x00, 0xFC, 0x00, 0x07, 0xC0, 0x00, 0x3E, + 0x00, 0x00, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1C, 0x00, 0x00, 0x70, 0x00, + 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, + 0x00, 0xFE, 0x00, 0x0F, 0xFF, 0x80, 0x3F, 0xFF, 0x80, 0xFF, 0xFF, 0x83, + 0xF0, 0x1F, 0x87, 0xC0, 0x1F, 0x1F, 0x00, 0x1F, 0x3C, 0x00, 0x1E, 0x78, + 0x00, 0x3C, 0xF0, 0x00, 0x78, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, + 0x07, 0x80, 0x00, 0x7F, 0x00, 0x1F, 0xFC, 0x00, 0x3F, 0xE0, 0x00, 0x7F, + 0xE0, 0x00, 0xFF, 0xF0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x03, + 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x0F, 0xF0, 0x00, 0x1F, + 0xE0, 0x00, 0x3F, 0xE0, 0x00, 0xFB, 0xC0, 0x01, 0xE7, 0xC0, 0x07, 0xC7, + 0xE0, 0x3F, 0x0F, 0xFF, 0xFE, 0x0F, 0xFF, 0xF8, 0x07, 0xFF, 0xC0, 0x03, + 0xFC, 0x00, 0x00, 0x01, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x1F, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xF8, 0x00, 0x0F, 0xF0, 0x00, 0x3F, + 0xE0, 0x00, 0x7B, 0xC0, 0x01, 0xE7, 0x80, 0x07, 0x8F, 0x00, 0x0F, 0x1E, + 0x00, 0x3C, 0x3C, 0x00, 0xF0, 0x78, 0x03, 0xC0, 0xF0, 0x07, 0x81, 0xE0, + 0x1E, 0x03, 0xC0, 0x78, 0x07, 0x81, 0xE0, 0x0F, 0x03, 0xC0, 0x1E, 0x0F, + 0x00, 0x3C, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFE, 0x00, 0x07, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0x78, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x03, + 0xC0, 0x1F, 0xFF, 0xF0, 0x7F, 0xFF, 0xC1, 0xFF, 0xFF, 0x07, 0xFF, 0xFC, + 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x1F, 0x3F, 0x80, 0x7B, 0xFF, + 0x81, 0xFF, 0xFF, 0x07, 0xFF, 0xFE, 0x1F, 0x80, 0xFC, 0x78, 0x01, 0xF8, + 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3F, 0xC0, 0x00, + 0xFF, 0x80, 0x07, 0x9E, 0x00, 0x1E, 0x7C, 0x00, 0xF1, 0xFC, 0x0F, 0xC3, + 0xFF, 0xFE, 0x07, 0xFF, 0xF0, 0x0F, 0xFF, 0x80, 0x07, 0xF0, 0x00, 0x00, + 0xFE, 0x00, 0x0F, 0xFE, 0x00, 0x7F, 0xFC, 0x03, 0xFF, 0xF8, 0x1F, 0x83, + 0xF0, 0xF8, 0x07, 0xC3, 0xC0, 0x0F, 0x8F, 0x00, 0x1E, 0x78, 0x00, 0x79, + 0xE0, 0x00, 0x07, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF0, 0xFE, 0x03, 0xCF, + 0xFE, 0x0F, 0x7F, 0xFE, 0x3F, 0xFF, 0xFC, 0xFF, 0x03, 0xF3, 0xF0, 0x03, + 0xEF, 0x80, 0x07, 0xBE, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, + 0x00, 0x03, 0xFC, 0x00, 0x0F, 0x70, 0x00, 0x3D, 0xC0, 0x00, 0xF7, 0x80, + 0x07, 0x9F, 0x00, 0x3E, 0x3E, 0x00, 0xF8, 0xFC, 0x0F, 0xC1, 0xFF, 0xFE, + 0x03, 0xFF, 0xF0, 0x07, 0xFF, 0x80, 0x07, 0xF8, 0x00, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x07, 0x00, 0x00, + 0x78, 0x00, 0x07, 0x80, 0x00, 0x38, 0x00, 0x03, 0xC0, 0x00, 0x3C, 0x00, + 0x01, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x70, + 0x00, 0x07, 0x80, 0x00, 0x38, 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x01, + 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x38, 0x00, + 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, + 0x01, 0xFE, 0x00, 0x1F, 0xFE, 0x00, 0xFF, 0xFC, 0x07, 0xFF, 0xF8, 0x3F, + 0x03, 0xF1, 0xF0, 0x03, 0xC7, 0xC0, 0x0F, 0x9E, 0x00, 0x1E, 0x78, 0x00, + 0x79, 0xE0, 0x01, 0xE7, 0x80, 0x0F, 0x8F, 0x00, 0x3C, 0x3F, 0x03, 0xF0, + 0x7F, 0xFF, 0x80, 0x7F, 0xF8, 0x03, 0xFF, 0xF0, 0x1F, 0xFF, 0xE0, 0xFC, + 0x0F, 0xC7, 0xC0, 0x0F, 0x9E, 0x00, 0x1E, 0xF8, 0x00, 0x7F, 0xC0, 0x00, + 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, + 0x80, 0x07, 0xDE, 0x00, 0x1E, 0x7C, 0x00, 0xF8, 0xFC, 0x0F, 0xC3, 0xFF, + 0xFF, 0x07, 0xFF, 0xF8, 0x07, 0xFF, 0x80, 0x07, 0xF8, 0x00, 0x01, 0xFC, + 0x00, 0x3F, 0xF8, 0x03, 0xFF, 0xE0, 0x3F, 0xFF, 0x83, 0xF0, 0x7E, 0x3E, + 0x00, 0xF1, 0xE0, 0x07, 0xCF, 0x00, 0x1E, 0xF0, 0x00, 0x77, 0x80, 0x03, + 0xBC, 0x00, 0x1F, 0xE0, 0x00, 0xFF, 0x00, 0x07, 0xF8, 0x00, 0x3F, 0xE0, + 0x03, 0xEF, 0x00, 0x1F, 0x7C, 0x01, 0xF9, 0xF8, 0x3F, 0xCF, 0xFF, 0xFE, + 0x3F, 0xFE, 0xF0, 0xFF, 0xE7, 0x80, 0xFC, 0x3C, 0x00, 0x01, 0xE0, 0x00, + 0x0E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x9E, 0x00, 0x3C, 0xF0, 0x03, 0xC7, + 0xC0, 0x3E, 0x1F, 0x03, 0xE0, 0xFF, 0xFE, 0x03, 0xFF, 0xE0, 0x0F, 0xFE, + 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xF3, 0x33, 0x36, 0xEC, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x1C, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x7F, 0xC0, + 0x03, 0xFC, 0x00, 0x3F, 0xE0, 0x01, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, + 0x80, 0x03, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x0F, 0xF0, + 0x00, 0x07, 0xFC, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, + 0xC0, 0x00, 0x3F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x07, 0xE0, 0x00, 0x01, + 0xC0, 0x00, 0x00, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xF0, 0x80, 0x00, 0x01, 0xC0, 0x00, 0x03, 0xF0, 0x00, 0x07, + 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFF, 0x00, 0x00, 0xFF, 0x80, 0x00, + 0x3F, 0xC0, 0x00, 0x1F, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x03, 0xF8, 0x00, + 0x01, 0xF0, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0xC0, 0x03, 0xFC, 0x00, 0x1F, + 0xE0, 0x01, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x80, 0x07, 0xFC, 0x00, + 0x0F, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0x30, 0x00, 0x00, 0x00, 0x03, 0xF8, + 0x00, 0xFF, 0xF0, 0x1F, 0xFF, 0x83, 0xFF, 0xFC, 0x7E, 0x0F, 0xE7, 0x80, + 0x3E, 0x78, 0x01, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, + 0x00, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, + 0x01, 0xF0, 0x00, 0x1E, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xE0, + 0x00, 0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, + 0xE0, 0x00, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xC0, + 0x00, 0x00, 0x3F, 0xFF, 0xFE, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xF0, 0x00, + 0x07, 0xFC, 0x03, 0xFF, 0x00, 0x01, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x7E, + 0x00, 0x00, 0x7F, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xF0, 0x07, 0xC0, 0x00, + 0x00, 0x3F, 0x01, 0xF0, 0x00, 0x00, 0x03, 0xF0, 0x3C, 0x00, 0x7E, 0x00, + 0x3E, 0x0F, 0x00, 0x3F, 0xE3, 0xC3, 0xE3, 0xE0, 0x1F, 0xFE, 0x78, 0x3C, + 0x78, 0x07, 0xE1, 0xFF, 0x07, 0xDF, 0x01, 0xF0, 0x1F, 0xC0, 0xFB, 0xC0, + 0x7C, 0x01, 0xF8, 0x0F, 0x78, 0x0F, 0x00, 0x3F, 0x01, 0xEF, 0x03, 0xC0, + 0x07, 0xC0, 0x3F, 0xC0, 0x78, 0x00, 0xF8, 0x07, 0xF8, 0x0F, 0x00, 0x1F, + 0x00, 0xFF, 0x03, 0xC0, 0x03, 0xC0, 0x1F, 0xE0, 0x78, 0x00, 0x78, 0x07, + 0xFC, 0x0F, 0x00, 0x1F, 0x00, 0xF7, 0x81, 0xE0, 0x03, 0xC0, 0x1E, 0xF0, + 0x3C, 0x00, 0x78, 0x07, 0x9E, 0x07, 0x80, 0x1F, 0x01, 0xF3, 0xE0, 0xF8, + 0x07, 0xC0, 0x3C, 0x3C, 0x0F, 0x81, 0xF8, 0x0F, 0x87, 0x81, 0xF8, 0x7F, + 0x87, 0xE0, 0xF8, 0x1F, 0xFE, 0xFF, 0xF8, 0x0F, 0x01, 0xFF, 0x1F, 0xFC, + 0x01, 0xF0, 0x0F, 0x80, 0xFE, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x00, 0x03, + 0xF0, 0x00, 0x00, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00, 0x00, 0x03, 0xF8, + 0x00, 0x00, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x00, 0x03, 0xFE, 0x00, + 0x7C, 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0x80, 0x00, 0x01, 0xFF, 0xFF, 0xF8, + 0x00, 0x00, 0x0F, 0xFF, 0xFC, 0x00, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, + 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x00, 0xF7, 0xC0, 0x00, 0x03, + 0xDF, 0x00, 0x00, 0x1F, 0x3C, 0x00, 0x00, 0x78, 0xF8, 0x00, 0x01, 0xE3, + 0xE0, 0x00, 0x0F, 0x87, 0x80, 0x00, 0x3C, 0x1F, 0x00, 0x01, 0xF0, 0x7C, + 0x00, 0x07, 0x80, 0xF0, 0x00, 0x1E, 0x03, 0xE0, 0x00, 0xF8, 0x0F, 0x80, + 0x03, 0xC0, 0x1E, 0x00, 0x0F, 0x00, 0x7C, 0x00, 0x7C, 0x01, 0xF0, 0x01, + 0xE0, 0x03, 0xC0, 0x07, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xFE, 0x00, 0xFF, + 0xFF, 0xFC, 0x07, 0xFF, 0xFF, 0xF0, 0x1F, 0x00, 0x07, 0xC0, 0x78, 0x00, + 0x0F, 0x83, 0xE0, 0x00, 0x3E, 0x0F, 0x80, 0x00, 0xF8, 0x3C, 0x00, 0x01, + 0xF1, 0xF0, 0x00, 0x07, 0xC7, 0xC0, 0x00, 0x1F, 0x1E, 0x00, 0x00, 0x3E, + 0xF8, 0x00, 0x00, 0xFB, 0xE0, 0x00, 0x01, 0xE0, 0xFF, 0xFF, 0x80, 0x7F, + 0xFF, 0xF0, 0x3F, 0xFF, 0xFE, 0x1F, 0xFF, 0xFF, 0x0F, 0x00, 0x0F, 0xC7, + 0x80, 0x01, 0xE3, 0xC0, 0x00, 0xF9, 0xE0, 0x00, 0x3C, 0xF0, 0x00, 0x1E, + 0x78, 0x00, 0x0F, 0x3C, 0x00, 0x07, 0x9E, 0x00, 0x07, 0x8F, 0x00, 0x03, + 0xC7, 0x80, 0x07, 0xC3, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, + 0xF8, 0x7F, 0xFF, 0xFE, 0x3C, 0x00, 0x0F, 0x9E, 0x00, 0x03, 0xEF, 0x00, + 0x00, 0xF7, 0x80, 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x0F, 0xF0, + 0x00, 0x07, 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x01, 0xFF, + 0x00, 0x01, 0xF7, 0x80, 0x01, 0xFB, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, 0xF8, + 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, 0xF0, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x07, + 0xFF, 0xE0, 0x00, 0x7F, 0xFF, 0xC0, 0x0F, 0xFF, 0xFF, 0x00, 0xFE, 0x01, + 0xF8, 0x07, 0xC0, 0x03, 0xE0, 0x7C, 0x00, 0x0F, 0x87, 0xC0, 0x00, 0x3C, + 0x3C, 0x00, 0x01, 0xE3, 0xE0, 0x00, 0x07, 0x9E, 0x00, 0x00, 0x3C, 0xF0, + 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x78, 0x00, 0x00, 0x03, 0xC0, 0x00, + 0x00, 0x1E, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x0F, 0x78, 0x00, + 0x00, 0x7B, 0xC0, 0x00, 0x07, 0xDF, 0x00, 0x00, 0x3C, 0x78, 0x00, 0x01, + 0xE3, 0xE0, 0x00, 0x1F, 0x0F, 0x80, 0x01, 0xF0, 0x3E, 0x00, 0x1F, 0x81, + 0xFE, 0x03, 0xF8, 0x07, 0xFF, 0xFF, 0x80, 0x0F, 0xFF, 0xF8, 0x00, 0x3F, + 0xFF, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0xFF, 0x80, 0x1F, 0xFF, 0xFE, + 0x03, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0xFE, 0x0F, 0x00, 0x0F, 0xE1, 0xE0, + 0x00, 0x7E, 0x3C, 0x00, 0x07, 0xE7, 0x80, 0x00, 0x7C, 0xF0, 0x00, 0x07, + 0xDE, 0x00, 0x00, 0x7B, 0xC0, 0x00, 0x0F, 0x78, 0x00, 0x01, 0xEF, 0x00, + 0x00, 0x1F, 0xE0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x0F, + 0xF0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x07, 0xF8, 0x00, + 0x00, 0xFF, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xF7, + 0x80, 0x00, 0x1E, 0xF0, 0x00, 0x03, 0xDE, 0x00, 0x00, 0xFB, 0xC0, 0x00, + 0x3E, 0x78, 0x00, 0x0F, 0xCF, 0x00, 0x03, 0xF1, 0xE0, 0x01, 0xFC, 0x3F, + 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xF0, 0x1F, 0xFF, 0xF0, + 0x00, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, + 0xFE, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xFF, 0xFF, + 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, + 0x3F, 0xFF, 0xFC, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0x3C, + 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF0, + 0x00, 0x03, 0xC0, 0x00, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0xFF, 0xFE, + 0x00, 0x07, 0xFF, 0xFF, 0x00, 0x1F, 0xFF, 0xFF, 0x00, 0x7F, 0x80, 0x7F, + 0x01, 0xF8, 0x00, 0x3F, 0x07, 0xE0, 0x00, 0x1F, 0x0F, 0x80, 0x00, 0x1E, + 0x3E, 0x00, 0x00, 0x3E, 0x78, 0x00, 0x00, 0x3D, 0xF0, 0x00, 0x00, 0x03, + 0xC0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x01, 0xE0, + 0x00, 0xFF, 0xFF, 0xC0, 0x01, 0xFF, 0xFF, 0x80, 0x03, 0xFF, 0xFF, 0x00, + 0x07, 0xFF, 0xFE, 0x00, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x07, 0xBC, 0x00, + 0x00, 0x0F, 0x78, 0x00, 0x00, 0x1E, 0xF8, 0x00, 0x00, 0x7D, 0xF0, 0x00, + 0x00, 0xF9, 0xF0, 0x00, 0x03, 0xF3, 0xF0, 0x00, 0x07, 0xE3, 0xF0, 0x00, + 0x1F, 0xC3, 0xF0, 0x00, 0xFF, 0x83, 0xFC, 0x07, 0xEF, 0x03, 0xFF, 0xFF, + 0x9E, 0x03, 0xFF, 0xFE, 0x1C, 0x01, 0xFF, 0xF0, 0x38, 0x00, 0x7F, 0x80, + 0x00, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x3F, 0xC0, + 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x3F, + 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, + 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, + 0x00, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, + 0x00, 0xFF, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, + 0x00, 0x00, 0xFF, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, + 0xFC, 0x00, 0x00, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x01, 0xE0, + 0x00, 0x3C, 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, + 0x00, 0x78, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x07, 0x80, + 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x0F, 0x00, + 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x1E, 0x00, + 0x03, 0xC0, 0x00, 0x7F, 0x80, 0x0F, 0xF0, 0x01, 0xFE, 0x00, 0x3F, 0xC0, + 0x07, 0xF8, 0x01, 0xFF, 0x80, 0x3E, 0xF0, 0x0F, 0x9F, 0x83, 0xF1, 0xFF, + 0xFC, 0x3F, 0xFF, 0x01, 0xFF, 0xC0, 0x0F, 0xE0, 0x00, 0xF0, 0x00, 0x07, + 0xDE, 0x00, 0x01, 0xF3, 0xC0, 0x00, 0x7C, 0x78, 0x00, 0x1F, 0x0F, 0x00, + 0x07, 0xC1, 0xE0, 0x01, 0xF0, 0x3C, 0x00, 0x7C, 0x07, 0x80, 0x1F, 0x00, + 0xF0, 0x07, 0xC0, 0x1E, 0x01, 0xF0, 0x03, 0xC0, 0x7C, 0x00, 0x78, 0x1F, + 0x00, 0x0F, 0x07, 0xC0, 0x01, 0xE1, 0xF0, 0x00, 0x3C, 0x7E, 0x00, 0x07, + 0x9F, 0xE0, 0x00, 0xF7, 0xFE, 0x00, 0x1F, 0xF7, 0xC0, 0x03, 0xFC, 0x7C, + 0x00, 0x7F, 0x07, 0xC0, 0x0F, 0xC0, 0xF8, 0x01, 0xF0, 0x0F, 0x80, 0x3C, + 0x00, 0xF8, 0x07, 0x80, 0x1F, 0x80, 0xF0, 0x01, 0xF0, 0x1E, 0x00, 0x1F, + 0x03, 0xC0, 0x03, 0xF0, 0x78, 0x00, 0x3E, 0x0F, 0x00, 0x03, 0xE1, 0xE0, + 0x00, 0x3E, 0x3C, 0x00, 0x07, 0xC7, 0x80, 0x00, 0x7C, 0xF0, 0x00, 0x07, + 0xDE, 0x00, 0x00, 0xFC, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x3C, 0x00, 0x01, + 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, + 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, + 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, + 0x07, 0x80, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, + 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFC, 0x00, + 0x00, 0x3F, 0xFC, 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x00, 0x7F, 0xFE, 0x00, + 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x7F, 0xFF, 0x00, 0x00, 0xFF, 0xFF, 0x00, + 0x00, 0xFF, 0xF7, 0x00, 0x00, 0xEF, 0xF7, 0x80, 0x01, 0xEF, 0xF7, 0x80, + 0x01, 0xEF, 0xF3, 0xC0, 0x01, 0xCF, 0xF3, 0xC0, 0x03, 0xCF, 0xF3, 0xC0, + 0x03, 0xCF, 0xF1, 0xE0, 0x03, 0x8F, 0xF1, 0xE0, 0x07, 0x8F, 0xF1, 0xE0, + 0x07, 0x8F, 0xF0, 0xF0, 0x0F, 0x0F, 0xF0, 0xF0, 0x0F, 0x0F, 0xF0, 0xF0, + 0x0F, 0x0F, 0xF0, 0x78, 0x1E, 0x0F, 0xF0, 0x78, 0x1E, 0x0F, 0xF0, 0x78, + 0x1E, 0x0F, 0xF0, 0x3C, 0x3C, 0x0F, 0xF0, 0x3C, 0x3C, 0x0F, 0xF0, 0x3C, + 0x3C, 0x0F, 0xF0, 0x1E, 0x78, 0x0F, 0xF0, 0x1E, 0x78, 0x0F, 0xF0, 0x0E, + 0x78, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x07, + 0xF0, 0x0F, 0xF0, 0x07, 0xE0, 0x0F, 0xF0, 0x07, 0xE0, 0x0F, 0xF0, 0x03, + 0xE0, 0x0F, 0xF8, 0x00, 0x03, 0xFF, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x3F, + 0xF8, 0x00, 0x0F, 0xFE, 0x00, 0x03, 0xFF, 0xC0, 0x00, 0xFF, 0xF8, 0x00, + 0x3F, 0xDE, 0x00, 0x0F, 0xF7, 0xC0, 0x03, 0xFC, 0xF8, 0x00, 0xFF, 0x1E, + 0x00, 0x3F, 0xC7, 0xC0, 0x0F, 0xF0, 0xF0, 0x03, 0xFC, 0x3E, 0x00, 0xFF, + 0x07, 0xC0, 0x3F, 0xC0, 0xF0, 0x0F, 0xF0, 0x3E, 0x03, 0xFC, 0x07, 0xC0, + 0xFF, 0x00, 0xF0, 0x3F, 0xC0, 0x3E, 0x0F, 0xF0, 0x07, 0x83, 0xFC, 0x01, + 0xF0, 0xFF, 0x00, 0x3E, 0x3F, 0xC0, 0x07, 0x8F, 0xF0, 0x01, 0xF3, 0xFC, + 0x00, 0x3E, 0xFF, 0x00, 0x07, 0xBF, 0xC0, 0x01, 0xFF, 0xF0, 0x00, 0x3F, + 0xFC, 0x00, 0x0F, 0xFF, 0x00, 0x01, 0xFF, 0xC0, 0x00, 0x3F, 0xF0, 0x00, + 0x0F, 0xFC, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x3F, 0xFF, + 0x80, 0x00, 0x7F, 0xFF, 0xF0, 0x00, 0x7F, 0xFF, 0xFC, 0x00, 0x7F, 0x80, + 0xFF, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x7E, 0x00, 0x03, 0xF0, 0x3E, 0x00, + 0x00, 0xF8, 0x3E, 0x00, 0x00, 0x3E, 0x1E, 0x00, 0x00, 0x0F, 0x1F, 0x00, + 0x00, 0x07, 0xCF, 0x00, 0x00, 0x01, 0xE7, 0x80, 0x00, 0x00, 0xF7, 0xC0, + 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x00, 0x3F, + 0xC0, 0x00, 0x00, 0x3E, 0xF0, 0x00, 0x00, 0x1E, 0x78, 0x00, 0x00, 0x0F, + 0x3E, 0x00, 0x00, 0x0F, 0x8F, 0x00, 0x00, 0x07, 0x87, 0xC0, 0x00, 0x07, + 0xC1, 0xF0, 0x00, 0x07, 0xC0, 0xFC, 0x00, 0x07, 0xE0, 0x3F, 0x00, 0x07, + 0xE0, 0x0F, 0xF0, 0x1F, 0xE0, 0x03, 0xFF, 0xFF, 0xE0, 0x00, 0xFF, 0xFF, + 0xE0, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0xFF, 0xFF, + 0x80, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xFC, 0xF0, 0x00, + 0xFE, 0xF0, 0x00, 0x3E, 0xF0, 0x00, 0x1F, 0xF0, 0x00, 0x0F, 0xF0, 0x00, + 0x0F, 0xF0, 0x00, 0x0F, 0xF0, 0x00, 0x0F, 0xF0, 0x00, 0x0F, 0xF0, 0x00, + 0x0F, 0xF0, 0x00, 0x1F, 0xF0, 0x00, 0x3E, 0xF0, 0x00, 0xFE, 0xFF, 0xFF, + 0xFC, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xC0, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x3F, 0xFF, 0x80, + 0x00, 0x7F, 0xFF, 0xE0, 0x00, 0x7F, 0xFF, 0xFC, 0x00, 0x7F, 0x80, 0xFF, + 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x7E, 0x00, 0x03, 0xF0, 0x3E, 0x00, 0x00, + 0xF8, 0x3E, 0x00, 0x00, 0x3E, 0x1E, 0x00, 0x00, 0x0F, 0x1F, 0x00, 0x00, + 0x07, 0xCF, 0x00, 0x00, 0x01, 0xE7, 0x80, 0x00, 0x00, 0xF7, 0xC0, 0x00, + 0x00, 0x7F, 0xC0, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x0F, 0xF0, 0x00, + 0x00, 0x07, 0xF8, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x01, 0xFE, 0x00, + 0x00, 0x00, 0xFF, 0x00, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x00, 0x3F, 0xC0, + 0x00, 0x00, 0x3E, 0xF0, 0x00, 0x00, 0x1E, 0x78, 0x00, 0x00, 0x0F, 0x3E, + 0x00, 0x00, 0x0F, 0x8F, 0x00, 0x03, 0x87, 0x87, 0xC0, 0x03, 0xE7, 0xC1, + 0xF0, 0x00, 0xFF, 0xC0, 0xFC, 0x00, 0x3F, 0xE0, 0x3F, 0x00, 0x0F, 0xE0, + 0x0F, 0xF0, 0x1F, 0xF0, 0x03, 0xFF, 0xFF, 0xFC, 0x00, 0xFF, 0xFF, 0xFF, + 0x00, 0x1F, 0xFF, 0xC7, 0xC0, 0x01, 0xFF, 0x01, 0xE0, 0x00, 0x00, 0x00, + 0x70, 0x00, 0x00, 0x00, 0x10, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, 0xFE, 0x0F, + 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xF8, 0xF0, 0x00, 0x3F, 0x3C, 0x00, 0x07, + 0xCF, 0x00, 0x00, 0xFB, 0xC0, 0x00, 0x1E, 0xF0, 0x00, 0x07, 0xBC, 0x00, + 0x01, 0xEF, 0x00, 0x00, 0x7B, 0xC0, 0x00, 0x1E, 0xF0, 0x00, 0x07, 0xBC, + 0x00, 0x03, 0xCF, 0x00, 0x01, 0xF3, 0xC0, 0x00, 0xF8, 0xFF, 0xFF, 0xFC, + 0x3F, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xF8, 0xF0, 0x00, + 0x3F, 0x3C, 0x00, 0x03, 0xCF, 0x00, 0x00, 0xFB, 0xC0, 0x00, 0x1E, 0xF0, + 0x00, 0x07, 0xBC, 0x00, 0x01, 0xEF, 0x00, 0x00, 0x7B, 0xC0, 0x00, 0x1E, + 0xF0, 0x00, 0x07, 0xBC, 0x00, 0x01, 0xEF, 0x00, 0x00, 0x7B, 0xC0, 0x00, + 0x1E, 0xF0, 0x00, 0x07, 0xFC, 0x00, 0x01, 0xF0, 0x00, 0x7F, 0xC0, 0x00, + 0x7F, 0xFF, 0x00, 0x1F, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0x81, 0xF8, 0x07, + 0xF0, 0x7C, 0x00, 0x1F, 0x0F, 0x00, 0x01, 0xE3, 0xE0, 0x00, 0x3E, 0x78, + 0x00, 0x03, 0xCF, 0x00, 0x00, 0x79, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x07, 0xC0, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0xFF, + 0xE0, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x7F, 0xFF, 0x00, 0x01, 0xFF, 0xF8, + 0x00, 0x03, 0xFF, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x01, 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x3F, + 0xC0, 0x00, 0x07, 0xF8, 0x00, 0x00, 0xF7, 0x80, 0x00, 0x3E, 0xF8, 0x00, + 0x07, 0x9F, 0x80, 0x01, 0xF1, 0xFE, 0x01, 0xFC, 0x1F, 0xFF, 0xFF, 0x01, + 0xFF, 0xFF, 0xC0, 0x0F, 0xFF, 0xE0, 0x00, 0x3F, 0xE0, 0x00, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, + 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x78, 0x00, + 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, + 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, 0x00, + 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, + 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, + 0x01, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, + 0x00, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x3F, 0xC0, + 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x3F, + 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, + 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, + 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, + 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, + 0x00, 0xFF, 0x00, 0x00, 0x7D, 0xE0, 0x00, 0x1E, 0x7C, 0x00, 0x0F, 0x9F, + 0x80, 0x07, 0xE3, 0xF8, 0x07, 0xF0, 0x7F, 0xFF, 0xF8, 0x0F, 0xFF, 0xFC, + 0x00, 0xFF, 0xFC, 0x00, 0x0F, 0xF8, 0x00, 0xF8, 0x00, 0x00, 0xF7, 0xC0, + 0x00, 0x0F, 0x9E, 0x00, 0x00, 0x7C, 0xF8, 0x00, 0x03, 0xC7, 0xC0, 0x00, + 0x3E, 0x1E, 0x00, 0x01, 0xF0, 0xF8, 0x00, 0x0F, 0x07, 0xC0, 0x00, 0xF8, + 0x1E, 0x00, 0x07, 0xC0, 0xF8, 0x00, 0x3C, 0x07, 0xC0, 0x03, 0xE0, 0x1E, + 0x00, 0x1F, 0x00, 0xF8, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x80, 0x1E, 0x00, + 0x7C, 0x00, 0xF8, 0x03, 0xC0, 0x03, 0xC0, 0x1E, 0x00, 0x1F, 0x01, 0xF0, + 0x00, 0xF8, 0x0F, 0x00, 0x03, 0xC0, 0x78, 0x00, 0x1F, 0x07, 0x80, 0x00, + 0xF8, 0x3C, 0x00, 0x03, 0xC1, 0xE0, 0x00, 0x1F, 0x1E, 0x00, 0x00, 0x78, + 0xF0, 0x00, 0x03, 0xC7, 0x80, 0x00, 0x1F, 0x78, 0x00, 0x00, 0x7B, 0xC0, + 0x00, 0x03, 0xDE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, + 0x00, 0x3F, 0x00, 0x07, 0xFE, 0x00, 0x0F, 0xC0, 0x01, 0xFF, 0x80, 0x03, + 0xF0, 0x00, 0x7D, 0xE0, 0x00, 0xFC, 0x00, 0x1E, 0x7C, 0x00, 0x7F, 0x80, + 0x0F, 0x9F, 0x00, 0x1F, 0xE0, 0x03, 0xE7, 0xC0, 0x07, 0xF8, 0x00, 0xF8, + 0xF0, 0x01, 0xFF, 0x00, 0x3C, 0x3E, 0x00, 0xF3, 0xC0, 0x1F, 0x0F, 0x80, + 0x3C, 0xF0, 0x07, 0xC3, 0xE0, 0x0F, 0x3C, 0x01, 0xF0, 0x78, 0x07, 0xC7, + 0x80, 0x78, 0x1F, 0x01, 0xE1, 0xE0, 0x1E, 0x07, 0xC0, 0x78, 0x78, 0x0F, + 0x80, 0xF0, 0x1E, 0x1E, 0x03, 0xE0, 0x3C, 0x0F, 0x83, 0xC0, 0xF0, 0x0F, + 0x83, 0xC0, 0xF0, 0x3C, 0x03, 0xE0, 0xF0, 0x3C, 0x1F, 0x00, 0x78, 0x3C, + 0x0F, 0x87, 0xC0, 0x1E, 0x1E, 0x01, 0xE1, 0xE0, 0x07, 0x87, 0x80, 0x78, + 0x78, 0x01, 0xF1, 0xE0, 0x1E, 0x1E, 0x00, 0x3C, 0xF8, 0x03, 0xCF, 0x80, + 0x0F, 0x3C, 0x00, 0xF3, 0xC0, 0x03, 0xCF, 0x00, 0x3C, 0xF0, 0x00, 0xFB, + 0xC0, 0x0F, 0xBC, 0x00, 0x1F, 0xF0, 0x01, 0xFF, 0x00, 0x07, 0xF8, 0x00, + 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x03, 0xF8, + 0x00, 0x0F, 0xC0, 0x00, 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x00, + 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x01, 0xF3, 0xF0, 0x00, 0x1F, 0x8F, 0x80, 0x00, 0xF8, 0x3E, 0x00, 0x0F, + 0x80, 0xF8, 0x00, 0xF8, 0x07, 0xC0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x00, + 0x7C, 0x07, 0xC0, 0x03, 0xE0, 0x3E, 0x00, 0x0F, 0x83, 0xE0, 0x00, 0x3E, + 0x3E, 0x00, 0x01, 0xF1, 0xF0, 0x00, 0x07, 0xDF, 0x00, 0x00, 0x1F, 0xF0, + 0x00, 0x00, 0xFF, 0x80, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x07, + 0xDF, 0x00, 0x00, 0x7C, 0x78, 0x00, 0x03, 0xE3, 0xE0, 0x00, 0x3E, 0x0F, + 0x80, 0x03, 0xE0, 0x3E, 0x00, 0x1F, 0x01, 0xF0, 0x01, 0xF0, 0x07, 0xC0, + 0x1F, 0x00, 0x3F, 0x00, 0xF8, 0x00, 0xF8, 0x0F, 0x80, 0x03, 0xE0, 0xF8, + 0x00, 0x1F, 0x8F, 0xC0, 0x00, 0x7C, 0x7C, 0x00, 0x01, 0xF7, 0xC0, 0x00, + 0x0F, 0xC0, 0xFC, 0x00, 0x00, 0xFD, 0xF0, 0x00, 0x03, 0xE7, 0xE0, 0x00, + 0x1F, 0x0F, 0x80, 0x00, 0x7C, 0x1F, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x1F, + 0x00, 0xF8, 0x00, 0x7C, 0x01, 0xF0, 0x03, 0xE0, 0x07, 0xC0, 0x0F, 0x80, + 0x0F, 0x80, 0x7C, 0x00, 0x1E, 0x01, 0xE0, 0x00, 0x7C, 0x0F, 0x80, 0x00, + 0xF8, 0x7C, 0x00, 0x03, 0xE1, 0xE0, 0x00, 0x07, 0xCF, 0x80, 0x00, 0x0F, + 0x3C, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x00, 0xFC, + 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x07, 0x80, 0x00, + 0x00, 0x1E, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, + 0x07, 0x80, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, + 0xE0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x3F, 0xFF, + 0xFF, 0xC7, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0xE0, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x01, + 0xF8, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0xFC, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x07, 0xE0, 0x00, 0x01, + 0xF8, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xF0, 0x00, + 0x00, 0xFC, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x7E, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x03, 0xE0, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xFF, 0xFF, 0xFF, + 0xFF, 0xE0, 0x07, 0x00, 0x18, 0x00, 0xE0, 0x07, 0x00, 0x18, 0x00, 0xE0, + 0x07, 0x00, 0x18, 0x00, 0xC0, 0x07, 0x00, 0x38, 0x00, 0xC0, 0x07, 0x00, + 0x38, 0x00, 0xC0, 0x06, 0x00, 0x38, 0x00, 0xC0, 0x06, 0x00, 0x38, 0x01, + 0xC0, 0x06, 0x00, 0x38, 0x01, 0xC0, 0x06, 0x00, 0x30, 0x01, 0xC0, 0x0E, + 0x00, 0x30, 0x01, 0xC0, 0x0E, 0x00, 0x30, 0x01, 0xC0, 0x0E, 0xFF, 0xFF, + 0xFF, 0xFF, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x3F, + 0x00, 0x0F, 0xC0, 0x07, 0xF8, 0x01, 0xCE, 0x00, 0x73, 0x80, 0x3C, 0x70, + 0x0E, 0x1C, 0x07, 0x87, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x38, 0x07, 0x0E, + 0x01, 0xC7, 0x80, 0x79, 0xC0, 0x0E, 0x70, 0x03, 0xB8, 0x00, 0x70, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x0F, 0x01, 0xE0, 0x3C, 0x07, + 0x00, 0xE0, 0x1C, 0x01, 0xFF, 0x00, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0xE0, + 0x3F, 0xFF, 0xF0, 0x7E, 0x03, 0xF8, 0x7C, 0x00, 0xF8, 0x78, 0x00, 0x78, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x78, 0x00, 0x00, 0x78, 0x00, 0x00, 0xF8, + 0x00, 0x03, 0xF8, 0x00, 0xFF, 0xF8, 0x0F, 0xFF, 0xF8, 0x3F, 0xFE, 0x78, + 0x7F, 0x80, 0x78, 0xFC, 0x00, 0x78, 0xF8, 0x00, 0x78, 0xF0, 0x00, 0x78, + 0xF0, 0x00, 0xF8, 0xF0, 0x00, 0xF8, 0xF8, 0x03, 0xF8, 0x7E, 0x0F, 0xF8, + 0x7F, 0xFF, 0x7F, 0x3F, 0xFE, 0x3F, 0x1F, 0xFC, 0x3F, 0x07, 0xE0, 0x1F, + 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF0, + 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF0, 0x7E, + 0x03, 0xC7, 0xFE, 0x0F, 0x7F, 0xFC, 0x3D, 0xFF, 0xF8, 0xFF, 0x07, 0xF3, + 0xF8, 0x07, 0xCF, 0xC0, 0x0F, 0xBE, 0x00, 0x1E, 0xF8, 0x00, 0x7B, 0xE0, + 0x01, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, + 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x01, 0xFF, + 0x80, 0x07, 0xBE, 0x00, 0x1E, 0xFC, 0x00, 0xFB, 0xF8, 0x07, 0xCF, 0xF0, + 0x7F, 0x3B, 0xFF, 0xF8, 0xE7, 0xFF, 0xC3, 0x8F, 0xFE, 0x00, 0x0F, 0xE0, + 0x00, 0x00, 0xFE, 0x00, 0x3F, 0xFC, 0x03, 0xFF, 0xF0, 0x3F, 0xFF, 0xC3, + 0xF0, 0x3F, 0x1F, 0x00, 0xF9, 0xF0, 0x03, 0xCF, 0x00, 0x0F, 0x78, 0x00, + 0x07, 0xC0, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, + 0x1E, 0x00, 0x1E, 0xF0, 0x00, 0xF7, 0xC0, 0x0F, 0x9F, 0x00, 0xF8, 0xFC, + 0x0F, 0xC3, 0xFF, 0xFC, 0x0F, 0xFF, 0xC0, 0x3F, 0xFC, 0x00, 0x7F, 0x00, + 0x00, 0x00, 0x1E, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x78, 0x00, 0x00, 0xF0, + 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x0F, 0x01, + 0xFC, 0x1E, 0x0F, 0xFE, 0x3C, 0x3F, 0xFF, 0x78, 0xFF, 0xFF, 0xF3, 0xF8, + 0x3F, 0xE7, 0xC0, 0x1F, 0xDF, 0x00, 0x1F, 0xBE, 0x00, 0x1F, 0x78, 0x00, + 0x3F, 0xF0, 0x00, 0x7F, 0xC0, 0x00, 0x7F, 0x80, 0x00, 0xFF, 0x00, 0x01, + 0xFE, 0x00, 0x03, 0xFC, 0x00, 0x07, 0xF8, 0x00, 0x0F, 0xF0, 0x00, 0x1F, + 0xF0, 0x00, 0x7D, 0xE0, 0x00, 0xFB, 0xC0, 0x01, 0xF7, 0xC0, 0x07, 0xE7, + 0xC0, 0x1F, 0xCF, 0xE0, 0xFF, 0x8F, 0xFF, 0xF7, 0x0F, 0xFF, 0xCE, 0x0F, + 0xFF, 0x1C, 0x07, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x0F, 0xFE, 0x00, 0xFF, + 0xFC, 0x07, 0xFF, 0xF8, 0x1F, 0x83, 0xF0, 0xF8, 0x07, 0xC7, 0xC0, 0x0F, + 0x9E, 0x00, 0x1E, 0x78, 0x00, 0x7B, 0xC0, 0x00, 0xFF, 0x00, 0x03, 0xFC, + 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, + 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x1E, + 0x7C, 0x00, 0x78, 0xF8, 0x03, 0xE3, 0xF0, 0x3F, 0x07, 0xFF, 0xF8, 0x0F, + 0xFF, 0xE0, 0x1F, 0xFE, 0x00, 0x0F, 0xE0, 0x00, 0x03, 0xC3, 0xF0, 0xFC, + 0x7F, 0x1F, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x3F, 0xFF, 0xFF, 0xFF, 0x1E, + 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, + 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x78, + 0x1E, 0x07, 0x80, 0x00, 0xFC, 0x00, 0x1F, 0xF8, 0xF0, 0xFF, 0xFB, 0xC7, + 0xFF, 0xFF, 0x3F, 0x83, 0xFC, 0xF8, 0x07, 0xF7, 0xC0, 0x0F, 0xDE, 0x00, + 0x1F, 0x78, 0x00, 0x7F, 0xE0, 0x00, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, + 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, + 0x00, 0x3F, 0xC0, 0x00, 0xF7, 0x80, 0x07, 0xDE, 0x00, 0x1F, 0x7C, 0x00, + 0xFC, 0xF8, 0x07, 0xF3, 0xF8, 0x3F, 0xC7, 0xFF, 0xEF, 0x0F, 0xFF, 0x3C, + 0x1F, 0xF8, 0xF0, 0x1F, 0x83, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x79, 0xE0, + 0x01, 0xE7, 0xC0, 0x0F, 0x8F, 0x80, 0xFC, 0x3F, 0xFF, 0xF0, 0x7F, 0xFF, + 0x80, 0xFF, 0xFC, 0x00, 0x7F, 0x80, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, + 0x00, 0x78, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x07, 0x80, + 0x00, 0xF0, 0xFE, 0x1E, 0x3F, 0xE3, 0xCF, 0xFF, 0x7B, 0xFF, 0xEF, 0xF0, + 0xFF, 0xF8, 0x07, 0xFF, 0x00, 0x7F, 0xC0, 0x0F, 0xF8, 0x01, 0xFE, 0x00, + 0x3F, 0xC0, 0x07, 0xF8, 0x00, 0xFF, 0x00, 0x1F, 0xE0, 0x03, 0xFC, 0x00, + 0x7F, 0x80, 0x0F, 0xF0, 0x01, 0xFE, 0x00, 0x3F, 0xC0, 0x07, 0xF8, 0x00, + 0xFF, 0x00, 0x1F, 0xE0, 0x03, 0xFC, 0x00, 0x7F, 0x80, 0x0F, 0xF0, 0x01, + 0xFE, 0x00, 0x3C, 0xFF, 0xFF, 0xF0, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x1F, + 0xFF, 0xFE, 0xFE, 0xF8, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x3C, 0x00, 0x01, + 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, + 0x00, 0xF0, 0x00, 0x07, 0x80, 0x1F, 0x3C, 0x01, 0xF1, 0xE0, 0x1F, 0x0F, + 0x01, 0xF0, 0x78, 0x1F, 0x03, 0xC1, 0xF0, 0x1E, 0x1F, 0x00, 0xF1, 0xF0, + 0x07, 0x9F, 0x00, 0x3D, 0xF8, 0x01, 0xFF, 0xE0, 0x0F, 0xFF, 0x80, 0x7F, + 0x7C, 0x03, 0xF1, 0xF0, 0x1F, 0x07, 0xC0, 0xF0, 0x3E, 0x07, 0x80, 0xF8, + 0x3C, 0x03, 0xC1, 0xE0, 0x1F, 0x0F, 0x00, 0x7C, 0x78, 0x03, 0xE3, 0xC0, + 0x0F, 0x9E, 0x00, 0x3C, 0xF0, 0x01, 0xF7, 0x80, 0x07, 0xC0, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0x00, 0xFC, 0x03, 0xF0, 0xE3, 0xFE, 0x0F, 0xFC, 0xE7, + 0xFF, 0x1F, 0xFE, 0xEF, 0xFF, 0xBF, 0xFE, 0xFE, 0x0F, 0xF8, 0x3F, 0xFC, + 0x07, 0xF0, 0x1F, 0xF8, 0x03, 0xE0, 0x0F, 0xF8, 0x03, 0xE0, 0x0F, 0xF0, + 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, + 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, + 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, + 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, + 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, + 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0x00, + 0x7E, 0x0E, 0x1F, 0xF8, 0xE7, 0xFF, 0xCE, 0xFF, 0xFE, 0xEF, 0x07, 0xFF, + 0xE0, 0x1F, 0xFC, 0x01, 0xFF, 0x80, 0x0F, 0xF8, 0x00, 0xFF, 0x00, 0x0F, + 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, + 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, + 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, + 0x00, 0xFF, 0x00, 0x0F, 0x00, 0xFE, 0x00, 0x07, 0xFF, 0x00, 0x3F, 0xFF, + 0x80, 0xFF, 0xFF, 0x83, 0xF8, 0x3F, 0x87, 0xC0, 0x1F, 0x1F, 0x00, 0x1F, + 0x3C, 0x00, 0x1E, 0x78, 0x00, 0x3D, 0xF0, 0x00, 0x7F, 0xC0, 0x00, 0x7F, + 0x80, 0x00, 0xFF, 0x00, 0x01, 0xFE, 0x00, 0x03, 0xFC, 0x00, 0x07, 0xF8, + 0x00, 0x0F, 0xF0, 0x00, 0x1F, 0xF0, 0x00, 0x7D, 0xE0, 0x00, 0xF3, 0xC0, + 0x01, 0xE7, 0xC0, 0x07, 0xC7, 0xC0, 0x1F, 0x0F, 0xE0, 0xFE, 0x0F, 0xFF, + 0xF8, 0x0F, 0xFF, 0xE0, 0x0F, 0xFF, 0x80, 0x03, 0xF8, 0x00, 0x00, 0xFE, + 0x03, 0x8F, 0xFE, 0x0E, 0x7F, 0xFC, 0x3B, 0xFF, 0xF8, 0xFF, 0x87, 0xF3, + 0xF8, 0x07, 0xCF, 0xC0, 0x0F, 0xBE, 0x00, 0x1E, 0xF8, 0x00, 0x7B, 0xE0, + 0x01, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, + 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x01, 0xFF, + 0x80, 0x07, 0xBE, 0x00, 0x1E, 0xFC, 0x00, 0xFB, 0xF8, 0x07, 0xCF, 0xF0, + 0x7F, 0x3F, 0xFF, 0xF8, 0xF7, 0xFF, 0xC3, 0xC7, 0xFE, 0x0F, 0x07, 0xE0, + 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x00, + 0xFE, 0x00, 0x07, 0xFF, 0x1C, 0x3F, 0xFF, 0x38, 0xFF, 0xFF, 0x73, 0xF8, + 0x3F, 0xE7, 0xC0, 0x1F, 0xDF, 0x00, 0x1F, 0xBE, 0x00, 0x1F, 0x78, 0x00, + 0x3F, 0xF0, 0x00, 0x7F, 0xC0, 0x00, 0x7F, 0x80, 0x00, 0xFF, 0x00, 0x01, + 0xFE, 0x00, 0x03, 0xFC, 0x00, 0x07, 0xF8, 0x00, 0x0F, 0xF0, 0x00, 0x1F, + 0xF0, 0x00, 0x7D, 0xE0, 0x00, 0xFB, 0xC0, 0x01, 0xF7, 0xC0, 0x07, 0xE7, + 0xC0, 0x1F, 0xCF, 0xE0, 0xFF, 0x8F, 0xFF, 0xEF, 0x0F, 0xFF, 0xDE, 0x0F, + 0xFE, 0x3C, 0x07, 0xF0, 0x78, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, + 0x03, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0x78, 0x00, 0xFE, 0x1F, 0xE7, 0xFE, 0xFF, 0xFF, 0x8F, + 0xC0, 0xF8, 0x0F, 0x80, 0xF8, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0x01, 0xFC, 0x00, 0xFF, 0xF0, + 0x1F, 0xFF, 0x83, 0xFF, 0xFC, 0x3E, 0x07, 0xE7, 0xC0, 0x3E, 0x78, 0x01, + 0xE7, 0x80, 0x00, 0x78, 0x00, 0x07, 0xC0, 0x00, 0x7E, 0x00, 0x03, 0xFC, + 0x00, 0x1F, 0xFC, 0x00, 0xFF, 0xF8, 0x03, 0xFF, 0xC0, 0x03, 0xFE, 0x00, + 0x03, 0xF0, 0x00, 0x1F, 0x00, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, + 0x80, 0x1F, 0x7E, 0x07, 0xE7, 0xFF, 0xFE, 0x3F, 0xFF, 0xC1, 0xFF, 0xF0, + 0x03, 0xFC, 0x00, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x8F, 0xFF, + 0xFF, 0xFF, 0xC7, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1E, + 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, + 0xE0, 0x78, 0x1F, 0xC7, 0xF0, 0xFC, 0x1F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, + 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, + 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, + 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, + 0x00, 0xFF, 0x00, 0x1F, 0xF0, 0x01, 0xFF, 0x00, 0x3F, 0xF8, 0x07, 0xFF, + 0xE0, 0xFF, 0x7F, 0xFF, 0x77, 0xFF, 0xE7, 0x1F, 0xFC, 0x70, 0x7E, 0x00, + 0x78, 0x00, 0x3E, 0xF0, 0x00, 0x79, 0xF0, 0x00, 0xF1, 0xE0, 0x03, 0xE3, + 0xC0, 0x07, 0x87, 0xC0, 0x0F, 0x07, 0x80, 0x3C, 0x0F, 0x00, 0x78, 0x1F, + 0x01, 0xF0, 0x1E, 0x03, 0xC0, 0x3C, 0x07, 0x80, 0x7C, 0x1F, 0x00, 0x78, + 0x3C, 0x00, 0xF0, 0x78, 0x01, 0xF1, 0xE0, 0x01, 0xE3, 0xC0, 0x03, 0xC7, + 0x80, 0x03, 0xDE, 0x00, 0x07, 0xBC, 0x00, 0x0F, 0x70, 0x00, 0x0F, 0xE0, + 0x00, 0x1F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, + 0xF8, 0x03, 0xE0, 0x07, 0x9E, 0x00, 0xFC, 0x01, 0xE7, 0x80, 0x3F, 0x00, + 0x79, 0xF0, 0x0F, 0xC0, 0x3E, 0x3C, 0x07, 0xF0, 0x0F, 0x0F, 0x01, 0xFE, + 0x03, 0xC3, 0xC0, 0x7F, 0x80, 0xF0, 0x78, 0x1D, 0xE0, 0x78, 0x1E, 0x0F, + 0x38, 0x1E, 0x07, 0x83, 0xCF, 0x07, 0x81, 0xE0, 0xF3, 0xC1, 0xE0, 0x3C, + 0x38, 0xF0, 0xF0, 0x0F, 0x1E, 0x1C, 0x3C, 0x03, 0xC7, 0x87, 0x8F, 0x00, + 0x71, 0xE1, 0xE3, 0x80, 0x1E, 0x70, 0x79, 0xE0, 0x07, 0xBC, 0x0E, 0x78, + 0x01, 0xEF, 0x03, 0xDE, 0x00, 0x3B, 0xC0, 0xF7, 0x00, 0x0F, 0xE0, 0x3F, + 0xC0, 0x03, 0xF8, 0x07, 0xF0, 0x00, 0x7E, 0x01, 0xF8, 0x00, 0x1F, 0x80, + 0x7E, 0x00, 0x07, 0xC0, 0x1F, 0x80, 0x01, 0xF0, 0x03, 0xC0, 0x00, 0x7C, + 0x00, 0x78, 0xF0, 0x03, 0xE1, 0xE0, 0x0F, 0x07, 0xC0, 0x78, 0x0F, 0x03, + 0xE0, 0x1E, 0x0F, 0x00, 0x7C, 0x78, 0x00, 0xF3, 0xE0, 0x01, 0xEF, 0x00, + 0x07, 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0x1F, 0x00, 0x00, 0x7C, 0x00, 0x03, + 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x7F, 0xC0, 0x03, 0xCF, 0x00, 0x0F, 0x1E, + 0x00, 0x78, 0x7C, 0x03, 0xE0, 0xF0, 0x0F, 0x03, 0xE0, 0x78, 0x07, 0xC3, + 0xE0, 0x0F, 0x1F, 0x00, 0x3E, 0x78, 0x00, 0x7C, 0x78, 0x00, 0x3D, 0xE0, + 0x01, 0xF7, 0x80, 0x07, 0x8F, 0x00, 0x1E, 0x3C, 0x00, 0xF0, 0xF0, 0x03, + 0xC1, 0xE0, 0x0F, 0x07, 0x80, 0x78, 0x1E, 0x01, 0xE0, 0x3C, 0x07, 0x80, + 0xF0, 0x3C, 0x03, 0xC0, 0xF0, 0x07, 0x87, 0xC0, 0x1E, 0x1E, 0x00, 0x78, + 0x78, 0x00, 0xF3, 0xC0, 0x03, 0xCF, 0x00, 0x0F, 0x3C, 0x00, 0x1F, 0xE0, + 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xC0, 0x00, + 0x3E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x3C, + 0x00, 0x01, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x3E, 0x00, 0x0F, 0xF0, 0x00, + 0x3F, 0xC0, 0x00, 0xFE, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x7F, 0xFF, 0xF7, + 0xFF, 0xFF, 0x7F, 0xFF, 0xF7, 0xFF, 0xFF, 0x00, 0x01, 0xE0, 0x00, 0x3E, + 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7C, + 0x00, 0x07, 0x80, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7C, + 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x03, 0xC0, 0x00, 0x7C, + 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, + 0x01, 0xE0, 0xFC, 0x1F, 0x87, 0x80, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, + 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, + 0xC0, 0x78, 0x1E, 0x0F, 0x81, 0xE0, 0x3C, 0x07, 0xC0, 0x3C, 0x03, 0x80, + 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, + 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0F, 0x00, 0xFC, 0x1F, 0x80, + 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xF0, 0x1F, 0x83, 0xF0, 0x0F, 0x00, + 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, + 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x1C, 0x03, 0xC0, 0x3E, 0x03, + 0xC0, 0x78, 0x1F, 0x07, 0x80, 0xE0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, + 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, + 0x70, 0x1E, 0x1F, 0x83, 0xF0, 0x78, 0x00, 0x3E, 0x00, 0x0F, 0xF0, 0x0D, + 0xFF, 0x01, 0xF0, 0xF8, 0x7C, 0x0F, 0xFD, 0x80, 0x7F, 0x80, 0x03, 0xE0 }; + +const GFXglyph FreeSans24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 12, 0, 1 }, // 0x20 ' ' + { 0, 4, 34, 16, 6, -33 }, // 0x21 '!' + { 17, 11, 12, 16, 2, -32 }, // 0x22 '"' + { 34, 24, 33, 26, 1, -31 }, // 0x23 '#' + { 133, 23, 41, 26, 1, -34 }, // 0x24 '$' + { 251, 39, 34, 42, 1, -32 }, // 0x25 '%' + { 417, 28, 34, 31, 2, -32 }, // 0x26 '&' + { 536, 4, 12, 9, 2, -32 }, // 0x27 ''' + { 542, 10, 44, 16, 3, -33 }, // 0x28 '(' + { 597, 10, 44, 16, 2, -33 }, // 0x29 ')' + { 652, 14, 14, 18, 2, -33 }, // 0x2A '*' + { 677, 23, 22, 27, 2, -21 }, // 0x2B '+' + { 741, 4, 12, 13, 4, -4 }, // 0x2C ',' + { 747, 11, 4, 16, 2, -14 }, // 0x2D '-' + { 753, 4, 5, 12, 4, -4 }, // 0x2E '.' + { 756, 13, 35, 13, 0, -33 }, // 0x2F '/' + { 813, 22, 34, 26, 2, -32 }, // 0x30 '0' + { 907, 11, 33, 26, 5, -32 }, // 0x31 '1' + { 953, 22, 33, 26, 2, -32 }, // 0x32 '2' + { 1044, 23, 34, 26, 1, -32 }, // 0x33 '3' + { 1142, 23, 33, 26, 1, -32 }, // 0x34 '4' + { 1237, 22, 34, 26, 2, -32 }, // 0x35 '5' + { 1331, 22, 34, 26, 2, -32 }, // 0x36 '6' + { 1425, 21, 33, 26, 2, -32 }, // 0x37 '7' + { 1512, 22, 34, 26, 2, -32 }, // 0x38 '8' + { 1606, 21, 34, 26, 2, -32 }, // 0x39 '9' + { 1696, 4, 25, 12, 4, -24 }, // 0x3A ':' + { 1709, 4, 32, 12, 4, -24 }, // 0x3B ';' + { 1725, 23, 23, 27, 2, -22 }, // 0x3C '<' + { 1792, 23, 12, 27, 2, -16 }, // 0x3D '=' + { 1827, 23, 23, 27, 2, -22 }, // 0x3E '>' + { 1894, 20, 35, 26, 4, -34 }, // 0x3F '?' + { 1982, 43, 42, 48, 2, -34 }, // 0x40 '@' + { 2208, 30, 34, 31, 1, -33 }, // 0x41 'A' + { 2336, 25, 34, 31, 4, -33 }, // 0x42 'B' + { 2443, 29, 36, 33, 2, -34 }, // 0x43 'C' + { 2574, 27, 34, 33, 4, -33 }, // 0x44 'D' + { 2689, 24, 34, 30, 4, -33 }, // 0x45 'E' + { 2791, 22, 34, 28, 4, -33 }, // 0x46 'F' + { 2885, 31, 36, 36, 2, -34 }, // 0x47 'G' + { 3025, 26, 34, 34, 4, -33 }, // 0x48 'H' + { 3136, 4, 34, 13, 5, -33 }, // 0x49 'I' + { 3153, 19, 35, 25, 2, -33 }, // 0x4A 'J' + { 3237, 27, 34, 32, 4, -33 }, // 0x4B 'K' + { 3352, 21, 34, 26, 4, -33 }, // 0x4C 'L' + { 3442, 32, 34, 40, 4, -33 }, // 0x4D 'M' + { 3578, 26, 34, 34, 4, -33 }, // 0x4E 'N' + { 3689, 33, 36, 37, 2, -34 }, // 0x4F 'O' + { 3838, 24, 34, 31, 4, -33 }, // 0x50 'P' + { 3940, 33, 38, 37, 2, -34 }, // 0x51 'Q' + { 4097, 26, 34, 33, 4, -33 }, // 0x52 'R' + { 4208, 27, 36, 31, 2, -34 }, // 0x53 'S' + { 4330, 26, 34, 30, 2, -33 }, // 0x54 'T' + { 4441, 26, 35, 34, 4, -33 }, // 0x55 'U' + { 4555, 29, 34, 30, 1, -33 }, // 0x56 'V' + { 4679, 42, 34, 44, 1, -33 }, // 0x57 'W' + { 4858, 29, 34, 31, 1, -33 }, // 0x58 'X' + { 4982, 30, 34, 32, 1, -33 }, // 0x59 'Y' + { 5110, 27, 34, 29, 1, -33 }, // 0x5A 'Z' + { 5225, 8, 44, 13, 3, -33 }, // 0x5B '[' + { 5269, 13, 35, 13, 0, -33 }, // 0x5C '\' + { 5326, 8, 44, 13, 1, -33 }, // 0x5D ']' + { 5370, 18, 18, 22, 2, -32 }, // 0x5E '^' + { 5411, 28, 2, 26, -1, 7 }, // 0x5F '_' + { 5418, 10, 7, 12, 1, -34 }, // 0x60 '`' + { 5427, 24, 27, 26, 1, -25 }, // 0x61 'a' + { 5508, 22, 35, 26, 3, -33 }, // 0x62 'b' + { 5605, 21, 27, 24, 1, -25 }, // 0x63 'c' + { 5676, 23, 35, 26, 1, -33 }, // 0x64 'd' + { 5777, 22, 27, 25, 1, -25 }, // 0x65 'e' + { 5852, 10, 34, 13, 1, -33 }, // 0x66 'f' + { 5895, 22, 36, 26, 1, -25 }, // 0x67 'g' + { 5994, 19, 34, 25, 3, -33 }, // 0x68 'h' + { 6075, 4, 34, 10, 3, -33 }, // 0x69 'i' + { 6092, 8, 44, 11, 0, -33 }, // 0x6A 'j' + { 6136, 21, 34, 24, 3, -33 }, // 0x6B 'k' + { 6226, 4, 34, 10, 3, -33 }, // 0x6C 'l' + { 6243, 32, 26, 38, 3, -25 }, // 0x6D 'm' + { 6347, 20, 26, 25, 3, -25 }, // 0x6E 'n' + { 6412, 23, 27, 25, 1, -25 }, // 0x6F 'o' + { 6490, 22, 35, 26, 3, -25 }, // 0x70 'p' + { 6587, 23, 35, 26, 1, -25 }, // 0x71 'q' + { 6688, 12, 26, 16, 3, -25 }, // 0x72 'r' + { 6727, 20, 27, 23, 1, -25 }, // 0x73 's' + { 6795, 10, 32, 13, 1, -30 }, // 0x74 't' + { 6835, 20, 26, 25, 3, -24 }, // 0x75 'u' + { 6900, 23, 25, 23, 0, -24 }, // 0x76 'v' + { 6972, 34, 25, 34, 0, -24 }, // 0x77 'w' + { 7079, 22, 25, 22, 0, -24 }, // 0x78 'x' + { 7148, 22, 35, 22, 0, -24 }, // 0x79 'y' + { 7245, 20, 25, 23, 1, -24 }, // 0x7A 'z' + { 7308, 11, 44, 16, 2, -33 }, // 0x7B '{' + { 7369, 3, 44, 12, 4, -33 }, // 0x7C '|' + { 7386, 11, 44, 16, 2, -33 }, // 0x7D '}' + { 7447, 19, 7, 24, 2, -19 } }; // 0x7E '~' + +const GFXfont FreeSans24pt7b PROGMEM = { + (uint8_t *)FreeSans24pt7bBitmaps, + (GFXglyph *)FreeSans24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 8136 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSans9pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSans9pt7b.h new file mode 100644 index 0000000..1f006a1 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSans9pt7b.h @@ -0,0 +1,201 @@ +const uint8_t FreeSans9pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xF8, 0xC0, 0xDE, 0xF7, 0x20, 0x09, 0x86, 0x41, 0x91, 0xFF, + 0x13, 0x04, 0xC3, 0x20, 0xC8, 0xFF, 0x89, 0x82, 0x61, 0x90, 0x10, 0x1F, + 0x14, 0xDA, 0x3D, 0x1E, 0x83, 0x40, 0x78, 0x17, 0x08, 0xF4, 0x7A, 0x35, + 0x33, 0xF0, 0x40, 0x20, 0x38, 0x10, 0xEC, 0x20, 0xC6, 0x20, 0xC6, 0x40, + 0xC6, 0x40, 0x6C, 0x80, 0x39, 0x00, 0x01, 0x3C, 0x02, 0x77, 0x02, 0x63, + 0x04, 0x63, 0x04, 0x77, 0x08, 0x3C, 0x0E, 0x06, 0x60, 0xCC, 0x19, 0x81, + 0xE0, 0x18, 0x0F, 0x03, 0x36, 0xC2, 0xD8, 0x73, 0x06, 0x31, 0xE3, 0xC4, + 0xFE, 0x13, 0x26, 0x6C, 0xCC, 0xCC, 0xC4, 0x66, 0x23, 0x10, 0x8C, 0x46, + 0x63, 0x33, 0x33, 0x32, 0x66, 0x4C, 0x80, 0x25, 0x7E, 0xA5, 0x00, 0x30, + 0xC3, 0x3F, 0x30, 0xC3, 0x0C, 0xD6, 0xF0, 0xC0, 0x08, 0x44, 0x21, 0x10, + 0x84, 0x42, 0x11, 0x08, 0x00, 0x3C, 0x66, 0x42, 0xC3, 0xC3, 0xC3, 0xC3, + 0xC3, 0xC3, 0xC3, 0x42, 0x66, 0x3C, 0x11, 0x3F, 0x33, 0x33, 0x33, 0x33, + 0x30, 0x3E, 0x31, 0xB0, 0x78, 0x30, 0x18, 0x1C, 0x1C, 0x1C, 0x18, 0x18, + 0x10, 0x08, 0x07, 0xF8, 0x3C, 0x66, 0xC3, 0xC3, 0x03, 0x06, 0x1C, 0x07, + 0x03, 0xC3, 0xC3, 0x66, 0x3C, 0x0C, 0x18, 0x71, 0x62, 0xC9, 0xA3, 0x46, + 0xFE, 0x18, 0x30, 0x60, 0xC0, 0x7F, 0x20, 0x10, 0x08, 0x08, 0x07, 0xF3, + 0x8C, 0x03, 0x01, 0x80, 0xF0, 0x6C, 0x63, 0xE0, 0x1E, 0x31, 0x98, 0x78, + 0x0C, 0x06, 0xF3, 0x8D, 0x83, 0xC1, 0xE0, 0xD0, 0x6C, 0x63, 0xE0, 0xFF, + 0x03, 0x02, 0x06, 0x04, 0x0C, 0x08, 0x18, 0x18, 0x18, 0x10, 0x30, 0x30, + 0x3E, 0x31, 0xB0, 0x78, 0x3C, 0x1B, 0x18, 0xF8, 0xC6, 0xC1, 0xE0, 0xF0, + 0x6C, 0x63, 0xE0, 0x3C, 0x66, 0xC2, 0xC3, 0xC3, 0xC3, 0x67, 0x3B, 0x03, + 0x03, 0xC2, 0x66, 0x3C, 0xC0, 0x00, 0x30, 0xC0, 0x00, 0x00, 0x64, 0xA0, + 0x00, 0x81, 0xC7, 0x8E, 0x0C, 0x07, 0x80, 0x70, 0x0E, 0x01, 0x80, 0xFF, + 0x80, 0x00, 0x1F, 0xF0, 0x00, 0x70, 0x0E, 0x01, 0xC0, 0x18, 0x38, 0x71, + 0xC0, 0x80, 0x00, 0x3E, 0x31, 0xB0, 0x78, 0x30, 0x18, 0x18, 0x38, 0x18, + 0x18, 0x0C, 0x00, 0x00, 0x01, 0x80, 0x03, 0xF0, 0x06, 0x0E, 0x06, 0x01, + 0x86, 0x00, 0x66, 0x1D, 0xBB, 0x31, 0xCF, 0x18, 0xC7, 0x98, 0x63, 0xCC, + 0x31, 0xE6, 0x11, 0xB3, 0x99, 0xCC, 0xF7, 0x86, 0x00, 0x01, 0x80, 0x00, + 0x70, 0x40, 0x0F, 0xE0, 0x06, 0x00, 0xF0, 0x0F, 0x00, 0x90, 0x19, 0x81, + 0x98, 0x10, 0x83, 0x0C, 0x3F, 0xC2, 0x04, 0x60, 0x66, 0x06, 0xC0, 0x30, + 0xFF, 0x18, 0x33, 0x03, 0x60, 0x6C, 0x0D, 0x83, 0x3F, 0xC6, 0x06, 0xC0, + 0x78, 0x0F, 0x01, 0xE0, 0x6F, 0xF8, 0x1F, 0x86, 0x19, 0x81, 0xA0, 0x3C, + 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, 0x68, 0x0D, 0x83, 0x18, 0x61, 0xF0, + 0xFF, 0x18, 0x33, 0x03, 0x60, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, + 0x78, 0x0F, 0x03, 0x60, 0xCF, 0xF0, 0xFF, 0xE0, 0x30, 0x18, 0x0C, 0x06, + 0x03, 0xFD, 0x80, 0xC0, 0x60, 0x30, 0x18, 0x0F, 0xF8, 0xFF, 0xC0, 0xC0, + 0xC0, 0xC0, 0xC0, 0xFE, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0x0F, 0x83, + 0x0E, 0x60, 0x66, 0x03, 0xC0, 0x0C, 0x00, 0xC1, 0xFC, 0x03, 0xC0, 0x36, + 0x03, 0x60, 0x73, 0x0F, 0x0F, 0x10, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, + 0x07, 0x80, 0xFF, 0xFE, 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x06, + 0xFF, 0xFF, 0xFF, 0xC0, 0x06, 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x07, + 0x8F, 0x1E, 0x27, 0x80, 0xC0, 0xD8, 0x33, 0x0C, 0x63, 0x0C, 0xC1, 0xB8, + 0x3F, 0x07, 0x30, 0xC3, 0x18, 0x63, 0x06, 0x60, 0x6C, 0x0C, 0xC0, 0xC0, + 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xFF, 0xE0, + 0x3F, 0x01, 0xFC, 0x1F, 0xE0, 0xFD, 0x05, 0xEC, 0x6F, 0x63, 0x79, 0x13, + 0xCD, 0x9E, 0x6C, 0xF1, 0x47, 0x8E, 0x3C, 0x71, 0x80, 0xE0, 0x7C, 0x0F, + 0xC1, 0xE8, 0x3D, 0x87, 0x98, 0xF1, 0x1E, 0x33, 0xC3, 0x78, 0x6F, 0x07, + 0xE0, 0x7C, 0x0E, 0x0F, 0x81, 0x83, 0x18, 0x0C, 0xC0, 0x6C, 0x01, 0xE0, + 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1B, 0x01, 0x98, 0x0C, 0x60, 0xC0, 0xF8, + 0x00, 0xFF, 0x30, 0x6C, 0x0F, 0x03, 0xC0, 0xF0, 0x6F, 0xF3, 0x00, 0xC0, + 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x00, 0x0F, 0x81, 0x83, 0x18, 0x0C, 0xC0, + 0x6C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1B, 0x01, 0x98, 0x6C, + 0x60, 0xC0, 0xFB, 0x00, 0x08, 0xFF, 0x8C, 0x0E, 0xC0, 0x6C, 0x06, 0xC0, + 0x6C, 0x0C, 0xFF, 0x8C, 0x0E, 0xC0, 0x6C, 0x06, 0xC0, 0x6C, 0x06, 0xC0, + 0x70, 0x3F, 0x18, 0x6C, 0x0F, 0x03, 0xC0, 0x1E, 0x01, 0xF0, 0x0E, 0x00, + 0xF0, 0x3C, 0x0D, 0x86, 0x3F, 0x00, 0xFF, 0x86, 0x03, 0x01, 0x80, 0xC0, + 0x60, 0x30, 0x18, 0x0C, 0x06, 0x03, 0x01, 0x80, 0xC0, 0xC0, 0x78, 0x0F, + 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x01, + 0xB0, 0x61, 0xF0, 0xC0, 0x6C, 0x0D, 0x81, 0x10, 0x63, 0x0C, 0x61, 0x04, + 0x60, 0xCC, 0x19, 0x01, 0x60, 0x3C, 0x07, 0x00, 0x60, 0xC1, 0x81, 0x30, + 0xE1, 0x98, 0x70, 0xCC, 0x28, 0x66, 0x26, 0x21, 0x13, 0x30, 0xC8, 0x98, + 0x6C, 0x4C, 0x14, 0x34, 0x0A, 0x1A, 0x07, 0x07, 0x03, 0x03, 0x80, 0x81, + 0x80, 0x60, 0x63, 0x0C, 0x30, 0xC1, 0x98, 0x0F, 0x00, 0xE0, 0x06, 0x00, + 0xF0, 0x19, 0x01, 0x98, 0x30, 0xC6, 0x0E, 0x60, 0x60, 0xC0, 0x36, 0x06, + 0x30, 0xC3, 0x0C, 0x19, 0x81, 0xD8, 0x0F, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x06, 0x00, 0x60, 0x06, 0x00, 0xFF, 0xC0, 0x60, 0x30, 0x0C, 0x06, 0x03, + 0x01, 0xC0, 0x60, 0x30, 0x18, 0x06, 0x03, 0x00, 0xFF, 0xC0, 0xFB, 0x6D, + 0xB6, 0xDB, 0x6D, 0xB6, 0xE0, 0x84, 0x10, 0x84, 0x10, 0x84, 0x10, 0x84, + 0x10, 0x80, 0xED, 0xB6, 0xDB, 0x6D, 0xB6, 0xDB, 0xE0, 0x30, 0x60, 0xA2, + 0x44, 0xD8, 0xA1, 0x80, 0xFF, 0xC0, 0xC6, 0x30, 0x7E, 0x71, 0xB0, 0xC0, + 0x60, 0xF3, 0xDB, 0x0D, 0x86, 0xC7, 0x3D, 0xC0, 0xC0, 0x60, 0x30, 0x1B, + 0xCE, 0x36, 0x0F, 0x07, 0x83, 0xC1, 0xE0, 0xF0, 0x7C, 0x6D, 0xE0, 0x3C, + 0x66, 0xC3, 0xC0, 0xC0, 0xC0, 0xC0, 0xC3, 0x66, 0x3C, 0x03, 0x03, 0x03, + 0x3B, 0x67, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0x67, 0x3B, 0x3C, 0x66, + 0xC3, 0xC3, 0xFF, 0xC0, 0xC0, 0xC3, 0x66, 0x3C, 0x36, 0x6F, 0x66, 0x66, + 0x66, 0x66, 0x60, 0x3B, 0x67, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0x67, + 0x3B, 0x03, 0x03, 0xC6, 0x7C, 0xC0, 0xC0, 0xC0, 0xDE, 0xE3, 0xC3, 0xC3, + 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xFF, 0xFF, 0xC0, 0x30, 0x03, + 0x33, 0x33, 0x33, 0x33, 0x33, 0x33, 0xE0, 0xC0, 0x60, 0x30, 0x18, 0x4C, + 0x46, 0x63, 0x61, 0xF0, 0xEC, 0x62, 0x31, 0x98, 0x6C, 0x30, 0xFF, 0xFF, + 0xFF, 0xC0, 0xDE, 0xF7, 0x1C, 0xF0, 0xC7, 0x86, 0x3C, 0x31, 0xE1, 0x8F, + 0x0C, 0x78, 0x63, 0xC3, 0x1E, 0x18, 0xC0, 0xDE, 0xE3, 0xC3, 0xC3, 0xC3, + 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0x3C, 0x66, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, + 0xC3, 0x66, 0x3C, 0xDE, 0x71, 0xB0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, + 0xE3, 0x6F, 0x30, 0x18, 0x0C, 0x00, 0x3B, 0x67, 0xC3, 0xC3, 0xC3, 0xC3, + 0xC3, 0xC3, 0x67, 0x3B, 0x03, 0x03, 0x03, 0xDF, 0x31, 0x8C, 0x63, 0x18, + 0xC6, 0x00, 0x3E, 0xE3, 0xC0, 0xC0, 0xE0, 0x3C, 0x07, 0xC3, 0xE3, 0x7E, + 0x66, 0xF6, 0x66, 0x66, 0x66, 0x67, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, + 0xC3, 0xC3, 0xC7, 0x7B, 0xC1, 0xA0, 0x98, 0xCC, 0x42, 0x21, 0xB0, 0xD0, + 0x28, 0x1C, 0x0C, 0x00, 0xC6, 0x1E, 0x38, 0x91, 0xC4, 0xCA, 0x66, 0xD3, + 0x16, 0xD0, 0xA6, 0x87, 0x1C, 0x38, 0xC0, 0xC6, 0x00, 0x43, 0x62, 0x36, + 0x1C, 0x18, 0x1C, 0x3C, 0x26, 0x62, 0x43, 0xC1, 0x21, 0x98, 0xCC, 0x42, + 0x61, 0xB0, 0xD0, 0x38, 0x1C, 0x0C, 0x06, 0x03, 0x01, 0x03, 0x00, 0xFE, + 0x0C, 0x30, 0xC1, 0x86, 0x18, 0x20, 0xC1, 0xFC, 0x36, 0x66, 0x66, 0x6E, + 0xCE, 0x66, 0x66, 0x66, 0x30, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xC6, 0x66, + 0x66, 0x67, 0x37, 0x66, 0x66, 0x66, 0xC0, 0x61, 0x24, 0x38 }; + +const GFXglyph FreeSans9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 2, 13, 6, 2, -12 }, // 0x21 '!' + { 4, 5, 4, 6, 1, -12 }, // 0x22 '"' + { 7, 10, 12, 10, 0, -11 }, // 0x23 '#' + { 22, 9, 16, 10, 1, -13 }, // 0x24 '$' + { 40, 16, 13, 16, 1, -12 }, // 0x25 '%' + { 66, 11, 13, 12, 1, -12 }, // 0x26 '&' + { 84, 2, 4, 4, 1, -12 }, // 0x27 ''' + { 85, 4, 17, 6, 1, -12 }, // 0x28 '(' + { 94, 4, 17, 6, 1, -12 }, // 0x29 ')' + { 103, 5, 5, 7, 1, -12 }, // 0x2A '*' + { 107, 6, 8, 11, 3, -7 }, // 0x2B '+' + { 113, 2, 4, 5, 2, 0 }, // 0x2C ',' + { 114, 4, 1, 6, 1, -4 }, // 0x2D '-' + { 115, 2, 1, 5, 1, 0 }, // 0x2E '.' + { 116, 5, 13, 5, 0, -12 }, // 0x2F '/' + { 125, 8, 13, 10, 1, -12 }, // 0x30 '0' + { 138, 4, 13, 10, 3, -12 }, // 0x31 '1' + { 145, 9, 13, 10, 1, -12 }, // 0x32 '2' + { 160, 8, 13, 10, 1, -12 }, // 0x33 '3' + { 173, 7, 13, 10, 2, -12 }, // 0x34 '4' + { 185, 9, 13, 10, 1, -12 }, // 0x35 '5' + { 200, 9, 13, 10, 1, -12 }, // 0x36 '6' + { 215, 8, 13, 10, 0, -12 }, // 0x37 '7' + { 228, 9, 13, 10, 1, -12 }, // 0x38 '8' + { 243, 8, 13, 10, 1, -12 }, // 0x39 '9' + { 256, 2, 10, 5, 1, -9 }, // 0x3A ':' + { 259, 3, 12, 5, 1, -8 }, // 0x3B ';' + { 264, 9, 9, 11, 1, -8 }, // 0x3C '<' + { 275, 9, 4, 11, 1, -5 }, // 0x3D '=' + { 280, 9, 9, 11, 1, -8 }, // 0x3E '>' + { 291, 9, 13, 10, 1, -12 }, // 0x3F '?' + { 306, 17, 16, 18, 1, -12 }, // 0x40 '@' + { 340, 12, 13, 12, 0, -12 }, // 0x41 'A' + { 360, 11, 13, 12, 1, -12 }, // 0x42 'B' + { 378, 11, 13, 13, 1, -12 }, // 0x43 'C' + { 396, 11, 13, 13, 1, -12 }, // 0x44 'D' + { 414, 9, 13, 11, 1, -12 }, // 0x45 'E' + { 429, 8, 13, 11, 1, -12 }, // 0x46 'F' + { 442, 12, 13, 14, 1, -12 }, // 0x47 'G' + { 462, 11, 13, 13, 1, -12 }, // 0x48 'H' + { 480, 2, 13, 5, 2, -12 }, // 0x49 'I' + { 484, 7, 13, 10, 1, -12 }, // 0x4A 'J' + { 496, 11, 13, 12, 1, -12 }, // 0x4B 'K' + { 514, 8, 13, 10, 1, -12 }, // 0x4C 'L' + { 527, 13, 13, 15, 1, -12 }, // 0x4D 'M' + { 549, 11, 13, 13, 1, -12 }, // 0x4E 'N' + { 567, 13, 13, 14, 1, -12 }, // 0x4F 'O' + { 589, 10, 13, 12, 1, -12 }, // 0x50 'P' + { 606, 13, 14, 14, 1, -12 }, // 0x51 'Q' + { 629, 12, 13, 13, 1, -12 }, // 0x52 'R' + { 649, 10, 13, 12, 1, -12 }, // 0x53 'S' + { 666, 9, 13, 11, 1, -12 }, // 0x54 'T' + { 681, 11, 13, 13, 1, -12 }, // 0x55 'U' + { 699, 11, 13, 12, 0, -12 }, // 0x56 'V' + { 717, 17, 13, 17, 0, -12 }, // 0x57 'W' + { 745, 12, 13, 12, 0, -12 }, // 0x58 'X' + { 765, 12, 13, 12, 0, -12 }, // 0x59 'Y' + { 785, 10, 13, 11, 1, -12 }, // 0x5A 'Z' + { 802, 3, 17, 5, 1, -12 }, // 0x5B '[' + { 809, 5, 13, 5, 0, -12 }, // 0x5C '\' + { 818, 3, 17, 5, 0, -12 }, // 0x5D ']' + { 825, 7, 7, 8, 1, -12 }, // 0x5E '^' + { 832, 10, 1, 10, 0, 3 }, // 0x5F '_' + { 834, 4, 3, 5, 0, -12 }, // 0x60 '`' + { 836, 9, 10, 10, 1, -9 }, // 0x61 'a' + { 848, 9, 13, 10, 1, -12 }, // 0x62 'b' + { 863, 8, 10, 9, 1, -9 }, // 0x63 'c' + { 873, 8, 13, 10, 1, -12 }, // 0x64 'd' + { 886, 8, 10, 10, 1, -9 }, // 0x65 'e' + { 896, 4, 13, 5, 1, -12 }, // 0x66 'f' + { 903, 8, 14, 10, 1, -9 }, // 0x67 'g' + { 917, 8, 13, 10, 1, -12 }, // 0x68 'h' + { 930, 2, 13, 4, 1, -12 }, // 0x69 'i' + { 934, 4, 17, 4, 0, -12 }, // 0x6A 'j' + { 943, 9, 13, 9, 1, -12 }, // 0x6B 'k' + { 958, 2, 13, 4, 1, -12 }, // 0x6C 'l' + { 962, 13, 10, 15, 1, -9 }, // 0x6D 'm' + { 979, 8, 10, 10, 1, -9 }, // 0x6E 'n' + { 989, 8, 10, 10, 1, -9 }, // 0x6F 'o' + { 999, 9, 13, 10, 1, -9 }, // 0x70 'p' + { 1014, 8, 13, 10, 1, -9 }, // 0x71 'q' + { 1027, 5, 10, 6, 1, -9 }, // 0x72 'r' + { 1034, 8, 10, 9, 1, -9 }, // 0x73 's' + { 1044, 4, 12, 5, 1, -11 }, // 0x74 't' + { 1050, 8, 10, 10, 1, -9 }, // 0x75 'u' + { 1060, 9, 10, 9, 0, -9 }, // 0x76 'v' + { 1072, 13, 10, 13, 0, -9 }, // 0x77 'w' + { 1089, 8, 10, 9, 0, -9 }, // 0x78 'x' + { 1099, 9, 14, 9, 0, -9 }, // 0x79 'y' + { 1115, 7, 10, 9, 1, -9 }, // 0x7A 'z' + { 1124, 4, 17, 6, 1, -12 }, // 0x7B '{' + { 1133, 2, 17, 4, 2, -12 }, // 0x7C '|' + { 1138, 4, 17, 6, 1, -12 }, // 0x7D '}' + { 1147, 7, 3, 9, 1, -7 } }; // 0x7E '~' + +const GFXfont FreeSans9pt7b PROGMEM = { + (uint8_t *)FreeSans9pt7bBitmaps, + (GFXglyph *)FreeSans9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 1822 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBold12pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBold12pt7b.h new file mode 100644 index 0000000..e0922be --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBold12pt7b.h @@ -0,0 +1,288 @@ +const uint8_t FreeSansBold12pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xFF, 0x76, 0x66, 0x60, 0xFF, 0xF0, 0xF3, 0xFC, 0xFF, + 0x3F, 0xCF, 0x61, 0x98, 0x60, 0x0E, 0x70, 0x73, 0x83, 0x18, 0xFF, 0xF7, + 0xFF, 0xBF, 0xFC, 0x73, 0x83, 0x18, 0x18, 0xC7, 0xFF, 0xBF, 0xFD, 0xFF, + 0xE3, 0x18, 0x39, 0xC1, 0xCE, 0x0E, 0x70, 0x02, 0x00, 0x7E, 0x0F, 0xF8, + 0x7F, 0xE7, 0xAF, 0xB9, 0x3D, 0xC8, 0x0F, 0x40, 0x3F, 0x00, 0xFF, 0x00, + 0xFC, 0x05, 0xFF, 0x27, 0xF9, 0x3F, 0xEB, 0xEF, 0xFE, 0x3F, 0xE0, 0x7C, + 0x00, 0x80, 0x04, 0x00, 0x3C, 0x06, 0x0F, 0xC1, 0x81, 0xFC, 0x30, 0x73, + 0x8C, 0x0C, 0x31, 0x81, 0xCE, 0x60, 0x1F, 0xCC, 0x03, 0xF3, 0x00, 0x3C, + 0x67, 0x80, 0x19, 0xF8, 0x02, 0x7F, 0x80, 0xCE, 0x70, 0x11, 0x86, 0x06, + 0x39, 0xC1, 0x87, 0xF8, 0x30, 0x7E, 0x0C, 0x07, 0x80, 0x07, 0x80, 0x1F, + 0xC0, 0x3F, 0xE0, 0x3C, 0xE0, 0x3C, 0xE0, 0x3E, 0xE0, 0x0F, 0xC0, 0x07, + 0x00, 0x3F, 0x8C, 0x7F, 0xCC, 0xF1, 0xFC, 0xF0, 0xF8, 0xF0, 0x78, 0xF8, + 0xF8, 0x7F, 0xFC, 0x3F, 0xDE, 0x1F, 0x8E, 0xFF, 0xFF, 0x66, 0x0C, 0x73, + 0x8E, 0x71, 0xC7, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x8E, 0x1C, 0x71, 0xC3, + 0x8E, 0x18, 0x70, 0xC3, 0x87, 0x1C, 0x38, 0xE3, 0x87, 0x1C, 0x71, 0xC7, + 0x1C, 0x71, 0xCE, 0x38, 0xE7, 0x1C, 0x63, 0x80, 0x10, 0x23, 0x5F, 0xF3, + 0x87, 0x1B, 0x14, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x0F, 0xFF, 0xFF, 0xFF, + 0xF8, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x00, 0xFF, 0xF3, 0x36, 0xC0, 0xFF, + 0xFF, 0xC0, 0xFF, 0xF0, 0x0C, 0x30, 0x86, 0x18, 0x61, 0x0C, 0x30, 0xC2, + 0x18, 0x61, 0x84, 0x30, 0xC0, 0x1F, 0x83, 0xFC, 0x7F, 0xE7, 0x9E, 0xF0, + 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, + 0xF7, 0x9E, 0x7F, 0xE3, 0xFC, 0x0F, 0x00, 0x06, 0x1C, 0x7F, 0xFF, 0xE3, + 0xC7, 0x8F, 0x1E, 0x3C, 0x78, 0xF1, 0xE3, 0xC7, 0x8F, 0x1E, 0x1F, 0x83, + 0xFC, 0x7F, 0xEF, 0x9F, 0xF0, 0xFF, 0x0F, 0x00, 0xF0, 0x0F, 0x01, 0xE0, + 0x3C, 0x0F, 0x81, 0xE0, 0x3C, 0x03, 0x80, 0x7F, 0xF7, 0xFF, 0x7F, 0xF0, + 0x1F, 0x07, 0xFC, 0xFF, 0xEF, 0x1E, 0xF1, 0xE0, 0x1E, 0x03, 0xC0, 0x78, + 0x07, 0xC0, 0x1E, 0x00, 0xF0, 0x0F, 0xF0, 0xFF, 0x1F, 0x7F, 0xE7, 0xFC, + 0x1F, 0x80, 0x03, 0xC0, 0xF8, 0x1F, 0x07, 0xE1, 0xBC, 0x27, 0x8C, 0xF3, + 0x1E, 0x63, 0xD8, 0x7B, 0xFF, 0xFF, 0xFF, 0xFE, 0x07, 0x80, 0xF0, 0x1E, + 0x03, 0xC0, 0x3F, 0xE7, 0xFE, 0x7F, 0xE7, 0x00, 0x60, 0x06, 0xF8, 0x7F, + 0xCF, 0xFE, 0xF1, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xFE, 0x1E, 0xFF, + 0xE7, 0xFC, 0x3F, 0x00, 0x0F, 0x83, 0xFC, 0x7F, 0xE7, 0x9F, 0xF0, 0x0F, + 0x78, 0xFF, 0xCF, 0xFE, 0xF9, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xF7, + 0x9F, 0x7F, 0xE3, 0xFC, 0x0F, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0xE0, + 0x1C, 0x07, 0x01, 0xE0, 0x38, 0x0F, 0x01, 0xC0, 0x78, 0x0F, 0x01, 0xE0, + 0x38, 0x0F, 0x01, 0xE0, 0x3C, 0x00, 0x0F, 0x03, 0xFC, 0x7F, 0xC7, 0x9E, + 0x70, 0xE7, 0x0E, 0x39, 0xC1, 0xF8, 0x3F, 0xC7, 0x9E, 0xF0, 0xFF, 0x0F, + 0xF0, 0xFF, 0x9F, 0x7F, 0xE3, 0xFC, 0x1F, 0x80, 0x1F, 0x03, 0xFC, 0x7F, + 0xEF, 0x9E, 0xF0, 0xEF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF9, 0xF7, 0xFF, 0x3F, + 0xF1, 0xEF, 0x00, 0xEF, 0x1E, 0x7F, 0xE7, 0xFC, 0x1F, 0x00, 0xFF, 0xF0, + 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x0F, 0xFF, 0x11, 0x6C, + 0x00, 0x10, 0x07, 0x03, 0xF1, 0xFC, 0x7E, 0x0F, 0x80, 0xE0, 0x0F, 0xC0, + 0x3F, 0x80, 0x7F, 0x00, 0xF0, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, + 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x0E, 0x00, 0xFC, + 0x07, 0xF0, 0x0F, 0xE0, 0x1F, 0x00, 0xF0, 0x7F, 0x1F, 0x8F, 0xE0, 0xF0, + 0x08, 0x00, 0x1F, 0x07, 0xFC, 0x7F, 0xEF, 0x9F, 0xF0, 0xFF, 0x0F, 0x00, + 0xF0, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x0E, 0x00, 0xE0, 0x00, + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x00, 0xFE, 0x00, 0x1F, 0xFC, 0x03, 0xC0, + 0xF0, 0x38, 0x01, 0xC3, 0x80, 0x07, 0x18, 0x3D, 0x99, 0x87, 0xEC, 0x6C, + 0x71, 0xC3, 0xC3, 0x06, 0x1E, 0x18, 0x30, 0xF1, 0x81, 0x87, 0x8C, 0x18, + 0x7C, 0x60, 0xC3, 0x63, 0x8E, 0x3B, 0x8F, 0xDF, 0x8C, 0x3C, 0xF0, 0x70, + 0x00, 0x01, 0xC0, 0x00, 0x07, 0x80, 0x80, 0x1F, 0xFE, 0x00, 0x1F, 0xC0, + 0x00, 0x03, 0xE0, 0x03, 0xE0, 0x03, 0xE0, 0x07, 0xF0, 0x07, 0xF0, 0x07, + 0x70, 0x0F, 0x78, 0x0E, 0x78, 0x0E, 0x38, 0x1E, 0x3C, 0x1C, 0x3C, 0x3F, + 0xFC, 0x3F, 0xFE, 0x3F, 0xFE, 0x78, 0x0E, 0x78, 0x0F, 0x70, 0x0F, 0xF0, + 0x07, 0xFF, 0xC3, 0xFF, 0xCF, 0xFF, 0x3C, 0x3E, 0xF0, 0x7B, 0xC1, 0xEF, + 0x0F, 0xBF, 0xFC, 0xFF, 0xE3, 0xFF, 0xCF, 0x07, 0xBC, 0x0F, 0xF0, 0x3F, + 0xC0, 0xFF, 0x07, 0xFF, 0xFE, 0xFF, 0xFB, 0xFF, 0x80, 0x07, 0xE0, 0x1F, + 0xF8, 0x3F, 0xFC, 0x7C, 0x3E, 0x78, 0x1F, 0xF8, 0x0F, 0xF0, 0x00, 0xF0, + 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF8, 0x0F, 0x78, + 0x1F, 0x7C, 0x3E, 0x3F, 0xFE, 0x1F, 0xFC, 0x07, 0xF0, 0xFF, 0xE1, 0xFF, + 0xE3, 0xFF, 0xE7, 0x83, 0xEF, 0x03, 0xDE, 0x07, 0xFC, 0x07, 0xF8, 0x0F, + 0xF0, 0x1F, 0xE0, 0x3F, 0xC0, 0x7F, 0x80, 0xFF, 0x03, 0xFE, 0x07, 0xBC, + 0x1F, 0x7F, 0xFC, 0xFF, 0xF1, 0xFF, 0x80, 0xFF, 0xF7, 0xFF, 0xBF, 0xFD, + 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1F, 0xFC, 0xFF, 0xE7, 0xFF, 0x3C, + 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0xFE, 0xFF, 0xEF, 0xFE, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x0F, 0x00, 0x03, 0xF0, 0x0F, 0xFC, 0x3F, 0xFE, 0x3E, 0x1F, + 0x78, 0x07, 0x78, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF0, 0x7F, 0xF0, 0x7F, + 0xF0, 0x7F, 0xF0, 0x07, 0x78, 0x07, 0x7C, 0x0F, 0x3E, 0x1F, 0x3F, 0xFB, + 0x0F, 0xFB, 0x03, 0xE3, 0xF0, 0x3F, 0xC0, 0xFF, 0x03, 0xFC, 0x0F, 0xF0, + 0x3F, 0xC0, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFC, + 0x0F, 0xF0, 0x3F, 0xC0, 0xFF, 0x03, 0xFC, 0x0F, 0xF0, 0x3F, 0xC0, 0xF0, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x01, 0xE0, 0x3C, + 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, + 0xF8, 0xFF, 0x1F, 0xE3, 0xFC, 0x7B, 0xFE, 0x7F, 0xC3, 0xE0, 0xF0, 0x3E, + 0xF0, 0x3C, 0xF0, 0x78, 0xF0, 0xF0, 0xF1, 0xE0, 0xF3, 0xC0, 0xF7, 0x80, + 0xFF, 0x00, 0xFF, 0x80, 0xFF, 0x80, 0xFB, 0xC0, 0xF1, 0xE0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0x78, 0xF0, 0x3C, 0xF0, 0x3E, 0xF0, 0x1E, 0xF0, 0x1E, + 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, + 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0xFF, 0xFF, 0xFF, 0xFC, 0xF8, + 0x1F, 0xFE, 0x0F, 0xFF, 0x0F, 0xFF, 0x87, 0xFF, 0xC3, 0xFF, 0xE1, 0xFF, + 0xF9, 0xFF, 0xFC, 0xEF, 0xFE, 0x77, 0xFB, 0x3B, 0xFD, 0xDD, 0xFE, 0xFC, + 0xFF, 0x7E, 0x7F, 0x9F, 0x3F, 0xCF, 0x9F, 0xE7, 0x8F, 0xF3, 0xC7, 0xF8, + 0xE3, 0xC0, 0xF0, 0x1F, 0xF0, 0x3F, 0xF0, 0x7F, 0xE0, 0xFF, 0xE1, 0xFF, + 0xC3, 0xFD, 0xC7, 0xFB, 0x8F, 0xF3, 0x9F, 0xE7, 0x3F, 0xC7, 0x7F, 0x8F, + 0xFF, 0x0F, 0xFE, 0x1F, 0xFC, 0x1F, 0xF8, 0x1F, 0xF0, 0x3F, 0xE0, 0x3C, + 0x03, 0xE0, 0x0F, 0xFC, 0x0F, 0xFF, 0x87, 0xC7, 0xC7, 0x80, 0xF3, 0xC0, + 0x7B, 0xC0, 0x1F, 0xE0, 0x0F, 0xF0, 0x07, 0xF8, 0x03, 0xFC, 0x01, 0xFE, + 0x00, 0xF7, 0x80, 0xF3, 0xC0, 0x78, 0xF0, 0xF8, 0x7F, 0xFC, 0x1F, 0xFC, + 0x03, 0xF8, 0x00, 0xFF, 0xE3, 0xFF, 0xEF, 0xFF, 0xBC, 0x1F, 0xF0, 0x3F, + 0xC0, 0xFF, 0x03, 0xFC, 0x1F, 0xFF, 0xFB, 0xFF, 0xCF, 0xFE, 0x3C, 0x00, + 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x00, 0x03, + 0xE0, 0x0F, 0xFC, 0x0F, 0xFF, 0x87, 0xC7, 0xC7, 0x80, 0xF3, 0xC0, 0x7B, + 0xC0, 0x1F, 0xE0, 0x0F, 0xF0, 0x07, 0xF8, 0x03, 0xFC, 0x01, 0xFE, 0x04, + 0xF7, 0x87, 0xF3, 0xC3, 0xF8, 0xF0, 0xF8, 0x7F, 0xFC, 0x1F, 0xFF, 0x83, + 0xF1, 0x80, 0x00, 0x00, 0xFF, 0xF8, 0xFF, 0xFC, 0xFF, 0xFC, 0xF0, 0x3E, + 0xF0, 0x1E, 0xF0, 0x1E, 0xF0, 0x1E, 0xF0, 0x3C, 0xFF, 0xF8, 0xFF, 0xF0, + 0xFF, 0xF8, 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, 0x3C, + 0xF0, 0x3C, 0xF0, 0x1F, 0x0F, 0xC0, 0x7F, 0xE1, 0xFF, 0xE7, 0xC3, 0xEF, + 0x03, 0xDE, 0x00, 0x3C, 0x00, 0x7F, 0x00, 0x7F, 0xF0, 0x3F, 0xF8, 0x0F, + 0xF8, 0x01, 0xF0, 0x01, 0xFE, 0x03, 0xDE, 0x0F, 0xBF, 0xFE, 0x3F, 0xF8, + 0x1F, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0xF0, 0x3F, 0xC0, 0xFF, 0x03, 0xFC, 0x0F, + 0xF0, 0x3F, 0xC0, 0xFF, 0x03, 0xFC, 0x0F, 0xF0, 0x3F, 0xC0, 0xFF, 0x03, + 0xFC, 0x0F, 0xF0, 0x3F, 0xC0, 0xF7, 0x87, 0x9F, 0xFE, 0x3F, 0xF0, 0x3F, + 0x00, 0x70, 0x0E, 0xF0, 0x3D, 0xE0, 0x79, 0xC0, 0xE3, 0x81, 0xC7, 0x87, + 0x87, 0x0E, 0x0E, 0x1C, 0x1E, 0x78, 0x1C, 0xE0, 0x39, 0xC0, 0x73, 0x80, + 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x70, + 0x38, 0x1C, 0xE0, 0xF0, 0x79, 0xE1, 0xF0, 0xF3, 0xC3, 0xE1, 0xE3, 0x87, + 0xC3, 0x87, 0x0F, 0x87, 0x0E, 0x3B, 0x9E, 0x1E, 0x77, 0x38, 0x1C, 0xEE, + 0x70, 0x39, 0xCC, 0xE0, 0x73, 0x99, 0xC0, 0x6E, 0x3F, 0x00, 0xFC, 0x7E, + 0x01, 0xF8, 0xFC, 0x03, 0xF0, 0xF8, 0x03, 0xE1, 0xE0, 0x07, 0x83, 0xC0, + 0x0F, 0x07, 0x80, 0xF0, 0x3C, 0xF0, 0xF9, 0xE1, 0xE1, 0xE7, 0x83, 0xCF, + 0x03, 0xFC, 0x03, 0xF0, 0x07, 0xE0, 0x07, 0x80, 0x0F, 0x00, 0x3F, 0x00, + 0xFF, 0x01, 0xFE, 0x07, 0x9E, 0x0F, 0x1E, 0x3C, 0x3C, 0xF8, 0x3D, 0xE0, + 0x78, 0xF0, 0x1E, 0x78, 0x1E, 0x78, 0x3C, 0x3C, 0x3C, 0x3C, 0x78, 0x1E, + 0x78, 0x0E, 0x70, 0x0F, 0xF0, 0x07, 0xE0, 0x07, 0xE0, 0x03, 0xC0, 0x03, + 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, + 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x01, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF8, 0x07, 0x80, 0x78, 0x07, 0x80, 0x7C, 0x03, 0xC0, 0x3C, 0x03, + 0xC0, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFC, 0xF3, 0xCF, + 0x3C, 0xF3, 0xCF, 0x3C, 0xF3, 0xCF, 0x3C, 0xF3, 0xCF, 0x3C, 0xFF, 0xFF, + 0xC0, 0xC1, 0x81, 0x03, 0x06, 0x04, 0x0C, 0x18, 0x10, 0x30, 0x60, 0x40, + 0xC1, 0x81, 0x03, 0x06, 0xFF, 0xFF, 0xCF, 0x3C, 0xF3, 0xCF, 0x3C, 0xF3, + 0xCF, 0x3C, 0xF3, 0xCF, 0x3C, 0xF3, 0xCF, 0xFF, 0xFF, 0xC0, 0x0F, 0x00, + 0xF0, 0x0F, 0x01, 0xF8, 0x1B, 0x83, 0x9C, 0x39, 0xC3, 0x0C, 0x70, 0xE7, + 0x0E, 0xE0, 0x70, 0xFF, 0xFF, 0xFF, 0xFC, 0xE6, 0x30, 0x1F, 0x83, 0xFF, + 0x1F, 0xFD, 0xE1, 0xE0, 0x0F, 0x03, 0xF9, 0xFF, 0xDF, 0x1E, 0xF0, 0xF7, + 0x8F, 0xBF, 0xFC, 0xFF, 0xE3, 0xCF, 0x80, 0xF0, 0x07, 0x80, 0x3C, 0x01, + 0xE0, 0x0F, 0x00, 0x7B, 0xC3, 0xFF, 0x9F, 0xFE, 0xF8, 0xF7, 0x83, 0xFC, + 0x1F, 0xE0, 0xFF, 0x07, 0xF8, 0x3F, 0xE3, 0xDF, 0xFE, 0xFF, 0xE7, 0xBE, + 0x00, 0x0F, 0x83, 0xFE, 0x7F, 0xF7, 0x8F, 0xF0, 0x7F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x77, 0x8F, 0x7F, 0xF3, 0xFE, 0x0F, 0x80, 0x00, 0x78, 0x03, + 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x8F, 0xBC, 0xFF, 0xEF, 0xFF, 0x78, 0xFF, + 0x83, 0xFC, 0x1F, 0xE0, 0xFF, 0x07, 0xF8, 0x3D, 0xE3, 0xEF, 0xFF, 0x3F, + 0xF8, 0xFB, 0xC0, 0x1F, 0x81, 0xFE, 0x1F, 0xF9, 0xF1, 0xCF, 0x07, 0x7F, + 0xFB, 0xFF, 0xDE, 0x00, 0xF0, 0x03, 0xC3, 0x9F, 0xFC, 0x7F, 0xC0, 0xF8, + 0x00, 0x3E, 0xFD, 0xFB, 0xC7, 0x9F, 0xBF, 0x3C, 0x78, 0xF1, 0xE3, 0xC7, + 0x8F, 0x1E, 0x3C, 0x78, 0xF0, 0x1E, 0x79, 0xFB, 0xDF, 0xFE, 0xF1, 0xFF, + 0x07, 0xF8, 0x3F, 0xC1, 0xFE, 0x0F, 0xF0, 0x7F, 0xC7, 0xDF, 0xFE, 0x7F, + 0xF1, 0xF7, 0x80, 0x3C, 0x01, 0xFF, 0x1E, 0x7F, 0xF0, 0xFE, 0x00, 0xF0, + 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x7C, 0xFF, 0xEF, 0xFF, 0xF9, + 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, + 0xFF, 0x0F, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x3C, + 0xF3, 0xC0, 0x00, 0xF3, 0xCF, 0x3C, 0xF3, 0xCF, 0x3C, 0xF3, 0xCF, 0x3C, + 0xF3, 0xCF, 0xFF, 0xFF, 0x80, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, + 0x0F, 0x0F, 0xF1, 0xEF, 0x3C, 0xF7, 0x8F, 0xF0, 0xFF, 0x0F, 0xF8, 0xFF, + 0x8F, 0x3C, 0xF1, 0xCF, 0x1E, 0xF0, 0xEF, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF7, 0x8F, 0x9F, 0xFB, 0xFB, 0xFF, 0xFF, + 0xFC, 0xF8, 0xFF, 0x1E, 0x1F, 0xE3, 0xC3, 0xFC, 0x78, 0x7F, 0x8F, 0x0F, + 0xF1, 0xE1, 0xFE, 0x3C, 0x3F, 0xC7, 0x87, 0xF8, 0xF0, 0xFF, 0x1E, 0x1E, + 0xF7, 0xCF, 0xFE, 0xFF, 0xFF, 0x9F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, + 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xF0, 0x0F, 0x81, 0xFF, 0x1F, + 0xFC, 0xF1, 0xEF, 0x07, 0xF8, 0x3F, 0xC1, 0xFE, 0x0F, 0xF0, 0x7B, 0xC7, + 0x9F, 0xFC, 0x7F, 0xC0, 0xF8, 0x00, 0xF7, 0xC7, 0xFF, 0x3F, 0xFD, 0xF1, + 0xEF, 0x07, 0xF8, 0x3F, 0xC1, 0xFE, 0x0F, 0xF0, 0x7F, 0xC7, 0xBF, 0xFD, + 0xFF, 0xCF, 0x78, 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x00, + 0x0F, 0x79, 0xFF, 0xDF, 0xFE, 0xF1, 0xFF, 0x07, 0xF8, 0x3F, 0xC1, 0xFE, + 0x0F, 0xF0, 0x7B, 0xC7, 0xDF, 0xFE, 0x7F, 0xF1, 0xF7, 0x80, 0x3C, 0x01, + 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0xF3, 0xF7, 0xFF, 0xF8, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0x1F, 0x87, 0xFC, 0xFF, 0xEF, + 0x0F, 0xF8, 0x0F, 0xF0, 0x7F, 0xE0, 0xFF, 0x01, 0xFF, 0x0F, 0xFF, 0xE7, + 0xFE, 0x1F, 0x80, 0x79, 0xE7, 0xBF, 0xFD, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, + 0x7D, 0xF3, 0xC0, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, + 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x1F, 0xFF, 0xF7, 0xFF, 0x3E, 0xF0, 0xF0, + 0x7B, 0x83, 0x9E, 0x1C, 0xF1, 0xE3, 0x8E, 0x1C, 0x70, 0x77, 0x83, 0xB8, + 0x1D, 0xC0, 0x7E, 0x03, 0xE0, 0x1F, 0x00, 0x70, 0x00, 0xF0, 0xE1, 0xDC, + 0x78, 0x77, 0x1F, 0x3D, 0xE7, 0xCF, 0x79, 0xB3, 0x8E, 0x6C, 0xE3, 0xBB, + 0x38, 0xEE, 0xFC, 0x1F, 0x3F, 0x07, 0xC7, 0xC1, 0xF1, 0xF0, 0x7C, 0x78, + 0x0E, 0x1E, 0x00, 0x78, 0xF3, 0xC7, 0x8F, 0x78, 0x3B, 0x81, 0xFC, 0x07, + 0xC0, 0x1E, 0x01, 0xF0, 0x1F, 0xC0, 0xEF, 0x0F, 0x78, 0xF1, 0xE7, 0x87, + 0x00, 0xF0, 0x7B, 0x83, 0x9E, 0x1C, 0x71, 0xE3, 0x8E, 0x1E, 0x70, 0x73, + 0x83, 0xB8, 0x1F, 0xC0, 0x7E, 0x03, 0xE0, 0x0F, 0x00, 0x70, 0x03, 0x80, + 0x3C, 0x07, 0xC0, 0x3E, 0x01, 0xE0, 0x00, 0xFF, 0xFF, 0xFF, 0xFC, 0x0F, + 0x07, 0x83, 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x0F, 0xFF, 0xFF, 0xFF, 0xC0, + 0x1C, 0xF3, 0xCE, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0xBC, 0xF0, 0xE3, 0x8E, + 0x38, 0xE3, 0x8E, 0x3C, 0xF1, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, + 0xE3, 0x8F, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x0F, 0x3D, 0xC7, 0x1C, + 0x71, 0xC7, 0x1C, 0xF3, 0xCE, 0x00, 0x78, 0x0F, 0xE0, 0xCF, 0x30, 0x7F, + 0x01, 0xE0 }; + +const GFXglyph FreeSansBold12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 7, 0, 1 }, // 0x20 ' ' + { 0, 4, 17, 8, 3, -16 }, // 0x21 '!' + { 9, 10, 6, 11, 1, -17 }, // 0x22 '"' + { 17, 13, 16, 13, 0, -15 }, // 0x23 '#' + { 43, 13, 20, 13, 0, -17 }, // 0x24 '$' + { 76, 19, 17, 21, 1, -16 }, // 0x25 '%' + { 117, 16, 17, 17, 1, -16 }, // 0x26 '&' + { 151, 4, 6, 6, 1, -17 }, // 0x27 ''' + { 154, 6, 22, 8, 1, -17 }, // 0x28 '(' + { 171, 6, 22, 8, 1, -17 }, // 0x29 ')' + { 188, 7, 8, 9, 1, -17 }, // 0x2A '*' + { 195, 11, 11, 14, 2, -10 }, // 0x2B '+' + { 211, 4, 7, 6, 1, -2 }, // 0x2C ',' + { 215, 6, 3, 8, 1, -7 }, // 0x2D '-' + { 218, 4, 3, 6, 1, -2 }, // 0x2E '.' + { 220, 6, 17, 7, 0, -16 }, // 0x2F '/' + { 233, 12, 17, 13, 1, -16 }, // 0x30 '0' + { 259, 7, 17, 14, 3, -16 }, // 0x31 '1' + { 274, 12, 17, 13, 1, -16 }, // 0x32 '2' + { 300, 12, 17, 13, 1, -16 }, // 0x33 '3' + { 326, 11, 17, 13, 1, -16 }, // 0x34 '4' + { 350, 12, 17, 13, 1, -16 }, // 0x35 '5' + { 376, 12, 17, 13, 1, -16 }, // 0x36 '6' + { 402, 11, 17, 13, 1, -16 }, // 0x37 '7' + { 426, 12, 17, 13, 1, -16 }, // 0x38 '8' + { 452, 12, 17, 13, 1, -16 }, // 0x39 '9' + { 478, 4, 12, 6, 1, -11 }, // 0x3A ':' + { 484, 4, 16, 6, 1, -11 }, // 0x3B ';' + { 492, 12, 12, 14, 1, -11 }, // 0x3C '<' + { 510, 12, 9, 14, 1, -9 }, // 0x3D '=' + { 524, 12, 12, 14, 1, -11 }, // 0x3E '>' + { 542, 12, 18, 15, 2, -17 }, // 0x3F '?' + { 569, 21, 21, 23, 1, -17 }, // 0x40 '@' + { 625, 16, 18, 17, 0, -17 }, // 0x41 'A' + { 661, 14, 18, 17, 2, -17 }, // 0x42 'B' + { 693, 16, 18, 17, 1, -17 }, // 0x43 'C' + { 729, 15, 18, 17, 2, -17 }, // 0x44 'D' + { 763, 13, 18, 16, 2, -17 }, // 0x45 'E' + { 793, 12, 18, 15, 2, -17 }, // 0x46 'F' + { 820, 16, 18, 18, 1, -17 }, // 0x47 'G' + { 856, 14, 18, 18, 2, -17 }, // 0x48 'H' + { 888, 4, 18, 7, 2, -17 }, // 0x49 'I' + { 897, 11, 18, 14, 1, -17 }, // 0x4A 'J' + { 922, 16, 18, 17, 2, -17 }, // 0x4B 'K' + { 958, 11, 18, 15, 2, -17 }, // 0x4C 'L' + { 983, 17, 18, 21, 2, -17 }, // 0x4D 'M' + { 1022, 15, 18, 18, 2, -17 }, // 0x4E 'N' + { 1056, 17, 18, 19, 1, -17 }, // 0x4F 'O' + { 1095, 14, 18, 16, 2, -17 }, // 0x50 'P' + { 1127, 17, 19, 19, 1, -17 }, // 0x51 'Q' + { 1168, 16, 18, 17, 2, -17 }, // 0x52 'R' + { 1204, 15, 18, 16, 1, -17 }, // 0x53 'S' + { 1238, 12, 18, 15, 2, -17 }, // 0x54 'T' + { 1265, 14, 18, 18, 2, -17 }, // 0x55 'U' + { 1297, 15, 18, 16, 0, -17 }, // 0x56 'V' + { 1331, 23, 18, 23, 0, -17 }, // 0x57 'W' + { 1383, 15, 18, 16, 1, -17 }, // 0x58 'X' + { 1417, 16, 18, 15, 0, -17 }, // 0x59 'Y' + { 1453, 13, 18, 15, 1, -17 }, // 0x5A 'Z' + { 1483, 6, 23, 8, 2, -17 }, // 0x5B '[' + { 1501, 7, 17, 7, 0, -16 }, // 0x5C '\' + { 1516, 6, 23, 8, 0, -17 }, // 0x5D ']' + { 1534, 12, 11, 14, 1, -16 }, // 0x5E '^' + { 1551, 15, 2, 13, -1, 4 }, // 0x5F '_' + { 1555, 4, 3, 6, 0, -17 }, // 0x60 '`' + { 1557, 13, 13, 14, 1, -12 }, // 0x61 'a' + { 1579, 13, 18, 15, 2, -17 }, // 0x62 'b' + { 1609, 12, 13, 13, 1, -12 }, // 0x63 'c' + { 1629, 13, 18, 15, 1, -17 }, // 0x64 'd' + { 1659, 13, 13, 14, 1, -12 }, // 0x65 'e' + { 1681, 7, 18, 8, 1, -17 }, // 0x66 'f' + { 1697, 13, 18, 15, 1, -12 }, // 0x67 'g' + { 1727, 12, 18, 14, 2, -17 }, // 0x68 'h' + { 1754, 4, 18, 7, 2, -17 }, // 0x69 'i' + { 1763, 6, 23, 7, 0, -17 }, // 0x6A 'j' + { 1781, 12, 18, 14, 2, -17 }, // 0x6B 'k' + { 1808, 4, 18, 6, 2, -17 }, // 0x6C 'l' + { 1817, 19, 13, 21, 2, -12 }, // 0x6D 'm' + { 1848, 12, 13, 15, 2, -12 }, // 0x6E 'n' + { 1868, 13, 13, 15, 1, -12 }, // 0x6F 'o' + { 1890, 13, 18, 15, 2, -12 }, // 0x70 'p' + { 1920, 13, 18, 15, 1, -12 }, // 0x71 'q' + { 1950, 8, 13, 9, 2, -12 }, // 0x72 'r' + { 1963, 12, 13, 13, 1, -12 }, // 0x73 's' + { 1983, 6, 15, 8, 1, -14 }, // 0x74 't' + { 1995, 12, 13, 15, 2, -12 }, // 0x75 'u' + { 2015, 13, 13, 13, 0, -12 }, // 0x76 'v' + { 2037, 18, 13, 19, 0, -12 }, // 0x77 'w' + { 2067, 13, 13, 13, 0, -12 }, // 0x78 'x' + { 2089, 13, 18, 13, 0, -12 }, // 0x79 'y' + { 2119, 10, 13, 12, 1, -12 }, // 0x7A 'z' + { 2136, 6, 23, 9, 1, -17 }, // 0x7B '{' + { 2154, 2, 22, 7, 2, -17 }, // 0x7C '|' + { 2160, 6, 23, 9, 3, -17 }, // 0x7D '}' + { 2178, 12, 5, 12, 0, -7 } }; // 0x7E '~' + +const GFXfont FreeSansBold12pt7b PROGMEM = { + (uint8_t *)FreeSansBold12pt7bBitmaps, + (GFXglyph *)FreeSansBold12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 2858 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBold18pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBold18pt7b.h new file mode 100644 index 0000000..d5927cd --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBold18pt7b.h @@ -0,0 +1,481 @@ +const uint8_t FreeSansBold18pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xE7, 0x39, 0xCE, 0x73, 0x80, + 0x0F, 0xFF, 0xFF, 0xF8, 0xF8, 0xFF, 0xC7, 0xFE, 0x3F, 0xF1, 0xFF, 0x8F, + 0xFC, 0x7D, 0xC1, 0xCE, 0x0E, 0x70, 0x70, 0x03, 0xC3, 0x80, 0x3C, 0x78, + 0x03, 0xC7, 0x80, 0x38, 0x78, 0x07, 0x87, 0x07, 0xFF, 0xFF, 0x7F, 0xFF, + 0xF7, 0xFF, 0xFF, 0x7F, 0xFF, 0xF0, 0xF0, 0xE0, 0x0F, 0x0E, 0x00, 0xF1, + 0xE0, 0x0F, 0x1E, 0x00, 0xE1, 0xE0, 0xFF, 0xFF, 0xCF, 0xFF, 0xFC, 0xFF, + 0xFF, 0xCF, 0xFF, 0xFC, 0x1C, 0x3C, 0x03, 0xC3, 0x80, 0x3C, 0x78, 0x03, + 0xC7, 0x80, 0x38, 0x78, 0x03, 0x87, 0x80, 0x00, 0x60, 0x00, 0x7F, 0x80, + 0x3F, 0xFC, 0x0F, 0xFF, 0xC3, 0xFF, 0xFC, 0xFC, 0xDF, 0x9F, 0x19, 0xFB, + 0xC3, 0x1F, 0x78, 0x63, 0xEF, 0x8C, 0x01, 0xFD, 0x80, 0x1F, 0xF0, 0x01, + 0xFF, 0xC0, 0x1F, 0xFE, 0x00, 0x7F, 0xE0, 0x03, 0xFE, 0x00, 0x67, 0xE0, + 0x0C, 0x7F, 0xE1, 0x8F, 0xFC, 0x31, 0xFF, 0xC6, 0x3E, 0xFC, 0xDF, 0x9F, + 0xFF, 0xF1, 0xFF, 0xFC, 0x0F, 0xFF, 0x00, 0x7F, 0x80, 0x01, 0x80, 0x00, + 0x30, 0x00, 0x06, 0x00, 0x0F, 0x00, 0x1C, 0x01, 0xFE, 0x00, 0xE0, 0x1F, + 0xF8, 0x0E, 0x00, 0xFF, 0xC0, 0x70, 0x0F, 0x0F, 0x07, 0x00, 0x70, 0x38, + 0x38, 0x03, 0x81, 0xC3, 0x80, 0x1C, 0x0E, 0x3C, 0x00, 0xF0, 0xF1, 0xC0, + 0x03, 0xFF, 0x1C, 0x00, 0x1F, 0xF8, 0xE0, 0x00, 0x7F, 0x8E, 0x00, 0x00, + 0xF0, 0x70, 0xF8, 0x00, 0x07, 0x1F, 0xF0, 0x00, 0x39, 0xFF, 0xC0, 0x03, + 0x8F, 0xFE, 0x00, 0x1C, 0xF0, 0x78, 0x01, 0xC7, 0x01, 0xC0, 0x0C, 0x38, + 0x0E, 0x00, 0xE1, 0xC0, 0x70, 0x06, 0x0F, 0x07, 0x80, 0x70, 0x3F, 0xF8, + 0x07, 0x01, 0xFF, 0xC0, 0x38, 0x07, 0xFC, 0x03, 0x80, 0x0F, 0x80, 0x01, + 0xF0, 0x00, 0x1F, 0xE0, 0x00, 0xFF, 0xC0, 0x03, 0xFF, 0x80, 0x1F, 0x1E, + 0x00, 0x7C, 0x78, 0x01, 0xF1, 0xE0, 0x07, 0xE7, 0x80, 0x0F, 0xBC, 0x00, + 0x1F, 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0xF0, 0xF0, 0xFF, + 0xE3, 0xC7, 0xE7, 0xCF, 0x3F, 0x0F, 0xF8, 0xF8, 0x3F, 0xE3, 0xE0, 0x7F, + 0x8F, 0x80, 0xFC, 0x3F, 0x03, 0xF0, 0x7E, 0x3F, 0xE1, 0xFF, 0xFF, 0x83, + 0xFF, 0xFF, 0x07, 0xFE, 0x7E, 0x07, 0xF0, 0xFC, 0xFF, 0xFF, 0xFF, 0xFD, + 0xCE, 0x70, 0x07, 0x87, 0x83, 0xC3, 0xC1, 0xE1, 0xE0, 0xF0, 0x78, 0x78, + 0x3C, 0x1E, 0x1E, 0x0F, 0x07, 0x83, 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, + 0x0F, 0x03, 0x81, 0xE0, 0xF0, 0x78, 0x1E, 0x0F, 0x03, 0x81, 0xE0, 0x70, + 0x3C, 0x0E, 0x07, 0x80, 0xF0, 0x38, 0x1E, 0x07, 0x83, 0xC0, 0xF0, 0x78, + 0x3C, 0x0F, 0x07, 0x83, 0xC0, 0xF0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, + 0xC1, 0xE0, 0xF0, 0x78, 0x78, 0x3C, 0x1E, 0x0F, 0x0F, 0x07, 0x87, 0x83, + 0xC1, 0xC1, 0xE0, 0xE0, 0xF0, 0x00, 0x06, 0x00, 0x60, 0x06, 0x07, 0x6E, + 0x7F, 0xE3, 0xFC, 0x0F, 0x01, 0xF8, 0x1F, 0x83, 0x9C, 0x10, 0x80, 0x03, + 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xC0, 0x03, 0xC0, 0x03, + 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0xFF, 0xFF, 0xFF, 0x8C, 0x63, + 0x37, 0xB0, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0x80, 0x01, + 0x81, 0xC0, 0xC0, 0x60, 0x70, 0x38, 0x18, 0x0C, 0x0E, 0x06, 0x03, 0x01, + 0x81, 0xC0, 0xC0, 0x60, 0x30, 0x38, 0x18, 0x0C, 0x0E, 0x07, 0x03, 0x01, + 0x81, 0xC0, 0xC0, 0x00, 0x07, 0xF0, 0x0F, 0xFE, 0x0F, 0xFF, 0x87, 0xFF, + 0xC7, 0xE3, 0xF3, 0xE0, 0xF9, 0xF0, 0x7D, 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, + 0x07, 0xFE, 0x03, 0xFF, 0x01, 0xFF, 0x80, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, + 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, 0x07, 0xDF, 0x07, 0xCF, 0x83, 0xE7, 0xE3, + 0xF1, 0xFF, 0xF0, 0xFF, 0xF8, 0x3F, 0xF8, 0x07, 0xF0, 0x00, 0x01, 0xC0, + 0xF0, 0x3C, 0x1F, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0x07, 0xC1, 0xF0, 0x7C, + 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, + 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC0, 0x07, 0xF0, 0x0F, 0xFE, 0x0F, 0xFF, + 0x8F, 0xFF, 0xE7, 0xE3, 0xF7, 0xE0, 0xFF, 0xE0, 0x3F, 0xF0, 0x1F, 0xF8, + 0x0F, 0x80, 0x07, 0xC0, 0x07, 0xE0, 0x03, 0xE0, 0x03, 0xF0, 0x03, 0xF0, + 0x07, 0xF0, 0x07, 0xF0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xC0, 0x07, 0xC0, + 0x03, 0xE0, 0x03, 0xFF, 0xFD, 0xFF, 0xFE, 0xFF, 0xFF, 0x7F, 0xFF, 0x80, + 0x07, 0xE0, 0x0F, 0xFC, 0x0F, 0xFF, 0x0F, 0xFF, 0xCF, 0xC3, 0xF7, 0xC0, + 0xFB, 0xE0, 0x7D, 0xF0, 0x3E, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x0F, 0x80, + 0x3F, 0x80, 0x1F, 0xC0, 0x0F, 0xF0, 0x00, 0xFC, 0x00, 0x3F, 0x00, 0x0F, + 0xFC, 0x07, 0xFE, 0x03, 0xFF, 0x83, 0xF7, 0xC3, 0xF3, 0xFF, 0xF8, 0xFF, + 0xF8, 0x3F, 0xF8, 0x07, 0xF0, 0x00, 0x00, 0xFC, 0x00, 0xFC, 0x01, 0xFC, + 0x01, 0xFC, 0x03, 0xFC, 0x07, 0x7C, 0x07, 0x7C, 0x0E, 0x7C, 0x0E, 0x7C, + 0x1C, 0x7C, 0x18, 0x7C, 0x38, 0x7C, 0x70, 0x7C, 0x60, 0x7C, 0xE0, 0x7C, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x7C, 0x00, 0x7C, + 0x00, 0x7C, 0x00, 0x7C, 0x00, 0x7C, 0x00, 0x7C, 0x1F, 0xFF, 0x0F, 0xFF, + 0x8F, 0xFF, 0xC7, 0xFF, 0xE3, 0xC0, 0x01, 0xE0, 0x00, 0xE0, 0x00, 0x70, + 0x00, 0x79, 0xF0, 0x3F, 0xFE, 0x1F, 0xFF, 0x8F, 0xFF, 0xE7, 0xC3, 0xF0, + 0x00, 0xFC, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xFE, 0x03, + 0xFF, 0x03, 0xFF, 0xC3, 0xF3, 0xFF, 0xF1, 0xFF, 0xF8, 0x3F, 0xF0, 0x07, + 0xE0, 0x00, 0x03, 0xF8, 0x03, 0xFF, 0x81, 0xFF, 0xF0, 0xFF, 0xFE, 0x3E, + 0x1F, 0x9F, 0x03, 0xE7, 0xC0, 0x03, 0xE0, 0x00, 0xF8, 0xF8, 0x3E, 0xFF, + 0x8F, 0xFF, 0xF3, 0xFF, 0xFE, 0xFE, 0x1F, 0xBF, 0x03, 0xFF, 0x80, 0x7F, + 0xE0, 0x1F, 0xF8, 0x07, 0xFE, 0x01, 0xF7, 0x80, 0x7D, 0xF0, 0x3E, 0x7E, + 0x1F, 0x8F, 0xFF, 0xC1, 0xFF, 0xF0, 0x3F, 0xF0, 0x03, 0xF0, 0x00, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0xF0, 0x00, 0xF8, + 0x00, 0xF8, 0x00, 0x78, 0x00, 0x7C, 0x00, 0x3C, 0x00, 0x3E, 0x00, 0x1E, + 0x00, 0x1F, 0x00, 0x0F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xC0, 0x03, + 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x78, 0x00, 0x7C, 0x00, 0x3E, 0x00, + 0x1F, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xE0, 0x07, 0xFC, 0x0F, 0xFF, 0x07, + 0xFF, 0xC7, 0xC3, 0xF3, 0xC0, 0xF9, 0xE0, 0x3C, 0xF0, 0x1E, 0x78, 0x1F, + 0x1E, 0x1F, 0x07, 0xFF, 0x01, 0xFF, 0x03, 0xFF, 0xE3, 0xF1, 0xF9, 0xF0, + 0x7D, 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, 0x07, 0xFE, 0x03, 0xFF, 0x83, 0xF7, + 0xC3, 0xF3, 0xFF, 0xF8, 0xFF, 0xF8, 0x3F, 0xF8, 0x07, 0xF0, 0x00, 0x07, + 0xE0, 0x0F, 0xFC, 0x0F, 0xFF, 0x0F, 0xFF, 0xC7, 0xE3, 0xF7, 0xE0, 0xFB, + 0xE0, 0x3D, 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, 0x07, 0xFE, 0x03, 0xFF, 0x83, + 0xF7, 0xE3, 0xFB, 0xFF, 0xFC, 0xFF, 0xFE, 0x3F, 0xDF, 0x07, 0xCF, 0x80, + 0x07, 0x80, 0x03, 0xDF, 0x03, 0xE7, 0xC3, 0xE3, 0xFF, 0xF0, 0xFF, 0xF0, + 0x3F, 0xF0, 0x07, 0xE0, 0x00, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00, + 0x00, 0x7F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00, + 0x00, 0x7F, 0xFF, 0xFF, 0xC6, 0x33, 0x9B, 0xD8, 0x00, 0x00, 0xC0, 0x00, + 0xF0, 0x01, 0xFC, 0x03, 0xFF, 0x03, 0xFF, 0x07, 0xFE, 0x0F, 0xFC, 0x03, + 0xF8, 0x00, 0xF0, 0x00, 0x3F, 0x80, 0x0F, 0xFC, 0x00, 0x7F, 0xE0, 0x07, + 0xFF, 0x00, 0x3F, 0xF0, 0x01, 0xFC, 0x00, 0x1F, 0x00, 0x00, 0xC0, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF0, 0xC0, 0x00, 0x3C, 0x00, 0x0F, 0xE0, 0x03, 0xFF, 0x00, 0x3F, 0xF0, + 0x01, 0xFF, 0x80, 0x0F, 0xFC, 0x00, 0x7F, 0x00, 0x03, 0xC0, 0x07, 0xF0, + 0x0F, 0xFC, 0x1F, 0xF8, 0x3F, 0xF8, 0x3F, 0xF0, 0x0F, 0xE0, 0x03, 0xC0, + 0x00, 0xC0, 0x00, 0x00, 0x07, 0xF0, 0x07, 0xFF, 0x03, 0xFF, 0xF1, 0xFF, + 0xFC, 0x7E, 0x3F, 0xBF, 0x03, 0xFF, 0x80, 0x7F, 0xE0, 0x1F, 0xF8, 0x07, + 0xC0, 0x03, 0xF0, 0x01, 0xFC, 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x3F, 0x80, + 0x1F, 0xC0, 0x07, 0xC0, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, + 0x00, 0xF8, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x3F, 0xFF, 0x00, 0x00, + 0xFF, 0xFF, 0xC0, 0x01, 0xF8, 0x07, 0xF0, 0x03, 0xE0, 0x01, 0xF8, 0x07, + 0x80, 0x00, 0x7C, 0x0F, 0x00, 0x00, 0x3C, 0x1E, 0x03, 0xE3, 0x9E, 0x3C, + 0x0F, 0xF7, 0x8E, 0x38, 0x1F, 0xFF, 0x0E, 0x78, 0x3E, 0x1F, 0x07, 0x70, + 0x38, 0x0F, 0x07, 0x70, 0x78, 0x0F, 0x07, 0xE0, 0x70, 0x0E, 0x07, 0xE0, + 0x70, 0x0E, 0x07, 0xE0, 0xE0, 0x0E, 0x07, 0xE0, 0xE0, 0x1E, 0x0F, 0xE0, + 0xE0, 0x1C, 0x0E, 0xE0, 0xE0, 0x3C, 0x1E, 0xE0, 0xF0, 0x3C, 0x3C, 0xF0, + 0xF0, 0xFC, 0x7C, 0x70, 0x7F, 0xFF, 0xF8, 0x78, 0x3F, 0xCF, 0xF0, 0x3C, + 0x1F, 0x07, 0xC0, 0x3E, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x0F, + 0xC0, 0x01, 0x00, 0x07, 0xF0, 0x0F, 0x00, 0x03, 0xFF, 0xFF, 0x00, 0x00, + 0xFF, 0xFF, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0x00, 0x00, 0xFF, 0x80, 0x01, 0xFF, + 0x80, 0x01, 0xFF, 0x80, 0x01, 0xF7, 0xC0, 0x03, 0xE7, 0xC0, 0x03, 0xE7, + 0xC0, 0x03, 0xE3, 0xE0, 0x07, 0xC3, 0xE0, 0x07, 0xC3, 0xE0, 0x07, 0xC1, + 0xF0, 0x0F, 0x81, 0xF0, 0x0F, 0x81, 0xF0, 0x0F, 0xFF, 0xF8, 0x1F, 0xFF, + 0xF8, 0x1F, 0xFF, 0xFC, 0x1F, 0xFF, 0xFC, 0x3E, 0x00, 0x7C, 0x3E, 0x00, + 0x7E, 0x3E, 0x00, 0x3E, 0x7C, 0x00, 0x3E, 0x7C, 0x00, 0x3F, 0x7C, 0x00, + 0x1F, 0xFF, 0xFC, 0x0F, 0xFF, 0xF0, 0xFF, 0xFF, 0x8F, 0xFF, 0xFC, 0xF8, + 0x07, 0xEF, 0x80, 0x3E, 0xF8, 0x03, 0xEF, 0x80, 0x3E, 0xF8, 0x03, 0xEF, + 0x80, 0x3E, 0xF8, 0x07, 0xCF, 0xFF, 0xF8, 0xFF, 0xFF, 0x0F, 0xFF, 0xF8, + 0xFF, 0xFF, 0xCF, 0x80, 0x7E, 0xF8, 0x01, 0xEF, 0x80, 0x1F, 0xF8, 0x01, + 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x3E, 0xFF, 0xFF, 0xEF, 0xFF, + 0xFC, 0xFF, 0xFF, 0x8F, 0xFF, 0xE0, 0x00, 0xFF, 0x00, 0x07, 0xFF, 0x80, + 0x3F, 0xFF, 0xC0, 0xFF, 0xFF, 0xC3, 0xF8, 0x1F, 0x87, 0xE0, 0x1F, 0x9F, + 0x80, 0x1F, 0x3E, 0x00, 0x1F, 0x7C, 0x00, 0x3F, 0xF0, 0x00, 0x03, 0xE0, + 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x7D, 0xF0, 0x00, + 0xFB, 0xF0, 0x03, 0xF3, 0xF0, 0x0F, 0xC7, 0xF0, 0x3F, 0x87, 0xFF, 0xFE, + 0x07, 0xFF, 0xF8, 0x03, 0xFF, 0xC0, 0x01, 0xFE, 0x00, 0xFF, 0xFC, 0x07, + 0xFF, 0xF8, 0x3F, 0xFF, 0xE1, 0xFF, 0xFF, 0x8F, 0x80, 0xFE, 0x7C, 0x01, + 0xF3, 0xE0, 0x07, 0xDF, 0x00, 0x3E, 0xF8, 0x01, 0xF7, 0xC0, 0x07, 0xFE, + 0x00, 0x3F, 0xF0, 0x01, 0xFF, 0x80, 0x0F, 0xFC, 0x00, 0x7F, 0xE0, 0x03, + 0xFF, 0x00, 0x1F, 0xF8, 0x00, 0xFF, 0xC0, 0x0F, 0xFE, 0x00, 0x7D, 0xF0, + 0x03, 0xEF, 0x80, 0x3E, 0x7C, 0x07, 0xF3, 0xFF, 0xFF, 0x1F, 0xFF, 0xF0, + 0xFF, 0xFF, 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFF, 0xDF, 0xFF, 0xFB, 0xFF, + 0xFF, 0x7F, 0xFF, 0xEF, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7F, 0xFF, 0xCF, 0xFF, + 0xF9, 0xFF, 0xFF, 0x3F, 0xFF, 0xE7, 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, + 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, + 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0xFF, 0xEF, 0xFF, 0xF7, + 0xFF, 0xFB, 0xFF, 0xFD, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, + 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, + 0x00, 0x7C, 0x00, 0x00, 0x00, 0x7F, 0x80, 0x03, 0xFF, 0xE0, 0x07, 0xFF, + 0xF8, 0x0F, 0xFF, 0xFC, 0x1F, 0xC0, 0xFE, 0x3F, 0x00, 0x7E, 0x7E, 0x00, + 0x3F, 0x7C, 0x00, 0x1F, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x03, 0xFF, 0xF8, 0x03, 0xFF, 0xF8, 0x03, + 0xFF, 0xF8, 0x03, 0xFF, 0xFC, 0x00, 0x0F, 0x7C, 0x00, 0x1F, 0x7C, 0x00, + 0x1F, 0x7E, 0x00, 0x3F, 0x3F, 0x00, 0x7F, 0x1F, 0xC1, 0xFF, 0x0F, 0xFF, + 0xFF, 0x07, 0xFF, 0xE7, 0x03, 0xFF, 0xC7, 0x00, 0xFF, 0x07, 0xF8, 0x01, + 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, + 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x01, 0xFF, + 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, + 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, + 0xFF, 0x80, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x00, 0x1F, 0x00, 0x1F, + 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, + 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, + 0x00, 0x1F, 0x00, 0x1F, 0xF8, 0x1F, 0xF8, 0x1F, 0xF8, 0x1F, 0xF8, 0x1F, + 0xF8, 0x1F, 0xFC, 0x3F, 0x7F, 0xFE, 0x3F, 0xFC, 0x1F, 0xF8, 0x07, 0xE0, + 0xF8, 0x01, 0xFB, 0xE0, 0x0F, 0xCF, 0x80, 0x7E, 0x3E, 0x03, 0xF0, 0xF8, + 0x1F, 0x83, 0xE0, 0xFC, 0x0F, 0x87, 0xE0, 0x3E, 0x3F, 0x00, 0xF8, 0xF8, + 0x03, 0xE7, 0xE0, 0x0F, 0xBF, 0x00, 0x3F, 0xF8, 0x00, 0xFF, 0xF0, 0x03, + 0xFF, 0xE0, 0x0F, 0xFF, 0x80, 0x3F, 0xBF, 0x00, 0xFC, 0x7E, 0x03, 0xE0, + 0xFC, 0x0F, 0x81, 0xF8, 0x3E, 0x07, 0xE0, 0xF8, 0x0F, 0xC3, 0xE0, 0x1F, + 0x8F, 0x80, 0x7F, 0x3E, 0x00, 0xFC, 0xF8, 0x01, 0xFB, 0xE0, 0x03, 0xF0, + 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, + 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, + 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, + 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0x00, 0xFF, 0xFF, + 0x00, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, + 0x81, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0x81, 0xFF, 0xFB, 0xC3, 0xDF, 0xFB, + 0xC3, 0xDF, 0xFB, 0xC3, 0xDF, 0xFB, 0xC3, 0xDF, 0xF9, 0xC7, 0xDF, 0xF9, + 0xE7, 0x9F, 0xF9, 0xE7, 0x9F, 0xF9, 0xE7, 0x9F, 0xF9, 0xE7, 0x9F, 0xF8, + 0xFF, 0x1F, 0xF8, 0xFF, 0x1F, 0xF8, 0xFF, 0x1F, 0xF8, 0xFF, 0x1F, 0xF8, + 0x7F, 0x1F, 0xF8, 0x7E, 0x1F, 0xF8, 0x7E, 0x1F, 0xF8, 0x7E, 0x1F, 0xF8, + 0x3E, 0x1F, 0xF8, 0x01, 0xFF, 0xC0, 0x1F, 0xFE, 0x01, 0xFF, 0xE0, 0x1F, + 0xFF, 0x01, 0xFF, 0xF0, 0x1F, 0xFF, 0x81, 0xFF, 0xF8, 0x1F, 0xFF, 0xC1, + 0xFF, 0xBC, 0x1F, 0xFB, 0xE1, 0xFF, 0x9F, 0x1F, 0xF9, 0xF1, 0xFF, 0x8F, + 0x9F, 0xF8, 0x79, 0xFF, 0x87, 0xDF, 0xF8, 0x3D, 0xFF, 0x83, 0xFF, 0xF8, + 0x1F, 0xFF, 0x81, 0xFF, 0xF8, 0x0F, 0xFF, 0x80, 0xFF, 0xF8, 0x07, 0xFF, + 0x80, 0x3F, 0xF8, 0x03, 0xFF, 0x80, 0x1F, 0x00, 0x7F, 0x00, 0x01, 0xFF, + 0xF0, 0x01, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x01, 0xFC, 0x1F, 0xC1, 0xF8, + 0x03, 0xF1, 0xF8, 0x00, 0xFC, 0xF8, 0x00, 0x3E, 0x7C, 0x00, 0x1F, 0x7C, + 0x00, 0x07, 0xFE, 0x00, 0x03, 0xFF, 0x00, 0x01, 0xFF, 0x80, 0x00, 0xFF, + 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0xF0, 0x00, 0x1F, 0xF8, 0x00, 0x0F, + 0xBE, 0x00, 0x0F, 0x9F, 0x00, 0x07, 0xCF, 0xC0, 0x07, 0xE3, 0xF0, 0x07, + 0xE0, 0xFE, 0x0F, 0xE0, 0x7F, 0xFF, 0xE0, 0x0F, 0xFF, 0xE0, 0x03, 0xFF, + 0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFF, 0xFC, 0x1F, 0xFF, 0xE3, 0xFF, 0xFE, + 0x7F, 0xFF, 0xEF, 0x80, 0xFF, 0xF0, 0x0F, 0xFE, 0x00, 0xFF, 0xC0, 0x1F, + 0xF8, 0x03, 0xFF, 0x00, 0x7F, 0xE0, 0x1F, 0xFC, 0x07, 0xEF, 0xFF, 0xFD, + 0xFF, 0xFF, 0x3F, 0xFF, 0xC7, 0xFF, 0xE0, 0xF8, 0x00, 0x1F, 0x00, 0x03, + 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, + 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x01, 0xFF, + 0xF0, 0x01, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x01, 0xFC, 0x1F, 0xC1, 0xF8, + 0x03, 0xF1, 0xF8, 0x00, 0xFC, 0xF8, 0x00, 0x3E, 0x7C, 0x00, 0x1F, 0x7C, + 0x00, 0x07, 0xFE, 0x00, 0x03, 0xFF, 0x00, 0x01, 0xFF, 0x80, 0x00, 0xFF, + 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0xF0, 0x00, 0x1F, 0xF8, 0x01, 0x0F, + 0xBE, 0x01, 0xCF, 0x9F, 0x01, 0xFF, 0xCF, 0xC0, 0x7F, 0xE3, 0xF0, 0x1F, + 0xE0, 0xFE, 0x0F, 0xF0, 0x7F, 0xFF, 0xF8, 0x0F, 0xFF, 0xFE, 0x03, 0xFF, + 0xEF, 0x80, 0x3F, 0xC3, 0x80, 0x00, 0x00, 0x80, 0xFF, 0xFF, 0x07, 0xFF, + 0xFE, 0x3F, 0xFF, 0xF9, 0xFF, 0xFF, 0xCF, 0x80, 0x3F, 0x7C, 0x00, 0xFB, + 0xE0, 0x07, 0xDF, 0x00, 0x3E, 0xF8, 0x01, 0xF7, 0xC0, 0x0F, 0x3E, 0x00, + 0xF9, 0xFF, 0xFF, 0x8F, 0xFF, 0xF8, 0x7F, 0xFF, 0xC3, 0xFF, 0xFF, 0x1F, + 0x00, 0xFC, 0xF8, 0x03, 0xE7, 0xC0, 0x1F, 0x3E, 0x00, 0xF9, 0xF0, 0x07, + 0xCF, 0x80, 0x3E, 0x7C, 0x01, 0xF3, 0xE0, 0x0F, 0x9F, 0x00, 0x7C, 0xF8, + 0x03, 0xF7, 0xC0, 0x0F, 0xC0, 0x07, 0xF8, 0x01, 0xFF, 0xF0, 0x3F, 0xFF, + 0x87, 0xFF, 0xFC, 0x7E, 0x0F, 0xCF, 0xC0, 0x7E, 0xF8, 0x03, 0xEF, 0x80, + 0x3E, 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0xFF, 0x00, 0x07, 0xFF, 0xC0, 0x3F, + 0xFF, 0x81, 0xFF, 0xFC, 0x03, 0xFF, 0xE0, 0x01, 0xFF, 0x00, 0x03, 0xF0, + 0x00, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xFC, 0x03, 0xFF, 0xE0, 0x7E, + 0x7F, 0xFF, 0xE3, 0xFF, 0xFC, 0x1F, 0xFF, 0x00, 0x3F, 0xC0, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x1F, 0x00, 0x03, 0xE0, + 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, + 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, + 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, + 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, + 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, + 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, + 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, + 0x80, 0x1F, 0x7C, 0x03, 0xE7, 0xE0, 0x7E, 0x3F, 0xFF, 0xC3, 0xFF, 0xFC, + 0x0F, 0xFF, 0x00, 0x3F, 0xC0, 0xF8, 0x00, 0xFB, 0xE0, 0x03, 0xE7, 0xC0, + 0x1F, 0x9F, 0x00, 0x7C, 0x7C, 0x01, 0xF0, 0xF8, 0x07, 0xC3, 0xE0, 0x3E, + 0x0F, 0x80, 0xF8, 0x1E, 0x03, 0xE0, 0x7C, 0x1F, 0x01, 0xF0, 0x7C, 0x03, + 0xC1, 0xF0, 0x0F, 0x87, 0x80, 0x3E, 0x3E, 0x00, 0xF8, 0xF8, 0x01, 0xE3, + 0xC0, 0x07, 0xCF, 0x00, 0x1F, 0x7C, 0x00, 0x3D, 0xE0, 0x00, 0xFF, 0x80, + 0x03, 0xFE, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0x00, 0x00, + 0xF8, 0x00, 0x03, 0xE0, 0x00, 0xF8, 0x07, 0xC0, 0x3F, 0xF8, 0x07, 0xE0, + 0x3E, 0xFC, 0x07, 0xE0, 0x3E, 0x7C, 0x0F, 0xE0, 0x3E, 0x7C, 0x0F, 0xE0, + 0x7E, 0x7C, 0x0F, 0xE0, 0x7C, 0x7C, 0x0F, 0xF0, 0x7C, 0x3E, 0x0F, 0xF0, + 0x7C, 0x3E, 0x1E, 0xF0, 0x78, 0x3E, 0x1E, 0x70, 0xF8, 0x1E, 0x1E, 0x70, + 0xF8, 0x1E, 0x1E, 0x78, 0xF8, 0x1F, 0x1E, 0x78, 0xF0, 0x1F, 0x3C, 0x78, + 0xF0, 0x0F, 0x3C, 0x39, 0xF0, 0x0F, 0x3C, 0x3D, 0xF0, 0x0F, 0x3C, 0x3D, + 0xE0, 0x0F, 0xBC, 0x3D, 0xE0, 0x07, 0xF8, 0x3D, 0xE0, 0x07, 0xF8, 0x1F, + 0xE0, 0x07, 0xF8, 0x1F, 0xC0, 0x03, 0xF8, 0x1F, 0xC0, 0x03, 0xF8, 0x1F, + 0xC0, 0x03, 0xF0, 0x0F, 0x80, 0x03, 0xF0, 0x0F, 0x80, 0x01, 0xF0, 0x0F, + 0x80, 0xFE, 0x01, 0xF9, 0xF8, 0x07, 0xE3, 0xF0, 0x3F, 0x0F, 0xC0, 0xF8, + 0x1F, 0x87, 0xE0, 0x7E, 0x3F, 0x00, 0xFC, 0xFC, 0x01, 0xF7, 0xE0, 0x07, + 0xFF, 0x00, 0x0F, 0xFC, 0x00, 0x3F, 0xE0, 0x00, 0x7F, 0x00, 0x00, 0xFC, + 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xE0, 0x00, 0xFF, 0x80, 0x03, 0xFF, 0x00, + 0x1F, 0x7E, 0x00, 0xFC, 0xF8, 0x03, 0xE3, 0xF0, 0x1F, 0x87, 0xC0, 0x7C, + 0x1F, 0x83, 0xF0, 0x3F, 0x1F, 0x80, 0xFC, 0x7E, 0x01, 0xFB, 0xF0, 0x07, + 0xF0, 0xFC, 0x01, 0xFF, 0xE0, 0x0F, 0x9F, 0x00, 0xFC, 0xFC, 0x07, 0xC3, + 0xE0, 0x7E, 0x1F, 0x83, 0xE0, 0x7C, 0x1F, 0x03, 0xF1, 0xF0, 0x0F, 0x8F, + 0x80, 0x7E, 0xF8, 0x01, 0xF7, 0xC0, 0x0F, 0xFC, 0x00, 0x3F, 0xE0, 0x00, + 0xFE, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, + 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x03, + 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x7E, 0x00, 0x1F, + 0x80, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x3F, 0x00, 0x0F, 0xC0, 0x03, 0xF8, + 0x00, 0x7E, 0x00, 0x1F, 0x80, 0x07, 0xE0, 0x01, 0xFC, 0x00, 0x3F, 0x00, + 0x0F, 0xC0, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x1F, 0x80, 0x07, 0xE0, 0x01, + 0xFC, 0x00, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, + 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, + 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, + 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x38, 0x06, + 0x01, 0x80, 0x70, 0x0C, 0x03, 0x00, 0xE0, 0x18, 0x06, 0x01, 0xC0, 0x30, + 0x0C, 0x03, 0x00, 0xE0, 0x18, 0x06, 0x01, 0xC0, 0x30, 0x0C, 0x03, 0x80, + 0x60, 0x18, 0x07, 0x01, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0x1F, 0x1F, 0x1F, + 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, + 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0xFF, 0xFF, + 0xFF, 0xFF, 0x03, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x0F, 0xF0, 0x0F, 0xF0, + 0x0F, 0x78, 0x1E, 0x78, 0x1E, 0x78, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x1E, + 0x78, 0x1E, 0x78, 0x1E, 0x70, 0x0F, 0xF0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFE, 0xF8, 0xF0, 0xF0, 0xE0, 0xE0, 0x07, 0xF8, 0x07, + 0xFF, 0x83, 0xFF, 0xF1, 0xFF, 0xFE, 0x7C, 0x1F, 0xBE, 0x03, 0xE0, 0x00, + 0xF8, 0x01, 0xFE, 0x0F, 0xFF, 0x8F, 0xFF, 0xE7, 0xF8, 0xFB, 0xF0, 0x3E, + 0xF8, 0x0F, 0xBE, 0x07, 0xEF, 0xC3, 0xFB, 0xFF, 0xFE, 0x7F, 0xFF, 0x8F, + 0xFB, 0xF1, 0xF8, 0xFC, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, + 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE7, 0xE0, 0xFB, 0xFC, + 0x3F, 0xFF, 0xCF, 0xFF, 0xF3, 0xF8, 0x7E, 0xFC, 0x0F, 0xBF, 0x03, 0xFF, + 0x80, 0x7F, 0xE0, 0x1F, 0xF8, 0x07, 0xFE, 0x01, 0xFF, 0x80, 0x7F, 0xF0, + 0x3F, 0xFC, 0x0F, 0xBF, 0x87, 0xEF, 0xFF, 0xF3, 0xFF, 0xFC, 0xFB, 0xFC, + 0x3E, 0x7E, 0x00, 0x03, 0xF0, 0x07, 0xFE, 0x0F, 0xFF, 0x87, 0xFF, 0xE7, + 0xE1, 0xFB, 0xE0, 0x7F, 0xE0, 0x3F, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, + 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0xFB, 0xE0, 0x7D, 0xF8, 0x7E, 0x7F, + 0xFE, 0x3F, 0xFE, 0x0F, 0xFE, 0x00, 0xFC, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, + 0xF8, 0x1F, 0x1F, 0x0F, 0xFB, 0xE3, 0xFF, 0xFC, 0xFF, 0xFF, 0xBF, 0x8F, + 0xF7, 0xC0, 0x7F, 0xF8, 0x0F, 0xFE, 0x00, 0xFF, 0xC0, 0x1F, 0xF8, 0x03, + 0xFF, 0x00, 0x7F, 0xE0, 0x0F, 0xFE, 0x03, 0xF7, 0xC0, 0x7E, 0xFC, 0x3F, + 0xCF, 0xFF, 0xF8, 0xFF, 0xFF, 0x0F, 0xFB, 0xE0, 0xFC, 0x7C, 0x07, 0xE0, + 0x07, 0xFE, 0x03, 0xFF, 0xE0, 0xFF, 0xF8, 0x7E, 0x1F, 0x1F, 0x03, 0xCF, + 0x80, 0xFB, 0xE0, 0x1E, 0xFF, 0xFF, 0xBF, 0xFF, 0xEF, 0xFF, 0xFB, 0xE0, + 0x00, 0xF8, 0x00, 0x3F, 0x03, 0xE7, 0xE1, 0xF9, 0xFF, 0xFC, 0x3F, 0xFE, + 0x07, 0xFF, 0x00, 0x7F, 0x00, 0x0F, 0xC7, 0xF3, 0xFC, 0xFF, 0x3E, 0x0F, + 0x83, 0xE3, 0xFE, 0xFF, 0xBF, 0xE3, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, + 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, + 0x0F, 0x80, 0x07, 0xC7, 0xC3, 0xFD, 0xF3, 0xFF, 0xFC, 0xFF, 0xFF, 0x7E, + 0x1F, 0xDF, 0x03, 0xFF, 0xC0, 0xFF, 0xE0, 0x1F, 0xF8, 0x07, 0xFE, 0x01, + 0xFF, 0x80, 0x7F, 0xE0, 0x1F, 0xFC, 0x0F, 0xDF, 0x03, 0xF7, 0xE1, 0xFD, + 0xFF, 0xFF, 0x3F, 0xFF, 0xC7, 0xFD, 0xF0, 0x7C, 0x7C, 0x00, 0x1F, 0x00, + 0x07, 0xFF, 0x03, 0xF7, 0xE1, 0xF9, 0xFF, 0xFC, 0x3F, 0xFE, 0x01, 0xFE, + 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, + 0xC0, 0x03, 0xE0, 0x01, 0xF1, 0xF0, 0xFB, 0xFE, 0x7F, 0xFF, 0xBF, 0xFF, + 0xDF, 0xC3, 0xFF, 0xC0, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xF0, 0x1F, 0xF8, + 0x0F, 0xFC, 0x07, 0xFE, 0x03, 0xFF, 0x01, 0xFF, 0x80, 0xFF, 0xC0, 0x7F, + 0xE0, 0x3F, 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, 0x07, 0xC0, 0xFF, 0xFF, 0xF0, + 0x00, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xC0, 0x3E, 0x7C, 0xF9, 0xF0, 0x00, 0x00, 0x1F, 0x3E, 0x7C, 0xF9, + 0xF3, 0xE7, 0xCF, 0x9F, 0x3E, 0x7C, 0xF9, 0xF3, 0xE7, 0xCF, 0x9F, 0x3E, + 0x7C, 0xF9, 0xF3, 0xFF, 0xFF, 0xFE, 0xF8, 0xF8, 0x00, 0x7C, 0x00, 0x3E, + 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x3E, + 0xF8, 0x3E, 0x7C, 0x3F, 0x3E, 0x3F, 0x1F, 0x3F, 0x0F, 0x9F, 0x07, 0xDF, + 0x03, 0xFF, 0x81, 0xFF, 0xC0, 0xFF, 0xF0, 0x7F, 0xF8, 0x3F, 0x7E, 0x1F, + 0x1F, 0x0F, 0x87, 0xC7, 0xC3, 0xF3, 0xE0, 0xF9, 0xF0, 0x7E, 0xF8, 0x1F, + 0x7C, 0x0F, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xF8, 0xF8, 0x3F, 0x1F, + 0x7F, 0x9F, 0xF3, 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0xFF, 0xC3, 0xF8, + 0x7F, 0xF8, 0x3F, 0x07, 0xFE, 0x07, 0xC0, 0xFF, 0xC0, 0xF8, 0x1F, 0xF8, + 0x1F, 0x03, 0xFF, 0x03, 0xE0, 0x7F, 0xE0, 0x7C, 0x0F, 0xFC, 0x0F, 0x81, + 0xFF, 0x81, 0xF0, 0x3F, 0xF0, 0x3E, 0x07, 0xFE, 0x07, 0xC0, 0xFF, 0xC0, + 0xF8, 0x1F, 0xF8, 0x1F, 0x03, 0xFF, 0x03, 0xE0, 0x7F, 0xE0, 0x7C, 0x0F, + 0x80, 0xF8, 0xF8, 0x7D, 0xFF, 0x3F, 0xFF, 0xDF, 0xFF, 0xEF, 0xE1, 0xFF, + 0xE0, 0x7F, 0xE0, 0x3F, 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, 0x07, 0xFE, 0x03, + 0xFF, 0x01, 0xFF, 0x80, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xF0, 0x1F, 0xF8, + 0x0F, 0xFC, 0x07, 0xFE, 0x03, 0xE0, 0x03, 0xF8, 0x01, 0xFF, 0xC0, 0x7F, + 0xFC, 0x1F, 0xFF, 0xC7, 0xF0, 0xFC, 0xF8, 0x0F, 0xBF, 0x01, 0xFF, 0xC0, + 0x1F, 0xF8, 0x03, 0xFF, 0x00, 0x7F, 0xE0, 0x0F, 0xFC, 0x01, 0xFF, 0xC0, + 0x7E, 0xF8, 0x0F, 0x9F, 0x87, 0xF1, 0xFF, 0xFC, 0x1F, 0xFF, 0x01, 0xFF, + 0xC0, 0x0F, 0xE0, 0x00, 0xF8, 0xF8, 0x3E, 0xFF, 0x8F, 0xFF, 0xF3, 0xFF, + 0xFC, 0xFE, 0x1F, 0xBF, 0x03, 0xEF, 0xC0, 0xFF, 0xE0, 0x1F, 0xF8, 0x07, + 0xFE, 0x01, 0xFF, 0x80, 0x7F, 0xE0, 0x1F, 0xFC, 0x0F, 0xFF, 0x03, 0xEF, + 0xE1, 0xFB, 0xFF, 0xFC, 0xFF, 0xFF, 0x3E, 0xFF, 0x0F, 0x8F, 0x83, 0xE0, + 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF8, 0x00, + 0x3E, 0x00, 0x00, 0x07, 0xE3, 0xE1, 0xFF, 0x7C, 0x7F, 0xFF, 0x9F, 0xFF, + 0xF7, 0xF1, 0xFE, 0xF8, 0x0F, 0xFF, 0x01, 0xFF, 0xC0, 0x1F, 0xF8, 0x03, + 0xFF, 0x00, 0x7F, 0xE0, 0x0F, 0xFC, 0x01, 0xFF, 0xC0, 0x7E, 0xF8, 0x0F, + 0xDF, 0x83, 0xF9, 0xFF, 0xFF, 0x3F, 0xFF, 0xE1, 0xFF, 0x7C, 0x1F, 0x8F, + 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1F, + 0x00, 0x03, 0xE0, 0x00, 0x7C, 0xF8, 0xFF, 0x7F, 0xFF, 0xFF, 0xFF, 0xE1, + 0xF8, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, + 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x00, 0x07, 0xF0, 0x0F, 0xFE, + 0x0F, 0xFF, 0x87, 0xFF, 0xE7, 0xE1, 0xF3, 0xE0, 0x79, 0xF8, 0x00, 0xFF, + 0x80, 0x3F, 0xFC, 0x1F, 0xFF, 0x83, 0xFF, 0xC0, 0x3F, 0xF0, 0x01, 0xFF, + 0xC0, 0x7D, 0xF0, 0x7E, 0xFF, 0xFE, 0x3F, 0xFF, 0x0F, 0xFF, 0x01, 0xFE, + 0x00, 0x3E, 0x1F, 0x0F, 0x87, 0xC3, 0xE7, 0xFF, 0xFF, 0xFF, 0x3E, 0x1F, + 0x0F, 0x87, 0xC3, 0xE1, 0xF0, 0xF8, 0x7C, 0x3E, 0x1F, 0x0F, 0x87, 0xF3, + 0xF8, 0xFC, 0x3E, 0xF8, 0x0F, 0xFC, 0x07, 0xFE, 0x03, 0xFF, 0x01, 0xFF, + 0x80, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, 0x07, + 0xFE, 0x03, 0xFF, 0x01, 0xFF, 0x80, 0xFF, 0xC0, 0xFF, 0xF0, 0xFF, 0xFF, + 0xFF, 0x7F, 0xFF, 0x9F, 0xF7, 0xC7, 0xE3, 0xE0, 0x7C, 0x07, 0xCF, 0x80, + 0xF9, 0xF0, 0x1F, 0x1F, 0x07, 0xC3, 0xE0, 0xF8, 0x7C, 0x1F, 0x07, 0x83, + 0xC0, 0xF8, 0xF8, 0x1F, 0x1F, 0x01, 0xE3, 0xC0, 0x3E, 0x78, 0x07, 0xDF, + 0x00, 0x7B, 0xC0, 0x0F, 0xF8, 0x01, 0xFF, 0x00, 0x1F, 0xC0, 0x03, 0xF8, + 0x00, 0x7F, 0x00, 0x07, 0xC0, 0x00, 0xFC, 0x1F, 0x03, 0xEF, 0x83, 0xE0, + 0x7D, 0xF0, 0x7E, 0x1F, 0x3E, 0x0F, 0xC3, 0xE3, 0xC3, 0xF8, 0x7C, 0x7C, + 0x7F, 0x0F, 0x0F, 0x8F, 0xF3, 0xE1, 0xF1, 0xDE, 0x7C, 0x1E, 0x7B, 0xCF, + 0x83, 0xEF, 0x39, 0xE0, 0x7D, 0xE7, 0x3C, 0x07, 0xB8, 0xFF, 0x80, 0xF7, + 0x1F, 0xE0, 0x1F, 0xE3, 0xFC, 0x03, 0xFC, 0x3F, 0x80, 0x3F, 0x07, 0xF0, + 0x07, 0xE0, 0xFC, 0x00, 0xFC, 0x1F, 0x80, 0x0F, 0x83, 0xF0, 0x00, 0xFC, + 0x1F, 0x9F, 0x07, 0xE7, 0xE3, 0xF0, 0xF8, 0xF8, 0x1F, 0x7E, 0x07, 0xDF, + 0x00, 0xFF, 0x80, 0x1F, 0xE0, 0x07, 0xF0, 0x00, 0xF8, 0x00, 0x7F, 0x00, + 0x3F, 0xE0, 0x0F, 0xF8, 0x07, 0xDF, 0x03, 0xF7, 0xE0, 0xF8, 0xF8, 0x7E, + 0x3F, 0x1F, 0x07, 0xEF, 0xC0, 0xF8, 0x7C, 0x03, 0xEF, 0x80, 0xF9, 0xF8, + 0x1F, 0x1F, 0x03, 0xE3, 0xE0, 0xF8, 0x7C, 0x1F, 0x07, 0xC3, 0xE0, 0xF8, + 0x78, 0x0F, 0x1F, 0x01, 0xF3, 0xC0, 0x3E, 0x78, 0x03, 0xDF, 0x00, 0x7F, + 0xC0, 0x0F, 0xF8, 0x00, 0xFF, 0x00, 0x1F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, + 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1E, 0x00, 0x07, 0xC0, 0x07, 0xF8, + 0x00, 0xFE, 0x00, 0x1F, 0x80, 0x03, 0xE0, 0x00, 0x7F, 0xFE, 0x7F, 0xFE, + 0x7F, 0xFE, 0x7F, 0xFE, 0x00, 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, + 0x03, 0xF0, 0x07, 0xE0, 0x0F, 0xC0, 0x1F, 0x80, 0x3F, 0x00, 0x7E, 0x00, + 0xFE, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x07, 0x87, + 0xC7, 0xE3, 0xF1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, 0xC1, + 0xE0, 0xF0, 0xF9, 0xF8, 0xF0, 0x7E, 0x0F, 0x83, 0xC1, 0xE0, 0xF0, 0x78, + 0x3C, 0x1E, 0x0F, 0x07, 0x83, 0xC1, 0xE0, 0xFC, 0x7E, 0x1F, 0x07, 0x80, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xE0, 0xF0, 0x7C, 0x3E, 0x1F, 0x83, 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, + 0x0F, 0x07, 0x83, 0xC1, 0xE0, 0xF0, 0x7C, 0x1F, 0x83, 0xC7, 0xE7, 0xC3, + 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, 0xC7, 0xE3, 0xE1, + 0xF0, 0xF0, 0x00, 0x3C, 0x00, 0xFE, 0x0F, 0xFE, 0x1E, 0x1F, 0xFC, 0x0F, + 0xC0, 0x0F, 0x00 }; + +const GFXglyph FreeSansBold18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 10, 0, 1 }, // 0x20 ' ' + { 0, 5, 25, 12, 4, -24 }, // 0x21 '!' + { 16, 13, 9, 17, 2, -25 }, // 0x22 '"' + { 31, 20, 24, 19, 0, -23 }, // 0x23 '#' + { 91, 19, 29, 19, 0, -25 }, // 0x24 '$' + { 160, 29, 25, 31, 1, -24 }, // 0x25 '%' + { 251, 22, 25, 25, 2, -24 }, // 0x26 '&' + { 320, 5, 9, 9, 2, -25 }, // 0x27 ''' + { 326, 9, 33, 12, 1, -25 }, // 0x28 '(' + { 364, 9, 33, 12, 1, -25 }, // 0x29 ')' + { 402, 12, 11, 14, 0, -25 }, // 0x2A '*' + { 419, 16, 16, 20, 2, -15 }, // 0x2B '+' + { 451, 5, 11, 9, 2, -4 }, // 0x2C ',' + { 458, 9, 4, 12, 1, -10 }, // 0x2D '-' + { 463, 5, 5, 9, 2, -4 }, // 0x2E '.' + { 467, 9, 25, 10, 0, -24 }, // 0x2F '/' + { 496, 17, 25, 19, 1, -24 }, // 0x30 '0' + { 550, 10, 25, 19, 3, -24 }, // 0x31 '1' + { 582, 17, 25, 19, 1, -24 }, // 0x32 '2' + { 636, 17, 25, 19, 1, -24 }, // 0x33 '3' + { 690, 16, 25, 19, 2, -24 }, // 0x34 '4' + { 740, 17, 25, 19, 1, -24 }, // 0x35 '5' + { 794, 18, 25, 19, 1, -24 }, // 0x36 '6' + { 851, 17, 25, 19, 1, -24 }, // 0x37 '7' + { 905, 17, 25, 19, 1, -24 }, // 0x38 '8' + { 959, 17, 25, 19, 1, -24 }, // 0x39 '9' + { 1013, 5, 18, 9, 2, -17 }, // 0x3A ':' + { 1025, 5, 24, 9, 2, -17 }, // 0x3B ';' + { 1040, 18, 17, 20, 1, -16 }, // 0x3C '<' + { 1079, 17, 12, 20, 2, -13 }, // 0x3D '=' + { 1105, 18, 17, 20, 1, -16 }, // 0x3E '>' + { 1144, 18, 26, 21, 2, -25 }, // 0x3F '?' + { 1203, 32, 31, 34, 1, -25 }, // 0x40 '@' + { 1327, 24, 26, 24, 0, -25 }, // 0x41 'A' + { 1405, 20, 26, 25, 3, -25 }, // 0x42 'B' + { 1470, 23, 26, 25, 1, -25 }, // 0x43 'C' + { 1545, 21, 26, 25, 3, -25 }, // 0x44 'D' + { 1614, 19, 26, 23, 3, -25 }, // 0x45 'E' + { 1676, 17, 26, 22, 3, -25 }, // 0x46 'F' + { 1732, 24, 26, 27, 1, -25 }, // 0x47 'G' + { 1810, 20, 26, 26, 3, -25 }, // 0x48 'H' + { 1875, 5, 26, 11, 3, -25 }, // 0x49 'I' + { 1892, 16, 26, 20, 1, -25 }, // 0x4A 'J' + { 1944, 22, 26, 25, 3, -25 }, // 0x4B 'K' + { 2016, 17, 26, 22, 3, -25 }, // 0x4C 'L' + { 2072, 24, 26, 30, 3, -25 }, // 0x4D 'M' + { 2150, 20, 26, 26, 3, -25 }, // 0x4E 'N' + { 2215, 25, 26, 27, 1, -25 }, // 0x4F 'O' + { 2297, 19, 26, 24, 3, -25 }, // 0x50 'P' + { 2359, 25, 27, 27, 1, -25 }, // 0x51 'Q' + { 2444, 21, 26, 25, 3, -25 }, // 0x52 'R' + { 2513, 20, 26, 24, 2, -25 }, // 0x53 'S' + { 2578, 19, 26, 23, 2, -25 }, // 0x54 'T' + { 2640, 20, 26, 26, 3, -25 }, // 0x55 'U' + { 2705, 22, 26, 23, 1, -25 }, // 0x56 'V' + { 2777, 32, 26, 34, 1, -25 }, // 0x57 'W' + { 2881, 22, 26, 24, 1, -25 }, // 0x58 'X' + { 2953, 21, 26, 22, 1, -25 }, // 0x59 'Y' + { 3022, 19, 26, 21, 1, -25 }, // 0x5A 'Z' + { 3084, 8, 33, 12, 2, -25 }, // 0x5B '[' + { 3117, 10, 25, 10, 0, -24 }, // 0x5C '\' + { 3149, 8, 33, 12, 1, -25 }, // 0x5D ']' + { 3182, 16, 15, 20, 2, -23 }, // 0x5E '^' + { 3212, 21, 3, 19, -1, 5 }, // 0x5F '_' + { 3220, 7, 5, 9, 1, -25 }, // 0x60 '`' + { 3225, 18, 19, 20, 1, -18 }, // 0x61 'a' + { 3268, 18, 26, 22, 2, -25 }, // 0x62 'b' + { 3327, 17, 19, 20, 1, -18 }, // 0x63 'c' + { 3368, 19, 26, 22, 1, -25 }, // 0x64 'd' + { 3430, 18, 19, 20, 1, -18 }, // 0x65 'e' + { 3473, 10, 26, 12, 1, -25 }, // 0x66 'f' + { 3506, 18, 26, 21, 1, -18 }, // 0x67 'g' + { 3565, 17, 26, 21, 2, -25 }, // 0x68 'h' + { 3621, 5, 26, 10, 2, -25 }, // 0x69 'i' + { 3638, 7, 33, 10, 0, -25 }, // 0x6A 'j' + { 3667, 17, 26, 20, 2, -25 }, // 0x6B 'k' + { 3723, 5, 26, 9, 2, -25 }, // 0x6C 'l' + { 3740, 27, 19, 31, 2, -18 }, // 0x6D 'm' + { 3805, 17, 19, 21, 2, -18 }, // 0x6E 'n' + { 3846, 19, 19, 21, 1, -18 }, // 0x6F 'o' + { 3892, 18, 26, 22, 2, -18 }, // 0x70 'p' + { 3951, 19, 26, 22, 1, -18 }, // 0x71 'q' + { 4013, 11, 19, 14, 2, -18 }, // 0x72 'r' + { 4040, 17, 19, 19, 1, -18 }, // 0x73 's' + { 4081, 9, 23, 12, 1, -22 }, // 0x74 't' + { 4107, 17, 19, 21, 2, -18 }, // 0x75 'u' + { 4148, 19, 19, 19, 0, -18 }, // 0x76 'v' + { 4194, 27, 19, 27, 0, -18 }, // 0x77 'w' + { 4259, 18, 19, 19, 1, -18 }, // 0x78 'x' + { 4302, 19, 26, 19, 0, -18 }, // 0x79 'y' + { 4364, 16, 19, 18, 1, -18 }, // 0x7A 'z' + { 4402, 9, 33, 14, 1, -25 }, // 0x7B '{' + { 4440, 3, 33, 10, 4, -25 }, // 0x7C '|' + { 4453, 9, 33, 14, 3, -25 }, // 0x7D '}' + { 4491, 15, 6, 18, 1, -10 } }; // 0x7E '~' + +const GFXfont FreeSansBold18pt7b PROGMEM = { + (uint8_t *)FreeSansBold18pt7bBitmaps, + (GFXglyph *)FreeSansBold18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 5175 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBold24pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBold24pt7b.h new file mode 100644 index 0000000..aadc9a1 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBold24pt7b.h @@ -0,0 +1,784 @@ +const uint8_t FreeSansBold24pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xDF, 0x3E, 0x7C, 0xF9, 0xF3, 0xE7, 0xC7, 0x0E, 0x1C, 0x00, 0x00, 0x07, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFE, 0x1F, 0xFF, 0x87, 0xFF, 0xE1, + 0xFF, 0xF8, 0x7F, 0xFE, 0x1F, 0xFF, 0x87, 0xFF, 0xE1, 0xFD, 0xF0, 0x3E, + 0x7C, 0x0F, 0x9F, 0x03, 0xE3, 0x80, 0x70, 0xE0, 0x1C, 0x00, 0xF8, 0x3E, + 0x00, 0x3E, 0x0F, 0x80, 0x0F, 0x83, 0xE0, 0x03, 0xE0, 0xF8, 0x00, 0xF8, + 0x7C, 0x00, 0x7C, 0x1F, 0x00, 0x1F, 0x07, 0xC1, 0xFF, 0xFF, 0xFF, 0x7F, + 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFD, 0xFF, 0xFF, 0xFF, + 0x03, 0xE0, 0xF8, 0x00, 0xF8, 0x3E, 0x00, 0x3E, 0x1F, 0x00, 0x1F, 0x07, + 0xC0, 0x07, 0xC1, 0xF0, 0x01, 0xF0, 0x7C, 0x00, 0x7C, 0x1F, 0x03, 0xFF, + 0xFF, 0xFC, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0xF3, + 0xFF, 0xFF, 0xFC, 0x0F, 0x87, 0xC0, 0x07, 0xC1, 0xF0, 0x01, 0xF0, 0x7C, + 0x00, 0x7C, 0x1F, 0x00, 0x1F, 0x07, 0xC0, 0x07, 0xC3, 0xE0, 0x03, 0xE0, + 0xF8, 0x00, 0xF8, 0x3E, 0x00, 0x3E, 0x0F, 0x80, 0x00, 0x00, 0x38, 0x00, + 0x00, 0x1C, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0xFF, 0xFC, 0x00, 0xFF, 0xFF, + 0x80, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xF8, 0x7F, 0x73, 0xFE, 0x7F, 0x38, + 0xFF, 0x3F, 0x1C, 0x3F, 0xDF, 0x8E, 0x0F, 0xEF, 0xC7, 0x07, 0xF7, 0xE3, + 0x80, 0x03, 0xF9, 0xC0, 0x01, 0xFE, 0xE0, 0x00, 0x7F, 0xF0, 0x00, 0x3F, + 0xFC, 0x00, 0x0F, 0xFF, 0xC0, 0x03, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, 0x80, + 0x0F, 0xFF, 0xE0, 0x01, 0xFF, 0xF8, 0x00, 0xE7, 0xFC, 0x00, 0x71, 0xFF, + 0x00, 0x38, 0x7F, 0xFF, 0x1C, 0x1F, 0xFF, 0x8E, 0x0F, 0xFF, 0xC7, 0x07, + 0xFF, 0xE3, 0x87, 0xFB, 0xF9, 0xC3, 0xF9, 0xFE, 0xE7, 0xFC, 0x7F, 0xFF, + 0xFC, 0x3F, 0xFF, 0xFC, 0x0F, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x00, 0x3F, + 0xE0, 0x00, 0x03, 0x80, 0x00, 0x01, 0xC0, 0x00, 0x00, 0xE0, 0x00, 0x00, + 0x70, 0x00, 0x03, 0xE0, 0x00, 0x3C, 0x00, 0x1F, 0xF0, 0x00, 0x78, 0x00, + 0x7F, 0xF8, 0x01, 0xE0, 0x01, 0xFF, 0xF0, 0x03, 0xC0, 0x07, 0xFF, 0xF0, + 0x0F, 0x00, 0x0F, 0x83, 0xE0, 0x1E, 0x00, 0x3E, 0x03, 0xE0, 0x78, 0x00, + 0x78, 0x03, 0xC0, 0xF0, 0x00, 0xF0, 0x07, 0x83, 0xC0, 0x01, 0xE0, 0x0F, + 0x07, 0x80, 0x03, 0xE0, 0x3E, 0x1E, 0x00, 0x03, 0xE0, 0xF8, 0x3C, 0x00, + 0x07, 0xFF, 0xF0, 0xF0, 0x00, 0x07, 0xFF, 0xC1, 0xE0, 0x00, 0x07, 0xFF, + 0x07, 0x80, 0x00, 0x07, 0xFC, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x3C, 0x00, + 0x00, 0x00, 0x00, 0xF0, 0x1F, 0x00, 0x00, 0x01, 0xE0, 0xFF, 0x80, 0x00, + 0x07, 0x87, 0xFF, 0xC0, 0x00, 0x0F, 0x0F, 0xFF, 0x80, 0x00, 0x3C, 0x3F, + 0xFF, 0x80, 0x00, 0x78, 0xFC, 0x1F, 0x00, 0x01, 0xE1, 0xF0, 0x1F, 0x00, + 0x03, 0xC3, 0xC0, 0x1E, 0x00, 0x0F, 0x07, 0x80, 0x3C, 0x00, 0x1E, 0x0F, + 0x00, 0x78, 0x00, 0x78, 0x1F, 0x01, 0xF0, 0x00, 0xF0, 0x1F, 0x07, 0xC0, + 0x03, 0xC0, 0x3F, 0xFF, 0x80, 0x07, 0x80, 0x3F, 0xFE, 0x00, 0x1E, 0x00, + 0x7F, 0xF8, 0x00, 0x7C, 0x00, 0x3F, 0xE0, 0x00, 0xF0, 0x00, 0x1F, 0x00, + 0x00, 0x3F, 0x00, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x1F, 0xFC, 0x00, 0x00, + 0xFF, 0xF8, 0x00, 0x07, 0xFF, 0xF0, 0x00, 0x3F, 0xCF, 0xC0, 0x00, 0xFE, + 0x1F, 0x00, 0x03, 0xF8, 0x7C, 0x00, 0x0F, 0xE1, 0xF0, 0x00, 0x3F, 0xC7, + 0xC0, 0x00, 0x7F, 0x3E, 0x00, 0x01, 0xFF, 0xF8, 0x00, 0x03, 0xFF, 0xC0, + 0x00, 0x07, 0xFE, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x7F, 0x80, 0x00, + 0x07, 0xFF, 0x03, 0xE0, 0x3F, 0xFE, 0x0F, 0x83, 0xFF, 0xF8, 0x3E, 0x1F, + 0xF3, 0xF1, 0xF8, 0x7F, 0x07, 0xE7, 0xE3, 0xFC, 0x1F, 0xFF, 0x0F, 0xE0, + 0x3F, 0xFC, 0x3F, 0x80, 0x7F, 0xF0, 0xFE, 0x01, 0xFF, 0x83, 0xF8, 0x03, + 0xFE, 0x0F, 0xF0, 0x0F, 0xF0, 0x3F, 0xE0, 0x7F, 0xE0, 0x7F, 0xC3, 0xFF, + 0xC1, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFE, 0x07, 0xFF, 0xFB, 0xFC, + 0x0F, 0xFF, 0xC7, 0xF8, 0x1F, 0xFE, 0x0F, 0xE0, 0x0F, 0xE0, 0x00, 0x00, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xBE, 0x7C, 0xF8, 0xE1, 0xC0, 0x00, + 0xF0, 0x0F, 0x80, 0xF8, 0x07, 0xC0, 0x7C, 0x07, 0xE0, 0x3E, 0x03, 0xF0, + 0x1F, 0x80, 0xF8, 0x0F, 0xC0, 0x7E, 0x07, 0xE0, 0x3F, 0x01, 0xF8, 0x0F, + 0xC0, 0xFC, 0x07, 0xE0, 0x3F, 0x01, 0xF8, 0x0F, 0xC0, 0x7E, 0x03, 0xF0, + 0x1F, 0x80, 0xFC, 0x07, 0xE0, 0x3F, 0x00, 0xF8, 0x07, 0xE0, 0x3F, 0x01, + 0xF8, 0x07, 0xC0, 0x3F, 0x01, 0xF8, 0x07, 0xC0, 0x3F, 0x00, 0xF8, 0x07, + 0xE0, 0x1F, 0x00, 0xF8, 0x03, 0xE0, 0x1F, 0x00, 0x7C, 0x01, 0xE0, 0x78, + 0x03, 0xE0, 0x0F, 0x80, 0x7C, 0x01, 0xF0, 0x0F, 0x80, 0x3E, 0x01, 0xF0, + 0x0F, 0xC0, 0x3E, 0x01, 0xF8, 0x0F, 0xC0, 0x3F, 0x01, 0xF8, 0x0F, 0xC0, + 0x7E, 0x01, 0xF8, 0x0F, 0xC0, 0x7E, 0x03, 0xF0, 0x1F, 0x80, 0xFC, 0x07, + 0xE0, 0x3F, 0x01, 0xF8, 0x0F, 0xC0, 0x7E, 0x03, 0xE0, 0x3F, 0x01, 0xF8, + 0x0F, 0xC0, 0x7C, 0x07, 0xE0, 0x3F, 0x01, 0xF0, 0x1F, 0x80, 0xF8, 0x0F, + 0xC0, 0x7C, 0x07, 0xE0, 0x3E, 0x03, 0xF0, 0x1F, 0x01, 0xF0, 0x00, 0x03, + 0x80, 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x06, 0x38, 0xDF, 0xFF, 0xFF, 0xFF, + 0x9F, 0xFE, 0x07, 0xC0, 0x1F, 0xC0, 0x3F, 0x80, 0xF7, 0x83, 0xC7, 0x87, + 0x8F, 0x02, 0x08, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, + 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, + 0x00, 0x3E, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x1F, 0x00, 0x00, + 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, + 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0x87, 0x0E, 0x1C, 0x78, 0xEF, 0xDF, 0x38, 0x00, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0x80, 0x00, 0x38, 0x03, 0xC0, 0x1C, 0x00, 0xE0, 0x07, 0x00, + 0x70, 0x03, 0x80, 0x1C, 0x01, 0xE0, 0x0E, 0x00, 0x70, 0x03, 0x80, 0x38, + 0x01, 0xC0, 0x0E, 0x00, 0xF0, 0x07, 0x00, 0x38, 0x03, 0xC0, 0x1C, 0x00, + 0xE0, 0x07, 0x00, 0x70, 0x03, 0x80, 0x1C, 0x01, 0xE0, 0x0E, 0x00, 0x70, + 0x03, 0x80, 0x38, 0x01, 0xC0, 0x0E, 0x00, 0xF0, 0x07, 0x00, 0x00, 0x00, + 0xFF, 0x00, 0x03, 0xFF, 0xC0, 0x0F, 0xFF, 0xF0, 0x1F, 0xFF, 0xF8, 0x1F, + 0xFF, 0xF8, 0x3F, 0xFF, 0xFC, 0x3F, 0xC3, 0xFC, 0x7F, 0x81, 0xFE, 0x7F, + 0x00, 0xFE, 0x7F, 0x00, 0xFE, 0x7F, 0x00, 0xFE, 0xFE, 0x00, 0x7F, 0xFE, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0x7F, + 0x00, 0xFE, 0x7F, 0x00, 0xFE, 0x7F, 0x00, 0xFE, 0x7F, 0x81, 0xFE, 0x3F, + 0xC3, 0xFC, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, 0xF8, 0x1F, 0xFF, 0xF8, 0x0F, + 0xFF, 0xF0, 0x03, 0xFF, 0xC0, 0x00, 0xFF, 0x00, 0x00, 0x3C, 0x01, 0xF0, + 0x07, 0xC0, 0x3F, 0x01, 0xFC, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, + 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, + 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, + 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x01, 0xFE, 0x00, 0x0F, 0xFF, 0x80, + 0x3F, 0xFF, 0x80, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0x8F, 0xFF, 0xFF, 0x9F, + 0xE0, 0xFF, 0x7F, 0x80, 0xFF, 0xFE, 0x01, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, + 0x03, 0xFF, 0xF0, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, + 0x7F, 0x80, 0x00, 0xFE, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x7F, + 0xC0, 0x01, 0xFF, 0x00, 0x07, 0xF8, 0x00, 0x3F, 0xE0, 0x00, 0xFF, 0x00, + 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0x7F, 0x00, 0x01, + 0xFC, 0x00, 0x03, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xBF, + 0xFF, 0xFF, 0x7F, 0xFF, 0xFE, 0xFF, 0xFF, 0xFC, 0x01, 0xFE, 0x00, 0x0F, + 0xFF, 0x80, 0x7F, 0xFF, 0x81, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0x8F, 0xFF, + 0xFF, 0x1F, 0xE1, 0xFF, 0x7F, 0x81, 0xFE, 0xFE, 0x01, 0xFD, 0xFC, 0x03, + 0xFB, 0xF8, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x7F, + 0x00, 0x01, 0xFC, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0x7F, 0xC0, + 0x00, 0xFF, 0xE0, 0x00, 0x3F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x3F, 0xC0, + 0x00, 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, + 0x07, 0xFF, 0xF8, 0x0F, 0xF7, 0xF8, 0x3F, 0xCF, 0xFF, 0xFF, 0x9F, 0xFF, + 0xFE, 0x1F, 0xFF, 0xF8, 0x1F, 0xFF, 0xE0, 0x0F, 0xFF, 0x80, 0x07, 0xF8, + 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x03, 0xFE, 0x00, 0x0F, 0xF8, + 0x00, 0x7F, 0xE0, 0x03, 0xFF, 0x80, 0x0F, 0xFE, 0x00, 0x7B, 0xF8, 0x01, + 0xEF, 0xE0, 0x0F, 0x3F, 0x80, 0x78, 0xFE, 0x01, 0xE3, 0xF8, 0x0F, 0x0F, + 0xE0, 0x38, 0x3F, 0x81, 0xE0, 0xFE, 0x07, 0x03, 0xF8, 0x3C, 0x0F, 0xE1, + 0xE0, 0x3F, 0x87, 0x00, 0xFE, 0x3C, 0x03, 0xF8, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF0, 0x00, 0xFE, 0x00, 0x03, 0xF8, 0x00, 0x0F, 0xE0, 0x00, 0x3F, 0x80, + 0x00, 0xFE, 0x00, 0x03, 0xF8, 0x00, 0x0F, 0xE0, 0x1F, 0xFF, 0xFC, 0x3F, + 0xFF, 0xF8, 0x7F, 0xFF, 0xF0, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0xC7, 0xFF, + 0xFF, 0x8F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x78, 0x00, + 0x01, 0xF1, 0xF8, 0x03, 0xEF, 0xFE, 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xFE, + 0x1F, 0xFF, 0xFE, 0x7F, 0xFF, 0xFC, 0xFE, 0x07, 0xFC, 0x00, 0x07, 0xF8, + 0x00, 0x07, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, + 0x00, 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0xF8, 0x03, 0xFF, 0xF8, + 0x0F, 0xF7, 0xF8, 0x3F, 0xEF, 0xFF, 0xFF, 0x8F, 0xFF, 0xFF, 0x0F, 0xFF, + 0xFC, 0x0F, 0xFF, 0xE0, 0x0F, 0xFF, 0x80, 0x03, 0xF8, 0x00, 0x00, 0xFF, + 0x00, 0x07, 0xFF, 0x80, 0x1F, 0xFF, 0xC0, 0x7F, 0xFF, 0x81, 0xFF, 0xFF, + 0x87, 0xFF, 0xFF, 0x8F, 0xF0, 0xFF, 0x3F, 0xC0, 0xFE, 0x7F, 0x00, 0x00, + 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE3, 0xF0, 0x1F, + 0xDF, 0xF8, 0x3F, 0xFF, 0xFC, 0x7F, 0xFF, 0xFC, 0xFF, 0xFF, 0xF9, 0xFF, + 0x87, 0xFB, 0xFC, 0x07, 0xF7, 0xF8, 0x0F, 0xFF, 0xE0, 0x0F, 0xFF, 0xC0, + 0x1F, 0xFF, 0x80, 0x3F, 0xFF, 0x00, 0x7F, 0x7E, 0x00, 0xFE, 0xFC, 0x01, + 0xFD, 0xFC, 0x07, 0xFB, 0xF8, 0x0F, 0xE3, 0xFC, 0x7F, 0xC7, 0xFF, 0xFF, + 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xF8, 0x0F, 0xFF, 0xE0, 0x07, 0xFF, 0x80, + 0x03, 0xF8, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x00, 0x3F, 0x00, + 0x00, 0xFC, 0x00, 0x03, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x80, 0x00, + 0x7F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x1F, + 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xF8, 0x00, 0x07, 0xF0, + 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFC, 0x00, + 0x01, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, + 0x3F, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x03, 0xF8, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x03, 0xFF, 0xC0, 0x0F, 0xFF, 0xE0, 0x1F, + 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, 0x3F, 0xFF, 0xF8, 0x7F, 0x83, 0xFC, 0x7F, + 0x00, 0xFC, 0x7E, 0x00, 0xFC, 0x7E, 0x00, 0x7C, 0x7E, 0x00, 0x7C, 0x7E, + 0x00, 0xFC, 0x3F, 0x00, 0xF8, 0x3F, 0x83, 0xF8, 0x0F, 0xFF, 0xF0, 0x07, + 0xFF, 0xC0, 0x0F, 0xFF, 0xF0, 0x1F, 0xFF, 0xF8, 0x3F, 0xC3, 0xFC, 0x7F, + 0x00, 0xFE, 0x7F, 0x00, 0xFE, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFF, 0x00, 0xFF, 0xFF, + 0x00, 0xFE, 0x7F, 0x83, 0xFE, 0x7F, 0xFF, 0xFE, 0x3F, 0xFF, 0xFC, 0x1F, + 0xFF, 0xF8, 0x0F, 0xFF, 0xF0, 0x07, 0xFF, 0xC0, 0x00, 0xFF, 0x00, 0x00, + 0xFF, 0x00, 0x03, 0xFF, 0xC0, 0x0F, 0xFF, 0xE0, 0x1F, 0xFF, 0xF0, 0x3F, + 0xFF, 0xF8, 0x3F, 0xFF, 0xFC, 0x7F, 0xC3, 0xFC, 0x7F, 0x01, 0xFE, 0xFF, + 0x00, 0xFE, 0xFE, 0x00, 0x7E, 0xFE, 0x00, 0x7E, 0xFE, 0x00, 0x7F, 0xFE, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFF, 0x00, 0xFF, 0x7F, + 0x01, 0xFF, 0x7F, 0xC3, 0xFF, 0x7F, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0x1F, + 0xFF, 0xFF, 0x0F, 0xFF, 0x7F, 0x07, 0xFE, 0x7F, 0x01, 0xFC, 0x7E, 0x00, + 0x00, 0x7E, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x7F, 0x01, 0xFC, 0x7F, + 0x83, 0xFC, 0x7F, 0xFF, 0xF8, 0x3F, 0xFF, 0xF8, 0x3F, 0xFF, 0xF0, 0x1F, + 0xFF, 0xE0, 0x07, 0xFF, 0x80, 0x01, 0xFE, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFE, 0x1C, 0x38, 0x71, 0xE7, 0xBF, 0x7C, 0xE0, 0x00, + 0x00, 0x02, 0x00, 0x00, 0x3C, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0xF0, 0x01, + 0xFF, 0xE0, 0x0F, 0xFF, 0xC0, 0xFF, 0xFC, 0x0F, 0xFF, 0xC0, 0x7F, 0xFC, + 0x01, 0xFF, 0xC0, 0x03, 0xFC, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0xE0, 0x00, + 0x1F, 0xF8, 0x00, 0x3F, 0xFE, 0x00, 0x0F, 0xFF, 0x80, 0x07, 0xFF, 0xE0, + 0x01, 0xFF, 0xF8, 0x00, 0x7F, 0xF8, 0x00, 0x3F, 0xF0, 0x00, 0x0F, 0xE0, + 0x00, 0x03, 0xC0, 0x00, 0x00, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x80, 0x00, + 0x01, 0xC0, 0x00, 0x03, 0xF0, 0x00, 0x07, 0xFC, 0x00, 0x0F, 0xFE, 0x00, + 0x1F, 0xFF, 0x80, 0x07, 0xFF, 0xE0, 0x01, 0xFF, 0xF0, 0x00, 0x7F, 0xFC, + 0x00, 0x1F, 0xFC, 0x00, 0x07, 0xF8, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0xE0, + 0x01, 0xFF, 0xC0, 0x0F, 0xFF, 0x80, 0xFF, 0xF8, 0x0F, 0xFF, 0x80, 0xFF, + 0xFC, 0x03, 0xFF, 0xC0, 0x07, 0xFC, 0x00, 0x0F, 0xE0, 0x00, 0x1E, 0x00, + 0x00, 0x20, 0x00, 0x00, 0x00, 0x01, 0xFE, 0x00, 0x07, 0xFF, 0xC0, 0x1F, + 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, 0x3F, 0xFF, 0xFC, 0x7F, 0xFF, 0xFC, 0x7F, + 0x83, 0xFE, 0x7F, 0x01, 0xFE, 0xFF, 0x00, 0xFF, 0xFE, 0x00, 0x7F, 0xFE, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0x00, + 0x01, 0xFE, 0x00, 0x03, 0xFE, 0x00, 0x07, 0xFC, 0x00, 0x0F, 0xF8, 0x00, + 0x3F, 0xF0, 0x00, 0x3F, 0xE0, 0x00, 0x7F, 0x80, 0x00, 0x7F, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0x00, 0x3F, 0xFF, 0xE0, + 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xF8, 0x00, + 0x03, 0xFE, 0x01, 0xFF, 0x80, 0x01, 0xFE, 0x00, 0x07, 0xF8, 0x00, 0x7F, + 0x80, 0x00, 0x3F, 0x80, 0x1F, 0xC0, 0x00, 0x03, 0xF8, 0x07, 0xF0, 0x00, + 0x00, 0x1F, 0x00, 0xFC, 0x00, 0x00, 0x01, 0xF0, 0x3F, 0x00, 0x00, 0x00, + 0x3E, 0x0F, 0xC0, 0x07, 0xE3, 0xC3, 0xE1, 0xF0, 0x03, 0xFE, 0xF8, 0x3C, + 0x7E, 0x01, 0xFF, 0xFF, 0x07, 0x8F, 0x80, 0x7E, 0x1F, 0xC0, 0x7B, 0xF0, + 0x1F, 0x81, 0xF8, 0x0F, 0x7C, 0x03, 0xE0, 0x1F, 0x01, 0xEF, 0x80, 0xF8, + 0x03, 0xC0, 0x3F, 0xF0, 0x1E, 0x00, 0x78, 0x07, 0xFC, 0x07, 0xC0, 0x0F, + 0x00, 0xFF, 0x80, 0xF0, 0x01, 0xE0, 0x1F, 0xF0, 0x1E, 0x00, 0x38, 0x07, + 0xFE, 0x07, 0xC0, 0x0F, 0x00, 0xFF, 0xC0, 0xF8, 0x01, 0xE0, 0x1E, 0xF8, + 0x1F, 0x00, 0x38, 0x07, 0xDF, 0x03, 0xE0, 0x0F, 0x00, 0xF3, 0xF0, 0x7C, + 0x03, 0xE0, 0x3E, 0x3E, 0x0F, 0xC0, 0xFC, 0x0F, 0x87, 0xC0, 0xFC, 0x3F, + 0xC7, 0xF0, 0xFC, 0x1F, 0xFF, 0xFF, 0xFC, 0x0F, 0xC1, 0xFF, 0xEF, 0xFF, + 0x01, 0xFC, 0x1F, 0xF8, 0xFF, 0x80, 0x1F, 0xC0, 0xFC, 0x07, 0xC0, 0x01, + 0xFC, 0x00, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x60, 0x00, 0x01, 0xFF, 0xFF, + 0xFE, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x7F, 0xFF, 0xF0, + 0x00, 0x00, 0x00, 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, + 0x0F, 0xF8, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x1F, 0xFC, 0x00, 0x00, + 0x1F, 0xFC, 0x00, 0x00, 0x1F, 0xFC, 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x00, + 0x3F, 0xFE, 0x00, 0x00, 0x3F, 0x7E, 0x00, 0x00, 0x7F, 0x7F, 0x00, 0x00, + 0x7F, 0x7F, 0x00, 0x00, 0x7E, 0x3F, 0x00, 0x00, 0xFE, 0x3F, 0x80, 0x00, + 0xFE, 0x3F, 0x80, 0x01, 0xFC, 0x1F, 0x80, 0x01, 0xFC, 0x1F, 0xC0, 0x01, + 0xF8, 0x1F, 0xC0, 0x03, 0xF8, 0x0F, 0xE0, 0x03, 0xF8, 0x0F, 0xE0, 0x03, + 0xF0, 0x0F, 0xE0, 0x07, 0xF0, 0x07, 0xF0, 0x07, 0xFF, 0xFF, 0xF0, 0x07, + 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xF8, 0x1F, + 0xFF, 0xFF, 0xF8, 0x1F, 0xFF, 0xFF, 0xFC, 0x1F, 0xC0, 0x01, 0xFC, 0x3F, + 0x80, 0x01, 0xFC, 0x3F, 0x80, 0x00, 0xFE, 0x3F, 0x80, 0x00, 0xFE, 0x7F, + 0x00, 0x00, 0xFE, 0x7F, 0x00, 0x00, 0x7F, 0x7F, 0x00, 0x00, 0x7F, 0xFF, + 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, 0xFF, + 0x8F, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, 0xFF, 0x3F, 0x80, 0x1F, 0xF7, 0xF0, + 0x01, 0xFE, 0xFE, 0x00, 0x1F, 0xDF, 0xC0, 0x03, 0xFB, 0xF8, 0x00, 0x7F, + 0x7F, 0x00, 0x1F, 0xCF, 0xE0, 0x07, 0xF9, 0xFF, 0xFF, 0xFE, 0x3F, 0xFF, + 0xFF, 0x87, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFE, 0x1F, 0xFF, 0xFF, 0xE3, + 0xFF, 0xFF, 0xFE, 0x7F, 0x00, 0x1F, 0xEF, 0xE0, 0x01, 0xFD, 0xFC, 0x00, + 0x1F, 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, 0x7F, 0xFE, 0x00, 0x0F, 0xFF, + 0xC0, 0x01, 0xFF, 0xF8, 0x00, 0x7F, 0xFF, 0x00, 0x1F, 0xEF, 0xFF, 0xFF, + 0xFD, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xF8, 0xFF, + 0xFF, 0xFC, 0x1F, 0xFF, 0xFC, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x03, 0xFF, + 0xF8, 0x00, 0x1F, 0xFF, 0xF8, 0x01, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, + 0xE0, 0x3F, 0xFF, 0xFF, 0xC1, 0xFF, 0x81, 0xFF, 0x0F, 0xF8, 0x01, 0xFE, + 0x3F, 0xC0, 0x07, 0xF9, 0xFE, 0x00, 0x0F, 0xE7, 0xF8, 0x00, 0x1F, 0xDF, + 0xC0, 0x00, 0x7F, 0x7F, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x0F, 0xE0, + 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x03, 0xF8, 0x00, + 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, + 0x7F, 0x00, 0x01, 0xFD, 0xFC, 0x00, 0x07, 0xF7, 0xF8, 0x00, 0x3F, 0xCF, + 0xF0, 0x00, 0xFE, 0x3F, 0xE0, 0x07, 0xF8, 0x7F, 0xE0, 0x7F, 0xC0, 0xFF, + 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0xC0, 0x07, 0xFF, + 0xFE, 0x00, 0x0F, 0xFF, 0xE0, 0x00, 0x07, 0xFC, 0x00, 0xFF, 0xFF, 0xC0, + 0x0F, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xFC, 0x0F, 0xFF, 0xFF, 0xE0, 0xFF, + 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xF8, 0xFE, 0x00, 0xFF, 0xCF, 0xE0, 0x03, + 0xFC, 0xFE, 0x00, 0x1F, 0xEF, 0xE0, 0x01, 0xFE, 0xFE, 0x00, 0x0F, 0xEF, + 0xE0, 0x00, 0xFE, 0xFE, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x7F, 0xFE, 0x00, + 0x07, 0xFF, 0xE0, 0x00, 0x7F, 0xFE, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x7F, + 0xFE, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x7F, 0xFE, 0x00, 0x07, 0xFF, 0xE0, + 0x00, 0x7F, 0xFE, 0x00, 0x0F, 0xEF, 0xE0, 0x00, 0xFE, 0xFE, 0x00, 0x1F, + 0xEF, 0xE0, 0x01, 0xFE, 0xFE, 0x00, 0x3F, 0xCF, 0xE0, 0x0F, 0xFC, 0xFF, + 0xFF, 0xFF, 0x8F, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, + 0xC0, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFC, 0x00, 0xFF, 0xFF, 0xFF, 0x7F, + 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xF7, + 0xFF, 0xFF, 0xFB, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0x7F, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x0F, 0xE0, 0x00, + 0x07, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, + 0xFE, 0x7F, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0x9F, 0xC0, 0x00, 0x0F, 0xE0, + 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x0F, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFF, 0xFF, + 0xFC, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, + 0xFC, 0xFF, 0xFF, 0xFC, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0xFF, 0xFE, 0x00, 0x07, 0xFF, 0xFF, + 0x00, 0x1F, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0xFF, + 0x07, 0xFE, 0x03, 0xFF, 0x0F, 0xF0, 0x01, 0xFE, 0x3F, 0xC0, 0x01, 0xFC, + 0x7F, 0x00, 0x01, 0xFD, 0xFE, 0x00, 0x03, 0xFB, 0xF8, 0x00, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x00, 0xFE, 0x00, 0x3F, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, 0xF8, + 0x00, 0xFF, 0xFF, 0xF0, 0x01, 0xFF, 0xFF, 0xE0, 0x03, 0xFF, 0xFF, 0xC0, + 0x07, 0xFF, 0xFF, 0xC0, 0x00, 0x1F, 0xBF, 0x80, 0x00, 0x3F, 0x7F, 0x00, + 0x00, 0x7E, 0xFF, 0x00, 0x01, 0xFC, 0xFF, 0x00, 0x03, 0xF9, 0xFF, 0x00, + 0x0F, 0xF1, 0xFF, 0x00, 0x3F, 0xE3, 0xFF, 0x83, 0xFF, 0xC3, 0xFF, 0xFF, + 0xFF, 0x83, 0xFF, 0xFF, 0xDF, 0x03, 0xFF, 0xFF, 0x9E, 0x03, 0xFF, 0xFE, + 0x3C, 0x01, 0xFF, 0xF0, 0x78, 0x00, 0x7F, 0x80, 0x00, 0xFE, 0x00, 0x0F, + 0xFF, 0xC0, 0x01, 0xFF, 0xF8, 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFF, 0xE0, + 0x00, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, 0x7F, + 0xFE, 0x00, 0x0F, 0xFF, 0xC0, 0x01, 0xFF, 0xF8, 0x00, 0x3F, 0xFF, 0x00, + 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, + 0x80, 0x03, 0xFF, 0xF0, 0x00, 0x7F, 0xFE, 0x00, 0x0F, 0xFF, 0xC0, 0x01, + 0xFF, 0xF8, 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFC, + 0x00, 0x1F, 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, 0x7F, 0xFE, 0x00, 0x0F, + 0xFF, 0xC0, 0x01, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x01, + 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFC, + 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, + 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x07, + 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xF0, + 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xFF, 0xE0, + 0x1F, 0xFF, 0x80, 0x7F, 0xFE, 0x01, 0xFF, 0xF8, 0x07, 0xFF, 0xE0, 0x1F, + 0xFF, 0xC0, 0xFF, 0xFF, 0x87, 0xFD, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0x8F, + 0xFF, 0xFC, 0x1F, 0xFF, 0xE0, 0x3F, 0xFF, 0x00, 0x1F, 0xE0, 0x00, 0xFE, + 0x00, 0x0F, 0xF3, 0xF8, 0x00, 0x7F, 0x8F, 0xE0, 0x03, 0xFC, 0x3F, 0x80, + 0x1F, 0xE0, 0xFE, 0x00, 0xFF, 0x83, 0xF8, 0x07, 0xFC, 0x0F, 0xE0, 0x1F, + 0xE0, 0x3F, 0x80, 0xFF, 0x00, 0xFE, 0x07, 0xF8, 0x03, 0xF8, 0x3F, 0xC0, + 0x0F, 0xE1, 0xFE, 0x00, 0x3F, 0x8F, 0xF0, 0x00, 0xFE, 0x7F, 0x80, 0x03, + 0xFB, 0xFC, 0x00, 0x0F, 0xFF, 0xE0, 0x00, 0x3F, 0xFF, 0xC0, 0x00, 0xFF, + 0xFF, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x0F, 0xFF, 0xFC, 0x00, 0x3F, 0xF7, + 0xF8, 0x00, 0xFF, 0x8F, 0xF0, 0x03, 0xFC, 0x3F, 0xC0, 0x0F, 0xE0, 0x7F, + 0x80, 0x3F, 0x80, 0xFF, 0x00, 0xFE, 0x01, 0xFE, 0x03, 0xF8, 0x07, 0xFC, + 0x0F, 0xE0, 0x0F, 0xF0, 0x3F, 0x80, 0x1F, 0xE0, 0xFE, 0x00, 0x3F, 0xC3, + 0xF8, 0x00, 0xFF, 0x8F, 0xE0, 0x01, 0xFE, 0x3F, 0x80, 0x03, 0xFC, 0xFE, + 0x00, 0x07, 0xFB, 0xF8, 0x00, 0x1F, 0xF0, 0xFE, 0x00, 0x01, 0xFC, 0x00, + 0x03, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, + 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x03, + 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x3F, + 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x03, 0xF8, + 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x3F, 0x80, + 0x00, 0x7F, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x03, 0xF8, 0x00, + 0x07, 0xF0, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFF, 0xE0, 0x03, + 0xFF, 0xFF, 0xF0, 0x01, 0xFF, 0xFF, 0xF8, 0x00, 0xFF, 0xFF, 0xFC, 0x00, + 0x7F, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xFF, 0xC0, + 0x1F, 0xFF, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xF0, 0x07, 0xFF, 0xFF, 0xFC, + 0x07, 0xFF, 0xFF, 0xBE, 0x03, 0xEF, 0xFF, 0xDF, 0x01, 0xF7, 0xFF, 0xEF, + 0x80, 0xFB, 0xFF, 0xF7, 0xC0, 0xFD, 0xFF, 0xFB, 0xF0, 0x7C, 0xFF, 0xFC, + 0xF8, 0x3E, 0x7F, 0xFE, 0x7C, 0x1F, 0x3F, 0xFF, 0x3E, 0x0F, 0x9F, 0xFF, + 0x9F, 0x8F, 0x8F, 0xFF, 0xC7, 0xC7, 0xC7, 0xFF, 0xE3, 0xE3, 0xE3, 0xFF, + 0xF1, 0xF1, 0xF1, 0xFF, 0xF8, 0xFC, 0xF8, 0xFF, 0xFC, 0x3E, 0xF8, 0x7F, + 0xFE, 0x1F, 0x7C, 0x3F, 0xFF, 0x0F, 0xBE, 0x1F, 0xFF, 0x87, 0xDF, 0x0F, + 0xFF, 0xC3, 0xFF, 0x07, 0xFF, 0xE0, 0xFF, 0x83, 0xFF, 0xF0, 0x7F, 0xC1, + 0xFF, 0xF8, 0x3F, 0xE0, 0xFF, 0xFC, 0x1F, 0xF0, 0x7F, 0xFE, 0x07, 0xF0, + 0x3F, 0xFF, 0x03, 0xF8, 0x1F, 0xC0, 0xFE, 0x00, 0x07, 0xFF, 0xF0, 0x00, + 0x7F, 0xFF, 0x80, 0x07, 0xFF, 0xF8, 0x00, 0x7F, 0xFF, 0xC0, 0x07, 0xFF, + 0xFC, 0x00, 0x7F, 0xFF, 0xE0, 0x07, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xF0, + 0x07, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xF8, 0x07, 0xFF, 0xEF, 0xC0, 0x7F, + 0xFE, 0xFE, 0x07, 0xFF, 0xE7, 0xE0, 0x7F, 0xFE, 0x7F, 0x07, 0xFF, 0xE3, + 0xF0, 0x7F, 0xFE, 0x1F, 0x87, 0xFF, 0xE1, 0xFC, 0x7F, 0xFE, 0x0F, 0xC7, + 0xFF, 0xE0, 0xFE, 0x7F, 0xFE, 0x07, 0xE7, 0xFF, 0xE0, 0x3F, 0x7F, 0xFE, + 0x03, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, 0xE0, 0x0F, + 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xE0, 0x07, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, + 0xE0, 0x03, 0xFF, 0xFE, 0x00, 0x1F, 0xFF, 0xE0, 0x00, 0xFF, 0xFE, 0x00, + 0x0F, 0xFF, 0xE0, 0x00, 0x7F, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x3F, 0xFF, + 0x80, 0x00, 0x7F, 0xFF, 0xE0, 0x00, 0x7F, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, + 0xFF, 0x00, 0x7F, 0xFF, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xF0, 0x3F, 0xC0, + 0x0F, 0xF8, 0x3F, 0xC0, 0x01, 0xFE, 0x1F, 0xC0, 0x00, 0x7F, 0x1F, 0xE0, + 0x00, 0x3F, 0xCF, 0xE0, 0x00, 0x0F, 0xE7, 0xF0, 0x00, 0x07, 0xF7, 0xF8, + 0x00, 0x03, 0xFF, 0xF8, 0x00, 0x00, 0xFF, 0xFC, 0x00, 0x00, 0x7F, 0xFE, + 0x00, 0x00, 0x3F, 0xFF, 0x00, 0x00, 0x1F, 0xFF, 0x80, 0x00, 0x0F, 0xFF, + 0xC0, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x01, 0xFF, + 0xFC, 0x00, 0x01, 0xFE, 0xFE, 0x00, 0x00, 0xFE, 0x7F, 0x00, 0x00, 0x7F, + 0x3F, 0xC0, 0x00, 0x7F, 0x8F, 0xE0, 0x00, 0x3F, 0x87, 0xF8, 0x00, 0x3F, + 0xC1, 0xFE, 0x00, 0x3F, 0xC0, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xFF, 0xFF, + 0xE0, 0x0F, 0xFF, 0xFF, 0xE0, 0x03, 0xFF, 0xFF, 0xE0, 0x00, 0xFF, 0xFF, + 0xE0, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0xFF, 0xFF, + 0xE0, 0x3F, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0xFC, 0xFF, + 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0xEF, 0xE0, 0x0F, 0xFB, 0xF8, 0x00, 0xFF, + 0xFE, 0x00, 0x1F, 0xFF, 0x80, 0x07, 0xFF, 0xE0, 0x01, 0xFF, 0xF8, 0x00, + 0x7F, 0xFE, 0x00, 0x1F, 0xFF, 0x80, 0x07, 0xFF, 0xE0, 0x03, 0xFF, 0xF8, + 0x03, 0xFE, 0xFF, 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0xF3, + 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xF8, 0x3F, 0xFF, 0xF8, 0x0F, 0xE0, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x0F, 0xE0, + 0x00, 0x03, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x0F, + 0xE0, 0x00, 0x03, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x3F, 0xFF, 0x80, 0x00, 0x7F, 0xFF, + 0xE0, 0x00, 0x7F, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, + 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xF0, 0x3F, 0xC0, 0x07, 0xF8, 0x3F, 0xC0, + 0x01, 0xFE, 0x1F, 0xC0, 0x00, 0x7F, 0x1F, 0xE0, 0x00, 0x3F, 0xCF, 0xE0, + 0x00, 0x0F, 0xE7, 0xF0, 0x00, 0x07, 0xF7, 0xF8, 0x00, 0x03, 0xFF, 0xF8, + 0x00, 0x00, 0xFF, 0xFC, 0x00, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x3F, 0xFF, + 0x00, 0x00, 0x1F, 0xFF, 0x80, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x07, 0xFF, + 0xE0, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x01, 0xFF, 0xFC, 0x00, 0x21, 0xFE, + 0xFE, 0x00, 0x38, 0xFE, 0x7F, 0x00, 0x3E, 0x7F, 0x3F, 0xC0, 0x3F, 0xFF, + 0x8F, 0xE0, 0x0F, 0xFF, 0x87, 0xF8, 0x03, 0xFF, 0xC1, 0xFE, 0x00, 0xFF, + 0xC0, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, + 0xFC, 0x03, 0xFF, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xFF, 0xC0, 0x1F, 0xFF, + 0xCF, 0xC0, 0x01, 0xFF, 0x03, 0xC0, 0x00, 0x00, 0x00, 0xC0, 0xFF, 0xFF, + 0xF8, 0x0F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFF, 0x8F, 0xFF, 0xFF, 0xF8, + 0xFF, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0xFC, 0xFE, 0x00, 0x3F, 0xEF, 0xE0, + 0x01, 0xFE, 0xFE, 0x00, 0x0F, 0xEF, 0xE0, 0x00, 0xFE, 0xFE, 0x00, 0x0F, + 0xEF, 0xE0, 0x00, 0xFE, 0xFE, 0x00, 0x0F, 0xEF, 0xE0, 0x01, 0xFC, 0xFE, + 0x00, 0x3F, 0xCF, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, + 0xC0, 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0x8F, + 0xE0, 0x07, 0xF8, 0xFE, 0x00, 0x1F, 0xCF, 0xE0, 0x01, 0xFC, 0xFE, 0x00, + 0x1F, 0xCF, 0xE0, 0x01, 0xFC, 0xFE, 0x00, 0x1F, 0xCF, 0xE0, 0x01, 0xFC, + 0xFE, 0x00, 0x1F, 0xCF, 0xE0, 0x01, 0xFC, 0xFE, 0x00, 0x1F, 0xCF, 0xE0, + 0x01, 0xFC, 0xFE, 0x00, 0x1F, 0xEF, 0xE0, 0x00, 0xFF, 0x00, 0xFF, 0xC0, + 0x00, 0x3F, 0xFF, 0x80, 0x0F, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, 0xF0, 0x3F, + 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xFC, 0x7F, 0xC0, 0xFF, 0xCF, 0xF0, 0x03, + 0xFE, 0xFE, 0x00, 0x1F, 0xEF, 0xE0, 0x00, 0xFE, 0xFE, 0x00, 0x0F, 0xEF, + 0xE0, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x0F, 0xFC, 0x00, 0x00, 0x7F, 0xFC, + 0x00, 0x07, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0xFC, 0x01, 0xFF, 0xFF, 0xF0, + 0x07, 0xFF, 0xFF, 0xC0, 0x0F, 0xFF, 0xFE, 0x00, 0x07, 0xFF, 0xE0, 0x00, + 0x03, 0xFF, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x07, + 0xFF, 0xE0, 0x00, 0x7F, 0xFE, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFF, + 0x00, 0x0F, 0xE7, 0xFC, 0x03, 0xFE, 0x7F, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, + 0xFC, 0x1F, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xF0, 0x03, 0xFF, 0xFC, 0x00, + 0x07, 0xFE, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, + 0x0F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, + 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0x7F, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, + 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, + 0xF8, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x0F, 0xE0, 0x00, + 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0xFE, 0x00, + 0x0F, 0xFF, 0xC0, 0x01, 0xFF, 0xF8, 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFF, + 0xE0, 0x00, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, + 0x7F, 0xFE, 0x00, 0x0F, 0xFF, 0xC0, 0x01, 0xFF, 0xF8, 0x00, 0x3F, 0xFF, + 0x00, 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0x80, 0x03, + 0xFF, 0xF0, 0x00, 0x7F, 0xFE, 0x00, 0x0F, 0xFF, 0xC0, 0x01, 0xFF, 0xF8, + 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFC, 0x00, 0x1F, + 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, 0x7F, 0xFE, 0x00, 0x0F, 0xFF, 0xC0, + 0x01, 0xFF, 0xFC, 0x00, 0x7F, 0xBF, 0xC0, 0x1F, 0xE7, 0xFC, 0x07, 0xFC, + 0x7F, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, + 0xFE, 0x00, 0x7F, 0xFF, 0x00, 0x01, 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x03, + 0xFF, 0xF0, 0x00, 0x1F, 0xDF, 0xC0, 0x01, 0xFC, 0xFE, 0x00, 0x0F, 0xE7, + 0xF0, 0x00, 0x7F, 0x1F, 0xC0, 0x03, 0xF0, 0xFE, 0x00, 0x3F, 0x87, 0xF0, + 0x01, 0xFC, 0x1F, 0xC0, 0x0F, 0xC0, 0xFE, 0x00, 0xFE, 0x03, 0xF0, 0x07, + 0xF0, 0x1F, 0x80, 0x3F, 0x00, 0xFE, 0x03, 0xF8, 0x03, 0xF0, 0x1F, 0xC0, + 0x1F, 0x80, 0xFC, 0x00, 0xFE, 0x07, 0xE0, 0x03, 0xF0, 0x7F, 0x00, 0x1F, + 0x83, 0xF0, 0x00, 0xFE, 0x1F, 0x80, 0x03, 0xF1, 0xF8, 0x00, 0x1F, 0x8F, + 0xC0, 0x00, 0xFC, 0x7E, 0x00, 0x03, 0xF3, 0xE0, 0x00, 0x1F, 0xBF, 0x00, + 0x00, 0xFD, 0xF8, 0x00, 0x03, 0xFF, 0x80, 0x00, 0x1F, 0xFC, 0x00, 0x00, + 0xFF, 0xE0, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0xFF, + 0x80, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0xFF, 0x00, 0x3F, 0x80, 0x1F, 0xFF, 0xE0, 0x07, 0xF0, 0x03, 0xFD, + 0xFC, 0x01, 0xFE, 0x00, 0x7F, 0x3F, 0x80, 0x3F, 0xE0, 0x0F, 0xE7, 0xF0, + 0x07, 0xFC, 0x01, 0xFC, 0x7F, 0x00, 0xFF, 0x80, 0x7F, 0x8F, 0xE0, 0x1F, + 0xF0, 0x0F, 0xE1, 0xFC, 0x07, 0xFF, 0x01, 0xFC, 0x3F, 0x80, 0xFB, 0xE0, + 0x3F, 0x83, 0xF0, 0x1F, 0x7C, 0x07, 0xE0, 0x7F, 0x03, 0xEF, 0x81, 0xFC, + 0x0F, 0xE0, 0x7D, 0xF0, 0x3F, 0x80, 0xFC, 0x1F, 0x9F, 0x07, 0xF0, 0x1F, + 0x83, 0xE3, 0xE0, 0xFC, 0x03, 0xF0, 0x7C, 0x7C, 0x1F, 0x80, 0x7F, 0x0F, + 0x8F, 0x87, 0xF0, 0x07, 0xE1, 0xF0, 0xF8, 0xFC, 0x00, 0xFC, 0x7E, 0x1F, + 0x1F, 0x80, 0x1F, 0x8F, 0x83, 0xE3, 0xF0, 0x01, 0xF9, 0xF0, 0x7C, 0x7E, + 0x00, 0x3F, 0x3E, 0x0F, 0x9F, 0x80, 0x07, 0xE7, 0xC0, 0xFB, 0xF0, 0x00, + 0xFD, 0xF0, 0x1F, 0x7E, 0x00, 0x0F, 0xBE, 0x03, 0xEF, 0xC0, 0x01, 0xFF, + 0xC0, 0x7D, 0xF0, 0x00, 0x3F, 0xF8, 0x0F, 0xFE, 0x00, 0x03, 0xFF, 0x00, + 0xFF, 0xC0, 0x00, 0x7F, 0xC0, 0x1F, 0xF0, 0x00, 0x0F, 0xF8, 0x03, 0xFE, + 0x00, 0x01, 0xFF, 0x00, 0x7F, 0xC0, 0x00, 0x1F, 0xE0, 0x07, 0xF8, 0x00, + 0x03, 0xFC, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x1F, 0xC0, 0x00, 0x07, + 0xE0, 0x03, 0xF8, 0x00, 0x7F, 0x80, 0x07, 0xF9, 0xFF, 0x00, 0x3F, 0xC3, + 0xFC, 0x00, 0xFF, 0x07, 0xF8, 0x07, 0xF8, 0x1F, 0xE0, 0x1F, 0xC0, 0x3F, + 0xC0, 0xFF, 0x00, 0xFF, 0x07, 0xF8, 0x01, 0xFE, 0x1F, 0xE0, 0x03, 0xF8, + 0xFF, 0x00, 0x0F, 0xF3, 0xF8, 0x00, 0x1F, 0xDF, 0xE0, 0x00, 0x3F, 0xFF, + 0x00, 0x00, 0xFF, 0xF8, 0x00, 0x01, 0xFF, 0xE0, 0x00, 0x07, 0xFF, 0x00, + 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0xFF, 0x80, 0x00, + 0x03, 0xFF, 0x00, 0x00, 0x1F, 0xFC, 0x00, 0x00, 0x7F, 0xF8, 0x00, 0x03, + 0xFF, 0xF0, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x7F, 0x7F, 0x80, 0x03, 0xF8, + 0xFF, 0x00, 0x1F, 0xE1, 0xFC, 0x00, 0x7F, 0x07, 0xF8, 0x03, 0xFC, 0x0F, + 0xF0, 0x1F, 0xE0, 0x3F, 0xC0, 0x7F, 0x80, 0x7F, 0x83, 0xFC, 0x01, 0xFE, + 0x0F, 0xF0, 0x03, 0xFC, 0x7F, 0x80, 0x0F, 0xFB, 0xFE, 0x00, 0x1F, 0xE0, + 0xFF, 0x00, 0x07, 0xFF, 0xF8, 0x00, 0x7F, 0x9F, 0xE0, 0x03, 0xFC, 0xFF, + 0x00, 0x3F, 0xC3, 0xFC, 0x01, 0xFE, 0x0F, 0xE0, 0x0F, 0xE0, 0x7F, 0x00, + 0xFF, 0x01, 0xFC, 0x07, 0xF0, 0x0F, 0xE0, 0x7F, 0x80, 0x3F, 0x83, 0xF8, + 0x01, 0xFC, 0x3F, 0xC0, 0x07, 0xF1, 0xFC, 0x00, 0x3F, 0x8F, 0xE0, 0x00, + 0xFE, 0xFE, 0x00, 0x07, 0xF7, 0xF0, 0x00, 0x1F, 0xFF, 0x00, 0x00, 0xFF, + 0xF8, 0x00, 0x03, 0xFF, 0x80, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x7F, 0xC0, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x0F, 0xE0, + 0x00, 0x00, 0x7F, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x1F, 0xC0, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, + 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, + 0x80, 0x00, 0x3F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x03, + 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x3F, 0xC0, 0x00, + 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x03, 0xFE, 0x00, + 0x00, 0xFF, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, + 0x00, 0x0F, 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFC, 0x3F, 0x87, 0xF0, 0xFE, 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, + 0xE1, 0xFC, 0x3F, 0x87, 0xF0, 0xFE, 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, + 0xFC, 0x3F, 0x87, 0xF0, 0xFE, 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, 0xFC, + 0x3F, 0x87, 0xF0, 0xFE, 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, 0xFC, 0x3F, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0xE0, 0x03, 0xC0, 0x07, 0x00, + 0x1C, 0x00, 0x78, 0x00, 0xE0, 0x03, 0x80, 0x0F, 0x00, 0x1C, 0x00, 0x70, + 0x01, 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x38, 0x00, 0x70, 0x01, 0xC0, 0x07, + 0x00, 0x0E, 0x00, 0x38, 0x00, 0xE0, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, + 0x78, 0x00, 0xE0, 0x03, 0x80, 0x0F, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xE0, + 0x03, 0x80, 0x0E, 0x00, 0x3C, 0x00, 0x70, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFE, 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, 0xFC, 0x3F, 0x87, 0xF0, + 0xFE, 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, 0xFC, 0x3F, 0x87, 0xF0, 0xFE, + 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, 0xFC, 0x3F, 0x87, 0xF0, 0xFE, 0x1F, + 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, 0xFC, 0x3F, 0x87, 0xF0, 0xFE, 0x1F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xF0, + 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0x80, 0x03, 0xFE, 0x00, 0x0F, 0xFC, 0x00, + 0x7D, 0xF0, 0x01, 0xF7, 0xC0, 0x0F, 0xDF, 0x80, 0x3E, 0x3E, 0x00, 0xF8, + 0xFC, 0x07, 0xE1, 0xF0, 0x1F, 0x07, 0xC0, 0xFC, 0x1F, 0x83, 0xE0, 0x3E, + 0x0F, 0x80, 0xFC, 0x7E, 0x01, 0xF1, 0xF0, 0x07, 0xC7, 0xC0, 0x1F, 0xBE, + 0x00, 0x3E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x3E, 0x0F, 0x83, 0xC0, 0xF0, 0x38, 0x1E, + 0x01, 0xFF, 0x00, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, + 0x7F, 0xFF, 0xF8, 0x7F, 0xFF, 0xFC, 0x7F, 0x03, 0xFC, 0x7E, 0x01, 0xFC, + 0x00, 0x01, 0xFC, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xFC, 0x03, 0xFF, 0xFC, + 0x1F, 0xFF, 0xFC, 0x3F, 0xFF, 0xFC, 0x7F, 0xC1, 0xFC, 0xFF, 0x01, 0xFC, + 0xFE, 0x01, 0xFC, 0xFE, 0x03, 0xFC, 0xFE, 0x03, 0xFC, 0xFF, 0x07, 0xFC, + 0xFF, 0xFF, 0xFC, 0x7F, 0xFF, 0xFC, 0x7F, 0xFF, 0xFC, 0x3F, 0xFD, 0xFE, + 0x1F, 0xF0, 0xFF, 0x07, 0xE0, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x3F, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0x00, + 0x03, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x0F, + 0xC0, 0x3F, 0x9F, 0xF8, 0x1F, 0xDF, 0xFF, 0x0F, 0xFF, 0xFF, 0xC7, 0xFF, + 0xFF, 0xE3, 0xFF, 0xFF, 0xF9, 0xFF, 0x83, 0xFE, 0xFF, 0x80, 0xFF, 0x7F, + 0x80, 0x3F, 0xBF, 0xC0, 0x1F, 0xFF, 0xC0, 0x07, 0xFF, 0xE0, 0x03, 0xFF, + 0xF0, 0x01, 0xFF, 0xF8, 0x00, 0xFF, 0xFC, 0x00, 0x7F, 0xFE, 0x00, 0x3F, + 0xFF, 0x80, 0x3F, 0xFF, 0xC0, 0x1F, 0xDF, 0xF0, 0x1F, 0xEF, 0xFC, 0x1F, + 0xF7, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xF1, 0xFF, 0xFF, 0xF8, 0xFE, 0xFF, + 0xF8, 0x7F, 0x3F, 0xF0, 0x00, 0x07, 0xE0, 0x00, 0x00, 0xFF, 0x00, 0x07, + 0xFF, 0xC0, 0x3F, 0xFF, 0xC0, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xC7, 0xFF, + 0xFF, 0x9F, 0xF0, 0x7F, 0xBF, 0xC0, 0x7F, 0x7F, 0x00, 0x7F, 0xFC, 0x00, + 0x03, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, + 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0xFD, + 0xFE, 0x03, 0xFB, 0xFE, 0x0F, 0xF3, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0x87, + 0xFF, 0xFE, 0x07, 0xFF, 0xF8, 0x03, 0xFF, 0xE0, 0x01, 0xFE, 0x00, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, + 0x00, 0x03, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x3F, 0x80, 0x7E, 0x1F, 0xC0, 0xFF, 0xCF, 0xE1, 0xFF, 0xF7, + 0xF1, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFE, 0xFF, 0x83, + 0xFF, 0x7F, 0x80, 0xFF, 0xBF, 0x80, 0x3F, 0xFF, 0xC0, 0x1F, 0xFF, 0xC0, + 0x07, 0xFF, 0xE0, 0x03, 0xFF, 0xF0, 0x01, 0xFF, 0xF8, 0x00, 0xFF, 0xFC, + 0x00, 0x7F, 0xFE, 0x00, 0x3F, 0xFF, 0x80, 0x3F, 0xDF, 0xC0, 0x1F, 0xEF, + 0xF0, 0x1F, 0xF7, 0xFC, 0x1F, 0xF9, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFE, + 0x3F, 0xFF, 0xFF, 0x0F, 0xFF, 0xBF, 0x81, 0xFF, 0x9F, 0xC0, 0x3F, 0x00, + 0x00, 0x00, 0xFE, 0x00, 0x03, 0xFF, 0x80, 0x0F, 0xFF, 0xE0, 0x1F, 0xFF, + 0xF0, 0x3F, 0xFF, 0xF8, 0x3F, 0xC3, 0xF8, 0x7F, 0x80, 0xFC, 0x7F, 0x00, + 0xFC, 0x7F, 0x00, 0x7C, 0xFE, 0x00, 0x7E, 0xFE, 0x00, 0x7E, 0xFF, 0xFF, + 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xFE, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x7F, 0x7F, 0x00, + 0xFE, 0x3F, 0xC1, 0xFE, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, 0xF8, 0x0F, 0xFF, + 0xF0, 0x03, 0xFF, 0xC0, 0x00, 0xFF, 0x00, 0x01, 0xFC, 0x1F, 0xF0, 0xFF, + 0xC3, 0xFF, 0x1F, 0xFC, 0x7F, 0x81, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, + 0x0F, 0xFF, 0xBF, 0xFE, 0xFF, 0xFB, 0xFF, 0xE1, 0xFC, 0x07, 0xF0, 0x1F, + 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, + 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, + 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x00, 0x00, 0xF8, 0x7F, 0x07, 0xFE, + 0x7F, 0x0F, 0xFF, 0x7F, 0x1F, 0xFF, 0x7F, 0x3F, 0xFF, 0xFF, 0x3F, 0xFF, + 0xFF, 0x7F, 0xC3, 0xFF, 0x7F, 0x81, 0xFF, 0x7F, 0x00, 0xFF, 0xFF, 0x00, + 0xFF, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, + 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0xFF, 0xFF, 0x00, + 0xFF, 0x7F, 0x81, 0xFF, 0x7F, 0xC3, 0xFF, 0x3F, 0xFF, 0xFF, 0x3F, 0xFF, + 0xFF, 0x1F, 0xFF, 0xFF, 0x0F, 0xFF, 0x7F, 0x07, 0xFE, 0x7F, 0x01, 0xF8, + 0x7F, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0x7F, 0x00, + 0xFF, 0x7F, 0x01, 0xFE, 0x7F, 0xC3, 0xFE, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, + 0xF8, 0x0F, 0xFF, 0xE0, 0x01, 0xFF, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, + 0x03, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, + 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x3F, 0x83, + 0xF8, 0xFF, 0xC7, 0xF7, 0xFF, 0xCF, 0xEF, 0xFF, 0xDF, 0xFF, 0xFF, 0xBF, + 0xFF, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0x01, 0xFF, 0xFE, 0x01, 0xFF, 0xF8, + 0x03, 0xFF, 0xF0, 0x07, 0xFF, 0xE0, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, + 0x3F, 0xFF, 0x00, 0x7F, 0xFE, 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x03, + 0xFF, 0xF0, 0x07, 0xFF, 0xE0, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x3F, + 0xFF, 0x00, 0x7F, 0xFE, 0x00, 0xFF, 0xFC, 0x01, 0xFC, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xC0, 0x00, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFC, 0x1F, 0xC7, 0xF1, 0xFC, 0x7F, 0x1F, 0xC7, 0xF0, 0x00, + 0x00, 0x00, 0x07, 0xF1, 0xFC, 0x7F, 0x1F, 0xC7, 0xF1, 0xFC, 0x7F, 0x1F, + 0xC7, 0xF1, 0xFC, 0x7F, 0x1F, 0xC7, 0xF1, 0xFC, 0x7F, 0x1F, 0xC7, 0xF1, + 0xFC, 0x7F, 0x1F, 0xC7, 0xF1, 0xFC, 0x7F, 0x1F, 0xC7, 0xF1, 0xFC, 0x7F, + 0x1F, 0xC7, 0xF1, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFB, 0xFE, 0xFE, 0x00, + 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x03, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, + 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFE, + 0x00, 0x01, 0xFC, 0x03, 0xFB, 0xF8, 0x0F, 0xE7, 0xF0, 0x3F, 0xCF, 0xE0, + 0xFF, 0x1F, 0xC3, 0xFC, 0x3F, 0x87, 0xF0, 0x7F, 0x1F, 0xC0, 0xFE, 0x7F, + 0x01, 0xFD, 0xFC, 0x03, 0xFF, 0xF0, 0x07, 0xFF, 0xF0, 0x0F, 0xFF, 0xE0, + 0x1F, 0xFF, 0xE0, 0x3F, 0xFF, 0xE0, 0x7F, 0xDF, 0xC0, 0xFF, 0x3F, 0xC1, + 0xFC, 0x3F, 0x83, 0xF8, 0x3F, 0x87, 0xF0, 0x7F, 0x8F, 0xE0, 0x7F, 0x1F, + 0xC0, 0xFF, 0x3F, 0x80, 0xFE, 0x7F, 0x01, 0xFE, 0xFE, 0x01, 0xFD, 0xFC, + 0x03, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFE, 0x1F, 0x80, 0x7E, + 0x0F, 0xE7, 0xFE, 0x1F, 0xF8, 0xFE, 0xFF, 0xF3, 0xFF, 0xCF, 0xFF, 0xFF, + 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0x83, 0xFF, 0x0F, 0xFF, 0xF0, 0x1F, 0xE0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, + 0xFF, 0xE0, 0x1F, 0xC0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, 0xFF, 0xE0, 0x1F, + 0xC0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, 0xFF, 0xE0, 0x1F, 0xC0, 0x7F, 0xFE, + 0x01, 0xFC, 0x07, 0xFF, 0xE0, 0x1F, 0xC0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, + 0xFF, 0xE0, 0x1F, 0xC0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, 0xFF, 0xE0, 0x1F, + 0xC0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, 0xFF, 0xE0, 0x1F, 0xC0, 0x7F, 0xFE, + 0x01, 0xFC, 0x07, 0xFF, 0xE0, 0x1F, 0xC0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, + 0xF0, 0xFE, 0x1F, 0xC1, 0xFC, 0xFF, 0xE3, 0xFB, 0xFF, 0xE7, 0xFF, 0xFF, + 0xEF, 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0x80, 0xFF, + 0xFE, 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x03, 0xFF, 0xF0, 0x07, 0xFF, + 0xE0, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x3F, 0xFF, 0x00, 0x7F, 0xFE, + 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x03, 0xFF, 0xF0, 0x07, 0xFF, 0xE0, + 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x3F, 0xFF, 0x00, 0x7F, 0xFE, 0x00, + 0xFE, 0x00, 0x7F, 0x80, 0x01, 0xFF, 0xF0, 0x01, 0xFF, 0xFE, 0x01, 0xFF, + 0xFF, 0x81, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xF1, 0xFF, 0x07, 0xFC, 0xFF, + 0x01, 0xFE, 0x7F, 0x00, 0x7F, 0x7F, 0x80, 0x3F, 0xFF, 0x80, 0x0F, 0xFF, + 0xC0, 0x07, 0xFF, 0xE0, 0x03, 0xFF, 0xF0, 0x01, 0xFF, 0xF8, 0x00, 0xFF, + 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x7F, 0xBF, 0x80, 0x3F, 0x9F, 0xE0, 0x3F, + 0xCF, 0xF8, 0x3F, 0xE3, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xF0, 0x3F, 0xFF, + 0xF0, 0x0F, 0xFF, 0xF0, 0x03, 0xFF, 0xE0, 0x00, 0x3F, 0xC0, 0x00, 0xFE, + 0x1F, 0x80, 0x7F, 0x3F, 0xF0, 0x3F, 0xBF, 0xFE, 0x1F, 0xDF, 0xFF, 0x8F, + 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0xF3, 0xFF, 0x07, 0xFD, 0xFF, 0x01, 0xFE, + 0xFF, 0x00, 0x7F, 0x7F, 0x80, 0x3F, 0xFF, 0x80, 0x0F, 0xFF, 0xC0, 0x07, + 0xFF, 0xE0, 0x03, 0xFF, 0xF0, 0x01, 0xFF, 0xF8, 0x00, 0xFF, 0xFC, 0x00, + 0x7F, 0xFF, 0x00, 0x7F, 0xFF, 0x80, 0x3F, 0xBF, 0xE0, 0x3F, 0xDF, 0xF8, + 0x3F, 0xCF, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xE3, 0xFB, 0xFF, 0xE1, 0xFD, + 0xFF, 0xF0, 0xFE, 0x7F, 0xE0, 0x7F, 0x0F, 0xC0, 0x3F, 0x80, 0x00, 0x1F, + 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x1F, 0xC0, 0x00, 0x00, 0x00, 0xFC, 0x3F, 0x81, 0xFF, 0x9F, 0xC3, 0xFF, + 0xEF, 0xE1, 0xFF, 0xF7, 0xF1, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, 0xFD, 0xFF, + 0x07, 0xFE, 0xFF, 0x01, 0xFF, 0x7F, 0x00, 0x7F, 0xFF, 0x80, 0x3F, 0xFF, + 0x80, 0x0F, 0xFF, 0xC0, 0x07, 0xFF, 0xE0, 0x03, 0xFF, 0xF0, 0x01, 0xFF, + 0xF8, 0x00, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x7F, 0xBF, 0x80, 0x3F, + 0xDF, 0xE0, 0x3F, 0xEF, 0xF8, 0x3F, 0xF3, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, + 0xFC, 0x7F, 0xFE, 0xFE, 0x1F, 0xFF, 0x7F, 0x03, 0xFF, 0x3F, 0x80, 0x7E, + 0x1F, 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, 0x00, + 0x01, 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0x80, + 0x00, 0x1F, 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0xFE, 0x1F, 0xFC, + 0x7F, 0xFB, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x7F, 0x80, + 0xFF, 0x01, 0xFC, 0x03, 0xF8, 0x07, 0xF0, 0x0F, 0xE0, 0x1F, 0xC0, 0x3F, + 0x80, 0x7F, 0x00, 0xFE, 0x01, 0xFC, 0x03, 0xF8, 0x07, 0xF0, 0x0F, 0xE0, + 0x1F, 0xC0, 0x3F, 0x80, 0x7F, 0x00, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x07, + 0xFF, 0xE0, 0x0F, 0xFF, 0xF8, 0x1F, 0xFF, 0xFC, 0x3F, 0xFF, 0xFC, 0x7F, + 0x81, 0xFE, 0x7F, 0x00, 0xFE, 0x7F, 0x00, 0xFE, 0x7F, 0xC0, 0x00, 0x7F, + 0xFC, 0x00, 0x7F, 0xFF, 0x80, 0x3F, 0xFF, 0xF0, 0x1F, 0xFF, 0xFC, 0x07, + 0xFF, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x0F, 0xFF, 0x00, 0x01, 0xFF, 0x00, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0x7F, 0x00, 0x7F, 0x7F, 0x81, 0xFE, 0x7F, + 0xFF, 0xFE, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, 0xF8, 0x0F, 0xFF, 0xF0, 0x01, + 0xFF, 0x80, 0x3F, 0x83, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, + 0x8F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF3, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, + 0x83, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, + 0x83, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, 0x83, 0xFF, 0x3F, 0xF1, 0xFF, 0x0F, + 0xF0, 0x7F, 0xFE, 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x03, 0xFF, 0xF0, + 0x07, 0xFF, 0xE0, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x3F, 0xFF, 0x00, + 0x7F, 0xFE, 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x03, 0xFF, 0xF0, 0x07, + 0xFF, 0xE0, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x3F, 0xFF, 0x00, 0x7F, + 0xFE, 0x00, 0xFF, 0xFC, 0x03, 0xFF, 0xFC, 0x07, 0xFF, 0xFC, 0x3F, 0xFF, + 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xDF, 0xFF, 0xBF, 0x9F, 0xFF, 0x7F, 0x1F, + 0xFC, 0xFE, 0x0F, 0xE0, 0x00, 0x7F, 0x00, 0x3F, 0xBF, 0x80, 0x1F, 0x9F, + 0xC0, 0x1F, 0xC7, 0xE0, 0x0F, 0xE3, 0xF8, 0x07, 0xE1, 0xFC, 0x07, 0xF0, + 0x7E, 0x03, 0xF8, 0x3F, 0x81, 0xF8, 0x1F, 0xC0, 0xFC, 0x07, 0xE0, 0xFE, + 0x03, 0xF8, 0x7E, 0x00, 0xFC, 0x3F, 0x00, 0x7E, 0x1F, 0x80, 0x3F, 0x1F, + 0x80, 0x0F, 0xCF, 0xC0, 0x07, 0xE7, 0xE0, 0x03, 0xF7, 0xE0, 0x00, 0xFF, + 0xF0, 0x00, 0x7F, 0xF8, 0x00, 0x3F, 0xF8, 0x00, 0x0F, 0xFC, 0x00, 0x07, + 0xFE, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0xFC, 0x03, 0xF8, 0x0F, 0xFF, 0xC0, 0x7F, 0x01, 0xFF, 0xF8, 0x0F, 0xE0, + 0x3F, 0x3F, 0x03, 0xFE, 0x07, 0xE7, 0xE0, 0x7F, 0xC1, 0xFC, 0xFE, 0x0F, + 0xF8, 0x3F, 0x9F, 0xC1, 0xFF, 0x07, 0xE1, 0xF8, 0x3D, 0xE0, 0xFC, 0x3F, + 0x0F, 0xBE, 0x3F, 0x87, 0xF1, 0xF7, 0xC7, 0xE0, 0x7E, 0x3E, 0xF8, 0xFC, + 0x0F, 0xC7, 0xDF, 0x1F, 0x81, 0xF9, 0xF1, 0xE3, 0xF0, 0x3F, 0x3E, 0x3E, + 0xFC, 0x03, 0xF7, 0xC7, 0xDF, 0x80, 0x7E, 0xF8, 0xFB, 0xF0, 0x0F, 0xDE, + 0x1F, 0x7C, 0x00, 0xFF, 0xC1, 0xFF, 0x80, 0x1F, 0xF8, 0x3F, 0xF0, 0x03, + 0xFF, 0x07, 0xFE, 0x00, 0x7F, 0xC0, 0xFF, 0x80, 0x07, 0xF8, 0x1F, 0xF0, + 0x00, 0xFF, 0x01, 0xFE, 0x00, 0x1F, 0xE0, 0x3F, 0x80, 0x01, 0xFC, 0x07, + 0xF0, 0x00, 0xFF, 0x00, 0xFF, 0x7F, 0x81, 0xFE, 0x3F, 0x81, 0xFC, 0x3F, + 0xC3, 0xFC, 0x1F, 0xC3, 0xF8, 0x0F, 0xE7, 0xF0, 0x0F, 0xEF, 0xF0, 0x07, + 0xFF, 0xE0, 0x03, 0xFF, 0xC0, 0x03, 0xFF, 0xC0, 0x01, 0xFF, 0x80, 0x00, + 0xFF, 0x00, 0x00, 0xFF, 0x00, 0x01, 0xFF, 0x00, 0x01, 0xFF, 0x80, 0x03, + 0xFF, 0xC0, 0x07, 0xFF, 0xC0, 0x07, 0xFF, 0xE0, 0x0F, 0xE7, 0xF0, 0x1F, + 0xE7, 0xF0, 0x1F, 0xC3, 0xF8, 0x3F, 0xC3, 0xFC, 0x7F, 0x81, 0xFC, 0x7F, + 0x01, 0xFE, 0xFF, 0x00, 0xFF, 0x7F, 0x00, 0x3F, 0xBF, 0x80, 0x1F, 0xDF, + 0xC0, 0x0F, 0xC7, 0xF0, 0x07, 0xE3, 0xF8, 0x07, 0xF1, 0xFC, 0x03, 0xF0, + 0x7F, 0x01, 0xF8, 0x3F, 0x81, 0xFC, 0x0F, 0xC0, 0xFC, 0x07, 0xF0, 0x7E, + 0x03, 0xF8, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0x7E, 0x1F, 0x80, 0x3F, 0x8F, + 0xC0, 0x0F, 0xCF, 0xC0, 0x07, 0xE7, 0xE0, 0x03, 0xFB, 0xF0, 0x00, 0xFD, + 0xF0, 0x00, 0x7F, 0xF8, 0x00, 0x3F, 0xFC, 0x00, 0x0F, 0xFC, 0x00, 0x07, + 0xFE, 0x00, 0x03, 0xFF, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, 0x80, 0x00, + 0x1F, 0xC0, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03, 0xF0, 0x00, + 0x03, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x1F, 0xF8, 0x00, 0x0F, 0xFC, 0x00, + 0x07, 0xFC, 0x00, 0x03, 0xFC, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x7F, 0xFF, + 0xFB, 0xFF, 0xFF, 0xDF, 0xFF, 0xFE, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xBF, + 0xFF, 0xFC, 0x00, 0x3F, 0xE0, 0x03, 0xFE, 0x00, 0x1F, 0xE0, 0x01, 0xFE, + 0x00, 0x1F, 0xE0, 0x01, 0xFE, 0x00, 0x1F, 0xE0, 0x01, 0xFE, 0x00, 0x1F, + 0xE0, 0x01, 0xFE, 0x00, 0x1F, 0xE0, 0x01, 0xFE, 0x00, 0x1F, 0xE0, 0x01, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xF8, 0x01, 0xF8, 0x1F, 0xC1, 0xFE, 0x0F, 0xF0, 0xFF, + 0x87, 0xE0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x00, + 0xF8, 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x3F, + 0x0F, 0xF0, 0x7F, 0x03, 0xF8, 0x1F, 0xE0, 0x1F, 0x80, 0x7C, 0x03, 0xE0, + 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, + 0xE0, 0x1F, 0x00, 0xF8, 0x07, 0xE0, 0x3F, 0xE0, 0xFF, 0x07, 0xF8, 0x1F, + 0xC0, 0x7E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFC, 0x07, 0xF0, 0x3F, 0xC1, 0xFE, 0x0F, 0xF8, 0x0F, 0xC0, 0x3E, 0x01, + 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x3E, + 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x80, 0x7F, 0x81, 0xFC, + 0x0F, 0xE0, 0xFF, 0x0F, 0xC0, 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x07, + 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0xF8, + 0x0F, 0xC3, 0xFE, 0x1F, 0xE0, 0xFF, 0x07, 0xF0, 0x3F, 0x00, 0x1F, 0x00, + 0x03, 0xFE, 0x00, 0x1F, 0xF8, 0x0F, 0xFF, 0xF0, 0xFF, 0x0F, 0xFF, 0xF0, + 0x1F, 0xF8, 0x00, 0x7F, 0x80, 0x00, 0xF8 }; + +const GFXglyph FreeSansBold24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 13, 0, 1 }, // 0x20 ' ' + { 0, 7, 34, 16, 5, -33 }, // 0x21 '!' + { 30, 18, 12, 22, 2, -33 }, // 0x22 '"' + { 57, 26, 33, 26, 0, -31 }, // 0x23 '#' + { 165, 25, 40, 26, 1, -34 }, // 0x24 '$' + { 290, 39, 34, 42, 1, -32 }, // 0x25 '%' + { 456, 30, 35, 34, 3, -33 }, // 0x26 '&' + { 588, 7, 12, 12, 3, -33 }, // 0x27 ''' + { 599, 13, 44, 16, 2, -33 }, // 0x28 '(' + { 671, 13, 44, 16, 1, -33 }, // 0x29 ')' + { 743, 15, 15, 18, 1, -33 }, // 0x2A '*' + { 772, 23, 22, 27, 2, -21 }, // 0x2B '+' + { 836, 7, 15, 12, 2, -6 }, // 0x2C ',' + { 850, 13, 6, 16, 1, -15 }, // 0x2D '-' + { 860, 7, 7, 12, 2, -6 }, // 0x2E '.' + { 867, 13, 34, 13, 0, -32 }, // 0x2F '/' + { 923, 24, 35, 26, 1, -33 }, // 0x30 '0' + { 1028, 14, 33, 26, 4, -32 }, // 0x31 '1' + { 1086, 23, 34, 26, 2, -33 }, // 0x32 '2' + { 1184, 23, 35, 26, 2, -33 }, // 0x33 '3' + { 1285, 22, 33, 26, 2, -32 }, // 0x34 '4' + { 1376, 23, 34, 26, 2, -32 }, // 0x35 '5' + { 1474, 23, 35, 26, 2, -33 }, // 0x36 '6' + { 1575, 23, 33, 26, 1, -32 }, // 0x37 '7' + { 1670, 24, 35, 26, 1, -33 }, // 0x38 '8' + { 1775, 24, 35, 26, 1, -33 }, // 0x39 '9' + { 1880, 7, 25, 12, 2, -24 }, // 0x3A ':' + { 1902, 7, 33, 12, 2, -24 }, // 0x3B ';' + { 1931, 23, 23, 27, 2, -22 }, // 0x3C '<' + { 1998, 23, 18, 27, 2, -19 }, // 0x3D '=' + { 2050, 23, 23, 27, 2, -22 }, // 0x3E '>' + { 2117, 24, 35, 29, 3, -34 }, // 0x3F '?' + { 2222, 43, 41, 46, 1, -34 }, // 0x40 '@' + { 2443, 32, 34, 33, 0, -33 }, // 0x41 'A' + { 2579, 27, 34, 33, 4, -33 }, // 0x42 'B' + { 2694, 30, 36, 34, 2, -34 }, // 0x43 'C' + { 2829, 28, 34, 34, 4, -33 }, // 0x44 'D' + { 2948, 25, 34, 31, 4, -33 }, // 0x45 'E' + { 3055, 24, 34, 30, 4, -33 }, // 0x46 'F' + { 3157, 31, 36, 36, 2, -34 }, // 0x47 'G' + { 3297, 27, 34, 35, 4, -33 }, // 0x48 'H' + { 3412, 7, 34, 15, 4, -33 }, // 0x49 'I' + { 3442, 22, 35, 27, 1, -33 }, // 0x4A 'J' + { 3539, 30, 34, 34, 4, -33 }, // 0x4B 'K' + { 3667, 23, 34, 29, 4, -33 }, // 0x4C 'L' + { 3765, 33, 34, 41, 4, -33 }, // 0x4D 'M' + { 3906, 28, 34, 35, 4, -33 }, // 0x4E 'N' + { 4025, 33, 36, 37, 2, -34 }, // 0x4F 'O' + { 4174, 26, 34, 32, 4, -33 }, // 0x50 'P' + { 4285, 33, 37, 37, 2, -34 }, // 0x51 'Q' + { 4438, 28, 34, 34, 4, -33 }, // 0x52 'R' + { 4557, 28, 36, 32, 2, -34 }, // 0x53 'S' + { 4683, 27, 34, 30, 2, -33 }, // 0x54 'T' + { 4798, 27, 35, 35, 4, -33 }, // 0x55 'U' + { 4917, 29, 34, 31, 1, -33 }, // 0x56 'V' + { 5041, 43, 34, 45, 1, -33 }, // 0x57 'W' + { 5224, 30, 34, 32, 1, -33 }, // 0x58 'X' + { 5352, 29, 34, 30, 1, -33 }, // 0x59 'Y' + { 5476, 26, 34, 29, 1, -33 }, // 0x5A 'Z' + { 5587, 11, 43, 16, 3, -33 }, // 0x5B '[' + { 5647, 14, 34, 13, -1, -32 }, // 0x5C '\' + { 5707, 11, 43, 16, 1, -33 }, // 0x5D ']' + { 5767, 22, 20, 27, 3, -32 }, // 0x5E '^' + { 5822, 28, 4, 26, -1, 6 }, // 0x5F '_' + { 5836, 9, 7, 12, 1, -35 }, // 0x60 '`' + { 5844, 24, 26, 27, 2, -24 }, // 0x61 'a' + { 5922, 25, 35, 29, 3, -33 }, // 0x62 'b' + { 6032, 23, 26, 26, 2, -24 }, // 0x63 'c' + { 6107, 25, 35, 29, 2, -33 }, // 0x64 'd' + { 6217, 24, 26, 27, 2, -24 }, // 0x65 'e' + { 6295, 14, 34, 16, 1, -33 }, // 0x66 'f' + { 6355, 24, 36, 29, 2, -24 }, // 0x67 'g' + { 6463, 23, 34, 28, 3, -33 }, // 0x68 'h' + { 6561, 7, 34, 13, 3, -33 }, // 0x69 'i' + { 6591, 10, 45, 13, 0, -33 }, // 0x6A 'j' + { 6648, 23, 34, 27, 3, -33 }, // 0x6B 'k' + { 6746, 7, 34, 13, 3, -33 }, // 0x6C 'l' + { 6776, 36, 25, 42, 3, -24 }, // 0x6D 'm' + { 6889, 23, 25, 29, 3, -24 }, // 0x6E 'n' + { 6961, 25, 26, 29, 2, -24 }, // 0x6F 'o' + { 7043, 25, 36, 29, 3, -24 }, // 0x70 'p' + { 7156, 25, 36, 29, 2, -24 }, // 0x71 'q' + { 7269, 15, 25, 18, 3, -24 }, // 0x72 'r' + { 7316, 24, 26, 26, 1, -24 }, // 0x73 's' + { 7394, 12, 32, 16, 2, -30 }, // 0x74 't' + { 7442, 23, 26, 29, 3, -24 }, // 0x75 'u' + { 7517, 25, 25, 25, 0, -24 }, // 0x76 'v' + { 7596, 35, 25, 37, 1, -24 }, // 0x77 'w' + { 7706, 24, 25, 26, 1, -24 }, // 0x78 'x' + { 7781, 25, 36, 26, 0, -24 }, // 0x79 'y' + { 7894, 21, 25, 24, 1, -24 }, // 0x7A 'z' + { 7960, 13, 43, 18, 2, -33 }, // 0x7B '{' + { 8030, 4, 44, 13, 5, -33 }, // 0x7C '|' + { 8052, 13, 43, 18, 3, -33 }, // 0x7D '}' + { 8122, 21, 8, 23, 1, -14 } }; // 0x7E '~' + +const GFXfont FreeSansBold24pt7b PROGMEM = { + (uint8_t *)FreeSansBold24pt7bBitmaps, + (GFXglyph *)FreeSansBold24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 8815 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBold9pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBold9pt7b.h new file mode 100644 index 0000000..aeea463 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBold9pt7b.h @@ -0,0 +1,208 @@ +const uint8_t FreeSansBold9pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFE, 0x48, 0x7E, 0xEF, 0xDF, 0xBF, 0x74, 0x40, 0x19, 0x86, + 0x67, 0xFD, 0xFF, 0x33, 0x0C, 0xC3, 0x33, 0xFE, 0xFF, 0x99, 0x86, 0x61, + 0x90, 0x10, 0x1F, 0x1F, 0xDE, 0xFF, 0x3F, 0x83, 0xC0, 0xFC, 0x1F, 0x09, + 0xFC, 0xFE, 0xF7, 0xF1, 0xE0, 0x40, 0x38, 0x10, 0x7C, 0x30, 0xC6, 0x20, + 0xC6, 0x40, 0xC6, 0x40, 0x7C, 0x80, 0x39, 0x9C, 0x01, 0x3E, 0x03, 0x63, + 0x02, 0x63, 0x04, 0x63, 0x0C, 0x3E, 0x08, 0x1C, 0x0E, 0x01, 0xF8, 0x3B, + 0x83, 0xB8, 0x3F, 0x01, 0xE0, 0x3E, 0x67, 0x76, 0xE3, 0xEE, 0x1C, 0xF3, + 0xC7, 0xFE, 0x3F, 0x70, 0xFF, 0xF4, 0x18, 0x63, 0x1C, 0x73, 0x8E, 0x38, + 0xE3, 0x8E, 0x18, 0x70, 0xC3, 0x06, 0x08, 0x61, 0x83, 0x0E, 0x38, 0x71, + 0xC7, 0x1C, 0x71, 0xC6, 0x38, 0xE3, 0x18, 0x40, 0x21, 0x3E, 0x45, 0x28, + 0x38, 0x70, 0xE7, 0xFF, 0xE7, 0x0E, 0x1C, 0xFC, 0x9C, 0xFF, 0xC0, 0xFC, + 0x08, 0xC4, 0x23, 0x10, 0x84, 0x62, 0x11, 0x88, 0x00, 0x3E, 0x3F, 0x9D, + 0xDC, 0x7E, 0x3F, 0x1F, 0x8F, 0xC7, 0xE3, 0xF1, 0xDD, 0xCF, 0xE3, 0xE0, + 0x08, 0xFF, 0xF3, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x80, 0x3E, 0x3F, 0xB8, + 0xFC, 0x70, 0x38, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x0F, 0xF7, 0xF8, + 0x3C, 0x7F, 0xE7, 0xE7, 0x07, 0x0C, 0x0E, 0x07, 0x07, 0xE7, 0xE7, 0x7E, + 0x3C, 0x0E, 0x1E, 0x1E, 0x2E, 0x2E, 0x4E, 0x4E, 0x8E, 0xFF, 0xFF, 0x0E, + 0x0E, 0x0E, 0x7F, 0x3F, 0x90, 0x18, 0x0D, 0xE7, 0xFB, 0x9E, 0x07, 0x03, + 0x81, 0xF1, 0xFF, 0xE7, 0xC0, 0x3E, 0x3F, 0x9C, 0xFC, 0x0E, 0xE7, 0xFB, + 0xDF, 0xC7, 0xE3, 0xF1, 0xDD, 0xEF, 0xE3, 0xE0, 0xFF, 0xFF, 0xC0, 0xE0, + 0xE0, 0x60, 0x70, 0x30, 0x38, 0x1C, 0x0C, 0x0E, 0x07, 0x03, 0x80, 0x3F, + 0x1F, 0xEE, 0x3F, 0x87, 0xE3, 0xCF, 0xC7, 0xFB, 0xCF, 0xE1, 0xF8, 0x7F, + 0x3D, 0xFE, 0x3F, 0x00, 0x3E, 0x3F, 0xBD, 0xDC, 0x7E, 0x3F, 0x1F, 0xDE, + 0xFF, 0x3B, 0x81, 0xF9, 0xCF, 0xE3, 0xC0, 0xFC, 0x00, 0x07, 0xE0, 0xFC, + 0x00, 0x07, 0xE5, 0xE0, 0x00, 0x83, 0xC7, 0xDF, 0x0C, 0x07, 0x80, 0xF8, + 0x1F, 0x01, 0x80, 0xFF, 0xFF, 0xC0, 0x00, 0x0F, 0xFF, 0xFC, 0x00, 0x70, + 0x3F, 0x03, 0xE0, 0x38, 0x7D, 0xF1, 0xE0, 0x80, 0x00, 0x3E, 0x3F, 0xB8, + 0xFC, 0x70, 0x38, 0x1C, 0x1C, 0x1C, 0x1C, 0x0E, 0x00, 0x03, 0x81, 0xC0, + 0x03, 0xF0, 0x0F, 0xFC, 0x1E, 0x0E, 0x38, 0x02, 0x70, 0xE9, 0x63, 0x19, + 0xC2, 0x19, 0xC6, 0x11, 0xC6, 0x33, 0xC6, 0x32, 0x63, 0xFE, 0x73, 0xDC, + 0x3C, 0x00, 0x1F, 0xF8, 0x07, 0xF0, 0x07, 0x00, 0xF0, 0x0F, 0x80, 0xF8, + 0x1D, 0x81, 0x9C, 0x19, 0xC3, 0x8C, 0x3F, 0xE7, 0xFE, 0x70, 0x66, 0x07, + 0xE0, 0x70, 0xFF, 0x9F, 0xFB, 0x83, 0xF0, 0x7E, 0x0F, 0xFF, 0x3F, 0xF7, + 0x06, 0xE0, 0xFC, 0x1F, 0x83, 0xFF, 0xEF, 0xF8, 0x1F, 0x83, 0xFE, 0x78, + 0xE7, 0x07, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x07, 0x07, 0x78, + 0xF3, 0xFE, 0x1F, 0x80, 0xFF, 0x8F, 0xFC, 0xE0, 0xEE, 0x0E, 0xE0, 0x7E, + 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0x7E, 0x0E, 0xE0, 0xEF, 0xFC, 0xFF, 0x80, + 0xFF, 0xFF, 0xF8, 0x1C, 0x0E, 0x07, 0xFB, 0xFD, 0xC0, 0xE0, 0x70, 0x38, + 0x1F, 0xFF, 0xF8, 0xFF, 0xFF, 0xF8, 0x1C, 0x0E, 0x07, 0xFB, 0xFD, 0xC0, + 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x00, 0x0F, 0x87, 0xF9, 0xE3, 0xB8, 0x3E, + 0x01, 0xC0, 0x38, 0xFF, 0x1F, 0xE0, 0x6E, 0x0D, 0xE3, 0x9F, 0xD0, 0xF2, + 0xE0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xFF, 0xFF, 0xFF, 0x07, 0xE0, + 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x07, + 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0xE7, 0xE7, 0xE7, 0x7E, 0x3C, + 0xE0, 0xEE, 0x1C, 0xE3, 0x8E, 0x70, 0xEE, 0x0F, 0xC0, 0xFE, 0x0F, 0x70, + 0xE7, 0x0E, 0x38, 0xE1, 0xCE, 0x0E, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, + 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0xFF, 0xFF, 0xF8, 0x7F, 0xE1, + 0xFF, 0x87, 0xFE, 0x1F, 0xEC, 0x7F, 0xB3, 0x7E, 0xCD, 0xFB, 0x37, 0xEC, + 0xDF, 0x9E, 0x7E, 0x79, 0xF9, 0xE7, 0xE7, 0x9C, 0xE0, 0xFE, 0x1F, 0xC3, + 0xFC, 0x7F, 0xCF, 0xD9, 0xFB, 0xBF, 0x37, 0xE7, 0xFC, 0x7F, 0x87, 0xF0, + 0xFE, 0x0E, 0x0F, 0x81, 0xFF, 0x1E, 0x3C, 0xE0, 0xEE, 0x03, 0xF0, 0x1F, + 0x80, 0xFC, 0x07, 0xE0, 0x3B, 0x83, 0x9E, 0x3C, 0x7F, 0xC0, 0xF8, 0x00, + 0xFF, 0x9F, 0xFB, 0x87, 0xF0, 0x7E, 0x0F, 0xC3, 0xFF, 0xF7, 0xFC, 0xE0, + 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x00, 0x0F, 0x81, 0xFF, 0x1E, 0x3C, 0xE0, + 0xEE, 0x03, 0xF0, 0x1F, 0x80, 0xFC, 0x07, 0xE1, 0xBB, 0x8F, 0x9E, 0x3C, + 0x7F, 0xE0, 0xFB, 0x80, 0x08, 0xFF, 0x8F, 0xFC, 0xE0, 0xEE, 0x0E, 0xE0, + 0xEE, 0x0E, 0xFF, 0xCF, 0xFC, 0xE0, 0xEE, 0x0E, 0xE0, 0xEE, 0x0E, 0xE0, + 0xF0, 0x3F, 0x0F, 0xFB, 0xC7, 0xF0, 0x7E, 0x01, 0xFC, 0x1F, 0xF0, 0x3F, + 0x00, 0xFC, 0x1D, 0xC7, 0xBF, 0xE1, 0xF8, 0xFF, 0xFF, 0xC7, 0x03, 0x81, + 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0xFC, + 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x07, 0xE0, 0xFC, 0x1F, + 0xC7, 0xBF, 0xE1, 0xF0, 0x60, 0x67, 0x0E, 0x70, 0xE3, 0x0C, 0x30, 0xC3, + 0x9C, 0x19, 0x81, 0x98, 0x1F, 0x80, 0xF0, 0x0F, 0x00, 0xF0, 0x06, 0x00, + 0x61, 0xC3, 0xB8, 0xE1, 0x9C, 0x70, 0xCE, 0x3C, 0xE3, 0x36, 0x71, 0x9B, + 0x30, 0xED, 0x98, 0x36, 0x7C, 0x1B, 0x3C, 0x0F, 0x1E, 0x07, 0x8F, 0x01, + 0xC3, 0x80, 0xE1, 0x80, 0x70, 0xE7, 0x8E, 0x39, 0xC1, 0xF8, 0x1F, 0x80, + 0xF0, 0x07, 0x00, 0xF0, 0x1F, 0x81, 0x9C, 0x39, 0xC7, 0x0E, 0x70, 0xE0, + 0xE0, 0xFC, 0x39, 0xC7, 0x18, 0xC3, 0xB8, 0x36, 0x07, 0xC0, 0x70, 0x0E, + 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0xFF, 0xFF, 0xC0, 0xE0, 0xE0, 0xF0, + 0x70, 0x70, 0x70, 0x78, 0x38, 0x38, 0x1F, 0xFF, 0xF8, 0xFF, 0xEE, 0xEE, + 0xEE, 0xEE, 0xEE, 0xEE, 0xEF, 0xF0, 0x86, 0x10, 0x86, 0x10, 0x84, 0x30, + 0x84, 0x30, 0x80, 0xFF, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x7F, 0xF0, + 0x18, 0x1C, 0x3C, 0x3E, 0x36, 0x66, 0x63, 0xC3, 0xFF, 0xC0, 0xCC, 0x3F, + 0x1F, 0xEE, 0x38, 0x0E, 0x3F, 0x9E, 0xEE, 0x3B, 0x9E, 0xFF, 0x9E, 0xE0, + 0xE0, 0x38, 0x0E, 0x03, 0xBC, 0xFF, 0xBC, 0xEE, 0x1F, 0x87, 0xE1, 0xF8, + 0x7F, 0x3B, 0xFE, 0xEF, 0x00, 0x1F, 0x3F, 0xDC, 0x7C, 0x0E, 0x07, 0x03, + 0x80, 0xE3, 0x7F, 0x8F, 0x00, 0x03, 0x81, 0xC0, 0xE7, 0x77, 0xFB, 0xBF, + 0x8F, 0xC7, 0xE3, 0xF1, 0xFD, 0xEF, 0xF3, 0xB8, 0x3E, 0x3F, 0x9C, 0xDC, + 0x3F, 0xFF, 0xFF, 0x81, 0xC3, 0x7F, 0x8F, 0x00, 0x3B, 0xDD, 0xFF, 0xB9, + 0xCE, 0x73, 0x9C, 0xE7, 0x00, 0x3B, 0xBF, 0xDD, 0xFC, 0x7E, 0x3F, 0x1F, + 0x8F, 0xEF, 0x7F, 0x9D, 0xC0, 0xFC, 0x77, 0xF1, 0xF0, 0xE0, 0x70, 0x38, + 0x1D, 0xEF, 0xFF, 0x9F, 0x8F, 0xC7, 0xE3, 0xF1, 0xF8, 0xFC, 0x7E, 0x38, + 0xFC, 0x7F, 0xFF, 0xFF, 0xFE, 0x77, 0x07, 0x77, 0x77, 0x77, 0x77, 0x77, + 0x7F, 0xE0, 0xE0, 0x70, 0x38, 0x1C, 0x7E, 0x77, 0x73, 0xF1, 0xF8, 0xFE, + 0x77, 0x39, 0xDC, 0x6E, 0x38, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xEF, 0x7B, + 0xFF, 0xFE, 0x39, 0xF8, 0xE7, 0xE3, 0x9F, 0x8E, 0x7E, 0x39, 0xF8, 0xE7, + 0xE3, 0x9F, 0x8E, 0x70, 0xEF, 0x7F, 0xF8, 0xFC, 0x7E, 0x3F, 0x1F, 0x8F, + 0xC7, 0xE3, 0xF1, 0xC0, 0x1E, 0x1F, 0xE7, 0x3B, 0x87, 0xE1, 0xF8, 0x7E, + 0x1D, 0xCE, 0x7F, 0x87, 0x80, 0xEF, 0x3F, 0xEF, 0x3B, 0x87, 0xE1, 0xF8, + 0x7E, 0x1F, 0xCE, 0xFF, 0xBB, 0xCE, 0x03, 0x80, 0xE0, 0x38, 0x00, 0x3B, + 0xBF, 0xFD, 0xFC, 0x7E, 0x3F, 0x1F, 0x8F, 0xEF, 0x7F, 0x9D, 0xC0, 0xE0, + 0x70, 0x38, 0x1C, 0xEF, 0xFF, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x80, 0x3E, + 0x3F, 0xB8, 0xFC, 0x0F, 0xC3, 0xFC, 0x3F, 0xC7, 0xFF, 0x1F, 0x00, 0x73, + 0xBF, 0xF7, 0x39, 0xCE, 0x73, 0x9E, 0x70, 0xE3, 0xF1, 0xF8, 0xFC, 0x7E, + 0x3F, 0x1F, 0x8F, 0xC7, 0xFF, 0xBD, 0xC0, 0xE1, 0x98, 0x67, 0x39, 0xCC, + 0x33, 0x0D, 0xC3, 0xE0, 0x78, 0x1E, 0x07, 0x00, 0xE3, 0x1D, 0x9E, 0x66, + 0x79, 0x99, 0xE6, 0x77, 0xB8, 0xD2, 0xC3, 0xCF, 0x0F, 0x3C, 0x3C, 0xF0, + 0x73, 0x80, 0x73, 0x9C, 0xE3, 0xF0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0xFC, + 0x73, 0x9C, 0xE0, 0xE1, 0xD8, 0x67, 0x39, 0xCE, 0x33, 0x0E, 0xC3, 0xE0, + 0x78, 0x1E, 0x03, 0x00, 0xC0, 0x70, 0x38, 0x0E, 0x00, 0xFE, 0xFE, 0x0E, + 0x1C, 0x38, 0x38, 0x70, 0xE0, 0xFF, 0xFF, 0x37, 0x66, 0x66, 0x6E, 0xE6, + 0x66, 0x66, 0x67, 0x30, 0xFF, 0xFF, 0x80, 0xCE, 0x66, 0x66, 0x67, 0x76, + 0x66, 0x66, 0x6E, 0xC0, 0x71, 0x8E }; + +const GFXglyph FreeSansBold9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 3, 13, 6, 2, -12 }, // 0x21 '!' + { 5, 7, 5, 9, 1, -12 }, // 0x22 '"' + { 10, 10, 12, 10, 0, -11 }, // 0x23 '#' + { 25, 9, 15, 10, 1, -13 }, // 0x24 '$' + { 42, 16, 13, 16, 0, -12 }, // 0x25 '%' + { 68, 12, 13, 13, 1, -12 }, // 0x26 '&' + { 88, 3, 5, 5, 1, -12 }, // 0x27 ''' + { 90, 6, 17, 6, 1, -12 }, // 0x28 '(' + { 103, 6, 17, 6, 0, -12 }, // 0x29 ')' + { 116, 5, 6, 7, 1, -12 }, // 0x2A '*' + { 120, 7, 8, 11, 2, -7 }, // 0x2B '+' + { 127, 3, 5, 4, 1, -1 }, // 0x2C ',' + { 129, 5, 2, 6, 0, -5 }, // 0x2D '-' + { 131, 3, 2, 4, 1, -1 }, // 0x2E '.' + { 132, 5, 13, 5, 0, -12 }, // 0x2F '/' + { 141, 9, 13, 10, 1, -12 }, // 0x30 '0' + { 156, 5, 13, 10, 2, -12 }, // 0x31 '1' + { 165, 9, 13, 10, 1, -12 }, // 0x32 '2' + { 180, 8, 13, 10, 1, -12 }, // 0x33 '3' + { 193, 8, 13, 10, 2, -12 }, // 0x34 '4' + { 206, 9, 13, 10, 1, -12 }, // 0x35 '5' + { 221, 9, 13, 10, 1, -12 }, // 0x36 '6' + { 236, 9, 13, 10, 0, -12 }, // 0x37 '7' + { 251, 10, 13, 10, 0, -12 }, // 0x38 '8' + { 268, 9, 13, 10, 1, -12 }, // 0x39 '9' + { 283, 3, 9, 4, 1, -8 }, // 0x3A ':' + { 287, 3, 12, 4, 1, -8 }, // 0x3B ';' + { 292, 9, 9, 11, 1, -8 }, // 0x3C '<' + { 303, 9, 6, 11, 1, -6 }, // 0x3D '=' + { 310, 9, 9, 11, 1, -8 }, // 0x3E '>' + { 321, 9, 13, 11, 1, -12 }, // 0x3F '?' + { 336, 16, 15, 18, 0, -12 }, // 0x40 '@' + { 366, 12, 13, 13, 0, -12 }, // 0x41 'A' + { 386, 11, 13, 13, 1, -12 }, // 0x42 'B' + { 404, 12, 13, 13, 1, -12 }, // 0x43 'C' + { 424, 12, 13, 13, 1, -12 }, // 0x44 'D' + { 444, 9, 13, 12, 1, -12 }, // 0x45 'E' + { 459, 9, 13, 11, 1, -12 }, // 0x46 'F' + { 474, 11, 13, 14, 1, -12 }, // 0x47 'G' + { 492, 11, 13, 13, 1, -12 }, // 0x48 'H' + { 510, 3, 13, 6, 1, -12 }, // 0x49 'I' + { 515, 8, 13, 10, 1, -12 }, // 0x4A 'J' + { 528, 12, 13, 13, 1, -12 }, // 0x4B 'K' + { 548, 8, 13, 11, 1, -12 }, // 0x4C 'L' + { 561, 14, 13, 16, 1, -12 }, // 0x4D 'M' + { 584, 11, 13, 14, 1, -12 }, // 0x4E 'N' + { 602, 13, 13, 14, 1, -12 }, // 0x4F 'O' + { 624, 11, 13, 12, 1, -12 }, // 0x50 'P' + { 642, 13, 14, 14, 1, -12 }, // 0x51 'Q' + { 665, 12, 13, 13, 1, -12 }, // 0x52 'R' + { 685, 11, 13, 12, 1, -12 }, // 0x53 'S' + { 703, 9, 13, 12, 2, -12 }, // 0x54 'T' + { 718, 11, 13, 13, 1, -12 }, // 0x55 'U' + { 736, 12, 13, 12, 0, -12 }, // 0x56 'V' + { 756, 17, 13, 17, 0, -12 }, // 0x57 'W' + { 784, 12, 13, 12, 0, -12 }, // 0x58 'X' + { 804, 11, 13, 12, 1, -12 }, // 0x59 'Y' + { 822, 9, 13, 11, 1, -12 }, // 0x5A 'Z' + { 837, 4, 17, 6, 1, -12 }, // 0x5B '[' + { 846, 5, 13, 5, 0, -12 }, // 0x5C '\' + { 855, 4, 17, 6, 0, -12 }, // 0x5D ']' + { 864, 8, 8, 11, 1, -12 }, // 0x5E '^' + { 872, 10, 1, 10, 0, 4 }, // 0x5F '_' + { 874, 3, 2, 5, 0, -12 }, // 0x60 '`' + { 875, 10, 10, 10, 1, -9 }, // 0x61 'a' + { 888, 10, 13, 11, 1, -12 }, // 0x62 'b' + { 905, 9, 10, 10, 1, -9 }, // 0x63 'c' + { 917, 9, 13, 11, 1, -12 }, // 0x64 'd' + { 932, 9, 10, 10, 1, -9 }, // 0x65 'e' + { 944, 5, 13, 6, 1, -12 }, // 0x66 'f' + { 953, 9, 14, 11, 1, -9 }, // 0x67 'g' + { 969, 9, 13, 11, 1, -12 }, // 0x68 'h' + { 984, 3, 13, 5, 1, -12 }, // 0x69 'i' + { 989, 4, 17, 5, 0, -12 }, // 0x6A 'j' + { 998, 9, 13, 10, 1, -12 }, // 0x6B 'k' + { 1013, 3, 13, 5, 1, -12 }, // 0x6C 'l' + { 1018, 14, 10, 16, 1, -9 }, // 0x6D 'm' + { 1036, 9, 10, 11, 1, -9 }, // 0x6E 'n' + { 1048, 10, 10, 11, 1, -9 }, // 0x6F 'o' + { 1061, 10, 14, 11, 1, -9 }, // 0x70 'p' + { 1079, 9, 14, 11, 1, -9 }, // 0x71 'q' + { 1095, 6, 10, 7, 1, -9 }, // 0x72 'r' + { 1103, 9, 10, 10, 1, -9 }, // 0x73 's' + { 1115, 5, 12, 6, 1, -11 }, // 0x74 't' + { 1123, 9, 10, 11, 1, -9 }, // 0x75 'u' + { 1135, 10, 10, 10, 0, -9 }, // 0x76 'v' + { 1148, 14, 10, 14, 0, -9 }, // 0x77 'w' + { 1166, 10, 10, 10, 0, -9 }, // 0x78 'x' + { 1179, 10, 14, 10, 0, -9 }, // 0x79 'y' + { 1197, 8, 10, 9, 1, -9 }, // 0x7A 'z' + { 1207, 4, 17, 7, 1, -12 }, // 0x7B '{' + { 1216, 1, 17, 5, 2, -12 }, // 0x7C '|' + { 1219, 4, 17, 7, 2, -12 }, // 0x7D '}' + { 1228, 8, 2, 9, 0, -4 } }; // 0x7E '~' + +const GFXfont FreeSansBold9pt7b PROGMEM = { + (uint8_t *)FreeSansBold9pt7bBitmaps, + (GFXglyph *)FreeSansBold9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 1902 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique12pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique12pt7b.h new file mode 100644 index 0000000..fabbad3 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique12pt7b.h @@ -0,0 +1,317 @@ +const uint8_t FreeSansBoldOblique12pt7bBitmaps[] PROGMEM = { + 0x1C, 0x3C, 0x78, 0xE1, 0xC3, 0x8F, 0x1C, 0x38, 0x70, 0xC1, 0x83, 0x00, + 0x1C, 0x78, 0xF0, 0x71, 0xFC, 0xFE, 0x3B, 0x8E, 0xC3, 0x30, 0xC0, 0x01, + 0x8C, 0x07, 0x38, 0x0C, 0x61, 0xFF, 0xF3, 0xFF, 0xE7, 0xFF, 0x83, 0x9C, + 0x0E, 0x70, 0x1C, 0xE1, 0xFF, 0xF3, 0xFF, 0xC7, 0xFF, 0x83, 0x18, 0x0E, + 0x70, 0x18, 0xC0, 0x73, 0x80, 0x00, 0x40, 0x07, 0xF0, 0x3F, 0xF0, 0xFF, + 0xF3, 0xC9, 0xE7, 0xB3, 0xCF, 0x60, 0x1F, 0xC0, 0x3F, 0xC0, 0x3F, 0xE0, + 0x1F, 0xE0, 0x1B, 0xE0, 0x33, 0xDE, 0x47, 0xBC, 0x8F, 0x7F, 0x7C, 0x7F, + 0xF0, 0x7F, 0x80, 0x18, 0x00, 0x20, 0x00, 0xC0, 0x00, 0x00, 0x01, 0x87, + 0x80, 0xC3, 0xF0, 0x61, 0xFE, 0x10, 0xE1, 0x8C, 0x30, 0x66, 0x0C, 0x3B, + 0x03, 0xFC, 0x80, 0x7E, 0x60, 0x0F, 0x30, 0x00, 0x18, 0x70, 0x0C, 0x7E, + 0x03, 0x1F, 0xC1, 0x8E, 0x30, 0xC3, 0x1C, 0x60, 0xFE, 0x18, 0x1F, 0x8C, + 0x07, 0x80, 0x01, 0xE0, 0x07, 0xF0, 0x1F, 0xE0, 0x79, 0xC0, 0xF3, 0x81, + 0xEE, 0x01, 0xF8, 0x01, 0xE0, 0x1F, 0xC6, 0x7B, 0xDD, 0xE3, 0xF7, 0x87, + 0xEF, 0x07, 0x9F, 0x1F, 0x3F, 0xFF, 0x3F, 0xDE, 0x3F, 0x1C, 0x7F, 0xEE, + 0xCC, 0x03, 0x83, 0x81, 0x81, 0xC1, 0xC0, 0xE0, 0xE0, 0x70, 0x70, 0x38, + 0x3C, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x18, 0x0E, 0x07, + 0x01, 0x80, 0x06, 0x03, 0x81, 0xC0, 0x60, 0x38, 0x1C, 0x0E, 0x07, 0x03, + 0x81, 0xC0, 0xE0, 0xE0, 0x70, 0x38, 0x38, 0x1C, 0x1C, 0x0E, 0x0E, 0x06, + 0x07, 0x07, 0x00, 0x0C, 0x0C, 0x4F, 0xFF, 0x1C, 0x3C, 0x6C, 0x44, 0x03, + 0x80, 0x38, 0x07, 0x00, 0x70, 0x7F, 0xFF, 0xFF, 0xFF, 0xF0, 0xE0, 0x0E, + 0x00, 0xE0, 0x0C, 0x00, 0x7B, 0xDC, 0x23, 0x33, 0x00, 0x7F, 0xFF, 0xF0, + 0x7F, 0xE0, 0x00, 0xC0, 0x30, 0x18, 0x04, 0x03, 0x00, 0x80, 0x60, 0x10, + 0x0C, 0x02, 0x01, 0x80, 0x40, 0x30, 0x08, 0x06, 0x01, 0x00, 0xC0, 0x00, + 0x03, 0xC0, 0x7F, 0x87, 0xFC, 0x78, 0xF3, 0xC7, 0xBC, 0x3D, 0xE1, 0xEF, + 0x0F, 0xF0, 0x7F, 0x87, 0xBC, 0x3D, 0xE1, 0xEF, 0x1E, 0x78, 0xF3, 0xFF, + 0x0F, 0xF0, 0x3E, 0x00, 0x03, 0x83, 0x83, 0xCF, 0xEF, 0xF0, 0x78, 0x38, + 0x1C, 0x0E, 0x0F, 0x07, 0x03, 0x81, 0xC1, 0xE0, 0xF0, 0x70, 0x38, 0x00, + 0x03, 0xF0, 0x0F, 0xF8, 0x7F, 0xF8, 0xF1, 0xF3, 0xC1, 0xE7, 0x83, 0xC0, + 0x07, 0x80, 0x1E, 0x00, 0x78, 0x03, 0xE0, 0x0F, 0x00, 0x7C, 0x01, 0xE0, + 0x07, 0x00, 0x1F, 0xFC, 0x3F, 0xF8, 0xFF, 0xF0, 0x07, 0xE0, 0xFF, 0x8F, + 0xFE, 0xF8, 0xF7, 0x87, 0x80, 0x78, 0x0F, 0x80, 0xFC, 0x07, 0xE0, 0x0F, + 0x80, 0x3C, 0x01, 0xEF, 0x0F, 0x78, 0xF3, 0xFF, 0x8F, 0xF8, 0x3F, 0x00, + 0x00, 0x78, 0x07, 0xC0, 0x7E, 0x03, 0xF0, 0x37, 0x03, 0x38, 0x31, 0xC3, + 0x9E, 0x38, 0xF1, 0x87, 0x1F, 0xFE, 0xFF, 0xF7, 0xFF, 0x80, 0xF0, 0x07, + 0x00, 0x38, 0x03, 0xC0, 0x07, 0xFC, 0x1F, 0xF0, 0xFF, 0xC3, 0x00, 0x1C, + 0x00, 0x7F, 0x81, 0xFF, 0x0F, 0xFE, 0x38, 0xF8, 0x01, 0xE0, 0x07, 0x80, + 0x1E, 0xF0, 0xF3, 0xC7, 0xCF, 0xFE, 0x1F, 0xF0, 0x3F, 0x00, 0x03, 0xE0, + 0x7F, 0x87, 0xFE, 0x78, 0xF3, 0xC0, 0x3D, 0xE1, 0xFF, 0x8F, 0xFE, 0xF8, + 0xF7, 0xC7, 0xBC, 0x3D, 0xE1, 0xEF, 0x1E, 0x7C, 0xF3, 0xFF, 0x0F, 0xF0, + 0x1F, 0x00, 0x7F, 0xFB, 0xFF, 0xDF, 0xFE, 0x00, 0xE0, 0x0E, 0x00, 0xE0, + 0x0E, 0x00, 0xE0, 0x0F, 0x00, 0x70, 0x07, 0x00, 0x78, 0x03, 0x80, 0x3C, + 0x01, 0xC0, 0x0E, 0x00, 0xF0, 0x00, 0x03, 0xF0, 0x1F, 0xE0, 0xFF, 0xC7, + 0x8F, 0x1C, 0x3C, 0x71, 0xE0, 0xFF, 0x03, 0xF8, 0x3F, 0xF1, 0xF1, 0xE7, + 0x87, 0xBC, 0x1E, 0xF0, 0x7B, 0xE3, 0xCF, 0xFF, 0x1F, 0xF8, 0x1F, 0x80, + 0x03, 0xE0, 0x3F, 0xE1, 0xFF, 0x8F, 0x9F, 0x3C, 0x3D, 0xE0, 0xF7, 0x83, + 0xDE, 0x1F, 0x78, 0xFD, 0xFF, 0xE3, 0xFF, 0x87, 0xDE, 0x00, 0xF3, 0xC7, + 0x8F, 0xFE, 0x1F, 0xF0, 0x3F, 0x00, 0x1C, 0xF3, 0x80, 0x00, 0x00, 0x00, + 0x01, 0xCF, 0x38, 0x0E, 0x3C, 0x70, 0x00, 0x00, 0x00, 0x00, 0x00, 0xF1, + 0xE3, 0x81, 0x06, 0x18, 0x60, 0x00, 0x00, 0x01, 0xC0, 0x7E, 0x1F, 0xE7, + 0xF8, 0x7E, 0x03, 0xE0, 0x1F, 0xE0, 0x3F, 0xC0, 0x7F, 0x00, 0x78, 0x00, + 0xC0, 0x3F, 0xFC, 0xFF, 0xF3, 0xFF, 0x80, 0x00, 0x00, 0x00, 0x00, 0x07, + 0xFF, 0x9F, 0xFC, 0x7F, 0xF0, 0x30, 0x01, 0xE0, 0x0F, 0xE0, 0x3F, 0xC0, + 0x7F, 0x80, 0x7C, 0x07, 0xE1, 0xFE, 0x7F, 0x87, 0xE0, 0x38, 0x00, 0x00, + 0x00, 0x0F, 0xC1, 0xFF, 0x8F, 0xFC, 0xF1, 0xFF, 0x07, 0xF0, 0x3C, 0x01, + 0xE0, 0x1E, 0x01, 0xE0, 0x3E, 0x03, 0xE0, 0x1C, 0x01, 0xC0, 0x0E, 0x00, + 0x00, 0x07, 0x80, 0x3C, 0x01, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x03, 0xFF, + 0x80, 0x3C, 0x0F, 0x01, 0xC0, 0x0E, 0x0E, 0x00, 0x1C, 0x70, 0xF7, 0x73, + 0x87, 0xF8, 0xCC, 0x31, 0xE3, 0x61, 0x87, 0x0D, 0x8C, 0x1C, 0x3C, 0x30, + 0x61, 0xB1, 0x81, 0x86, 0xC6, 0x0C, 0x3B, 0x18, 0x71, 0xCC, 0x63, 0xCE, + 0x31, 0xFB, 0xF0, 0xE3, 0xCF, 0x01, 0xC0, 0x00, 0x03, 0xC0, 0xC0, 0x07, + 0xFF, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x3F, 0x00, 0x1F, 0x80, + 0x1F, 0xC0, 0x0F, 0xE0, 0x0F, 0xF0, 0x07, 0x7C, 0x07, 0x1E, 0x03, 0x8F, + 0x03, 0x87, 0x83, 0xC3, 0xC1, 0xFF, 0xE1, 0xFF, 0xF0, 0xFF, 0xFC, 0xF0, + 0x1E, 0x70, 0x0F, 0x78, 0x07, 0xB8, 0x03, 0xC0, 0x0F, 0xFE, 0x0F, 0xFF, + 0x87, 0xFF, 0xE3, 0xC0, 0xF1, 0xC0, 0x78, 0xE0, 0x3C, 0xF0, 0x3C, 0x7F, + 0xFC, 0x3F, 0xFC, 0x1F, 0xFF, 0x0E, 0x07, 0xCF, 0x01, 0xE7, 0x80, 0xF3, + 0x80, 0x79, 0xC0, 0x79, 0xFF, 0xF8, 0xFF, 0xFC, 0x7F, 0xF8, 0x00, 0x01, + 0xF8, 0x03, 0xFF, 0x03, 0xFF, 0xC3, 0xE1, 0xF3, 0xC0, 0x79, 0xE0, 0x3D, + 0xE0, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1E, 0x00, + 0x0F, 0x00, 0xE7, 0x80, 0xF3, 0xE0, 0xF0, 0xFF, 0xF8, 0x3F, 0xF0, 0x07, + 0xE0, 0x00, 0x1F, 0xFC, 0x0F, 0xFF, 0x87, 0xFF, 0xC3, 0x81, 0xF1, 0xC0, + 0x79, 0xE0, 0x3C, 0xF0, 0x1E, 0x78, 0x0F, 0x38, 0x07, 0x9C, 0x03, 0xDE, + 0x03, 0xCF, 0x01, 0xE7, 0x81, 0xF3, 0x80, 0xF1, 0xC1, 0xF1, 0xFF, 0xF0, + 0xFF, 0xF0, 0x7F, 0xE0, 0x00, 0x0F, 0xFF, 0x1F, 0xFF, 0x1F, 0xFF, 0x1C, + 0x00, 0x1C, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, + 0xFC, 0x78, 0x00, 0x78, 0x00, 0x78, 0x00, 0x70, 0x00, 0x70, 0x00, 0xFF, + 0xF8, 0xFF, 0xF8, 0xFF, 0xF8, 0x1F, 0xFF, 0x1F, 0xFE, 0x1F, 0xFE, 0x1C, + 0x00, 0x1C, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x3F, 0xF8, 0x3F, 0xF8, 0x3F, + 0xF8, 0x78, 0x00, 0x78, 0x00, 0x78, 0x00, 0x70, 0x00, 0xF0, 0x00, 0xF0, + 0x00, 0xF0, 0x00, 0xE0, 0x00, 0x01, 0xFC, 0x03, 0xFF, 0x03, 0xFF, 0xC3, + 0xE0, 0xF3, 0xC0, 0x39, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, 0xF0, 0x7F, + 0x78, 0x3F, 0xBC, 0x1F, 0xDE, 0x01, 0xCF, 0x00, 0xE7, 0xC0, 0xF1, 0xF0, + 0xF8, 0xFF, 0xFC, 0x3F, 0xEC, 0x07, 0xE6, 0x00, 0x1E, 0x03, 0x8F, 0x01, + 0xC7, 0x01, 0xE3, 0x80, 0xF3, 0xC0, 0x79, 0xE0, 0x38, 0xF0, 0x1C, 0x7F, + 0xFE, 0x3F, 0xFF, 0x3F, 0xFF, 0x9E, 0x03, 0x8F, 0x01, 0xC7, 0x01, 0xE3, + 0x80, 0xF3, 0xC0, 0x71, 0xE0, 0x38, 0xF0, 0x3C, 0x70, 0x1E, 0x00, 0x1E, + 0x3C, 0x78, 0xE1, 0xC7, 0x8F, 0x1E, 0x38, 0x71, 0xE3, 0xC7, 0x8E, 0x1C, + 0x78, 0xF1, 0xE0, 0x00, 0x1C, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x38, + 0x00, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, 0xC0, 0x07, 0x3C, 0x3C, + 0xF0, 0xF3, 0xC3, 0x8F, 0x1E, 0x3F, 0xF8, 0x7F, 0xC0, 0xFC, 0x00, 0x1E, + 0x07, 0xC7, 0x83, 0xE1, 0xE1, 0xE0, 0x70, 0xF0, 0x1C, 0x78, 0x0F, 0x3C, + 0x03, 0xDE, 0x00, 0xFF, 0x00, 0x3F, 0xC0, 0x0F, 0xF0, 0x07, 0xDE, 0x01, + 0xE7, 0xC0, 0x78, 0xF0, 0x1C, 0x3E, 0x0F, 0x07, 0x83, 0xC0, 0xF0, 0xF0, + 0x3C, 0x38, 0x07, 0x80, 0x0E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xC0, + 0x0E, 0x00, 0xF0, 0x07, 0x80, 0x38, 0x01, 0xC0, 0x1E, 0x00, 0xF0, 0x07, + 0x80, 0x38, 0x01, 0xC0, 0x1F, 0xFE, 0xFF, 0xF7, 0xFF, 0x80, 0x1F, 0x03, + 0xF1, 0xF0, 0x3F, 0x1F, 0x07, 0xF1, 0xF0, 0x7F, 0x3F, 0x0F, 0xE3, 0xF0, + 0xEE, 0x3B, 0x1E, 0xE3, 0xB1, 0xDE, 0x3B, 0x1D, 0xE7, 0xB3, 0x9C, 0x7B, + 0x39, 0xC7, 0x37, 0x9C, 0x73, 0x73, 0xCF, 0x3F, 0x3C, 0xF3, 0xE3, 0x8F, + 0x3E, 0x38, 0xE3, 0xC3, 0x8E, 0x3C, 0x78, 0x1E, 0x03, 0x87, 0xC0, 0xE1, + 0xF0, 0x38, 0x7C, 0x1E, 0x1F, 0x87, 0x8F, 0xE1, 0xC3, 0xB8, 0x70, 0xEF, + 0x1C, 0x39, 0xCF, 0x1E, 0x73, 0xC7, 0x8E, 0xE1, 0xC3, 0xB8, 0x70, 0xEE, + 0x1C, 0x1F, 0x8F, 0x07, 0xE3, 0xC1, 0xF0, 0xE0, 0x3C, 0x38, 0x0F, 0x00, + 0x01, 0xF8, 0x03, 0xFF, 0x03, 0xFF, 0xC3, 0xE3, 0xE3, 0xC0, 0xF9, 0xE0, + 0x3D, 0xE0, 0x1E, 0xF0, 0x0F, 0xF0, 0x07, 0xF8, 0x03, 0xFC, 0x03, 0xDE, + 0x01, 0xEF, 0x00, 0xF7, 0xC0, 0xF1, 0xF0, 0xF0, 0xFF, 0xF0, 0x3F, 0xF0, + 0x07, 0xE0, 0x00, 0x1F, 0xFC, 0x1F, 0xFE, 0x1F, 0xFF, 0x1C, 0x1F, 0x1C, + 0x0F, 0x3C, 0x0F, 0x3C, 0x0F, 0x3C, 0x1E, 0x3F, 0xFC, 0x3F, 0xFC, 0x7F, + 0xF0, 0x78, 0x00, 0x78, 0x00, 0x70, 0x00, 0x70, 0x00, 0xF0, 0x00, 0xF0, + 0x00, 0xF0, 0x00, 0x01, 0xF8, 0x03, 0xFF, 0x03, 0xFF, 0xC3, 0xE3, 0xE3, + 0xC0, 0xF9, 0xC0, 0x3D, 0xE0, 0x1E, 0xF0, 0x0F, 0xF0, 0x07, 0xF8, 0x03, + 0xFC, 0x03, 0xDE, 0x09, 0xEF, 0x0E, 0xE7, 0xC7, 0xF1, 0xF1, 0xF0, 0xFF, + 0xF8, 0x3F, 0xFE, 0x07, 0xE6, 0x00, 0x02, 0x00, 0x0F, 0xFE, 0x0F, 0xFF, + 0x87, 0xFF, 0xE3, 0x81, 0xF1, 0xC0, 0x78, 0xE0, 0x3C, 0xF0, 0x1C, 0x78, + 0x1E, 0x3F, 0xFC, 0x1F, 0xFC, 0x1F, 0xFF, 0x8F, 0x03, 0xC7, 0x81, 0xE3, + 0x80, 0xF1, 0xC0, 0xF1, 0xE0, 0x78, 0xF0, 0x3C, 0x78, 0x1F, 0x00, 0x03, + 0xF8, 0x0F, 0xFE, 0x1F, 0xFF, 0x1E, 0x1F, 0x3C, 0x0F, 0x3C, 0x0F, 0x3C, + 0x00, 0x3F, 0x00, 0x1F, 0xF0, 0x0F, 0xFC, 0x01, 0xFE, 0x00, 0x3E, 0xF0, + 0x1E, 0xF0, 0x1E, 0xF8, 0x3C, 0x7F, 0xF8, 0x7F, 0xF0, 0x1F, 0xC0, 0x7F, + 0xFE, 0xFF, 0xFD, 0xFF, 0xF8, 0x1C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, + 0x03, 0x80, 0x07, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xE0, 0x01, + 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x38, 0x00, 0x1E, 0x07, 0x1C, + 0x0F, 0x3C, 0x0F, 0x3C, 0x0F, 0x3C, 0x0E, 0x38, 0x0E, 0x78, 0x1E, 0x78, + 0x1E, 0x78, 0x1E, 0x78, 0x1C, 0x70, 0x1C, 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, + 0x38, 0xF8, 0x78, 0xFF, 0xF0, 0x7F, 0xE0, 0x1F, 0x80, 0xF0, 0x1F, 0xE0, + 0x39, 0xC0, 0xF3, 0x81, 0xC7, 0x07, 0x8E, 0x0E, 0x1C, 0x3C, 0x3C, 0x70, + 0x79, 0xE0, 0xF3, 0x80, 0xEF, 0x01, 0xDC, 0x03, 0xB8, 0x07, 0xE0, 0x0F, + 0x80, 0x1F, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x70, 0x7F, 0x87, 0x83, + 0xFC, 0x3C, 0x3D, 0xE1, 0xE1, 0xEF, 0x1F, 0x0E, 0x78, 0xD8, 0xF3, 0xC6, + 0xC7, 0x0E, 0x76, 0x78, 0x73, 0x33, 0x83, 0xB9, 0x9C, 0x1D, 0xCD, 0xC0, + 0xEC, 0x6E, 0x07, 0xE3, 0xE0, 0x3E, 0x1F, 0x01, 0xF0, 0xF0, 0x0F, 0x87, + 0x80, 0x78, 0x38, 0x03, 0xC1, 0xC0, 0x00, 0x0F, 0x03, 0xC3, 0xC1, 0xE0, + 0xF8, 0xF0, 0x1E, 0x78, 0x07, 0x9E, 0x00, 0xFF, 0x00, 0x3F, 0x80, 0x0F, + 0xC0, 0x01, 0xE0, 0x00, 0xF8, 0x00, 0x3F, 0x00, 0x1F, 0xC0, 0x0F, 0xF0, + 0x07, 0x9E, 0x03, 0xC7, 0x80, 0xF0, 0xF0, 0x78, 0x3C, 0x3C, 0x0F, 0x80, + 0x78, 0x1E, 0xF0, 0x79, 0xE0, 0xF3, 0xC3, 0xC3, 0xCF, 0x07, 0x9E, 0x0F, + 0x78, 0x0F, 0xE0, 0x1F, 0x80, 0x3F, 0x00, 0x3C, 0x00, 0x70, 0x00, 0xE0, + 0x03, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x1F, 0xFF, + 0x0F, 0xFF, 0x87, 0xFF, 0xC0, 0x03, 0xC0, 0x03, 0xE0, 0x03, 0xE0, 0x03, + 0xE0, 0x03, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, + 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xFF, 0xF0, 0xFF, 0xF8, 0x7F, 0xFC, + 0x00, 0x0F, 0xC3, 0xF0, 0xFC, 0x38, 0x1E, 0x07, 0x01, 0xC0, 0x70, 0x1C, + 0x0F, 0x03, 0x80, 0xE0, 0x38, 0x0E, 0x07, 0x01, 0xC0, 0x70, 0x1C, 0x0F, + 0x03, 0x80, 0xFC, 0x3F, 0x0F, 0xC0, 0x08, 0x88, 0xC4, 0x44, 0x66, 0x66, + 0x66, 0x62, 0x22, 0x33, 0x33, 0x30, 0x0F, 0xC3, 0xF0, 0xFC, 0x07, 0x03, + 0xC0, 0xE0, 0x38, 0x0E, 0x03, 0x81, 0xC0, 0x70, 0x1C, 0x07, 0x03, 0xC0, + 0xE0, 0x38, 0x0E, 0x03, 0x81, 0xE0, 0x70, 0xFC, 0x3F, 0x0F, 0xC0, 0x03, + 0x80, 0xF0, 0x1E, 0x07, 0xE1, 0xDC, 0x3B, 0x8E, 0x71, 0x86, 0x70, 0xFC, + 0x1F, 0x83, 0x80, 0x7F, 0xFE, 0xFF, 0xFC, 0xE6, 0x30, 0x07, 0xE0, 0xFF, + 0x8F, 0xFE, 0x70, 0xE0, 0x07, 0x03, 0xF8, 0xFF, 0xCF, 0x9E, 0xF0, 0xF7, + 0x8F, 0x3F, 0xF8, 0xFF, 0xC3, 0xDF, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, + 0x00, 0xF0, 0x01, 0xE0, 0x03, 0x9F, 0x07, 0xFF, 0x0F, 0xFF, 0x3E, 0x3E, + 0x78, 0x3C, 0xF0, 0x79, 0xC0, 0xF3, 0x81, 0xEF, 0x07, 0x9F, 0x1F, 0x3F, + 0xFC, 0x7F, 0xF0, 0xEF, 0x80, 0x07, 0xC0, 0xFF, 0x8F, 0xFE, 0xF8, 0xF7, + 0x87, 0xB8, 0x03, 0xC0, 0x1E, 0x00, 0xF0, 0xF7, 0x8F, 0x1F, 0xF8, 0xFF, + 0x81, 0xF0, 0x00, 0x00, 0x1E, 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x03, + 0xC0, 0xF7, 0x87, 0xFE, 0x1F, 0xFC, 0x7C, 0x78, 0xF0, 0x73, 0xC0, 0xE7, + 0x81, 0x8F, 0x07, 0x1E, 0x0E, 0x3E, 0x3C, 0x7F, 0xF8, 0x7F, 0xE0, 0x7D, + 0xC0, 0x07, 0xC0, 0xFF, 0x8F, 0xFE, 0xF0, 0xF7, 0x87, 0xFF, 0xFF, 0xFF, + 0xFE, 0x00, 0xF0, 0x07, 0xC7, 0x9F, 0xF8, 0xFF, 0x81, 0xF0, 0x00, 0x07, + 0x87, 0xC7, 0xE3, 0xC1, 0xC3, 0xF9, 0xFC, 0x78, 0x3C, 0x1C, 0x0E, 0x07, + 0x07, 0x83, 0x81, 0xC0, 0xE0, 0xF0, 0x78, 0x00, 0x03, 0xDE, 0x1F, 0xF8, + 0x7F, 0xF1, 0xF1, 0xE3, 0xC1, 0xCF, 0x03, 0x9E, 0x06, 0x3C, 0x0C, 0x78, + 0x38, 0xF8, 0xF1, 0xFF, 0xC1, 0xFF, 0x81, 0xF7, 0x00, 0x0E, 0x3C, 0x3C, + 0x78, 0xF0, 0x7F, 0xC0, 0x7E, 0x00, 0x1E, 0x00, 0x70, 0x01, 0xC0, 0x07, + 0x00, 0x3C, 0x00, 0xF7, 0xC3, 0xBF, 0x8F, 0xFF, 0x3C, 0x3D, 0xE0, 0xE7, + 0x83, 0x9C, 0x0E, 0x70, 0x79, 0xC1, 0xEF, 0x07, 0x3C, 0x1C, 0xE0, 0x73, + 0x83, 0xC0, 0x0E, 0x3C, 0x70, 0x00, 0x03, 0x8F, 0x1E, 0x38, 0x71, 0xE3, + 0xC7, 0x0E, 0x1C, 0x78, 0xF1, 0xC0, 0x03, 0xC0, 0xE0, 0x38, 0x00, 0x00, + 0x01, 0xE0, 0x70, 0x1C, 0x07, 0x03, 0xC0, 0xF0, 0x38, 0x0E, 0x03, 0x81, + 0xE0, 0x70, 0x1C, 0x07, 0x03, 0xC0, 0xF0, 0xF8, 0x3E, 0x0F, 0x00, 0x0E, + 0x00, 0x1C, 0x00, 0x38, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0x87, 0x87, 0x1E, + 0x0E, 0x78, 0x3D, 0xE0, 0x7F, 0x80, 0xFE, 0x01, 0xFE, 0x03, 0xFC, 0x0F, + 0x38, 0x1E, 0x78, 0x38, 0xF0, 0x70, 0xF0, 0xE1, 0xE0, 0x0E, 0x3C, 0x78, + 0xE1, 0xC3, 0x8F, 0x1E, 0x38, 0x71, 0xE3, 0xC7, 0x0E, 0x1C, 0x78, 0xF1, + 0xC0, 0x1C, 0xF1, 0xE0, 0xEF, 0xDF, 0x87, 0xFF, 0xFE, 0x7C, 0x78, 0xF3, + 0xC3, 0x87, 0x9C, 0x1C, 0x38, 0xE1, 0xE1, 0xC7, 0x0E, 0x0E, 0x78, 0x70, + 0xF3, 0xC3, 0x87, 0x9C, 0x3C, 0x38, 0xE1, 0xE1, 0xC7, 0x0E, 0x0E, 0x00, + 0x3D, 0xF0, 0xEF, 0xE3, 0xFF, 0xCF, 0x0F, 0x78, 0x39, 0xC0, 0xE7, 0x03, + 0x9C, 0x1E, 0xF0, 0x7B, 0xC1, 0xCE, 0x07, 0x38, 0x1C, 0xE0, 0xF0, 0x07, + 0xE0, 0x7F, 0xE3, 0xFF, 0x9F, 0x1F, 0x78, 0x3F, 0xC0, 0xFF, 0x03, 0xFC, + 0x1F, 0xF0, 0x7B, 0xE3, 0xE7, 0xFF, 0x1F, 0xF8, 0x1F, 0x80, 0x0E, 0x7C, + 0x0F, 0xFE, 0x0F, 0xFF, 0x1F, 0x1F, 0x1E, 0x0F, 0x1E, 0x0F, 0x1C, 0x0F, + 0x1C, 0x0F, 0x3C, 0x1E, 0x3E, 0x3E, 0x3F, 0xFC, 0x3F, 0xF8, 0x7B, 0xE0, + 0x78, 0x00, 0x70, 0x00, 0x70, 0x00, 0x70, 0x00, 0xF0, 0x00, 0x07, 0xBC, + 0x7F, 0xF3, 0xFF, 0x9F, 0x1E, 0x78, 0x3B, 0xC0, 0xEF, 0x03, 0x3C, 0x0C, + 0xF0, 0x73, 0xE3, 0xCF, 0xFF, 0x1F, 0xF8, 0x3C, 0xE0, 0x03, 0x80, 0x1E, + 0x00, 0x78, 0x01, 0xC0, 0x07, 0x00, 0x3D, 0xCE, 0xE3, 0xF8, 0xF0, 0x78, + 0x1E, 0x07, 0x01, 0xC0, 0xF0, 0x3C, 0x0E, 0x03, 0x80, 0xE0, 0x00, 0x1F, + 0xC3, 0xFE, 0x7F, 0xFF, 0x0F, 0xF0, 0x0F, 0xE0, 0x7F, 0xC1, 0xFE, 0x03, + 0xEE, 0x1E, 0xFF, 0xC7, 0xFC, 0x3F, 0x00, 0x1E, 0x1E, 0x1C, 0x7F, 0xFF, + 0x3C, 0x38, 0x38, 0x38, 0x78, 0x78, 0x70, 0x7C, 0xF8, 0x78, 0x38, 0x3C, + 0xE0, 0xE3, 0x83, 0x9E, 0x0E, 0x70, 0x79, 0xC1, 0xE7, 0x07, 0x3C, 0x1C, + 0xF0, 0xF3, 0xE7, 0xCF, 0xFF, 0x1F, 0xF8, 0x3C, 0xE0, 0xF0, 0x77, 0x87, + 0xBC, 0x38, 0xE3, 0xC7, 0x1C, 0x39, 0xE1, 0xCE, 0x0E, 0xE0, 0x77, 0x03, + 0xF0, 0x0F, 0x80, 0x78, 0x03, 0xC0, 0x00, 0xF1, 0xC3, 0xF8, 0xE3, 0xFC, + 0xF1, 0xDE, 0x79, 0xEF, 0x3C, 0xE7, 0xB6, 0x73, 0xDB, 0x70, 0xED, 0xB8, + 0x7C, 0xF8, 0x3E, 0x7C, 0x1F, 0x3C, 0x0F, 0x1E, 0x07, 0x8E, 0x00, 0x0F, + 0x1E, 0x0F, 0x3C, 0x0F, 0x38, 0x07, 0x70, 0x07, 0xF0, 0x03, 0xE0, 0x03, + 0xC0, 0x07, 0xC0, 0x0F, 0xE0, 0x1E, 0xE0, 0x3C, 0xF0, 0x3C, 0xF0, 0x78, + 0x78, 0x3C, 0x1C, 0x78, 0x78, 0xF0, 0xE1, 0xE3, 0xC1, 0xC7, 0x03, 0x9E, + 0x07, 0x38, 0x0E, 0xE0, 0x1D, 0xC0, 0x3F, 0x00, 0x7E, 0x00, 0x78, 0x00, + 0xF0, 0x01, 0xC0, 0x07, 0x00, 0x7E, 0x00, 0xF8, 0x01, 0xE0, 0x00, 0x1F, + 0xF9, 0xFF, 0xCF, 0xFC, 0x01, 0xE0, 0x3E, 0x03, 0xC0, 0x3C, 0x03, 0xC0, + 0x3C, 0x03, 0xC0, 0x3F, 0xF9, 0xFF, 0xCF, 0xFC, 0x00, 0x07, 0x87, 0xC3, + 0xE3, 0xC1, 0xC0, 0xE0, 0x70, 0x38, 0x3C, 0x1C, 0x0E, 0x1E, 0x0F, 0x03, + 0x81, 0xC0, 0xE0, 0x70, 0x78, 0x38, 0x1C, 0x0F, 0x87, 0xC1, 0xC0, 0x0C, + 0x30, 0x86, 0x18, 0x61, 0x8C, 0x30, 0xC3, 0x0C, 0x61, 0x86, 0x18, 0x63, + 0x0C, 0x30, 0xC2, 0x00, 0x00, 0x07, 0x07, 0xC3, 0xE0, 0x70, 0x38, 0x3C, + 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xE0, 0xF0, 0xE0, 0x70, 0x78, 0x38, 0x1C, + 0x0E, 0x07, 0x07, 0x8F, 0x87, 0xC3, 0xC0, 0x3C, 0x07, 0xE0, 0xC7, 0x30, + 0x7E, 0x01, 0xC0 }; + +const GFXglyph FreeSansBoldOblique12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 7, 0, 1 }, // 0x20 ' ' + { 0, 7, 17, 8, 3, -16 }, // 0x21 '!' + { 15, 10, 6, 11, 4, -17 }, // 0x22 '"' + { 23, 15, 16, 13, 1, -15 }, // 0x23 '#' + { 53, 15, 21, 13, 1, -17 }, // 0x24 '$' + { 93, 18, 18, 21, 3, -17 }, // 0x25 '%' + { 134, 15, 17, 17, 2, -16 }, // 0x26 '&' + { 166, 4, 6, 6, 4, -17 }, // 0x27 ''' + { 169, 9, 22, 8, 2, -17 }, // 0x28 '(' + { 194, 9, 22, 8, -1, -16 }, // 0x29 ')' + { 219, 8, 8, 9, 3, -17 }, // 0x2A '*' + { 227, 12, 11, 14, 2, -10 }, // 0x2B '+' + { 244, 5, 7, 7, 1, -2 }, // 0x2C ',' + { 249, 7, 3, 8, 2, -7 }, // 0x2D '-' + { 252, 4, 3, 7, 2, -2 }, // 0x2E '.' + { 254, 10, 17, 7, 0, -16 }, // 0x2F '/' + { 276, 13, 17, 13, 2, -16 }, // 0x30 '0' + { 304, 9, 17, 13, 4, -16 }, // 0x31 '1' + { 324, 15, 17, 13, 1, -16 }, // 0x32 '2' + { 356, 13, 17, 13, 2, -16 }, // 0x33 '3' + { 384, 13, 17, 13, 1, -16 }, // 0x34 '4' + { 412, 14, 17, 13, 1, -16 }, // 0x35 '5' + { 442, 13, 17, 13, 2, -16 }, // 0x36 '6' + { 470, 13, 17, 13, 3, -16 }, // 0x37 '7' + { 498, 14, 17, 13, 1, -16 }, // 0x38 '8' + { 528, 14, 17, 13, 2, -16 }, // 0x39 '9' + { 558, 6, 12, 8, 3, -11 }, // 0x3A ':' + { 567, 7, 16, 8, 2, -11 }, // 0x3B ';' + { 581, 13, 12, 14, 2, -11 }, // 0x3C '<' + { 601, 14, 9, 14, 1, -9 }, // 0x3D '=' + { 617, 13, 12, 14, 1, -10 }, // 0x3E '>' + { 637, 13, 18, 15, 4, -17 }, // 0x3F '?' + { 667, 22, 21, 23, 2, -17 }, // 0x40 '@' + { 725, 17, 18, 17, 0, -17 }, // 0x41 'A' + { 764, 17, 18, 17, 2, -17 }, // 0x42 'B' + { 803, 17, 18, 17, 3, -17 }, // 0x43 'C' + { 842, 17, 18, 17, 2, -17 }, // 0x44 'D' + { 881, 16, 18, 16, 2, -17 }, // 0x45 'E' + { 917, 16, 18, 15, 2, -17 }, // 0x46 'F' + { 953, 17, 18, 19, 3, -17 }, // 0x47 'G' + { 992, 17, 18, 17, 2, -17 }, // 0x48 'H' + { 1031, 7, 18, 7, 2, -17 }, // 0x49 'I' + { 1047, 14, 18, 13, 1, -17 }, // 0x4A 'J' + { 1079, 18, 18, 17, 2, -17 }, // 0x4B 'K' + { 1120, 13, 18, 15, 2, -17 }, // 0x4C 'L' + { 1150, 20, 18, 20, 2, -17 }, // 0x4D 'M' + { 1195, 18, 18, 17, 2, -17 }, // 0x4E 'N' + { 1236, 17, 18, 19, 3, -17 }, // 0x4F 'O' + { 1275, 16, 18, 16, 2, -17 }, // 0x50 'P' + { 1311, 17, 19, 19, 3, -17 }, // 0x51 'Q' + { 1352, 17, 18, 17, 2, -17 }, // 0x52 'R' + { 1391, 16, 18, 16, 2, -17 }, // 0x53 'S' + { 1427, 15, 18, 15, 3, -17 }, // 0x54 'T' + { 1461, 16, 18, 17, 3, -17 }, // 0x55 'U' + { 1497, 15, 18, 16, 4, -17 }, // 0x56 'V' + { 1531, 21, 18, 23, 4, -17 }, // 0x57 'W' + { 1579, 18, 18, 16, 1, -17 }, // 0x58 'X' + { 1620, 15, 18, 16, 4, -17 }, // 0x59 'Y' + { 1654, 17, 18, 15, 1, -17 }, // 0x5A 'Z' + { 1693, 10, 23, 8, 1, -17 }, // 0x5B '[' + { 1722, 4, 23, 7, 3, -22 }, // 0x5C '\' + { 1734, 10, 23, 8, 0, -17 }, // 0x5D ']' + { 1763, 11, 11, 14, 3, -16 }, // 0x5E '^' + { 1779, 15, 2, 13, -2, 4 }, // 0x5F '_' + { 1783, 4, 3, 8, 4, -17 }, // 0x60 '`' + { 1785, 13, 13, 13, 1, -12 }, // 0x61 'a' + { 1807, 15, 18, 15, 1, -17 }, // 0x62 'b' + { 1841, 13, 13, 13, 2, -12 }, // 0x63 'c' + { 1863, 15, 18, 15, 2, -17 }, // 0x64 'd' + { 1897, 13, 13, 13, 2, -12 }, // 0x65 'e' + { 1919, 9, 18, 8, 2, -17 }, // 0x66 'f' + { 1940, 15, 18, 15, 1, -12 }, // 0x67 'g' + { 1974, 14, 18, 15, 2, -17 }, // 0x68 'h' + { 2006, 7, 18, 7, 2, -17 }, // 0x69 'i' + { 2022, 10, 23, 7, -1, -17 }, // 0x6A 'j' + { 2051, 15, 18, 13, 1, -17 }, // 0x6B 'k' + { 2085, 7, 18, 7, 2, -17 }, // 0x6C 'l' + { 2101, 21, 13, 21, 1, -12 }, // 0x6D 'm' + { 2136, 14, 13, 15, 2, -12 }, // 0x6E 'n' + { 2159, 14, 13, 15, 2, -12 }, // 0x6F 'o' + { 2182, 16, 18, 15, 0, -12 }, // 0x70 'p' + { 2218, 14, 18, 15, 2, -12 }, // 0x71 'q' + { 2250, 10, 13, 9, 2, -12 }, // 0x72 'r' + { 2267, 12, 13, 13, 3, -12 }, // 0x73 's' + { 2287, 8, 15, 8, 2, -14 }, // 0x74 't' + { 2302, 14, 13, 15, 2, -12 }, // 0x75 'u' + { 2325, 13, 13, 13, 3, -12 }, // 0x76 'v' + { 2347, 17, 13, 19, 3, -12 }, // 0x77 'w' + { 2375, 16, 13, 13, 0, -12 }, // 0x78 'x' + { 2401, 15, 18, 13, 1, -12 }, // 0x79 'y' + { 2435, 13, 13, 12, 1, -12 }, // 0x7A 'z' + { 2457, 9, 23, 9, 3, -17 }, // 0x7B '{' + { 2483, 6, 23, 7, 1, -17 }, // 0x7C '|' + { 2501, 9, 23, 9, 0, -17 }, // 0x7D '}' + { 2527, 12, 5, 14, 2, -7 } }; // 0x7E '~' + +const GFXfont FreeSansBoldOblique12pt7b PROGMEM = { + (uint8_t *)FreeSansBoldOblique12pt7bBitmaps, + (GFXglyph *)FreeSansBoldOblique12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 3207 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique18pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique18pt7b.h new file mode 100644 index 0000000..79c748c --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique18pt7b.h @@ -0,0 +1,545 @@ +const uint8_t FreeSansBoldOblique18pt7bBitmaps[] PROGMEM = { + 0x06, 0x01, 0xC0, 0x7C, 0x1F, 0x0F, 0xC3, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, + 0xC0, 0xF0, 0x7C, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1C, 0x07, 0x01, 0xC0, + 0x60, 0x7C, 0x1F, 0x07, 0xC3, 0xF0, 0xF8, 0x00, 0x78, 0x7B, 0xC3, 0xFE, + 0x3F, 0xE1, 0xEF, 0x0F, 0x78, 0x7B, 0x83, 0x9C, 0x1C, 0xC0, 0xC0, 0x00, + 0x3C, 0x38, 0x00, 0xF1, 0xE0, 0x07, 0x87, 0x00, 0x1E, 0x3C, 0x00, 0xF0, + 0xE0, 0x3F, 0xFF, 0xF0, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0x1F, 0xFF, 0xF8, + 0x0F, 0x0E, 0x00, 0x3C, 0x78, 0x00, 0xE1, 0xE0, 0x07, 0x8F, 0x00, 0x1C, + 0x3C, 0x07, 0xFF, 0xFE, 0x1F, 0xFF, 0xF8, 0x7F, 0xFF, 0xE3, 0xFF, 0xFF, + 0x01, 0xE3, 0xC0, 0x0F, 0x0E, 0x00, 0x3C, 0x78, 0x01, 0xE1, 0xC0, 0x07, + 0x8F, 0x00, 0x3C, 0x38, 0x00, 0x00, 0x0C, 0x00, 0x01, 0x80, 0x00, 0xFC, + 0x00, 0xFF, 0xC0, 0x3F, 0xFC, 0x0F, 0xFF, 0xC3, 0xE6, 0x78, 0x78, 0xCF, + 0x1E, 0x39, 0xE3, 0xC7, 0x3C, 0x78, 0xC0, 0x0F, 0x98, 0x01, 0xFF, 0x00, + 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x00, 0x7F, 0x80, 0x0F, 0xF0, + 0x03, 0xBE, 0x00, 0x67, 0xCF, 0x8C, 0xF9, 0xF1, 0x9F, 0x3E, 0x77, 0xC7, + 0xEF, 0xF8, 0x7F, 0xFE, 0x0F, 0xFF, 0x80, 0xFF, 0xE0, 0x03, 0xE0, 0x00, + 0x38, 0x00, 0x06, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x00, 0x07, 0x01, 0xE0, + 0x03, 0x81, 0xFE, 0x00, 0xC0, 0xFF, 0x80, 0x70, 0x7F, 0xF0, 0x38, 0x1E, + 0x3C, 0x1C, 0x0F, 0x07, 0x06, 0x03, 0x81, 0xC3, 0x80, 0xE0, 0xF1, 0xC0, + 0x3C, 0x78, 0xE0, 0x0F, 0xFE, 0x30, 0x01, 0xFF, 0x1C, 0x00, 0x7F, 0x8E, + 0x00, 0x07, 0x83, 0x00, 0x00, 0x01, 0x83, 0xE0, 0x00, 0xE3, 0xFE, 0x00, + 0x71, 0xFF, 0x80, 0x18, 0xFF, 0xF0, 0x0C, 0x3C, 0x3C, 0x07, 0x1C, 0x07, + 0x03, 0x87, 0x01, 0xC0, 0xC1, 0xE1, 0xE0, 0x60, 0x7F, 0xF8, 0x38, 0x0F, + 0xFC, 0x1C, 0x03, 0xFE, 0x06, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, 0x03, + 0xFC, 0x00, 0x3F, 0xF0, 0x03, 0xFF, 0x80, 0x3F, 0x3C, 0x01, 0xF1, 0xE0, + 0x0F, 0x8F, 0x00, 0x7C, 0xF0, 0x03, 0xFF, 0x80, 0x0F, 0xF8, 0x00, 0x3F, + 0x00, 0x03, 0xF0, 0x00, 0x7F, 0xC7, 0x8F, 0xFE, 0x3C, 0xFC, 0xFB, 0xCF, + 0x83, 0xFE, 0xF8, 0x1F, 0xE7, 0xC0, 0x7E, 0x3E, 0x03, 0xE1, 0xF0, 0x1F, + 0x0F, 0xE3, 0xFC, 0x7F, 0xFF, 0xE1, 0xFF, 0xFF, 0x87, 0xFE, 0x7C, 0x0F, + 0xE1, 0xF0, 0x7B, 0xFF, 0xEF, 0x7B, 0x9C, 0xC0, 0x00, 0x78, 0x07, 0x80, + 0x78, 0x03, 0x80, 0x3C, 0x03, 0xC0, 0x1E, 0x01, 0xE0, 0x1E, 0x00, 0xF0, + 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0xF0, 0x07, + 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xF0, + 0x07, 0x80, 0x1C, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x00, 0xE0, 0x07, 0x80, + 0x1C, 0x00, 0x01, 0xC0, 0x0F, 0x00, 0x38, 0x01, 0xE0, 0x0F, 0x00, 0x78, + 0x01, 0xC0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, + 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0xF8, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x1E, + 0x00, 0xF0, 0x07, 0x80, 0x78, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x1E, 0x01, + 0xE0, 0x1E, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x00, 0x03, 0x00, 0x70, 0x07, + 0x04, 0x63, 0xFF, 0xF7, 0xFF, 0x1F, 0x83, 0xF0, 0x3B, 0x87, 0x38, 0x21, + 0x00, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, + 0x00, 0x7C, 0x07, 0xFF, 0xFD, 0xFF, 0xFF, 0xFF, 0xFF, 0xBF, 0xFF, 0xE0, + 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x7C, 0x00, 0x1E, + 0x00, 0x3E, 0x7C, 0xF3, 0xE7, 0xC1, 0x87, 0x0C, 0x39, 0xE3, 0x00, 0x7F, + 0xDF, 0xFF, 0xFB, 0xFE, 0x7D, 0xF7, 0xBE, 0xF8, 0x00, 0x0E, 0x00, 0x18, + 0x00, 0x70, 0x00, 0xC0, 0x03, 0x80, 0x06, 0x00, 0x1C, 0x00, 0x30, 0x00, + 0xE0, 0x01, 0x80, 0x07, 0x00, 0x0C, 0x00, 0x38, 0x00, 0x60, 0x01, 0xC0, + 0x03, 0x00, 0x0E, 0x00, 0x18, 0x00, 0x70, 0x00, 0xC0, 0x03, 0x80, 0x06, + 0x00, 0x1C, 0x00, 0x30, 0x00, 0xE0, 0x00, 0x00, 0xFC, 0x00, 0x7F, 0xC0, + 0x7F, 0xF8, 0x3F, 0xFE, 0x0F, 0x8F, 0xC7, 0xC1, 0xF1, 0xE0, 0x7C, 0xF8, + 0x1F, 0x3E, 0x07, 0xDF, 0x01, 0xF7, 0xC0, 0x7D, 0xF0, 0x3F, 0x7C, 0x0F, + 0xBF, 0x03, 0xEF, 0x80, 0xFB, 0xE0, 0x3E, 0xF8, 0x1F, 0x3E, 0x07, 0xCF, + 0x81, 0xE3, 0xE0, 0xF8, 0xFC, 0x7C, 0x1F, 0xFF, 0x07, 0xFF, 0x80, 0xFF, + 0xC0, 0x0F, 0x80, 0x00, 0x00, 0x70, 0x03, 0x80, 0x3C, 0x03, 0xE0, 0xFF, + 0x3F, 0xF3, 0xFF, 0x9F, 0xFC, 0x03, 0xE0, 0x1F, 0x01, 0xF0, 0x0F, 0x80, + 0x7C, 0x03, 0xE0, 0x1E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x3E, + 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x3E, 0x00, 0x00, 0x1F, 0x80, + 0x07, 0xFF, 0x00, 0x7F, 0xFC, 0x07, 0xFF, 0xE0, 0x7E, 0x1F, 0x83, 0xE0, + 0x7C, 0x1F, 0x03, 0xE1, 0xF0, 0x1F, 0x0F, 0x80, 0xF8, 0x00, 0x0F, 0x80, + 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xE0, 0x00, 0xFC, + 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x80, 0x03, 0xF8, 0x00, 0x3F, + 0x00, 0x03, 0xF0, 0x00, 0x1F, 0xFF, 0xE1, 0xFF, 0xFF, 0x0F, 0xFF, 0xF0, + 0x7F, 0xFF, 0x80, 0x00, 0x7F, 0x00, 0x1F, 0xFC, 0x03, 0xFF, 0xE0, 0x7F, + 0xFF, 0x0F, 0x83, 0xF0, 0xF0, 0x1F, 0x1F, 0x01, 0xF1, 0xE0, 0x1F, 0x00, + 0x03, 0xE0, 0x00, 0xFC, 0x00, 0xFF, 0x80, 0x0F, 0xF0, 0x00, 0xFF, 0x80, + 0x0F, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xCF, 0x80, 0x7C, + 0xF8, 0x07, 0xCF, 0x80, 0xF8, 0xFC, 0x3F, 0x8F, 0xFF, 0xF0, 0x7F, 0xFE, + 0x03, 0xFF, 0xC0, 0x0F, 0xE0, 0x00, 0x00, 0x07, 0xE0, 0x01, 0xFC, 0x00, + 0x7F, 0x00, 0x1F, 0xE0, 0x03, 0xFC, 0x00, 0xEF, 0x80, 0x3D, 0xF0, 0x0F, + 0x7C, 0x03, 0xCF, 0x80, 0xF1, 0xF0, 0x1C, 0x3E, 0x07, 0x07, 0xC1, 0xE1, + 0xF0, 0x78, 0x3E, 0x1E, 0x07, 0xC3, 0xFF, 0xFE, 0x7F, 0xFF, 0xDF, 0xFF, + 0xFB, 0xFF, 0xFF, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x78, 0x00, 0x1F, + 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x01, 0xFF, 0xF0, 0x3F, 0xFF, 0x03, + 0xFF, 0xF0, 0x3F, 0xFF, 0x07, 0x80, 0x00, 0x78, 0x00, 0x0F, 0x00, 0x00, + 0xF7, 0xE0, 0x0F, 0xFF, 0x01, 0xFF, 0xF8, 0x1F, 0xFF, 0x83, 0xF0, 0xFC, + 0x3E, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, + 0x8F, 0x80, 0xF8, 0xF8, 0x1F, 0x8F, 0xC3, 0xF0, 0xFF, 0xFE, 0x07, 0xFF, + 0xC0, 0x3F, 0xF8, 0x00, 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x3F, 0xF0, 0x0F, + 0xFF, 0x03, 0xFF, 0xE0, 0xF8, 0x7E, 0x3E, 0x07, 0xC7, 0x80, 0x01, 0xF0, + 0x00, 0x3C, 0xFC, 0x07, 0xFF, 0xC1, 0xFF, 0xFC, 0x3F, 0xFF, 0xC7, 0xE1, + 0xF8, 0xF8, 0x1F, 0x3E, 0x03, 0xE7, 0x80, 0x7C, 0xF0, 0x0F, 0x9E, 0x01, + 0xE3, 0xC0, 0x7C, 0x78, 0x1F, 0x0F, 0x87, 0xE0, 0xFF, 0xF8, 0x1F, 0xFE, + 0x01, 0xFF, 0x80, 0x0F, 0xC0, 0x00, 0x7F, 0xFF, 0xEF, 0xFF, 0xF9, 0xFF, + 0xFF, 0x7F, 0xFF, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, + 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x07, 0x80, 0x01, 0xF0, 0x00, 0x7C, + 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x3E, 0x00, + 0x07, 0xC0, 0x00, 0x00, 0x7F, 0x00, 0x1F, 0xFC, 0x07, 0xFF, 0xE0, 0xFF, + 0xFF, 0x0F, 0x81, 0xF1, 0xF0, 0x0F, 0x1E, 0x00, 0xF1, 0xE0, 0x1E, 0x1F, + 0x07, 0xE0, 0xFF, 0xFC, 0x07, 0xFF, 0x00, 0xFF, 0xF8, 0x1F, 0xFF, 0x83, + 0xF0, 0xFC, 0x7C, 0x07, 0xC7, 0xC0, 0x7C, 0xF8, 0x07, 0xCF, 0x80, 0x7C, + 0xF8, 0x0F, 0x8F, 0x80, 0xF8, 0xFC, 0x3F, 0x0F, 0xFF, 0xF0, 0x7F, 0xFE, + 0x03, 0xFF, 0x80, 0x0F, 0xE0, 0x00, 0x00, 0x7E, 0x00, 0x3F, 0xF0, 0x0F, + 0xFF, 0x03, 0xFF, 0xE0, 0xFC, 0x3E, 0x3F, 0x03, 0xC7, 0xC0, 0x79, 0xF0, + 0x0F, 0x3E, 0x01, 0xE7, 0xC0, 0x3C, 0xF8, 0x0F, 0x9F, 0x03, 0xE3, 0xF0, + 0xFC, 0x7F, 0xFF, 0x87, 0xFF, 0xF0, 0x7F, 0xFE, 0x07, 0xE7, 0x80, 0x01, + 0xF0, 0x00, 0x3C, 0x7C, 0x0F, 0x8F, 0xC3, 0xE1, 0xFF, 0xF8, 0x1F, 0xFE, + 0x01, 0xFF, 0x80, 0x0F, 0xC0, 0x00, 0x0F, 0x87, 0xC3, 0xC3, 0xE1, 0xF0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xE1, 0xF0, 0xF0, + 0xF8, 0x7C, 0x00, 0x07, 0xC1, 0xF0, 0x78, 0x3E, 0x0F, 0x80, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x83, 0xE0, 0xF0, 0x7C, + 0x1F, 0x00, 0xC0, 0x70, 0x18, 0x0E, 0x0F, 0x03, 0x00, 0x00, 0x00, 0x20, + 0x00, 0x3C, 0x00, 0x3F, 0x80, 0x3F, 0xE0, 0x3F, 0xFC, 0x3F, 0xFC, 0x1F, + 0xFC, 0x07, 0xFC, 0x00, 0xFC, 0x00, 0x1F, 0xF0, 0x03, 0xFF, 0x80, 0x1F, + 0xFE, 0x00, 0xFF, 0xF0, 0x03, 0xFE, 0x00, 0x1F, 0xC0, 0x00, 0x78, 0x00, + 0x03, 0x00, 0x1F, 0xFF, 0xF3, 0xFF, 0xFE, 0x3F, 0xFF, 0xE3, 0xFF, 0xFE, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, + 0xC7, 0xFF, 0xFC, 0xFF, 0xFF, 0x8F, 0xFF, 0xF8, 0x18, 0x00, 0x03, 0xC0, + 0x00, 0x7F, 0x00, 0x0F, 0xF8, 0x01, 0xFF, 0xE0, 0x0F, 0xFF, 0x00, 0x3F, + 0xF8, 0x01, 0xFF, 0x00, 0x07, 0xE0, 0x07, 0xFC, 0x07, 0xFF, 0x07, 0xFF, + 0x87, 0xFF, 0x80, 0xFF, 0x80, 0x3F, 0x80, 0x07, 0x80, 0x00, 0x80, 0x00, + 0x00, 0x03, 0xF8, 0x03, 0xFF, 0xC1, 0xFF, 0xF8, 0xFF, 0xFE, 0x7E, 0x1F, + 0xDF, 0x03, 0xFF, 0x80, 0x7F, 0xE0, 0x1F, 0xF8, 0x07, 0xC0, 0x03, 0xE0, + 0x01, 0xF8, 0x00, 0xFC, 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x3F, 0x80, 0x1F, + 0x80, 0x07, 0x80, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x07, 0xC0, 0x01, 0xF0, 0x00, 0xFC, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x00, + 0x00, 0x00, 0x7F, 0x80, 0x00, 0x01, 0xFF, 0xF8, 0x00, 0x03, 0xFF, 0xFE, + 0x00, 0x07, 0xF0, 0x1F, 0xC0, 0x0F, 0xC0, 0x03, 0xE0, 0x0F, 0x80, 0x00, + 0xF8, 0x0F, 0x00, 0x00, 0x3C, 0x0F, 0x01, 0xF1, 0xCF, 0x0F, 0x03, 0xFD, + 0xC7, 0x8F, 0x03, 0xFF, 0xE1, 0xC7, 0x03, 0xE3, 0xE0, 0xE7, 0x03, 0xC0, + 0xF0, 0x73, 0x83, 0xC0, 0x78, 0x3B, 0x81, 0xE0, 0x38, 0x1D, 0xC1, 0xE0, + 0x1C, 0x1C, 0xC0, 0xF0, 0x1C, 0x0E, 0xE0, 0x70, 0x0E, 0x0F, 0x70, 0x78, + 0x0E, 0x07, 0x38, 0x3C, 0x0F, 0x07, 0x1C, 0x1E, 0x0F, 0x87, 0x8E, 0x0F, + 0x8F, 0xCF, 0x87, 0x07, 0xFF, 0xFF, 0x83, 0xC1, 0xFE, 0x7F, 0x00, 0xE0, + 0x3C, 0x1F, 0x00, 0x78, 0x00, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x0F, + 0xC0, 0x01, 0x00, 0x03, 0xF8, 0x07, 0x80, 0x00, 0xFF, 0xFF, 0xC0, 0x00, + 0x1F, 0xFF, 0xE0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x00, 0x03, 0xF0, 0x00, + 0x0F, 0xE0, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0xC0, 0x00, 0xFF, 0x80, 0x03, + 0xFF, 0x00, 0x07, 0xFE, 0x00, 0x1F, 0x7C, 0x00, 0x7E, 0xF8, 0x00, 0xF9, + 0xF0, 0x03, 0xF3, 0xE0, 0x07, 0xC3, 0xE0, 0x1F, 0x87, 0xC0, 0x3E, 0x0F, + 0x80, 0xF8, 0x1F, 0x01, 0xF0, 0x3E, 0x07, 0xFF, 0xFC, 0x1F, 0xFF, 0xF8, + 0x3F, 0xFF, 0xF0, 0xFF, 0xFF, 0xF1, 0xF0, 0x03, 0xE7, 0xC0, 0x07, 0xCF, + 0x80, 0x0F, 0xBE, 0x00, 0x1F, 0x7C, 0x00, 0x3F, 0xF0, 0x00, 0x7C, 0x07, + 0xFF, 0xF0, 0x07, 0xFF, 0xFC, 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0x0F, + 0xC0, 0x3F, 0x0F, 0x80, 0x1F, 0x0F, 0x80, 0x1F, 0x0F, 0x80, 0x1F, 0x1F, + 0x80, 0x1E, 0x1F, 0x80, 0x3E, 0x1F, 0x00, 0x7C, 0x1F, 0xFF, 0xF8, 0x1F, + 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, 0x3F, 0xFF, 0xF8, 0x3E, 0x00, 0xFC, 0x3E, + 0x00, 0x7C, 0x3E, 0x00, 0x7C, 0x7E, 0x00, 0x7C, 0x7C, 0x00, 0x7C, 0x7C, + 0x00, 0xF8, 0x7C, 0x01, 0xF8, 0x7F, 0xFF, 0xF0, 0xFF, 0xFF, 0xE0, 0xFF, + 0xFF, 0xC0, 0xFF, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0xF8, 0x01, + 0xFF, 0xFC, 0x03, 0xFF, 0xFE, 0x07, 0xE0, 0x7F, 0x0F, 0xC0, 0x3F, 0x1F, + 0x80, 0x1F, 0x3F, 0x00, 0x1F, 0x3E, 0x00, 0x1F, 0x7E, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x7C, 0xF8, + 0x00, 0x7C, 0xFC, 0x00, 0xF8, 0xFC, 0x01, 0xF8, 0x7F, 0x07, 0xF0, 0x7F, + 0xFF, 0xE0, 0x3F, 0xFF, 0xC0, 0x0F, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x07, + 0xFF, 0xE0, 0x07, 0xFF, 0xF8, 0x07, 0xFF, 0xFC, 0x0F, 0xFF, 0xFE, 0x0F, + 0x80, 0x7E, 0x0F, 0x80, 0x3F, 0x0F, 0x80, 0x1F, 0x1F, 0x80, 0x1F, 0x1F, + 0x80, 0x1F, 0x1F, 0x00, 0x1F, 0x1F, 0x00, 0x1F, 0x1F, 0x00, 0x1F, 0x3F, + 0x00, 0x1F, 0x3E, 0x00, 0x3E, 0x3E, 0x00, 0x3E, 0x3E, 0x00, 0x3E, 0x3E, + 0x00, 0x3E, 0x7E, 0x00, 0x7C, 0x7C, 0x00, 0x7C, 0x7C, 0x00, 0xF8, 0x7C, + 0x01, 0xF8, 0x7C, 0x07, 0xF0, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xC0, 0xFF, + 0xFF, 0x00, 0xFF, 0xF8, 0x00, 0x07, 0xFF, 0xFF, 0x07, 0xFF, 0xFE, 0x07, + 0xFF, 0xFE, 0x0F, 0xFF, 0xFE, 0x0F, 0x80, 0x00, 0x0F, 0x80, 0x00, 0x0F, + 0x80, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x1F, 0xFF, 0xF0, 0x1F, 0xFF, 0xF0, 0x3F, 0xFF, 0xF0, 0x3F, + 0xFF, 0xF0, 0x3E, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7E, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xFF, + 0xFF, 0xF0, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xE0, 0x07, + 0xFF, 0xFE, 0x0F, 0xFF, 0xFC, 0x3F, 0xFF, 0xF0, 0x7F, 0xFF, 0xE0, 0xF8, + 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x1F, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xFF, 0xFF, 0x03, 0xFF, 0xFE, + 0x07, 0xFF, 0xFC, 0x0F, 0xFF, 0xF0, 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0xFC, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, + 0x80, 0x00, 0x3F, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0xF8, 0x01, 0xFF, 0xFC, 0x03, + 0xFF, 0xFE, 0x07, 0xE0, 0x7E, 0x0F, 0x80, 0x3F, 0x1F, 0x00, 0x1F, 0x3E, + 0x00, 0x1F, 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0xF8, 0x03, 0xFF, 0xF8, 0x07, 0xFF, 0xF8, 0x07, 0xFE, 0xF8, + 0x07, 0xFE, 0xF8, 0x00, 0x3E, 0xF8, 0x00, 0x3E, 0xFC, 0x00, 0x7E, 0xFC, + 0x00, 0x7C, 0x7E, 0x00, 0xFC, 0x7F, 0x83, 0xFC, 0x3F, 0xFF, 0xFC, 0x1F, + 0xFF, 0xBC, 0x0F, 0xFF, 0x38, 0x03, 0xFC, 0x38, 0x03, 0xE0, 0x07, 0xC0, + 0xF8, 0x01, 0xF0, 0x7E, 0x00, 0x7C, 0x1F, 0x00, 0x3F, 0x07, 0xC0, 0x0F, + 0x81, 0xF0, 0x03, 0xE0, 0xFC, 0x00, 0xF8, 0x3E, 0x00, 0x3E, 0x0F, 0x80, + 0x1F, 0x83, 0xE0, 0x07, 0xC0, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xFC, 0x1F, + 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xC1, 0xF0, 0x03, 0xE0, 0x7C, 0x00, 0xF8, + 0x3F, 0x00, 0x3E, 0x0F, 0x80, 0x0F, 0x83, 0xE0, 0x07, 0xE0, 0xF8, 0x01, + 0xF0, 0x3E, 0x00, 0x7C, 0x1F, 0x80, 0x1F, 0x07, 0xC0, 0x0F, 0xC1, 0xF0, + 0x03, 0xF0, 0x7C, 0x00, 0xF8, 0x3F, 0x00, 0x3E, 0x00, 0x07, 0xC3, 0xF0, + 0xFC, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x7E, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, + 0x3F, 0x0F, 0xC3, 0xE0, 0xF8, 0x3E, 0x0F, 0x87, 0xE1, 0xF0, 0x7C, 0x1F, + 0x07, 0xC3, 0xF0, 0xFC, 0x3E, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, + 0x01, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xE0, + 0x00, 0x3E, 0x00, 0x07, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, + 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x7C, 0x0F, + 0x8F, 0x81, 0xF8, 0xF8, 0x1F, 0x0F, 0x81, 0xF0, 0xF8, 0x1F, 0x0F, 0xC3, + 0xF0, 0xFF, 0xFE, 0x07, 0xFF, 0xC0, 0x3F, 0xF8, 0x01, 0xFC, 0x00, 0x07, + 0xC0, 0x0F, 0xC1, 0xF0, 0x07, 0xE0, 0x7C, 0x03, 0xF0, 0x3F, 0x03, 0xF8, + 0x0F, 0x81, 0xF8, 0x03, 0xE0, 0xFC, 0x00, 0xF8, 0x7E, 0x00, 0x7E, 0x3F, + 0x00, 0x1F, 0x1F, 0x80, 0x07, 0xCF, 0xC0, 0x01, 0xF7, 0xE0, 0x00, 0x7F, + 0xF0, 0x00, 0x3F, 0xFC, 0x00, 0x0F, 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, + 0xFE, 0xFC, 0x00, 0x3F, 0x1F, 0x80, 0x1F, 0x87, 0xE0, 0x07, 0xC0, 0xFC, + 0x01, 0xF0, 0x3F, 0x00, 0x7C, 0x07, 0xE0, 0x1F, 0x01, 0xFC, 0x0F, 0xC0, + 0x3F, 0x03, 0xE0, 0x0F, 0xE0, 0xF8, 0x01, 0xF8, 0x3E, 0x00, 0x3F, 0x00, + 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x0F, 0xC0, 0x03, + 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x1F, 0x80, 0x07, 0xC0, 0x01, 0xF0, + 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x0F, 0xC0, 0x03, 0xE0, 0x00, 0xF8, 0x00, + 0x3E, 0x00, 0x0F, 0x80, 0x07, 0xE0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1F, + 0x00, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xBF, 0xFF, 0xE0, 0x03, + 0xF8, 0x01, 0xFC, 0x07, 0xF0, 0x07, 0xF8, 0x1F, 0xE0, 0x0F, 0xF0, 0x3F, + 0xC0, 0x3F, 0xE0, 0x7F, 0x80, 0x7F, 0xC0, 0xFF, 0x01, 0xFF, 0x01, 0xFE, + 0x03, 0xFE, 0x07, 0xDC, 0x07, 0x7C, 0x0F, 0xB8, 0x1E, 0xF8, 0x1F, 0x70, + 0x3D, 0xF0, 0x3E, 0xF0, 0xF7, 0xC0, 0xF9, 0xE1, 0xEF, 0x81, 0xF3, 0xC7, + 0x9F, 0x03, 0xE7, 0x8F, 0x3E, 0x07, 0xCF, 0x3C, 0x7C, 0x0F, 0x9E, 0x79, + 0xF0, 0x3E, 0x3C, 0xE3, 0xE0, 0x7C, 0x7B, 0xC7, 0xC0, 0xF8, 0xF7, 0x8F, + 0x81, 0xF1, 0xFE, 0x1E, 0x07, 0xE3, 0xFC, 0x7C, 0x0F, 0x87, 0xF0, 0xF8, + 0x1F, 0x0F, 0xE1, 0xF0, 0x3E, 0x1F, 0x83, 0xE0, 0x7C, 0x3F, 0x0F, 0x81, + 0xF0, 0x7E, 0x1F, 0x00, 0x03, 0xE0, 0x07, 0xC0, 0x7E, 0x00, 0xF8, 0x1F, + 0xC0, 0x1F, 0x03, 0xF8, 0x03, 0xE0, 0x7F, 0x80, 0x7C, 0x0F, 0xF0, 0x1F, + 0x01, 0xFF, 0x03, 0xE0, 0x7F, 0xE0, 0x7C, 0x0F, 0xBC, 0x0F, 0x81, 0xF7, + 0xC1, 0xF0, 0x3E, 0xF8, 0x7C, 0x0F, 0x8F, 0x0F, 0x81, 0xF1, 0xF1, 0xF0, + 0x3E, 0x3E, 0x3E, 0x07, 0xC3, 0xC7, 0xC0, 0xF8, 0x7D, 0xF0, 0x3E, 0x0F, + 0xBE, 0x07, 0xC0, 0xF7, 0xC0, 0xF8, 0x1F, 0xF8, 0x1F, 0x01, 0xFE, 0x03, + 0xC0, 0x3F, 0xC0, 0xF8, 0x07, 0xF8, 0x1F, 0x00, 0x7F, 0x03, 0xE0, 0x0F, + 0xE0, 0x7C, 0x01, 0xF8, 0x1F, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0xE0, 0x00, + 0x3F, 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x7F, 0xFF, 0xC0, 0x7E, 0x07, 0xF0, + 0x7E, 0x01, 0xF8, 0x7C, 0x00, 0x7E, 0x3E, 0x00, 0x1F, 0x3E, 0x00, 0x0F, + 0x9E, 0x00, 0x07, 0xDF, 0x00, 0x03, 0xEF, 0x80, 0x01, 0xFF, 0x80, 0x00, + 0xFF, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x7D, 0xF0, 0x00, 0x3E, 0xF8, 0x00, + 0x1F, 0x7C, 0x00, 0x1F, 0x3E, 0x00, 0x1F, 0x9F, 0x80, 0x0F, 0x87, 0xE0, + 0x0F, 0x83, 0xF8, 0x1F, 0x80, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0x80, 0x0F, + 0xFF, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x07, 0xFF, 0xE0, 0x0F, 0xFF, 0xF0, + 0x3F, 0xFF, 0xF0, 0x7F, 0xFF, 0xF0, 0xF8, 0x07, 0xE1, 0xF0, 0x07, 0xC3, + 0xE0, 0x0F, 0x8F, 0xC0, 0x1F, 0x1F, 0x00, 0x3E, 0x3E, 0x00, 0xF8, 0x7C, + 0x01, 0xF0, 0xF8, 0x07, 0xC3, 0xFF, 0xFF, 0x87, 0xFF, 0xFE, 0x0F, 0xFF, + 0xF8, 0x1F, 0xFF, 0x80, 0x3E, 0x00, 0x00, 0xFC, 0x00, 0x01, 0xF0, 0x00, + 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x3F, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x3F, 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x7F, 0xFF, 0xC0, 0x7F, 0x07, + 0xF0, 0x7E, 0x01, 0xF8, 0x7E, 0x00, 0x7E, 0x3E, 0x00, 0x1F, 0x3E, 0x00, + 0x0F, 0x9E, 0x00, 0x07, 0xDF, 0x00, 0x03, 0xEF, 0x80, 0x01, 0xF7, 0x80, + 0x00, 0xFF, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x7D, 0xF0, 0x00, 0x3E, 0xF8, + 0x02, 0x1F, 0x7C, 0x03, 0x9F, 0x3E, 0x03, 0xFF, 0x9F, 0x81, 0xFF, 0x87, + 0xE0, 0x7F, 0x83, 0xF8, 0x3F, 0xC0, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, 0xF0, + 0x0F, 0xFF, 0xFC, 0x01, 0xFE, 0x1C, 0x00, 0x00, 0x0C, 0x00, 0x07, 0xFF, + 0xF8, 0x07, 0xFF, 0xFE, 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0x0F, 0x80, + 0x3F, 0x0F, 0x80, 0x1F, 0x0F, 0x80, 0x1F, 0x0F, 0x80, 0x1F, 0x1F, 0x80, + 0x1E, 0x1F, 0x00, 0x3E, 0x1F, 0x00, 0x7C, 0x1F, 0xFF, 0xF8, 0x1F, 0xFF, + 0xE0, 0x3F, 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, 0x3E, 0x01, 0xF8, 0x3E, 0x00, + 0xF8, 0x3E, 0x00, 0xF8, 0x7E, 0x00, 0xF8, 0x7C, 0x00, 0xF8, 0x7C, 0x01, + 0xF0, 0x7C, 0x01, 0xF0, 0x7C, 0x01, 0xF0, 0xFC, 0x01, 0xF0, 0xF8, 0x01, + 0xF0, 0xF8, 0x01, 0xF0, 0x00, 0x3F, 0xC0, 0x07, 0xFF, 0xC0, 0x3F, 0xFF, + 0x81, 0xFF, 0xFF, 0x0F, 0xC0, 0xFC, 0x3E, 0x01, 0xF1, 0xF0, 0x07, 0xC7, + 0xC0, 0x1F, 0x1F, 0x00, 0x00, 0x7E, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xFF, + 0x80, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x03, 0xFE, + 0x00, 0x01, 0xF8, 0x00, 0x03, 0xEF, 0x80, 0x0F, 0xBE, 0x00, 0x3C, 0xFC, + 0x01, 0xF3, 0xF8, 0x1F, 0x87, 0xFF, 0xFE, 0x0F, 0xFF, 0xF0, 0x1F, 0xFF, + 0x00, 0x1F, 0xF0, 0x00, 0x7F, 0xFF, 0xFB, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xF0, 0x0F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xC0, 0x00, 0x3E, + 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xC0, 0x00, + 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xC0, + 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, 0x07, + 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, + 0x00, 0x0F, 0x80, 0x1F, 0x1F, 0x80, 0x1F, 0x1F, 0x00, 0x1F, 0x1F, 0x00, + 0x3F, 0x1F, 0x00, 0x3E, 0x1F, 0x00, 0x3E, 0x3E, 0x00, 0x3E, 0x3E, 0x00, + 0x7E, 0x3E, 0x00, 0x7C, 0x3E, 0x00, 0x7C, 0x3E, 0x00, 0x7C, 0x7C, 0x00, + 0x7C, 0x7C, 0x00, 0xFC, 0x7C, 0x00, 0xF8, 0x7C, 0x00, 0xF8, 0x7C, 0x00, + 0xF8, 0xF8, 0x00, 0xF8, 0xF8, 0x01, 0xF8, 0xF8, 0x01, 0xF0, 0xF8, 0x01, + 0xF0, 0xF8, 0x03, 0xE0, 0xFE, 0x0F, 0xE0, 0x7F, 0xFF, 0xC0, 0x7F, 0xFF, + 0x80, 0x1F, 0xFE, 0x00, 0x07, 0xF8, 0x00, 0xFC, 0x00, 0x7F, 0xF0, 0x03, + 0xE7, 0xC0, 0x0F, 0x9F, 0x00, 0x7C, 0x7C, 0x01, 0xF1, 0xF0, 0x0F, 0x87, + 0xC0, 0x3E, 0x1F, 0x01, 0xF0, 0x7C, 0x07, 0x81, 0xF0, 0x3E, 0x03, 0xC0, + 0xF0, 0x0F, 0x07, 0xC0, 0x3E, 0x1E, 0x00, 0xF8, 0xF8, 0x03, 0xE3, 0xC0, + 0x0F, 0x9F, 0x00, 0x3E, 0x78, 0x00, 0xFB, 0xE0, 0x01, 0xEF, 0x00, 0x07, + 0xFC, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xE0, + 0x00, 0x1F, 0x80, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x07, 0xE0, 0x1F, 0xF8, + 0x07, 0xE0, 0x3F, 0xF8, 0x0F, 0xE0, 0x3E, 0xF8, 0x0F, 0xE0, 0x7E, 0xF8, + 0x1F, 0xE0, 0x7C, 0xF8, 0x1F, 0xE0, 0x7C, 0xF8, 0x3F, 0xE0, 0xF8, 0xF8, + 0x3D, 0xE0, 0xF8, 0x78, 0x3D, 0xE1, 0xF0, 0x78, 0x79, 0xE1, 0xF0, 0x78, + 0x79, 0xE1, 0xE0, 0x78, 0xF9, 0xE3, 0xE0, 0x78, 0xF1, 0xE3, 0xC0, 0x79, + 0xF1, 0xE7, 0xC0, 0x79, 0xE1, 0xE7, 0x80, 0x79, 0xE1, 0xE7, 0x80, 0x7B, + 0xC1, 0xEF, 0x80, 0x7B, 0xC1, 0xEF, 0x00, 0x7F, 0x81, 0xFF, 0x00, 0x7F, + 0x81, 0xFE, 0x00, 0x7F, 0x01, 0xFE, 0x00, 0x7F, 0x01, 0xFC, 0x00, 0x7F, + 0x01, 0xFC, 0x00, 0x7E, 0x01, 0xF8, 0x00, 0x3E, 0x01, 0xF8, 0x00, 0x3C, + 0x01, 0xF0, 0x00, 0x03, 0xF0, 0x07, 0xE0, 0x7E, 0x01, 0xF8, 0x07, 0xE0, + 0x7E, 0x00, 0xFC, 0x1F, 0x80, 0x1F, 0x83, 0xE0, 0x01, 0xF8, 0xF8, 0x00, + 0x3F, 0x3F, 0x00, 0x03, 0xEF, 0xC0, 0x00, 0x7F, 0xF0, 0x00, 0x0F, 0xFC, + 0x00, 0x00, 0xFF, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0x7F, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0xFF, 0xC0, + 0x00, 0x3E, 0xF8, 0x00, 0x0F, 0xDF, 0x80, 0x03, 0xF3, 0xF0, 0x00, 0xFC, + 0x3F, 0x00, 0x3F, 0x07, 0xE0, 0x07, 0xE0, 0xFC, 0x01, 0xF8, 0x0F, 0xC0, + 0x7E, 0x01, 0xF8, 0x1F, 0x80, 0x3F, 0x80, 0x7C, 0x00, 0xFD, 0xF8, 0x07, + 0xE7, 0xE0, 0x1F, 0x1F, 0x80, 0xFC, 0x3E, 0x07, 0xE0, 0xFC, 0x1F, 0x03, + 0xF0, 0xFC, 0x07, 0xC7, 0xE0, 0x1F, 0x1F, 0x00, 0x7E, 0xFC, 0x00, 0xFB, + 0xE0, 0x03, 0xFF, 0x00, 0x0F, 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x00, + 0x01, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0x7C, 0x00, 0x01, + 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, + 0x00, 0x0F, 0x80, 0x00, 0x3E, 0x00, 0x00, 0x07, 0xFF, 0xFF, 0x83, 0xFF, + 0xFF, 0x81, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xE0, 0x00, 0x07, 0xE0, 0x00, + 0x07, 0xE0, 0x00, 0x07, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF0, 0x00, + 0x07, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, + 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, + 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF8, 0x00, + 0x03, 0xF8, 0x00, 0x01, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, + 0xF0, 0x7F, 0xFF, 0xF0, 0x00, 0x01, 0xFE, 0x03, 0xFC, 0x07, 0xF8, 0x1F, + 0xF0, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x07, 0x80, 0x0F, 0x00, + 0x1E, 0x00, 0x3C, 0x00, 0xF8, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, + 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x07, 0x80, 0x0F, 0x00, + 0x1E, 0x00, 0x3C, 0x00, 0xF8, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, + 0xF0, 0x3F, 0xC0, 0x7F, 0x80, 0xFF, 0x00, 0xE7, 0x39, 0xCE, 0x31, 0x8C, + 0x63, 0x1C, 0xE7, 0x39, 0xCE, 0x31, 0x8C, 0x63, 0x9C, 0xE7, 0x38, 0x01, + 0xFE, 0x03, 0xFC, 0x07, 0xF8, 0x1F, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, + 0x00, 0x3E, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x0F, 0x00, + 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, + 0x00, 0x3E, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x0F, 0x00, + 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x1F, 0xF0, 0x3F, 0xC0, 0x7F, 0x80, 0xFF, + 0x00, 0x00, 0x7C, 0x00, 0xFC, 0x01, 0xFC, 0x01, 0xFC, 0x03, 0xFC, 0x03, + 0x9E, 0x07, 0x9E, 0x0F, 0x1E, 0x0F, 0x1E, 0x1E, 0x1E, 0x1C, 0x0F, 0x3C, + 0x0F, 0x78, 0x0F, 0x78, 0x0F, 0xF0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFE, 0xF3, 0x8C, 0x71, 0x80, 0x01, 0xFE, 0x01, 0xFF, 0xE0, + 0xFF, 0xF8, 0x7F, 0xFF, 0x1F, 0x0F, 0xC7, 0x81, 0xF0, 0x00, 0x7C, 0x00, + 0xFE, 0x07, 0xFF, 0x87, 0xFF, 0xE3, 0xFE, 0xF9, 0xF0, 0x7C, 0xF8, 0x1F, + 0x3E, 0x0F, 0xCF, 0x87, 0xF3, 0xFF, 0xF8, 0xFF, 0xFE, 0x1F, 0xEF, 0x81, + 0xE3, 0xF0, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, + 0x07, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF9, 0xF8, 0x0F, 0xFF, + 0xC1, 0xFF, 0xFE, 0x1F, 0xFF, 0xE1, 0xFC, 0x3F, 0x1F, 0x83, 0xF1, 0xF0, + 0x1F, 0x3E, 0x01, 0xF3, 0xE0, 0x1F, 0x3C, 0x01, 0xF3, 0xC0, 0x1F, 0x3C, + 0x03, 0xE7, 0xC0, 0x3E, 0x7E, 0x07, 0xC7, 0xF1, 0xFC, 0x7F, 0xFF, 0x87, + 0xFF, 0xF0, 0xFB, 0xFE, 0x0F, 0x9F, 0x80, 0x00, 0xFC, 0x01, 0xFF, 0xC0, + 0xFF, 0xF8, 0x7F, 0xFF, 0x3F, 0x0F, 0xCF, 0x81, 0xF7, 0xC0, 0x7D, 0xF0, + 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF8, 0x0F, + 0xBE, 0x07, 0xCF, 0xC3, 0xF1, 0xFF, 0xF8, 0x7F, 0xFC, 0x0F, 0xFE, 0x00, + 0xFE, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0x80, 0x00, + 0x3E, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x1F, 0x00, 0x7E, 0x7C, + 0x07, 0xFD, 0xF0, 0x3F, 0xFF, 0xC1, 0xFF, 0xFE, 0x0F, 0xE3, 0xF8, 0x3E, + 0x07, 0xE1, 0xF0, 0x1F, 0x87, 0xC0, 0x3C, 0x3E, 0x00, 0xF0, 0xF8, 0x07, + 0xC3, 0xE0, 0x1F, 0x0F, 0x80, 0x7C, 0x3E, 0x03, 0xE0, 0xF8, 0x1F, 0x83, + 0xF0, 0xFE, 0x07, 0xFF, 0xF8, 0x1F, 0xFF, 0xE0, 0x3F, 0xFF, 0x00, 0x7E, + 0x7C, 0x00, 0x00, 0xFE, 0x00, 0x7F, 0xE0, 0x3F, 0xFE, 0x0F, 0xFF, 0xE3, + 0xF0, 0x7E, 0x7C, 0x07, 0xDF, 0x00, 0xFB, 0xE0, 0x1F, 0x7F, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x1F, 0x3F, + 0x07, 0xE3, 0xFF, 0xF8, 0x7F, 0xFE, 0x03, 0xFF, 0x00, 0x3F, 0x80, 0x00, + 0x00, 0xF8, 0x1F, 0xC1, 0xFE, 0x0F, 0xF0, 0x7C, 0x07, 0xC0, 0x3E, 0x0F, + 0xFE, 0x7F, 0xF3, 0xFF, 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, + 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x78, 0x07, 0xC0, 0x3E, 0x01, + 0xF0, 0x0F, 0x80, 0xF8, 0x07, 0xC0, 0x00, 0x00, 0x7C, 0x7C, 0x07, 0xFD, + 0xF0, 0x3F, 0xF7, 0x81, 0xFF, 0xFE, 0x0F, 0xE3, 0xF8, 0x3E, 0x07, 0xE1, + 0xF8, 0x0F, 0x87, 0xC0, 0x3C, 0x1E, 0x00, 0xF0, 0xF8, 0x03, 0xC3, 0xE0, + 0x1F, 0x0F, 0x80, 0x78, 0x3E, 0x03, 0xE0, 0xF8, 0x1F, 0x83, 0xF0, 0xFE, + 0x07, 0xFF, 0xF8, 0x1F, 0xFF, 0xC0, 0x3F, 0xEF, 0x00, 0x3E, 0x7C, 0x00, + 0x01, 0xF0, 0x00, 0x07, 0xC3, 0xE0, 0x3E, 0x0F, 0x80, 0xF8, 0x3F, 0x0F, + 0xC0, 0x7F, 0xFE, 0x00, 0xFF, 0xF0, 0x00, 0xFE, 0x00, 0x00, 0x03, 0xE0, + 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, + 0x00, 0x0F, 0x80, 0x00, 0xF8, 0xF8, 0x0F, 0xBF, 0xE0, 0xFF, 0xFF, 0x0F, + 0xFF, 0xF1, 0xFC, 0x3F, 0x1F, 0x81, 0xF1, 0xF0, 0x1F, 0x1F, 0x01, 0xF1, + 0xE0, 0x1F, 0x3E, 0x03, 0xE3, 0xE0, 0x3E, 0x3E, 0x03, 0xE3, 0xE0, 0x3E, + 0x7C, 0x03, 0xE7, 0xC0, 0x7C, 0x7C, 0x07, 0xC7, 0xC0, 0x7C, 0x7C, 0x07, + 0xCF, 0x80, 0x78, 0x07, 0xC1, 0xF0, 0x7C, 0x3E, 0x00, 0x00, 0x00, 0x00, + 0x3E, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, + 0x0F, 0x87, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC3, 0xE0, 0xF8, 0x3E, 0x00, + 0x00, 0x3E, 0x00, 0x78, 0x01, 0xF0, 0x03, 0xE0, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x7C, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, 0x0F, 0x80, 0x1F, + 0x00, 0x3E, 0x00, 0x7C, 0x00, 0xF8, 0x03, 0xE0, 0x07, 0xC0, 0x0F, 0x80, + 0x1F, 0x00, 0x3C, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, 0x07, 0xC0, 0x1F, + 0x00, 0x3E, 0x00, 0x7C, 0x00, 0xF8, 0x03, 0xF0, 0x1F, 0xC0, 0x3F, 0x80, + 0x7E, 0x01, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, + 0x0F, 0x80, 0x00, 0x78, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, + 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x07, 0xC7, 0xE0, 0x3E, 0x7E, 0x01, + 0xF7, 0xE0, 0x0F, 0xFE, 0x00, 0xFF, 0xE0, 0x07, 0xFF, 0x00, 0x3F, 0xFC, + 0x01, 0xFF, 0xE0, 0x0F, 0xDF, 0x00, 0xFC, 0xFC, 0x07, 0xC3, 0xE0, 0x3E, + 0x1F, 0x01, 0xF0, 0xFC, 0x0F, 0x83, 0xE0, 0xF8, 0x1F, 0x87, 0xC0, 0xFC, + 0x00, 0x07, 0xC1, 0xF0, 0x7C, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x1F, + 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x87, + 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC3, 0xE0, 0xF8, 0x3E, 0x00, 0x0F, 0x8F, + 0x83, 0xF0, 0x3E, 0xFF, 0x3F, 0xE0, 0xF7, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, + 0xFF, 0x1F, 0xC7, 0xF8, 0x7C, 0x7C, 0x0F, 0x81, 0xF1, 0xF0, 0x3E, 0x07, + 0xCF, 0x81, 0xF0, 0x3E, 0x3E, 0x07, 0xC0, 0xF8, 0xF8, 0x1F, 0x03, 0xE3, + 0xE0, 0x7C, 0x0F, 0x8F, 0x81, 0xF0, 0x3E, 0x7C, 0x0F, 0x81, 0xF1, 0xF0, + 0x3E, 0x07, 0xC7, 0xC0, 0xF8, 0x1F, 0x1F, 0x03, 0xE0, 0x7C, 0x7C, 0x0F, + 0x81, 0xE3, 0xE0, 0x7C, 0x0F, 0x8F, 0x81, 0xF0, 0x3E, 0x00, 0x0F, 0x8F, + 0x80, 0xFB, 0xFE, 0x0F, 0xFF, 0xF1, 0xFF, 0xFF, 0x1F, 0xC3, 0xF1, 0xF8, + 0x1F, 0x1F, 0x01, 0xF1, 0xF0, 0x1F, 0x3E, 0x01, 0xF3, 0xE0, 0x3E, 0x3E, + 0x03, 0xE3, 0xE0, 0x3E, 0x3C, 0x03, 0xE7, 0xC0, 0x3E, 0x7C, 0x07, 0xC7, + 0xC0, 0x7C, 0x7C, 0x07, 0xC7, 0x80, 0x7C, 0xF8, 0x07, 0x80, 0x00, 0xFE, + 0x00, 0x7F, 0xF0, 0x3F, 0xFF, 0x0F, 0xFF, 0xE3, 0xF8, 0xFE, 0x7C, 0x0F, + 0xDF, 0x00, 0xFB, 0xE0, 0x1F, 0xF8, 0x03, 0xFF, 0x00, 0x7F, 0xE0, 0x1F, + 0xFC, 0x03, 0xEF, 0x80, 0x7D, 0xF8, 0x1F, 0x3F, 0x07, 0xE3, 0xFF, 0xF8, + 0x7F, 0xFE, 0x07, 0xFF, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xE7, 0xE0, 0x0F, + 0xBF, 0xC0, 0x7D, 0xFF, 0x81, 0xFF, 0xFE, 0x07, 0xF0, 0xFC, 0x1F, 0x81, + 0xF0, 0x7C, 0x07, 0xC3, 0xE0, 0x1F, 0x0F, 0x80, 0x7C, 0x3E, 0x01, 0xF0, + 0xF0, 0x07, 0xC3, 0xC0, 0x3E, 0x1F, 0x00, 0xF8, 0x7E, 0x07, 0xC1, 0xFC, + 0x7F, 0x07, 0xFF, 0xF8, 0x1F, 0xFF, 0xC0, 0xFB, 0xFE, 0x03, 0xE7, 0xE0, + 0x0F, 0x80, 0x00, 0x3E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x1F, + 0x00, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x01, + 0xF1, 0xF0, 0x7F, 0xDF, 0x0F, 0xFD, 0xF1, 0xFF, 0xFE, 0x3F, 0x8F, 0xE3, + 0xE0, 0x7E, 0x7C, 0x03, 0xE7, 0xC0, 0x3E, 0xF8, 0x03, 0xCF, 0x80, 0x3C, + 0xF8, 0x07, 0xCF, 0x80, 0x7C, 0xF8, 0x0F, 0x8F, 0x81, 0xF8, 0xFC, 0x3F, + 0x87, 0xFF, 0xF8, 0x7F, 0xFF, 0x83, 0xFF, 0xF0, 0x1F, 0x9F, 0x00, 0x01, + 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, + 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x0F, 0x8E, 0x1F, 0x7C, 0x3F, + 0xF0, 0xFF, 0xE1, 0xFC, 0x03, 0xF0, 0x07, 0xC0, 0x0F, 0x80, 0x3E, 0x00, + 0x7C, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, 0x0F, 0x80, 0x1F, 0x00, 0x3E, + 0x00, 0x7C, 0x00, 0xF0, 0x03, 0xE0, 0x00, 0x01, 0xFC, 0x01, 0xFF, 0xC0, + 0xFF, 0xF8, 0x7F, 0xFF, 0x3F, 0x0F, 0xCF, 0x81, 0xF3, 0xF0, 0x00, 0xFF, + 0x80, 0x3F, 0xFC, 0x07, 0xFF, 0xC0, 0x7F, 0xF8, 0x03, 0xFE, 0x00, 0x1F, + 0xBE, 0x03, 0xEF, 0xC1, 0xFB, 0xFF, 0xFC, 0x7F, 0xFE, 0x0F, 0xFF, 0x00, + 0xFE, 0x00, 0x0F, 0x81, 0xF0, 0x7C, 0x0F, 0x81, 0xF0, 0xFF, 0xBF, 0xF7, + 0xFE, 0x3E, 0x07, 0xC0, 0xF8, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, + 0xF8, 0x1F, 0x03, 0xE0, 0x7F, 0x0F, 0xE1, 0xFC, 0x1F, 0x80, 0x1F, 0x01, + 0xF1, 0xF0, 0x1F, 0x3E, 0x03, 0xE3, 0xE0, 0x3E, 0x3E, 0x03, 0xE3, 0xE0, + 0x3E, 0x3E, 0x03, 0xE7, 0xC0, 0x7C, 0x7C, 0x07, 0xC7, 0xC0, 0x7C, 0x7C, + 0x07, 0xC7, 0xC0, 0x7C, 0xF8, 0x0F, 0x8F, 0x81, 0xF8, 0xF8, 0x3F, 0x8F, + 0xFF, 0xF8, 0xFF, 0xFF, 0x07, 0xFD, 0xF0, 0x3F, 0x1F, 0x00, 0xF8, 0x0F, + 0xFE, 0x03, 0xEF, 0x81, 0xF3, 0xE0, 0x7C, 0xF8, 0x3E, 0x3E, 0x0F, 0x8F, + 0x87, 0xC1, 0xE1, 0xF0, 0x78, 0xF8, 0x1E, 0x3E, 0x07, 0x9F, 0x01, 0xF7, + 0x80, 0x7F, 0xE0, 0x1F, 0xF0, 0x03, 0xFC, 0x00, 0xFE, 0x00, 0x3F, 0x80, + 0x0F, 0xC0, 0x03, 0xF0, 0x00, 0xF8, 0x1F, 0x07, 0xFF, 0x03, 0xE0, 0xFB, + 0xE0, 0xFC, 0x1F, 0x7C, 0x1F, 0x87, 0xCF, 0x87, 0xF0, 0xF9, 0xF0, 0xFE, + 0x3E, 0x3E, 0x3D, 0xC7, 0xC3, 0xC7, 0xB9, 0xF0, 0x79, 0xE7, 0x3E, 0x0F, + 0x3C, 0xE7, 0x81, 0xEF, 0x1D, 0xF0, 0x3D, 0xE3, 0xBC, 0x07, 0xBC, 0x7F, + 0x80, 0xFF, 0x0F, 0xE0, 0x1F, 0xE1, 0xFC, 0x03, 0xF8, 0x3F, 0x00, 0x7F, + 0x07, 0xE0, 0x0F, 0xC0, 0xF8, 0x01, 0xF8, 0x1F, 0x00, 0x00, 0x0F, 0xC1, + 0xF8, 0x3F, 0x07, 0xC0, 0x7C, 0x3E, 0x01, 0xF9, 0xF8, 0x03, 0xEF, 0xC0, + 0x0F, 0xBE, 0x00, 0x1F, 0xF0, 0x00, 0x7F, 0x80, 0x01, 0xFC, 0x00, 0x03, + 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0x00, 0x07, 0xFE, 0x00, 0x3E, 0xF8, + 0x01, 0xFB, 0xF0, 0x07, 0xC7, 0xC0, 0x3E, 0x1F, 0x81, 0xF8, 0x7E, 0x0F, + 0xC0, 0xF8, 0x00, 0x1F, 0x80, 0x7C, 0x3E, 0x03, 0xE0, 0xF8, 0x0F, 0x03, + 0xE0, 0x7C, 0x0F, 0x81, 0xE0, 0x3E, 0x0F, 0x80, 0xF8, 0x3C, 0x03, 0xE1, + 0xF0, 0x07, 0x87, 0x80, 0x1F, 0x3E, 0x00, 0x7C, 0xF0, 0x01, 0xF7, 0xC0, + 0x07, 0xDE, 0x00, 0x1F, 0xF0, 0x00, 0x7F, 0xC0, 0x01, 0xFE, 0x00, 0x03, + 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, + 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x00, 0x01, + 0xF8, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x0F, 0xFF, 0xE1, 0xFF, 0xFC, 0x3F, + 0xFF, 0x87, 0xFF, 0xE0, 0x00, 0xFC, 0x00, 0x3F, 0x00, 0x0F, 0xC0, 0x03, + 0xF0, 0x01, 0xFC, 0x00, 0x7E, 0x00, 0x1F, 0x80, 0x07, 0xE0, 0x01, 0xF8, + 0x00, 0x7E, 0x00, 0x1F, 0x80, 0x07, 0xFF, 0xF8, 0xFF, 0xFF, 0x1F, 0xFF, + 0xE3, 0xFF, 0xFC, 0x00, 0x00, 0x7C, 0x03, 0xF0, 0x1F, 0xC0, 0xFE, 0x03, + 0xE0, 0x0F, 0x00, 0x3C, 0x00, 0xF0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, + 0xE0, 0x0F, 0x80, 0x3C, 0x01, 0xF0, 0x1F, 0x80, 0x70, 0x01, 0xF8, 0x01, + 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x03, 0xC0, 0x0F, 0x00, 0x3C, 0x00, + 0xF0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, 0xFC, 0x07, 0xE0, 0x0F, 0x80, + 0x1E, 0x00, 0x03, 0x81, 0xC0, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0C, 0x0E, + 0x07, 0x03, 0x81, 0xC0, 0xC0, 0xE0, 0x70, 0x38, 0x18, 0x1C, 0x0E, 0x07, + 0x03, 0x81, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x18, 0x1C, 0x0E, 0x07, 0x01, + 0x80, 0x80, 0x00, 0x00, 0x01, 0xE0, 0x07, 0xC0, 0x1F, 0x80, 0xFE, 0x00, + 0x78, 0x01, 0xE0, 0x07, 0x80, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x00, + 0x78, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x7E, 0x00, 0x38, 0x07, 0xE0, + 0x3E, 0x00, 0xF0, 0x07, 0xC0, 0x1E, 0x00, 0x78, 0x01, 0xE0, 0x07, 0x80, + 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x1F, 0x01, 0xF8, 0x0F, 0xE0, 0x3F, 0x00, + 0xF8, 0x00, 0x0F, 0x00, 0x1F, 0xC1, 0xDF, 0xF0, 0xEE, 0x3F, 0xE6, 0x07, + 0xF0, 0x01, 0xE0 }; + +const GFXglyph FreeSansBoldOblique18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 10, 0, 1 }, // 0x20 ' ' + { 0, 10, 25, 12, 4, -24 }, // 0x21 '!' + { 32, 13, 9, 17, 6, -25 }, // 0x22 '"' + { 47, 22, 24, 19, 1, -23 }, // 0x23 '#' + { 113, 19, 31, 19, 2, -26 }, // 0x24 '$' + { 187, 26, 26, 31, 5, -25 }, // 0x25 '%' + { 272, 21, 25, 25, 3, -24 }, // 0x26 '&' + { 338, 5, 9, 8, 6, -25 }, // 0x27 ''' + { 344, 13, 33, 12, 3, -25 }, // 0x28 '(' + { 398, 13, 33, 12, -1, -25 }, // 0x29 ')' + { 452, 12, 11, 14, 5, -25 }, // 0x2A '*' + { 469, 18, 16, 20, 3, -15 }, // 0x2B '+' + { 505, 7, 11, 10, 1, -4 }, // 0x2C ',' + { 515, 10, 4, 12, 2, -10 }, // 0x2D '-' + { 520, 6, 5, 10, 2, -4 }, // 0x2E '.' + { 524, 15, 25, 10, 0, -24 }, // 0x2F '/' + { 571, 18, 25, 19, 3, -24 }, // 0x30 '0' + { 628, 13, 25, 19, 6, -24 }, // 0x31 '1' + { 669, 21, 25, 19, 1, -24 }, // 0x32 '2' + { 735, 20, 25, 19, 2, -24 }, // 0x33 '3' + { 798, 19, 25, 19, 2, -24 }, // 0x34 '4' + { 858, 20, 24, 19, 2, -23 }, // 0x35 '5' + { 918, 19, 25, 19, 3, -24 }, // 0x36 '6' + { 978, 19, 24, 19, 5, -23 }, // 0x37 '7' + { 1035, 20, 25, 19, 2, -24 }, // 0x38 '8' + { 1098, 19, 25, 19, 2, -24 }, // 0x39 '9' + { 1158, 9, 18, 12, 4, -17 }, // 0x3A ':' + { 1179, 10, 24, 12, 3, -17 }, // 0x3B ';' + { 1209, 19, 17, 20, 3, -16 }, // 0x3C '<' + { 1250, 20, 12, 20, 2, -13 }, // 0x3D '=' + { 1280, 19, 17, 20, 1, -15 }, // 0x3E '>' + { 1321, 18, 26, 21, 6, -25 }, // 0x3F '?' + { 1380, 33, 31, 34, 3, -25 }, // 0x40 '@' + { 1508, 23, 26, 25, 1, -25 }, // 0x41 'A' + { 1583, 24, 26, 25, 3, -25 }, // 0x42 'B' + { 1661, 24, 26, 25, 4, -25 }, // 0x43 'C' + { 1739, 24, 26, 25, 3, -25 }, // 0x44 'D' + { 1817, 24, 26, 23, 3, -25 }, // 0x45 'E' + { 1895, 23, 26, 21, 3, -25 }, // 0x46 'F' + { 1970, 24, 26, 27, 4, -25 }, // 0x47 'G' + { 2048, 26, 26, 25, 2, -25 }, // 0x48 'H' + { 2133, 10, 26, 10, 2, -25 }, // 0x49 'I' + { 2166, 20, 26, 19, 2, -25 }, // 0x4A 'J' + { 2231, 26, 26, 25, 3, -25 }, // 0x4B 'K' + { 2316, 18, 26, 21, 3, -25 }, // 0x4C 'L' + { 2375, 31, 26, 29, 2, -25 }, // 0x4D 'M' + { 2476, 27, 26, 25, 2, -25 }, // 0x4E 'N' + { 2564, 25, 26, 27, 4, -25 }, // 0x4F 'O' + { 2646, 23, 26, 23, 3, -25 }, // 0x50 'P' + { 2721, 25, 27, 27, 4, -25 }, // 0x51 'Q' + { 2806, 24, 26, 25, 3, -25 }, // 0x52 'R' + { 2884, 22, 26, 23, 3, -25 }, // 0x53 'S' + { 2956, 21, 26, 21, 5, -25 }, // 0x54 'T' + { 3025, 24, 26, 25, 4, -25 }, // 0x55 'U' + { 3103, 22, 26, 23, 6, -25 }, // 0x56 'V' + { 3175, 32, 26, 33, 6, -25 }, // 0x57 'W' + { 3279, 27, 26, 23, 1, -25 }, // 0x58 'X' + { 3367, 22, 26, 23, 6, -25 }, // 0x59 'Y' + { 3439, 25, 26, 21, 1, -25 }, // 0x5A 'Z' + { 3521, 15, 33, 12, 1, -25 }, // 0x5B '[' + { 3583, 5, 25, 10, 5, -24 }, // 0x5C '\' + { 3599, 15, 33, 12, -1, -25 }, // 0x5D ']' + { 3661, 16, 15, 20, 4, -23 }, // 0x5E '^' + { 3691, 21, 3, 19, -2, 5 }, // 0x5F '_' + { 3699, 5, 5, 12, 6, -25 }, // 0x60 '`' + { 3703, 18, 19, 19, 2, -18 }, // 0x61 'a' + { 3746, 20, 26, 21, 2, -25 }, // 0x62 'b' + { 3811, 18, 19, 19, 3, -18 }, // 0x63 'c' + { 3854, 22, 26, 21, 3, -25 }, // 0x64 'd' + { 3926, 19, 19, 19, 2, -18 }, // 0x65 'e' + { 3972, 13, 26, 12, 3, -25 }, // 0x66 'f' + { 4015, 22, 27, 21, 1, -18 }, // 0x67 'g' + { 4090, 20, 26, 21, 2, -25 }, // 0x68 'h' + { 4155, 10, 26, 10, 2, -25 }, // 0x69 'i' + { 4188, 15, 34, 10, -2, -25 }, // 0x6A 'j' + { 4252, 21, 26, 19, 2, -25 }, // 0x6B 'k' + { 4321, 10, 26, 10, 2, -25 }, // 0x6C 'l' + { 4354, 30, 19, 31, 2, -18 }, // 0x6D 'm' + { 4426, 20, 19, 21, 2, -18 }, // 0x6E 'n' + { 4474, 19, 19, 21, 3, -18 }, // 0x6F 'o' + { 4520, 22, 27, 21, 0, -18 }, // 0x70 'p' + { 4595, 20, 27, 21, 3, -18 }, // 0x71 'q' + { 4663, 15, 19, 14, 2, -18 }, // 0x72 'r' + { 4699, 18, 19, 19, 2, -18 }, // 0x73 's' + { 4742, 11, 23, 12, 4, -22 }, // 0x74 't' + { 4774, 20, 19, 21, 3, -18 }, // 0x75 'u' + { 4822, 18, 19, 19, 5, -18 }, // 0x76 'v' + { 4865, 27, 19, 27, 4, -18 }, // 0x77 'w' + { 4930, 22, 19, 19, 1, -18 }, // 0x78 'x' + { 4983, 22, 27, 19, 1, -18 }, // 0x79 'y' + { 5058, 19, 19, 17, 1, -18 }, // 0x7A 'z' + { 5104, 14, 33, 14, 2, -25 }, // 0x7B '{' + { 5162, 9, 33, 10, 2, -25 }, // 0x7C '|' + { 5200, 14, 33, 14, 2, -25 }, // 0x7D '}' + { 5258, 17, 6, 20, 3, -10 } }; // 0x7E '~' + +const GFXfont FreeSansBoldOblique18pt7b PROGMEM = { + (uint8_t *)FreeSansBoldOblique18pt7bBitmaps, + (GFXglyph *)FreeSansBoldOblique18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 5943 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique24pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique24pt7b.h new file mode 100644 index 0000000..ea65f9b --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique24pt7b.h @@ -0,0 +1,893 @@ +const uint8_t FreeSansBoldOblique24pt7bBitmaps[] PROGMEM = { + 0x01, 0xE0, 0x07, 0xF0, 0x1F, 0xC0, 0xFF, 0x03, 0xF8, 0x0F, 0xE0, 0x3F, + 0x80, 0xFE, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xE0, 0x1F, + 0x80, 0x7E, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0xF8, 0x03, 0xE0, 0x0F, + 0x80, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x1F, + 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0xFE, 0x03, 0xF8, 0x00, + 0x7E, 0x0F, 0xDF, 0x83, 0xF7, 0xE0, 0xFF, 0xF0, 0x7E, 0xFC, 0x1F, 0xBF, + 0x07, 0xEF, 0xC1, 0xFB, 0xE0, 0x7C, 0xF8, 0x1F, 0x3C, 0x07, 0x8F, 0x01, + 0xE3, 0x80, 0x70, 0x00, 0x07, 0xC1, 0xF0, 0x00, 0x3E, 0x0F, 0x80, 0x03, + 0xE0, 0xF8, 0x00, 0x1F, 0x07, 0xC0, 0x01, 0xF0, 0x7C, 0x00, 0x0F, 0x83, + 0xE0, 0x00, 0xF8, 0x3E, 0x00, 0xFF, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xF8, + 0x7F, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xE0, 0x0F, + 0x83, 0xE0, 0x00, 0x7C, 0x3E, 0x00, 0x07, 0xC1, 0xF0, 0x00, 0x3E, 0x0F, + 0x80, 0x03, 0xE0, 0xF8, 0x00, 0x1F, 0x07, 0xC0, 0x00, 0xF8, 0x7C, 0x00, + 0xFF, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, 0xFF, 0x83, 0xFF, + 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xE0, 0x1F, 0x07, 0xC0, 0x00, 0xF8, 0x3E, + 0x00, 0x0F, 0x83, 0xE0, 0x00, 0x7C, 0x1F, 0x00, 0x07, 0xC1, 0xF0, 0x00, + 0x3E, 0x0F, 0x80, 0x01, 0xF0, 0xF8, 0x00, 0x1F, 0x07, 0xC0, 0x00, 0xF8, + 0x3C, 0x00, 0x00, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x38, 0x00, 0x00, 0x0E, + 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x7F, 0xFF, 0x00, 0x3F, 0xFF, 0xE0, 0x1F, + 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0x07, 0xF3, 0x9F, 0xC1, 0xF8, 0xE3, 0xF0, + 0x7C, 0x38, 0xFC, 0x3F, 0x0E, 0x3F, 0x0F, 0xC7, 0x8F, 0xC3, 0xF1, 0xC0, + 0x00, 0xFE, 0x70, 0x00, 0x3F, 0xDC, 0x00, 0x0F, 0xFF, 0x00, 0x01, 0xFF, + 0xE0, 0x00, 0x3F, 0xFE, 0x00, 0x0F, 0xFF, 0xE0, 0x00, 0xFF, 0xFC, 0x00, + 0x0F, 0xFF, 0x00, 0x01, 0xFF, 0xE0, 0x00, 0x77, 0xF8, 0x00, 0x1C, 0xFE, + 0x00, 0x07, 0x3F, 0x8F, 0xE3, 0xCF, 0xE3, 0xF8, 0xE3, 0xF8, 0xFE, 0x38, + 0xFC, 0x3F, 0x8E, 0x7F, 0x0F, 0xF3, 0x9F, 0xC3, 0xFD, 0xFF, 0xE0, 0x7F, + 0xFF, 0xF0, 0x1F, 0xFF, 0xFC, 0x03, 0xFF, 0xFC, 0x00, 0x7F, 0xFE, 0x00, + 0x03, 0xFC, 0x00, 0x00, 0x38, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x03, 0x80, + 0x00, 0x01, 0xE0, 0x00, 0x00, 0x70, 0x00, 0x00, 0x01, 0xF8, 0x00, 0x07, + 0x80, 0x7F, 0xE0, 0x00, 0xF0, 0x0F, 0xFF, 0x00, 0x1E, 0x01, 0xFF, 0xF0, + 0x01, 0xC0, 0x3F, 0xFF, 0x80, 0x3C, 0x07, 0xE1, 0xF8, 0x07, 0x80, 0x78, + 0x07, 0x80, 0xF0, 0x0F, 0x80, 0x78, 0x0E, 0x00, 0xF0, 0x07, 0x81, 0xC0, + 0x0F, 0x00, 0xF8, 0x3C, 0x00, 0xF0, 0x0F, 0x07, 0x80, 0x0F, 0xC3, 0xF0, + 0xF0, 0x00, 0xFF, 0xFE, 0x0E, 0x00, 0x07, 0xFF, 0xC1, 0xE0, 0x00, 0x7F, + 0xF8, 0x3C, 0x00, 0x03, 0xFF, 0x07, 0x80, 0x00, 0x0F, 0xC0, 0x70, 0x00, + 0x00, 0x00, 0x0E, 0x03, 0xF0, 0x00, 0x01, 0xE0, 0xFF, 0xC0, 0x00, 0x3C, + 0x1F, 0xFE, 0x00, 0x03, 0x83, 0xFF, 0xE0, 0x00, 0x70, 0x7F, 0xFF, 0x00, + 0x0F, 0x0F, 0xC3, 0xF0, 0x01, 0xE0, 0xF0, 0x0F, 0x00, 0x3C, 0x1F, 0x00, + 0xF0, 0x03, 0x81, 0xE0, 0x0F, 0x00, 0x78, 0x1E, 0x01, 0xF0, 0x0F, 0x01, + 0xE0, 0x1E, 0x01, 0xE0, 0x1F, 0x87, 0xE0, 0x1C, 0x01, 0xFF, 0xFC, 0x03, + 0x80, 0x0F, 0xFF, 0x80, 0x78, 0x00, 0xFF, 0xF0, 0x0F, 0x00, 0x07, 0xFE, + 0x01, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x3F, 0xF0, + 0x00, 0x07, 0xFF, 0xC0, 0x00, 0x7F, 0xFF, 0x00, 0x03, 0xFF, 0xF8, 0x00, + 0x3F, 0x9F, 0xC0, 0x03, 0xF8, 0x7E, 0x00, 0x1F, 0xC3, 0xF0, 0x00, 0xFE, + 0x1F, 0x00, 0x07, 0xF1, 0xF8, 0x00, 0x3F, 0xCF, 0xC0, 0x01, 0xFE, 0xFC, + 0x00, 0x07, 0xFF, 0xC0, 0x00, 0x3F, 0xFC, 0x00, 0x00, 0xFF, 0xC0, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x1F, 0xFF, 0x07, 0xC1, 0xFF, + 0xF8, 0x3E, 0x3F, 0xFF, 0xE3, 0xE3, 0xFE, 0x3F, 0x1F, 0x1F, 0xC1, 0xFD, + 0xF1, 0xFC, 0x07, 0xFF, 0x8F, 0xC0, 0x3F, 0xF8, 0xFE, 0x00, 0xFF, 0xC7, + 0xF0, 0x07, 0xFC, 0x3F, 0x80, 0x1F, 0xC1, 0xFC, 0x00, 0xFE, 0x0F, 0xF0, + 0x1F, 0xF8, 0x7F, 0xC1, 0xFF, 0xC1, 0xFF, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, + 0xFC, 0x3F, 0xFF, 0xCF, 0xE0, 0x7F, 0xF8, 0x7F, 0x80, 0xFF, 0x00, 0x00, + 0x7E, 0xFD, 0xFF, 0xEF, 0xDF, 0xBF, 0x7C, 0xF9, 0xE3, 0xC7, 0x00, 0x00, + 0x0F, 0x80, 0x0F, 0x80, 0x0F, 0x80, 0x0F, 0xC0, 0x07, 0xC0, 0x07, 0xC0, + 0x07, 0xE0, 0x03, 0xE0, 0x03, 0xE0, 0x03, 0xF0, 0x01, 0xF0, 0x01, 0xF8, + 0x00, 0xF8, 0x00, 0xFC, 0x00, 0x7C, 0x00, 0x7E, 0x00, 0x3E, 0x00, 0x1F, + 0x00, 0x1F, 0x80, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x03, 0xF0, 0x01, + 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, + 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x1E, + 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x3E, 0x00, 0x1F, 0x00, 0x07, 0x80, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, + 0x1E, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x7C, + 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x07, 0x80, 0x03, 0xE0, 0x01, 0xF0, 0x00, + 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, + 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, + 0x00, 0x1F, 0x00, 0x1F, 0x80, 0x0F, 0x80, 0x07, 0xC0, 0x07, 0xE0, 0x03, + 0xE0, 0x03, 0xF0, 0x01, 0xF0, 0x01, 0xF8, 0x00, 0xF8, 0x00, 0xFC, 0x00, + 0x7C, 0x00, 0x7C, 0x00, 0x7E, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x3F, 0x00, + 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x00, 0x01, 0xE0, 0x03, 0x80, 0x07, + 0x00, 0x0E, 0x07, 0x3C, 0x6F, 0xFF, 0xFF, 0xFF, 0xBF, 0xFE, 0x0F, 0xE0, + 0x1F, 0xC0, 0x7F, 0x81, 0xEF, 0x87, 0x8F, 0x0E, 0x1E, 0x08, 0x10, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, + 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFE, + 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0x00, 0xFC, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0xFC, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF8, 0x00, + 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0xC7, 0xF1, 0xF8, 0xFE, 0x3F, + 0x8F, 0xE0, 0x38, 0x1C, 0x07, 0x03, 0xC0, 0xE0, 0xF0, 0xFC, 0x3C, 0x0C, + 0x00, 0x7F, 0xFD, 0xFF, 0xF7, 0xFF, 0x9F, 0xFE, 0xFF, 0xFB, 0xFF, 0xE0, + 0x7F, 0x7F, 0x7F, 0x7E, 0xFE, 0xFE, 0xFE, 0x00, 0x00, 0x70, 0x00, 0x0E, + 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x03, + 0x80, 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x01, + 0xC0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, + 0x70, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, + 0x38, 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, + 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, + 0x07, 0x00, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x00, 0x00, 0x0F, 0xE0, 0x00, + 0x1F, 0xFC, 0x00, 0x3F, 0xFF, 0x80, 0x3F, 0xFF, 0xC0, 0x3F, 0xFF, 0xF0, + 0x1F, 0xC7, 0xF8, 0x1F, 0xC1, 0xFE, 0x1F, 0xC0, 0x7F, 0x0F, 0xC0, 0x3F, + 0x8F, 0xE0, 0x1F, 0xC7, 0xF0, 0x0F, 0xE3, 0xF0, 0x07, 0xF3, 0xF8, 0x03, + 0xF9, 0xFC, 0x01, 0xFC, 0xFC, 0x01, 0xFE, 0xFE, 0x00, 0xFE, 0x7F, 0x00, + 0x7F, 0x3F, 0x80, 0x3F, 0x9F, 0xC0, 0x1F, 0xCF, 0xE0, 0x1F, 0xEF, 0xE0, + 0x0F, 0xE7, 0xF0, 0x07, 0xF3, 0xF8, 0x03, 0xF9, 0xFC, 0x03, 0xF8, 0xFE, + 0x01, 0xFC, 0x7F, 0x00, 0xFE, 0x3F, 0x80, 0xFE, 0x1F, 0xE0, 0x7F, 0x0F, + 0xF8, 0xFF, 0x03, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0x80, + 0x1F, 0xFF, 0x00, 0x07, 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x00, 0x0F, + 0x80, 0x0F, 0x80, 0x07, 0xC0, 0x07, 0xE0, 0x0F, 0xF0, 0x3F, 0xF9, 0xFF, + 0xF8, 0xFF, 0xFC, 0xFF, 0xFE, 0x7F, 0xFF, 0x00, 0x3F, 0x80, 0x1F, 0x80, + 0x0F, 0xC0, 0x0F, 0xE0, 0x07, 0xF0, 0x03, 0xF8, 0x01, 0xF8, 0x01, 0xFC, + 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x3F, 0x00, 0x1F, 0x80, 0x1F, 0xC0, 0x0F, + 0xE0, 0x07, 0xF0, 0x03, 0xF0, 0x01, 0xF8, 0x01, 0xFC, 0x00, 0xFE, 0x00, + 0x7F, 0x00, 0x3F, 0x00, 0x3F, 0x80, 0x1F, 0xC0, 0x00, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x7F, 0xFC, 0x00, 0x0F, 0xFF, 0xF8, 0x00, 0xFF, 0xFF, 0xE0, + 0x0F, 0xFF, 0xFF, 0x00, 0xFF, 0x07, 0xFC, 0x07, 0xF0, 0x1F, 0xE0, 0x7F, + 0x00, 0x7F, 0x03, 0xF0, 0x03, 0xF8, 0x1F, 0x80, 0x1F, 0xC1, 0xF8, 0x00, + 0xFE, 0x0F, 0xC0, 0x0F, 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x07, 0xF0, + 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x7F, 0x80, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x1F, 0xF8, 0x00, 0x01, 0xFF, + 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0x7F, 0xC0, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x7F, + 0x80, 0x00, 0x03, 0xFF, 0xFF, 0xF0, 0x3F, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, + 0xFC, 0x1F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xF0, + 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x0F, 0xFF, 0x80, 0x0F, 0xFF, 0xF0, 0x07, + 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xC0, 0xFE, 0x1F, 0xF0, 0x7F, 0x01, 0xFC, + 0x1F, 0x80, 0x7F, 0x07, 0xE0, 0x1F, 0xC3, 0xF0, 0x07, 0xF0, 0xFC, 0x01, + 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0x80, 0x01, + 0xFF, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x1F, 0xFC, 0x00, 0x07, 0xFF, 0x80, + 0x01, 0xFF, 0xE0, 0x00, 0x07, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x07, 0xF0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x7F, 0x3F, 0x80, + 0x3F, 0xCF, 0xE0, 0x0F, 0xE3, 0xF8, 0x07, 0xF8, 0xFF, 0x83, 0xFC, 0x3F, + 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xE0, + 0x03, 0xFF, 0xE0, 0x00, 0x3F, 0xC0, 0x00, 0x00, 0x00, 0x7F, 0x80, 0x00, + 0x7F, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0xF0, 0x00, + 0x3F, 0xF8, 0x00, 0x3D, 0xFC, 0x00, 0x3C, 0xFE, 0x00, 0x3E, 0x7E, 0x00, + 0x3E, 0x7F, 0x00, 0x1E, 0x3F, 0x80, 0x1E, 0x1F, 0xC0, 0x1E, 0x0F, 0xC0, + 0x1F, 0x07, 0xE0, 0x1F, 0x07, 0xF0, 0x1F, 0x03, 0xF8, 0x1F, 0x01, 0xFC, + 0x0F, 0x80, 0xFC, 0x0F, 0x80, 0xFE, 0x0F, 0x80, 0x7F, 0x07, 0xFF, 0xFF, + 0xF7, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, 0xFD, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, + 0xFE, 0x00, 0x03, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0x80, 0x00, + 0x7F, 0xFF, 0xE0, 0x0F, 0xFF, 0xFC, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, + 0xF0, 0x0F, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x80, 0x7C, 0x00, 0x00, 0x0F, + 0x80, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x03, 0xE3, 0xF0, 0x00, 0x7F, 0xFF, 0x80, 0x1F, 0xFF, 0xF8, 0x03, 0xFF, + 0xFF, 0x80, 0x7F, 0xFF, 0xF0, 0x1F, 0xE1, 0xFF, 0x03, 0xF0, 0x1F, 0xE0, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xF0, 0xFE, 0x00, 0xFE, 0x1F, + 0xC0, 0x3F, 0x83, 0xF8, 0x07, 0xF0, 0x7F, 0x83, 0xFC, 0x0F, 0xFF, 0xFF, + 0x80, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xF8, 0x01, 0xFF, 0xFE, 0x00, 0x0F, + 0xFF, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xFE, + 0x00, 0x1F, 0xFF, 0x80, 0x1F, 0xFF, 0xE0, 0x1F, 0xFF, 0xF8, 0x1F, 0xC3, + 0xFC, 0x1F, 0x80, 0xFE, 0x0F, 0xC0, 0x3F, 0x0F, 0xC0, 0x00, 0x07, 0xE0, + 0x00, 0x07, 0xE0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF8, 0xFC, 0x01, 0xF9, + 0xFF, 0x80, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, 0xFC, 0x3F, + 0xE1, 0xFF, 0x1F, 0xE0, 0x7F, 0x8F, 0xE0, 0x1F, 0xCF, 0xE0, 0x0F, 0xE7, + 0xF0, 0x07, 0xF3, 0xF0, 0x03, 0xF9, 0xF8, 0x01, 0xF8, 0xFC, 0x01, 0xFC, + 0x7E, 0x00, 0xFE, 0x3F, 0x00, 0xFE, 0x1F, 0xC0, 0xFF, 0x0F, 0xF0, 0xFF, + 0x03, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0x80, 0x1F, 0xFF, + 0x80, 0x07, 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x3F, 0xFF, 0xFF, 0xCF, + 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, + 0x9F, 0xFF, 0xFF, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x1F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03, 0xF0, 0x00, 0x01, 0xF8, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x0F, 0xE0, + 0x00, 0x03, 0xF0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, + 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xF0, 0x00, 0x01, 0xF8, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xF0, 0x00, + 0x01, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x00, 0x00, 0x07, 0xF0, 0x00, + 0x0F, 0xFF, 0x80, 0x07, 0xFF, 0xF0, 0x03, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, + 0xC0, 0xFE, 0x0F, 0xF0, 0x3E, 0x01, 0xFC, 0x1F, 0x80, 0x3F, 0x07, 0xC0, + 0x0F, 0xC1, 0xF0, 0x03, 0xF0, 0x7C, 0x01, 0xF8, 0x1F, 0x00, 0xFC, 0x03, + 0xF0, 0x7F, 0x00, 0xFF, 0xFF, 0x00, 0x1F, 0xFF, 0x80, 0x07, 0xFF, 0xE0, + 0x07, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x81, 0xFE, 0x1F, 0xE0, 0xFE, 0x03, + 0xFC, 0x3F, 0x00, 0x7F, 0x1F, 0xC0, 0x1F, 0xC7, 0xE0, 0x07, 0xF3, 0xF8, + 0x01, 0xFC, 0xFE, 0x00, 0x7F, 0x3F, 0x80, 0x3F, 0x8F, 0xE0, 0x0F, 0xE3, + 0xFC, 0x07, 0xF0, 0xFF, 0x87, 0xFC, 0x3F, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, + 0x00, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xC0, 0x03, 0xFF, 0xE0, 0x00, 0x3F, + 0xC0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xFC, 0x00, 0x3F, 0xFF, 0x00, + 0x3F, 0xFF, 0xC0, 0x3F, 0xFF, 0xF0, 0x3F, 0xC3, 0xF8, 0x3F, 0xC0, 0xFE, + 0x1F, 0xC0, 0x3F, 0x1F, 0xC0, 0x1F, 0x8F, 0xE0, 0x0F, 0xC7, 0xE0, 0x07, + 0xE7, 0xF0, 0x03, 0xF3, 0xF8, 0x01, 0xF9, 0xFC, 0x01, 0xFC, 0xFE, 0x00, + 0xFE, 0x7F, 0x00, 0xFE, 0x3F, 0xC0, 0xFF, 0x1F, 0xF0, 0xFF, 0x87, 0xFF, + 0xFF, 0xC3, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xE0, 0x3F, 0xF3, 0xF0, 0x07, + 0xE3, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0x7E, 0x1F, 0xC0, 0x7E, 0x0F, 0xF0, 0xFF, 0x07, 0xFF, 0xFF, 0x01, + 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0x00, 0x3F, 0xFF, 0x00, 0x0F, 0xFF, 0x00, + 0x01, 0xFC, 0x00, 0x00, 0x07, 0xF0, 0x7F, 0x07, 0xF0, 0x7E, 0x0F, 0xE0, + 0xFE, 0x0F, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0x07, 0xF0, 0x7F, 0x07, + 0xE0, 0xFE, 0x0F, 0xE0, 0xFE, 0x00, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, + 0x7E, 0x03, 0xF8, 0x0F, 0xE0, 0x3F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0x80, 0xFE, 0x03, 0xF8, 0x0F, 0xE0, + 0x03, 0x80, 0x1C, 0x00, 0x70, 0x03, 0xC0, 0x0E, 0x00, 0xF0, 0x0F, 0xC0, + 0x3C, 0x00, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0xE0, 0x00, + 0x01, 0xF8, 0x00, 0x03, 0xFE, 0x00, 0x07, 0xFF, 0x80, 0x0F, 0xFF, 0xE0, + 0x1F, 0xFF, 0xF0, 0x1F, 0xFF, 0xE0, 0x3F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, + 0x0F, 0xFF, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFF, 0xE0, 0x00, 0x3F, 0xFE, + 0x00, 0x0F, 0xFF, 0xF0, 0x00, 0xFF, 0xFF, 0x80, 0x07, 0xFF, 0xF8, 0x00, + 0x7F, 0xFF, 0x00, 0x03, 0xFF, 0xC0, 0x00, 0x3F, 0xF0, 0x00, 0x01, 0xF8, + 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x80, 0x1F, 0xFF, 0xFF, 0xC7, 0xFF, + 0xFF, 0xF1, 0xFF, 0xFF, 0xFC, 0x7F, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0x8F, + 0xFF, 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, + 0xFF, 0x1F, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0xF8, 0xFF, + 0xFF, 0xFE, 0x3F, 0xFF, 0xFF, 0x80, 0x04, 0x00, 0x00, 0x01, 0xE0, 0x00, + 0x00, 0x7E, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x0F, 0xFF, 0x00, 0x03, 0xFF, + 0xF8, 0x00, 0x7F, 0xFF, 0x80, 0x07, 0xFF, 0xFC, 0x00, 0x3F, 0xFF, 0xC0, + 0x01, 0xFF, 0xF0, 0x00, 0x1F, 0xFC, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xFF, + 0xC0, 0x07, 0xFF, 0xE0, 0x0F, 0xFF, 0xF0, 0x1F, 0xFF, 0xE0, 0x3F, 0xFF, + 0xE0, 0x1F, 0xFF, 0xC0, 0x07, 0xFF, 0x80, 0x01, 0xFF, 0x00, 0x00, 0x7E, + 0x00, 0x00, 0x1C, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x3F, 0x80, + 0x01, 0xFF, 0xF0, 0x07, 0xFF, 0xF8, 0x0F, 0xFF, 0xFC, 0x1F, 0xFF, 0xFE, + 0x1F, 0xFF, 0xFE, 0x3F, 0xC1, 0xFF, 0x3F, 0x80, 0xFF, 0x7F, 0x00, 0x7F, + 0x7E, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xFC, 0x00, 0x0F, 0xF8, + 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0x7F, 0x80, 0x00, 0xFE, 0x00, + 0x01, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xE0, 0x00, + 0x0F, 0xE0, 0x00, 0x0F, 0xE0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, + 0x1F, 0xC0, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xC0, 0x00, + 0x00, 0x00, 0x7F, 0xFF, 0xC0, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0x80, 0x00, + 0x01, 0xFF, 0xFF, 0xFE, 0x00, 0x00, 0x3F, 0xE0, 0x1F, 0xF8, 0x00, 0x07, + 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0x80, 0x07, 0xE0, + 0x00, 0x00, 0xFE, 0x00, 0xFE, 0x00, 0x00, 0x03, 0xF0, 0x0F, 0xC0, 0x00, + 0x00, 0x0F, 0x80, 0xFC, 0x00, 0x00, 0x00, 0x3E, 0x07, 0xC0, 0x03, 0xF1, + 0xF1, 0xF0, 0x7C, 0x00, 0xFF, 0xCF, 0x07, 0x87, 0xE0, 0x1F, 0xFF, 0xF8, + 0x3C, 0x7E, 0x01, 0xF8, 0x7F, 0x81, 0xE3, 0xE0, 0x1F, 0x01, 0xF8, 0x0F, + 0x3E, 0x01, 0xF0, 0x0F, 0xC0, 0x79, 0xF0, 0x1F, 0x00, 0x7C, 0x03, 0xDF, + 0x00, 0xF0, 0x03, 0xE0, 0x1C, 0xF8, 0x0F, 0x80, 0x1E, 0x01, 0xE7, 0xC0, + 0x78, 0x00, 0xF0, 0x0F, 0x3C, 0x07, 0xC0, 0x0F, 0x00, 0xF3, 0xE0, 0x3C, + 0x00, 0x78, 0x07, 0x9F, 0x03, 0xE0, 0x07, 0x80, 0x78, 0xF8, 0x1F, 0x00, + 0x7C, 0x07, 0xC7, 0xC0, 0xF8, 0x07, 0xC0, 0x7C, 0x3E, 0x07, 0xC0, 0x7E, + 0x07, 0xC1, 0xF0, 0x3F, 0x07, 0xF8, 0xFC, 0x0F, 0x81, 0xFF, 0xFF, 0xFF, + 0xC0, 0x7E, 0x07, 0xFF, 0xBF, 0xFC, 0x01, 0xF0, 0x1F, 0xF8, 0xFF, 0x80, + 0x0F, 0xC0, 0x7E, 0x03, 0xF0, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x3F, + 0xE0, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xE0, 0x03, 0x80, 0x00, 0x01, 0xFF, + 0xFF, 0xFE, 0x00, 0x00, 0x07, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x0F, 0xFF, + 0xFE, 0x00, 0x00, 0x00, 0x07, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, + 0xF0, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x7F, + 0xF0, 0x00, 0x00, 0x7F, 0xF0, 0x00, 0x00, 0xFF, 0xF0, 0x00, 0x00, 0xFF, + 0xF0, 0x00, 0x01, 0xFF, 0xF0, 0x00, 0x03, 0xFF, 0xF8, 0x00, 0x03, 0xFB, + 0xF8, 0x00, 0x07, 0xF3, 0xF8, 0x00, 0x07, 0xE3, 0xF8, 0x00, 0x0F, 0xE3, + 0xF8, 0x00, 0x0F, 0xC3, 0xF8, 0x00, 0x1F, 0xC3, 0xF8, 0x00, 0x1F, 0x83, + 0xF8, 0x00, 0x3F, 0x81, 0xFC, 0x00, 0x7F, 0x01, 0xFC, 0x00, 0x7F, 0x01, + 0xFC, 0x00, 0xFE, 0x01, 0xFC, 0x00, 0xFC, 0x01, 0xFC, 0x01, 0xFF, 0xFF, + 0xFC, 0x01, 0xFF, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, + 0xFE, 0x07, 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xFE, 0x0F, 0xE0, 0x00, + 0xFE, 0x1F, 0xC0, 0x00, 0xFE, 0x1F, 0xC0, 0x00, 0xFE, 0x3F, 0x80, 0x00, + 0xFE, 0x3F, 0x80, 0x00, 0x7F, 0x7F, 0x00, 0x00, 0x7F, 0xFF, 0x00, 0x00, + 0x7F, 0x01, 0xFF, 0xFF, 0xC0, 0x01, 0xFF, 0xFF, 0xF8, 0x01, 0xFF, 0xFF, + 0xFC, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, + 0xFF, 0x03, 0xF8, 0x00, 0xFF, 0x03, 0xF8, 0x00, 0x7F, 0x07, 0xF0, 0x00, + 0x7F, 0x07, 0xF0, 0x00, 0x7F, 0x07, 0xF0, 0x00, 0x7E, 0x07, 0xF0, 0x00, + 0xFE, 0x0F, 0xF0, 0x03, 0xFC, 0x0F, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, + 0xF0, 0x0F, 0xFF, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, + 0xF8, 0x1F, 0xFF, 0xFF, 0xF8, 0x1F, 0xC0, 0x07, 0xFC, 0x1F, 0xC0, 0x01, + 0xFC, 0x1F, 0xC0, 0x01, 0xFC, 0x3F, 0x80, 0x01, 0xFC, 0x3F, 0x80, 0x01, + 0xFC, 0x3F, 0x80, 0x01, 0xFC, 0x3F, 0x80, 0x03, 0xF8, 0x7F, 0x00, 0x07, + 0xF8, 0x7F, 0x00, 0x0F, 0xF0, 0x7F, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xFF, + 0xE0, 0x7F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xFE, + 0x00, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x07, 0xFF, + 0xE0, 0x00, 0x1F, 0xFF, 0xF0, 0x00, 0x7F, 0xFF, 0xF8, 0x00, 0xFF, 0xFF, + 0xFC, 0x01, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0x03, 0xFE, 0x07, 0xFC, 0x01, + 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, 0xE0, 0x00, 0x7F, 0x1F, 0xE0, 0x00, + 0x7F, 0x1F, 0xC0, 0x00, 0x7F, 0x3F, 0x80, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x00, 0x7F, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xF8, 0xFE, 0x00, 0x03, + 0xF8, 0xFF, 0x00, 0x07, 0xF8, 0xFF, 0x00, 0x07, 0xF0, 0x7F, 0x80, 0x1F, + 0xF0, 0x7F, 0xE0, 0x7F, 0xE0, 0x3F, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xFF, + 0x80, 0x1F, 0xFF, 0xFF, 0x00, 0x0F, 0xFF, 0xFE, 0x00, 0x03, 0xFF, 0xF8, + 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x01, 0xFF, 0xFF, + 0xE0, 0x03, 0xFF, 0xFF, 0xF8, 0x03, 0xFF, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, + 0xFC, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xF8, 0x03, 0xFE, 0x07, 0xF0, 0x01, + 0xFF, 0x07, 0xF0, 0x00, 0xFF, 0x07, 0xF0, 0x00, 0x7F, 0x07, 0xF0, 0x00, + 0x7F, 0x0F, 0xF0, 0x00, 0x7F, 0x0F, 0xE0, 0x00, 0x7F, 0x0F, 0xE0, 0x00, + 0x7F, 0x0F, 0xE0, 0x00, 0x7F, 0x0F, 0xE0, 0x00, 0x7F, 0x1F, 0xC0, 0x00, + 0x7F, 0x1F, 0xC0, 0x00, 0xFE, 0x1F, 0xC0, 0x00, 0xFE, 0x1F, 0xC0, 0x00, + 0xFE, 0x1F, 0xC0, 0x01, 0xFE, 0x3F, 0x80, 0x01, 0xFC, 0x3F, 0x80, 0x01, + 0xFC, 0x3F, 0x80, 0x03, 0xF8, 0x3F, 0x80, 0x07, 0xF8, 0x7F, 0x00, 0x0F, + 0xF0, 0x7F, 0x00, 0x1F, 0xF0, 0x7F, 0x00, 0x7F, 0xE0, 0x7F, 0xFF, 0xFF, + 0xC0, 0x7F, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xFE, + 0x00, 0xFF, 0xFF, 0xF8, 0x00, 0xFF, 0xFF, 0x80, 0x00, 0x01, 0xFF, 0xFF, + 0xFF, 0x01, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, + 0xFE, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xF8, 0x00, + 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, 0xF0, 0x00, + 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x0F, 0xE0, 0x00, + 0x00, 0x0F, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, + 0xE0, 0x1F, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, + 0xE0, 0x1F, 0xC0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x00, 0x7F, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, + 0xC0, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, + 0x80, 0x00, 0xFF, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, + 0xFE, 0x01, 0xFF, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, + 0xFE, 0x03, 0xF8, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x03, 0xF8, 0x00, + 0x00, 0x03, 0xF8, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x07, 0xF0, 0x00, + 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, 0xFF, 0xFF, 0xE0, 0x07, 0xFF, 0xFF, + 0xE0, 0x0F, 0xFF, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xC0, 0x0F, 0xFF, 0xFF, + 0xC0, 0x0F, 0xFF, 0xFF, 0xC0, 0x0F, 0xE0, 0x00, 0x00, 0x1F, 0xC0, 0x00, + 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x1F, 0xC0, 0x00, + 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x00, 0x7F, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x00, 0x7F, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x03, 0xFF, + 0xF8, 0x00, 0x07, 0xFF, 0xFE, 0x00, 0x0F, 0xFF, 0xFF, 0x80, 0x0F, 0xFF, + 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xF8, 0x0F, 0xFC, 0x07, 0xFC, 0x0F, 0xF8, + 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0x3F, 0x87, 0xF0, 0x00, 0x1F, 0xC7, 0xF0, + 0x00, 0x0F, 0xE3, 0xF8, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x01, 0xFC, + 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x00, 0x7F, + 0x00, 0x3F, 0xFF, 0x3F, 0x00, 0x1F, 0xFF, 0xBF, 0x80, 0x0F, 0xFF, 0x9F, + 0xC0, 0x07, 0xFF, 0xCF, 0xE0, 0x03, 0xFF, 0xE7, 0xF0, 0x03, 0xFF, 0xF3, + 0xF8, 0x00, 0x01, 0xF9, 0xFC, 0x00, 0x01, 0xF8, 0xFF, 0x00, 0x00, 0xFC, + 0x7F, 0x80, 0x00, 0xFE, 0x3F, 0xC0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, + 0x87, 0xFC, 0x00, 0xFF, 0x81, 0xFF, 0x81, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, + 0xE0, 0x3F, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFE, 0xF8, 0x03, 0xFF, 0xFC, + 0x78, 0x00, 0x7F, 0xFC, 0x3C, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x01, 0xFC, + 0x00, 0x0F, 0xE0, 0x3F, 0x80, 0x01, 0xFC, 0x07, 0xF0, 0x00, 0x3F, 0x80, + 0xFE, 0x00, 0x0F, 0xE0, 0x1F, 0xC0, 0x01, 0xFC, 0x07, 0xF0, 0x00, 0x3F, + 0x80, 0xFE, 0x00, 0x07, 0xF0, 0x1F, 0xC0, 0x00, 0xFE, 0x03, 0xF8, 0x00, + 0x3F, 0x80, 0xFF, 0x00, 0x07, 0xF0, 0x1F, 0xC0, 0x00, 0xFE, 0x03, 0xF8, + 0x00, 0x1F, 0xC0, 0x7F, 0x00, 0x07, 0xF0, 0x0F, 0xFF, 0xFF, 0xFE, 0x03, + 0xFF, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xFF, + 0x01, 0xFF, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xFF, 0xF8, 0x0F, 0xE0, 0x00, + 0x7F, 0x01, 0xFC, 0x00, 0x0F, 0xE0, 0x3F, 0x80, 0x01, 0xFC, 0x07, 0xF0, + 0x00, 0x7F, 0x01, 0xFC, 0x00, 0x0F, 0xE0, 0x3F, 0x80, 0x01, 0xFC, 0x07, + 0xF0, 0x00, 0x3F, 0x80, 0xFE, 0x00, 0x0F, 0xE0, 0x1F, 0xC0, 0x01, 0xFC, + 0x07, 0xF0, 0x00, 0x3F, 0x80, 0xFE, 0x00, 0x07, 0xF0, 0x1F, 0xC0, 0x00, + 0xFE, 0x03, 0xF8, 0x00, 0x3F, 0x80, 0x7F, 0x00, 0x07, 0xF0, 0x1F, 0xC0, + 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x07, 0xF0, 0x3F, 0x80, 0xFE, 0x03, 0xF8, + 0x0F, 0xE0, 0x3F, 0x81, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, + 0x0F, 0xE0, 0x3F, 0x80, 0xFE, 0x03, 0xF8, 0x0F, 0xE0, 0x7F, 0x01, 0xFC, + 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x03, 0xF8, 0x0F, 0xE0, 0x3F, 0x80, 0xFE, + 0x03, 0xF8, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0xFE, + 0x03, 0xF8, 0x00, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x00, + 0x3F, 0x80, 0x00, 0x0F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, + 0x00, 0x07, 0xF0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xF0, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x0F, 0xE0, 0xFE, 0x03, 0xFC, 0x1F, 0xC0, 0x7F, 0x03, 0xF8, 0x0F, 0xE0, + 0xFE, 0x01, 0xFC, 0x1F, 0xC0, 0x3F, 0x83, 0xF8, 0x0F, 0xE0, 0x7F, 0x01, + 0xFC, 0x0F, 0xF0, 0xFF, 0x81, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, 0xF8, 0x03, + 0xFF, 0xFF, 0x00, 0x3F, 0xFF, 0x80, 0x03, 0xFF, 0xE0, 0x00, 0x1F, 0xE0, + 0x00, 0x00, 0x00, 0xFE, 0x00, 0x0F, 0xF0, 0x0F, 0xF0, 0x00, 0xFF, 0x00, + 0x7F, 0x00, 0x1F, 0xF0, 0x03, 0xF8, 0x01, 0xFF, 0x00, 0x1F, 0xC0, 0x1F, + 0xE0, 0x00, 0xFE, 0x01, 0xFE, 0x00, 0x0F, 0xE0, 0x1F, 0xE0, 0x00, 0x7F, + 0x01, 0xFE, 0x00, 0x03, 0xF8, 0x1F, 0xE0, 0x00, 0x1F, 0xC1, 0xFE, 0x00, + 0x00, 0xFE, 0x1F, 0xE0, 0x00, 0x0F, 0xE3, 0xFE, 0x00, 0x00, 0x7F, 0x3F, + 0xC0, 0x00, 0x03, 0xFB, 0xFC, 0x00, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x01, + 0xFF, 0xFE, 0x00, 0x00, 0x0F, 0xFF, 0xF8, 0x00, 0x00, 0x7F, 0xFF, 0xC0, + 0x00, 0x03, 0xFF, 0xFF, 0x00, 0x00, 0x1F, 0xFF, 0xF8, 0x00, 0x01, 0xFF, + 0x9F, 0xE0, 0x00, 0x0F, 0xF8, 0xFF, 0x00, 0x00, 0x7F, 0x83, 0xFC, 0x00, + 0x03, 0xF8, 0x1F, 0xF0, 0x00, 0x1F, 0xC0, 0x7F, 0x80, 0x01, 0xFC, 0x01, + 0xFE, 0x00, 0x0F, 0xE0, 0x0F, 0xF0, 0x00, 0x7F, 0x00, 0x3F, 0xC0, 0x03, + 0xF8, 0x01, 0xFF, 0x00, 0x3F, 0x80, 0x07, 0xF8, 0x01, 0xFC, 0x00, 0x3F, + 0xE0, 0x0F, 0xE0, 0x00, 0xFF, 0x00, 0x7F, 0x00, 0x07, 0xFC, 0x03, 0xF8, + 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x01, 0xFC, 0x00, 0x01, 0xFC, + 0x00, 0x03, 0xF8, 0x00, 0x03, 0xF8, 0x00, 0x03, 0xF8, 0x00, 0x03, 0xF8, + 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF0, + 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x0F, 0xE0, 0x00, 0x0F, 0xE0, + 0x00, 0x0F, 0xE0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x1F, 0xC0, + 0x00, 0x1F, 0xC0, 0x00, 0x1F, 0xC0, 0x00, 0x3F, 0x80, 0x00, 0x3F, 0x80, + 0x00, 0x3F, 0x80, 0x00, 0x3F, 0x80, 0x00, 0x3F, 0x80, 0x00, 0x7F, 0x00, + 0x00, 0x7F, 0x00, 0x00, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x01, 0xFF, + 0x80, 0x03, 0xFF, 0x80, 0xFF, 0xC0, 0x01, 0xFF, 0x80, 0x7F, 0xE0, 0x01, + 0xFF, 0xC0, 0x3F, 0xF0, 0x00, 0xFF, 0xE0, 0x3F, 0xF8, 0x00, 0xFF, 0xF0, + 0x1F, 0xFC, 0x00, 0x7F, 0xF8, 0x0F, 0xFE, 0x00, 0x7D, 0xF8, 0x07, 0xEF, + 0x00, 0x3E, 0xFC, 0x03, 0xF7, 0x80, 0x3F, 0xFE, 0x03, 0xFB, 0xC0, 0x1F, + 0x7F, 0x01, 0xFD, 0xE0, 0x1F, 0xBF, 0x00, 0xFE, 0xF0, 0x0F, 0x9F, 0x80, + 0x7E, 0x78, 0x0F, 0xDF, 0xC0, 0x7F, 0x3E, 0x07, 0xCF, 0xE0, 0x3F, 0x9F, + 0x07, 0xE7, 0xF0, 0x1F, 0xCF, 0x83, 0xE3, 0xF0, 0x0F, 0xE7, 0xC3, 0xF1, + 0xF8, 0x07, 0xE3, 0xE1, 0xF9, 0xFC, 0x07, 0xF1, 0xF0, 0xF8, 0xFE, 0x03, + 0xF8, 0xF8, 0xFC, 0x7F, 0x01, 0xFC, 0x7C, 0x7C, 0x3F, 0x00, 0xFC, 0x3E, + 0x7E, 0x1F, 0x80, 0x7E, 0x1F, 0x3E, 0x1F, 0xC0, 0x7F, 0x0F, 0xBF, 0x0F, + 0xE0, 0x3F, 0x87, 0xDF, 0x07, 0xE0, 0x1F, 0xC3, 0xFF, 0x83, 0xF0, 0x0F, + 0xC1, 0xFF, 0xC3, 0xF8, 0x0F, 0xE0, 0xFF, 0xC1, 0xFC, 0x07, 0xF0, 0x7F, + 0xE0, 0xFE, 0x03, 0xF8, 0x3F, 0xE0, 0x7E, 0x01, 0xFC, 0x1F, 0xF0, 0x3F, + 0x00, 0xFC, 0x0F, 0xF0, 0x3F, 0x80, 0xFE, 0x07, 0xF8, 0x1F, 0xC0, 0x7F, + 0x03, 0xF8, 0x0F, 0xC0, 0x00, 0x01, 0xFE, 0x00, 0x07, 0xE0, 0x3F, 0xC0, + 0x01, 0xFC, 0x07, 0xFC, 0x00, 0x3F, 0x80, 0xFF, 0x80, 0x07, 0xF0, 0x1F, + 0xF0, 0x00, 0xFC, 0x07, 0xFF, 0x00, 0x3F, 0x80, 0xFF, 0xE0, 0x07, 0xF0, + 0x1F, 0xFC, 0x00, 0xFE, 0x03, 0xFF, 0xC0, 0x1F, 0x80, 0xFF, 0xF8, 0x03, + 0xF0, 0x1F, 0xFF, 0x80, 0xFE, 0x03, 0xFB, 0xF0, 0x1F, 0xC0, 0x7E, 0x7E, + 0x03, 0xF8, 0x0F, 0xC7, 0xE0, 0x7E, 0x03, 0xF8, 0xFC, 0x0F, 0xC0, 0x7F, + 0x1F, 0x83, 0xF8, 0x0F, 0xE1, 0xF8, 0x7F, 0x01, 0xF8, 0x3F, 0x0F, 0xE0, + 0x3F, 0x07, 0xF1, 0xF8, 0x0F, 0xE0, 0x7E, 0x3F, 0x01, 0xFC, 0x0F, 0xCF, + 0xE0, 0x3F, 0x00, 0xFD, 0xFC, 0x07, 0xE0, 0x1F, 0xBF, 0x81, 0xFC, 0x03, + 0xF7, 0xE0, 0x3F, 0x80, 0x3F, 0xFC, 0x07, 0xF0, 0x07, 0xFF, 0x80, 0xFC, + 0x00, 0xFF, 0xF0, 0x1F, 0x80, 0x0F, 0xFC, 0x07, 0xF0, 0x01, 0xFF, 0x80, + 0xFE, 0x00, 0x3F, 0xF0, 0x1F, 0xC0, 0x03, 0xFE, 0x03, 0xF0, 0x00, 0x7F, + 0xC0, 0x7E, 0x00, 0x07, 0xF0, 0x1F, 0xC0, 0x00, 0xFE, 0x00, 0x00, 0x00, + 0xFF, 0x80, 0x00, 0x01, 0xFF, 0xF8, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x01, + 0xFF, 0xFF, 0xF0, 0x00, 0xFF, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xFF, 0xC0, + 0x3F, 0xF0, 0x3F, 0xF8, 0x1F, 0xF0, 0x03, 0xFE, 0x07, 0xF0, 0x00, 0x7F, + 0x83, 0xF8, 0x00, 0x0F, 0xF1, 0xFE, 0x00, 0x03, 0xFC, 0x7F, 0x00, 0x00, + 0x7F, 0x3F, 0x80, 0x00, 0x1F, 0xCF, 0xE0, 0x00, 0x07, 0xF7, 0xF0, 0x00, + 0x01, 0xFD, 0xFC, 0x00, 0x00, 0x7F, 0x7F, 0x00, 0x00, 0x1F, 0xDF, 0xC0, + 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x03, 0xFB, 0xF8, 0x00, 0x00, 0xFE, 0xFE, + 0x00, 0x00, 0x3F, 0xBF, 0x80, 0x00, 0x0F, 0xEF, 0xE0, 0x00, 0x07, 0xF3, + 0xF8, 0x00, 0x01, 0xFC, 0xFE, 0x00, 0x00, 0xFE, 0x3F, 0xC0, 0x00, 0x7F, + 0x8F, 0xF0, 0x00, 0x1F, 0xC1, 0xFE, 0x00, 0x0F, 0xE0, 0x7F, 0xC0, 0x0F, + 0xF8, 0x1F, 0xFC, 0x0F, 0xFC, 0x03, 0xFF, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, + 0xFF, 0x00, 0x0F, 0xFF, 0xFF, 0x80, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x1F, + 0xFF, 0x80, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x03, + 0xFF, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0xE0, 0x3F, + 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xC1, 0xFE, 0x00, 0xFF, 0x83, 0xF8, + 0x00, 0xFF, 0x07, 0xF0, 0x00, 0xFE, 0x0F, 0xE0, 0x01, 0xFC, 0x1F, 0xC0, + 0x03, 0xF8, 0x7F, 0x00, 0x07, 0xF0, 0xFE, 0x00, 0x1F, 0xC1, 0xFC, 0x00, + 0x3F, 0x83, 0xF8, 0x00, 0xFE, 0x07, 0xF0, 0x07, 0xFC, 0x1F, 0xFF, 0xFF, + 0xF0, 0x3F, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xFE, + 0x03, 0xFF, 0xFF, 0xF0, 0x07, 0xFF, 0xFF, 0x80, 0x0F, 0xE0, 0x00, 0x00, + 0x1F, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x0F, + 0xE0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0x80, 0x00, + 0x01, 0xFF, 0xF8, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x01, 0xFF, 0xFF, 0xF0, + 0x00, 0xFF, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xFF, 0xC0, 0x3F, 0xF0, 0x3F, + 0xF0, 0x1F, 0xF0, 0x03, 0xFE, 0x07, 0xF8, 0x00, 0x7F, 0x83, 0xFC, 0x00, + 0x0F, 0xF1, 0xFE, 0x00, 0x03, 0xFC, 0x7F, 0x00, 0x00, 0x7F, 0x3F, 0x80, + 0x00, 0x1F, 0xCF, 0xE0, 0x00, 0x07, 0xF3, 0xF0, 0x00, 0x01, 0xFD, 0xFC, + 0x00, 0x00, 0x7F, 0x7F, 0x00, 0x00, 0x1F, 0xDF, 0x80, 0x00, 0x07, 0xFF, + 0xE0, 0x00, 0x03, 0xFB, 0xF8, 0x00, 0x00, 0xFE, 0xFE, 0x00, 0x00, 0x3F, + 0xBF, 0x80, 0x00, 0x0F, 0xEF, 0xE0, 0x01, 0x87, 0xF3, 0xF8, 0x00, 0xF1, + 0xFC, 0xFE, 0x00, 0x7C, 0xFE, 0x3F, 0xC0, 0x3F, 0xFF, 0x8F, 0xF0, 0x07, + 0xFF, 0xC1, 0xFE, 0x01, 0xFF, 0xE0, 0x7F, 0xC0, 0x3F, 0xF8, 0x1F, 0xFC, + 0x0F, 0xFC, 0x03, 0xFF, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xFF, 0xC0, 0x0F, + 0xFF, 0xFF, 0xF8, 0x01, 0xFF, 0xFF, 0xFF, 0x00, 0x1F, 0xFF, 0x9F, 0x80, + 0x01, 0xFF, 0x03, 0xC0, 0x00, 0x00, 0x00, 0x60, 0x00, 0x01, 0xFF, 0xFF, + 0xF0, 0x00, 0xFF, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, + 0xFF, 0xE0, 0x3F, 0xFF, 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0xFC, 0x0F, 0xE0, + 0x03, 0xFE, 0x0F, 0xF0, 0x00, 0xFF, 0x07, 0xF0, 0x00, 0x3F, 0x83, 0xF8, + 0x00, 0x1F, 0xC1, 0xFC, 0x00, 0x0F, 0xC0, 0xFE, 0x00, 0x07, 0xE0, 0xFE, + 0x00, 0x07, 0xF0, 0x7F, 0x00, 0x07, 0xF0, 0x3F, 0x80, 0x0F, 0xF0, 0x1F, + 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xE0, 0x07, + 0xFF, 0xFF, 0xF0, 0x03, 0xFF, 0xFF, 0xFC, 0x01, 0xFF, 0xFF, 0xFF, 0x01, + 0xFC, 0x00, 0x7F, 0x80, 0xFE, 0x00, 0x1F, 0xC0, 0x7F, 0x00, 0x0F, 0xE0, + 0x3F, 0x80, 0x07, 0xF0, 0x1F, 0xC0, 0x03, 0xF8, 0x1F, 0xC0, 0x01, 0xFC, + 0x0F, 0xE0, 0x01, 0xFC, 0x07, 0xF0, 0x00, 0xFE, 0x03, 0xF8, 0x00, 0x7F, + 0x01, 0xFC, 0x00, 0x3F, 0x81, 0xFC, 0x00, 0x1F, 0xC0, 0xFE, 0x00, 0x0F, + 0xE0, 0x7F, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x7F, + 0xFF, 0x00, 0x07, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0xFC, 0x01, 0xFF, 0xFF, + 0xF8, 0x0F, 0xFF, 0xFF, 0xF0, 0x3F, 0xC0, 0x7F, 0xC1, 0xFE, 0x00, 0xFF, + 0x07, 0xF0, 0x01, 0xFC, 0x3F, 0x80, 0x07, 0xF0, 0xFE, 0x00, 0x1F, 0xC3, + 0xF8, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x00, 0xFF, + 0xE0, 0x00, 0x03, 0xFF, 0xFC, 0x00, 0x07, 0xFF, 0xFF, 0x00, 0x0F, 0xFF, + 0xFE, 0x00, 0x1F, 0xFF, 0xFE, 0x00, 0x0F, 0xFF, 0xF8, 0x00, 0x03, 0xFF, + 0xF0, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x01, 0xFC, + 0x00, 0x00, 0x07, 0xF3, 0xF8, 0x00, 0x1F, 0xCF, 0xE0, 0x00, 0x7E, 0x3F, + 0x80, 0x03, 0xF8, 0xFF, 0x00, 0x1F, 0xE3, 0xFF, 0x01, 0xFF, 0x07, 0xFF, + 0xFF, 0xF8, 0x1F, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, + 0xF0, 0x00, 0x7F, 0xFF, 0x80, 0x00, 0x3F, 0xF0, 0x00, 0x7F, 0xFF, 0xFF, + 0xF7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xFE, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xF8, + 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x07, 0xF0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x0F, 0xE0, 0x00, + 0x01, 0xFC, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xF8, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x7F, 0x00, + 0x00, 0x0F, 0xE0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x7F, + 0x07, 0xF0, 0x00, 0x7F, 0x07, 0xF0, 0x00, 0xFE, 0x0F, 0xE0, 0x00, 0xFE, + 0x0F, 0xE0, 0x00, 0xFE, 0x0F, 0xE0, 0x00, 0xFE, 0x0F, 0xE0, 0x00, 0xFE, + 0x0F, 0xE0, 0x01, 0xFC, 0x1F, 0xC0, 0x01, 0xFC, 0x1F, 0xC0, 0x01, 0xFC, + 0x1F, 0xC0, 0x01, 0xFC, 0x1F, 0xC0, 0x01, 0xFC, 0x3F, 0x80, 0x03, 0xF8, + 0x3F, 0x80, 0x03, 0xF8, 0x3F, 0x80, 0x03, 0xF8, 0x3F, 0x80, 0x03, 0xF8, + 0x3F, 0x80, 0x07, 0xF0, 0x7F, 0x00, 0x07, 0xF0, 0x7F, 0x00, 0x07, 0xF0, + 0x7F, 0x00, 0x07, 0xF0, 0x7F, 0x00, 0x07, 0xF0, 0x7F, 0x00, 0x0F, 0xE0, + 0xFE, 0x00, 0x0F, 0xE0, 0xFE, 0x00, 0x0F, 0xE0, 0xFE, 0x00, 0x0F, 0xE0, + 0xFE, 0x00, 0x1F, 0xC0, 0xFE, 0x00, 0x1F, 0xC0, 0xFF, 0x00, 0x3F, 0x80, + 0xFF, 0xC0, 0xFF, 0x80, 0x7F, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xFE, 0x00, + 0x3F, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0xF8, 0x00, 0x0F, 0xFF, 0xE0, 0x00, + 0x01, 0xFF, 0x00, 0x00, 0xFF, 0x00, 0x03, 0xF9, 0xFC, 0x00, 0x0F, 0xE7, + 0xF0, 0x00, 0x7F, 0x1F, 0xC0, 0x01, 0xFC, 0x7F, 0x00, 0x0F, 0xE1, 0xFC, + 0x00, 0x3F, 0x87, 0xF0, 0x01, 0xFC, 0x1F, 0xC0, 0x07, 0xF0, 0x3F, 0x00, + 0x3F, 0x80, 0xFC, 0x00, 0xFC, 0x03, 0xF0, 0x07, 0xF0, 0x0F, 0xC0, 0x1F, + 0x80, 0x3F, 0x80, 0xFE, 0x00, 0xFE, 0x03, 0xF0, 0x03, 0xF8, 0x1F, 0xC0, + 0x0F, 0xE0, 0x7E, 0x00, 0x1F, 0x83, 0xF8, 0x00, 0x7E, 0x0F, 0xC0, 0x01, + 0xF8, 0x7E, 0x00, 0x07, 0xE1, 0xF8, 0x00, 0x1F, 0x8F, 0xC0, 0x00, 0x7E, + 0x3F, 0x00, 0x01, 0xF9, 0xF8, 0x00, 0x07, 0xE7, 0xE0, 0x00, 0x0F, 0xFF, + 0x00, 0x00, 0x3F, 0xFC, 0x00, 0x00, 0xFF, 0xE0, 0x00, 0x03, 0xFF, 0x00, + 0x00, 0x0F, 0xFC, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x00, 0xFF, 0x80, 0x00, + 0x01, 0xFC, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x00, + 0xFE, 0x00, 0x7F, 0x80, 0x1F, 0xFF, 0xC0, 0x0F, 0xF0, 0x03, 0xFB, 0xF8, + 0x01, 0xFE, 0x00, 0x7F, 0x7F, 0x00, 0x7F, 0xC0, 0x1F, 0xCF, 0xE0, 0x0F, + 0xF8, 0x03, 0xF9, 0xFC, 0x03, 0xFF, 0x00, 0xFE, 0x3F, 0x80, 0x7F, 0xE0, + 0x1F, 0xC7, 0xF0, 0x1F, 0xFC, 0x07, 0xF0, 0x7E, 0x03, 0xFF, 0x80, 0xFE, + 0x0F, 0xC0, 0x7D, 0xF0, 0x1F, 0x81, 0xF8, 0x1F, 0xBE, 0x07, 0xF0, 0x3F, + 0x03, 0xE7, 0xC0, 0xFC, 0x07, 0xE0, 0xFC, 0xF8, 0x3F, 0x80, 0xFC, 0x1F, + 0x1F, 0x07, 0xE0, 0x1F, 0x83, 0xE3, 0xE0, 0xFC, 0x03, 0xF0, 0xFC, 0x7C, + 0x3F, 0x00, 0x7E, 0x1F, 0x0F, 0x87, 0xE0, 0x0F, 0xC7, 0xE1, 0xF1, 0xF8, + 0x01, 0xF8, 0xF8, 0x3E, 0x3F, 0x00, 0x3F, 0x3F, 0x07, 0xCF, 0xC0, 0x07, + 0xE7, 0xC0, 0xF9, 0xF8, 0x00, 0xFC, 0xF8, 0x1F, 0x3E, 0x00, 0x1F, 0xBE, + 0x03, 0xEF, 0xC0, 0x01, 0xF7, 0xC0, 0x7D, 0xF0, 0x00, 0x3F, 0xF8, 0x0F, + 0xFE, 0x00, 0x07, 0xFE, 0x01, 0xFF, 0x80, 0x00, 0xFF, 0xC0, 0x3F, 0xF0, + 0x00, 0x1F, 0xF0, 0x07, 0xFC, 0x00, 0x03, 0xFE, 0x00, 0xFF, 0x80, 0x00, + 0x7F, 0x80, 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x03, 0xFC, 0x00, 0x01, 0xFC, + 0x00, 0x7F, 0x80, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0x01, + 0xFC, 0x00, 0x00, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x07, 0xFC, 0x00, 0xFF, + 0x00, 0x1F, 0xE0, 0x07, 0xF8, 0x00, 0xFF, 0x00, 0x7F, 0x80, 0x03, 0xFC, + 0x07, 0xF8, 0x00, 0x1F, 0xE0, 0x7F, 0x80, 0x00, 0xFF, 0x07, 0xF8, 0x00, + 0x03, 0xFC, 0x3F, 0x80, 0x00, 0x1F, 0xE3, 0xF8, 0x00, 0x00, 0x7F, 0x3F, + 0xC0, 0x00, 0x03, 0xFF, 0xFC, 0x00, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x00, + 0x7F, 0xFC, 0x00, 0x00, 0x03, 0xFF, 0xC0, 0x00, 0x00, 0x0F, 0xFC, 0x00, + 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x00, 0x1F, + 0xF0, 0x00, 0x00, 0x01, 0xFF, 0x80, 0x00, 0x00, 0x1F, 0xFE, 0x00, 0x00, + 0x00, 0xFF, 0xF0, 0x00, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x00, 0xFF, 0xFE, + 0x00, 0x00, 0x0F, 0xE7, 0xF0, 0x00, 0x00, 0xFF, 0x3F, 0xC0, 0x00, 0x0F, + 0xF1, 0xFE, 0x00, 0x00, 0xFF, 0x07, 0xF8, 0x00, 0x07, 0xF0, 0x3F, 0xC0, + 0x00, 0x7F, 0x01, 0xFE, 0x00, 0x07, 0xF8, 0x07, 0xF8, 0x00, 0x7F, 0x80, + 0x3F, 0xC0, 0x07, 0xF8, 0x01, 0xFF, 0x00, 0x7F, 0x80, 0x07, 0xF8, 0x07, + 0xFC, 0x00, 0x3F, 0xE0, 0x00, 0xFF, 0x00, 0x07, 0xF7, 0xF8, 0x00, 0x7F, + 0xBF, 0xC0, 0x07, 0xF8, 0xFE, 0x00, 0x3F, 0x87, 0xF8, 0x03, 0xFC, 0x3F, + 0xC0, 0x3F, 0xC0, 0xFE, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x3F, 0xC1, + 0xFE, 0x00, 0xFE, 0x0F, 0xE0, 0x07, 0xF0, 0xFE, 0x00, 0x3F, 0x8F, 0xE0, + 0x00, 0xFE, 0x7F, 0x00, 0x07, 0xF7, 0xF0, 0x00, 0x3F, 0xFF, 0x00, 0x01, + 0xFF, 0xF8, 0x00, 0x07, 0xFF, 0x80, 0x00, 0x3F, 0xF8, 0x00, 0x01, 0xFF, + 0x80, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0x3F, 0x80, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, + 0xFF, 0x80, 0xFF, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, + 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xF8, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xFF, + 0x01, 0xFF, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFF, + 0xC0, 0x3F, 0xFF, 0xFF, 0xE0, 0x00, 0x00, 0x7F, 0xF8, 0x03, 0xFF, 0x80, + 0x1F, 0xFC, 0x00, 0xFF, 0xE0, 0x0F, 0xFF, 0x00, 0x7E, 0x00, 0x03, 0xF0, + 0x00, 0x1F, 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0x7E, 0x00, 0x03, + 0xF0, 0x00, 0x1F, 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0x7E, 0x00, + 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0x7E, + 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x80, 0x01, 0xF8, 0x00, 0x0F, 0xC0, 0x00, + 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x80, 0x01, 0xF8, 0x00, 0x0F, 0xC0, + 0x00, 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x01, 0xF8, 0x00, 0x0F, + 0xC0, 0x00, 0x7E, 0x00, 0x07, 0xF0, 0x00, 0x3F, 0x00, 0x01, 0xFF, 0xC0, + 0x0F, 0xFE, 0x00, 0x7F, 0xF0, 0x07, 0xFF, 0x80, 0x3F, 0xFC, 0x00, 0x81, + 0xC3, 0xC7, 0x8F, 0x0E, 0x1C, 0x38, 0x70, 0xE1, 0xC3, 0xC7, 0x8F, 0x1E, + 0x1C, 0x38, 0x70, 0xE1, 0xC3, 0x87, 0x8F, 0x1E, 0x3C, 0x38, 0x70, 0xE1, + 0xC3, 0x87, 0x0F, 0x1E, 0x3C, 0x78, 0xF0, 0x00, 0x7F, 0xF8, 0x03, 0xFF, + 0xC0, 0x1F, 0xFC, 0x00, 0xFF, 0xE0, 0x07, 0xFF, 0x00, 0x01, 0xF8, 0x00, + 0x1F, 0xC0, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF8, + 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0x00, 0x03, + 0xF8, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0x00, + 0x03, 0xF8, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x7F, + 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, + 0x7F, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, + 0x00, 0x7F, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x01, 0xFF, + 0xE0, 0x0F, 0xFE, 0x00, 0x7F, 0xF0, 0x03, 0xFF, 0x80, 0x3F, 0xFC, 0x00, + 0x00, 0x1F, 0x80, 0x00, 0xFE, 0x00, 0x0F, 0xF0, 0x00, 0x7F, 0x80, 0x07, + 0xFC, 0x00, 0x7F, 0xE0, 0x03, 0xFF, 0x80, 0x3E, 0xFC, 0x01, 0xF3, 0xE0, + 0x1F, 0x1F, 0x01, 0xF8, 0xF8, 0x0F, 0x87, 0xE0, 0xFC, 0x3F, 0x07, 0xC0, + 0xF8, 0x7C, 0x07, 0xC7, 0xE0, 0x3E, 0x3E, 0x01, 0xFB, 0xF0, 0x0F, 0xDF, + 0x00, 0x3F, 0xF0, 0x01, 0xF0, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFD, 0xFF, 0xFF, 0xFF, 0xE0, 0xF8, 0xF0, 0xF1, 0xE1, + 0xC3, 0xC3, 0x80, 0x00, 0x1F, 0xF0, 0x00, 0x7F, 0xFF, 0x00, 0xFF, 0xFF, + 0xC0, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xF8, 0x7F, 0x03, 0xFC, 0x3F, 0x00, + 0xFE, 0x1F, 0x80, 0x7E, 0x00, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0x80, 0x1F, + 0xFF, 0xC0, 0x7F, 0xFF, 0xC0, 0xFF, 0xFF, 0xE0, 0xFF, 0xF7, 0xF0, 0xFF, + 0x83, 0xF8, 0xFF, 0x01, 0xF8, 0x7F, 0x00, 0xFC, 0x7F, 0x00, 0xFE, 0x3F, + 0x80, 0x7F, 0x1F, 0xC0, 0x7F, 0x8F, 0xF0, 0xFF, 0x87, 0xFF, 0xFF, 0xC3, + 0xFF, 0xFF, 0xE0, 0xFF, 0xF7, 0xF8, 0x3F, 0xF3, 0xFC, 0x07, 0xE0, 0x00, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xE0, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x3F, 0x80, 0x1F, + 0x9F, 0xFC, 0x03, 0xF7, 0xFF, 0xC0, 0xFF, 0xFF, 0xF8, 0x1F, 0xFF, 0xFF, + 0x83, 0xFF, 0x0F, 0xF0, 0x7F, 0x80, 0xFF, 0x0F, 0xE0, 0x1F, 0xE3, 0xF8, + 0x01, 0xFC, 0x7F, 0x00, 0x3F, 0x8F, 0xC0, 0x07, 0xF1, 0xF8, 0x00, 0xFE, + 0x7F, 0x00, 0x1F, 0xCF, 0xC0, 0x03, 0xF9, 0xF8, 0x00, 0xFE, 0x3F, 0x00, + 0x1F, 0xC7, 0xE0, 0x03, 0xF9, 0xFC, 0x00, 0xFE, 0x3F, 0xC0, 0x3F, 0xC7, + 0xF8, 0x0F, 0xF0, 0xFF, 0x83, 0xFC, 0x1F, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, + 0xC0, 0xFF, 0xFF, 0xF0, 0x1F, 0x9F, 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x00, + 0x00, 0x1F, 0xE0, 0x00, 0x3F, 0xFC, 0x00, 0x7F, 0xFF, 0x80, 0x7F, 0xFF, + 0xE0, 0x7F, 0xFF, 0xF0, 0x7F, 0x83, 0xFC, 0x7F, 0x00, 0xFE, 0x3F, 0x00, + 0x7F, 0x3F, 0x80, 0x3F, 0x9F, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x0F, 0xE0, + 0x00, 0x07, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x01, 0xFC, + 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x7F, 0x3F, 0x80, 0x3F, 0x9F, + 0xE0, 0x3F, 0x87, 0xF8, 0x3F, 0x83, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xC0, + 0x3F, 0xFF, 0xC0, 0x0F, 0xFF, 0x80, 0x01, 0xFE, 0x00, 0x00, 0x00, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x07, + 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x00, 0xFC, 0x00, 0x00, 0x0F, 0xE0, 0x01, 0xFC, 0x7F, 0x00, 0x3F, + 0xF3, 0xF8, 0x03, 0xFF, 0xDF, 0x80, 0x7F, 0xFF, 0xFC, 0x07, 0xFF, 0xFF, + 0xE0, 0x3F, 0xC3, 0xFF, 0x03, 0xFC, 0x0F, 0xF8, 0x3F, 0xC0, 0x3F, 0x81, + 0xFC, 0x01, 0xFC, 0x1F, 0xC0, 0x07, 0xE0, 0xFE, 0x00, 0x3F, 0x07, 0xF0, + 0x03, 0xF8, 0x7F, 0x00, 0x1F, 0x83, 0xF8, 0x00, 0xFC, 0x1F, 0xC0, 0x07, + 0xE0, 0xFE, 0x00, 0x3F, 0x07, 0xF0, 0x03, 0xF0, 0x3F, 0x80, 0x3F, 0x81, + 0xFC, 0x01, 0xFC, 0x0F, 0xF0, 0x1F, 0xE0, 0x3F, 0xC3, 0xFF, 0x01, 0xFF, + 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xFC, 0x00, 0xFF, 0xCF, + 0xE0, 0x01, 0xF8, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0xFC, 0x00, + 0x7F, 0xFF, 0x00, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xF0, 0x7F, 0x87, 0xF8, + 0x7F, 0x01, 0xFE, 0x7F, 0x00, 0x7F, 0x3F, 0x80, 0x3F, 0xBF, 0x80, 0x1F, + 0xDF, 0xC0, 0x0F, 0xEF, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFD, 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, + 0x00, 0x3F, 0x80, 0x3F, 0x9F, 0xE0, 0x3F, 0x87, 0xF8, 0x3F, 0xC3, 0xFF, + 0xFF, 0xC0, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0x80, 0x0F, 0xFF, 0x80, 0x00, + 0xFE, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x1F, 0xF0, 0x0F, 0xF8, 0x07, 0xFE, + 0x01, 0xFF, 0x80, 0xFE, 0x00, 0x3F, 0x80, 0x0F, 0xC0, 0x03, 0xF0, 0x01, + 0xFC, 0x03, 0xFF, 0xF1, 0xFF, 0xF8, 0x7F, 0xFE, 0x1F, 0xFF, 0x80, 0xFE, + 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x03, 0xF0, 0x00, 0xFC, 0x00, 0x7F, 0x00, + 0x1F, 0xC0, 0x07, 0xE0, 0x01, 0xF8, 0x00, 0xFE, 0x00, 0x3F, 0x80, 0x0F, + 0xE0, 0x03, 0xF0, 0x00, 0xFC, 0x00, 0x7F, 0x00, 0x1F, 0xC0, 0x07, 0xF0, + 0x01, 0xF8, 0x00, 0x7E, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x07, 0xC3, 0xF8, + 0x01, 0xFF, 0x9F, 0x80, 0x1F, 0xFE, 0xFC, 0x01, 0xFF, 0xFF, 0xE0, 0x1F, + 0xFF, 0xFF, 0x01, 0xFE, 0x1F, 0xF8, 0x1F, 0xE0, 0x3F, 0x80, 0xFE, 0x01, + 0xFC, 0x0F, 0xE0, 0x0F, 0xE0, 0x7F, 0x00, 0x3F, 0x07, 0xF0, 0x01, 0xF8, + 0x3F, 0x80, 0x0F, 0x81, 0xF8, 0x00, 0x7C, 0x1F, 0xC0, 0x07, 0xE0, 0xFE, + 0x00, 0x3F, 0x07, 0xF0, 0x01, 0xF0, 0x3F, 0x80, 0x1F, 0x81, 0xFC, 0x00, + 0xFC, 0x0F, 0xE0, 0x0F, 0xE0, 0x7F, 0x80, 0xFF, 0x03, 0xFE, 0x1F, 0xF0, + 0x0F, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xFC, 0x01, 0xFF, 0xF7, 0xE0, 0x07, + 0xFE, 0x7F, 0x00, 0x0F, 0xC3, 0xF0, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x01, + 0xFC, 0x0F, 0xE0, 0x0F, 0xC0, 0x7F, 0x00, 0xFE, 0x03, 0xFC, 0x1F, 0xE0, + 0x1F, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xE0, 0x01, 0xFF, 0xFC, 0x00, 0x01, + 0xFF, 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xE0, + 0x00, 0x00, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xFE, 0x0F, + 0xC0, 0x1F, 0xCF, 0xFE, 0x03, 0xFB, 0xFF, 0xE0, 0x7F, 0xFF, 0xFE, 0x0F, + 0xFF, 0xFF, 0xC3, 0xFF, 0x07, 0xF8, 0x7F, 0x80, 0x7F, 0x0F, 0xE0, 0x0F, + 0xE1, 0xFC, 0x01, 0xFC, 0x7F, 0x00, 0x3F, 0x0F, 0xE0, 0x07, 0xE1, 0xFC, + 0x01, 0xFC, 0x3F, 0x00, 0x3F, 0x87, 0xE0, 0x07, 0xF1, 0xFC, 0x00, 0xFC, + 0x3F, 0x80, 0x1F, 0x87, 0xF0, 0x07, 0xF0, 0xFC, 0x00, 0xFE, 0x1F, 0x80, + 0x1F, 0xC7, 0xF0, 0x03, 0xF0, 0xFE, 0x00, 0x7E, 0x1F, 0xC0, 0x1F, 0xC3, + 0xF0, 0x03, 0xF8, 0xFE, 0x00, 0x7F, 0x1F, 0xC0, 0x0F, 0xC0, 0x01, 0xFC, + 0x07, 0xF0, 0x1F, 0x80, 0x7E, 0x03, 0xF8, 0x0F, 0xE0, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xE0, 0x3F, 0x80, 0xFE, + 0x03, 0xF8, 0x0F, 0xC0, 0x3F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7E, + 0x03, 0xF8, 0x0F, 0xE0, 0x3F, 0x80, 0xFC, 0x03, 0xF0, 0x1F, 0xC0, 0x7F, + 0x01, 0xFC, 0x07, 0xE0, 0x1F, 0x80, 0xFE, 0x03, 0xF8, 0x00, 0x00, 0x0F, + 0xE0, 0x01, 0xFC, 0x00, 0x3F, 0x80, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x3F, + 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xF0, 0x00, 0xFE, + 0x00, 0x1F, 0xC0, 0x03, 0xF8, 0x00, 0x7E, 0x00, 0x1F, 0xC0, 0x03, 0xF8, + 0x00, 0x7F, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x7F, 0x00, 0x0F, 0xE0, + 0x01, 0xFC, 0x00, 0x3F, 0x00, 0x07, 0xE0, 0x01, 0xFC, 0x00, 0x3F, 0x80, + 0x07, 0xF0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x07, 0xF0, 0x00, 0xFE, 0x00, + 0x1F, 0x80, 0x03, 0xF0, 0x00, 0xFE, 0x00, 0x1F, 0xC0, 0x03, 0xF8, 0x00, + 0x7E, 0x00, 0x0F, 0xC0, 0x03, 0xF8, 0x03, 0xFF, 0x00, 0x7F, 0xC0, 0x0F, + 0xF8, 0x03, 0xFE, 0x00, 0x7E, 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x1F, + 0x80, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xF8, 0x00, + 0x00, 0x3F, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0x7F, 0x00, 0xFE, 0x07, 0xE0, 0x3F, 0xC0, 0x7E, 0x07, + 0xF8, 0x0F, 0xE0, 0xFF, 0x00, 0xFE, 0x1F, 0xC0, 0x0F, 0xE3, 0xF8, 0x00, + 0xFC, 0x7F, 0x00, 0x0F, 0xCF, 0xE0, 0x01, 0xFD, 0xFC, 0x00, 0x1F, 0xFF, + 0x80, 0x01, 0xFF, 0xF8, 0x00, 0x1F, 0xFF, 0x80, 0x03, 0xFF, 0xFC, 0x00, + 0x3F, 0xFF, 0xC0, 0x03, 0xFE, 0xFE, 0x00, 0x3F, 0xCF, 0xE0, 0x03, 0xF0, + 0xFE, 0x00, 0x7F, 0x07, 0xF0, 0x07, 0xF0, 0x7F, 0x00, 0x7F, 0x07, 0xF8, + 0x07, 0xE0, 0x3F, 0x80, 0x7E, 0x03, 0xF8, 0x0F, 0xE0, 0x3F, 0xC0, 0xFE, + 0x01, 0xFC, 0x0F, 0xC0, 0x1F, 0xE0, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0x80, + 0x7E, 0x03, 0xF8, 0x0F, 0xE0, 0x3F, 0x80, 0xFC, 0x03, 0xF0, 0x1F, 0xC0, + 0x7F, 0x01, 0xFC, 0x07, 0xE0, 0x3F, 0x80, 0xFE, 0x03, 0xF8, 0x0F, 0xC0, + 0x3F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7E, 0x03, 0xF8, 0x0F, 0xE0, + 0x3F, 0x80, 0xFC, 0x03, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xE0, + 0x1F, 0x80, 0xFE, 0x03, 0xF8, 0x00, 0x07, 0xF0, 0xFC, 0x03, 0xF0, 0x07, + 0xE3, 0xFF, 0x0F, 0xFC, 0x07, 0xEF, 0xFF, 0x3F, 0xFE, 0x0F, 0xFF, 0xFF, + 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0x0F, 0xF8, 0x7F, 0xF0, 0xFF, + 0x0F, 0xE0, 0x3F, 0xC0, 0x7F, 0x0F, 0xE0, 0x3F, 0x80, 0x7F, 0x1F, 0xC0, + 0x3F, 0x80, 0x7E, 0x1F, 0xC0, 0x3F, 0x00, 0x7E, 0x1F, 0xC0, 0x3F, 0x00, + 0xFE, 0x1F, 0x80, 0x7F, 0x00, 0xFE, 0x3F, 0x80, 0x7F, 0x00, 0xFC, 0x3F, + 0x80, 0x7F, 0x00, 0xFC, 0x3F, 0x80, 0x7E, 0x01, 0xFC, 0x3F, 0x00, 0x7E, + 0x01, 0xFC, 0x3F, 0x00, 0xFE, 0x01, 0xFC, 0x7F, 0x00, 0xFE, 0x01, 0xF8, + 0x7F, 0x00, 0xFE, 0x01, 0xF8, 0x7F, 0x00, 0xFC, 0x03, 0xF8, 0x7E, 0x01, + 0xFC, 0x03, 0xF8, 0x7E, 0x01, 0xFC, 0x03, 0xF8, 0xFE, 0x01, 0xFC, 0x03, + 0xF0, 0xFE, 0x01, 0xF8, 0x03, 0xF0, 0xFE, 0x01, 0xF8, 0x07, 0xF0, 0x07, + 0xF0, 0xFE, 0x00, 0xFE, 0x7F, 0xF0, 0x1F, 0x9F, 0xFF, 0x03, 0xFF, 0xFF, + 0xF0, 0xFF, 0xFF, 0xFE, 0x1F, 0xF8, 0x3F, 0xC3, 0xFC, 0x03, 0xF8, 0x7F, + 0x00, 0x7F, 0x0F, 0xE0, 0x0F, 0xE3, 0xF8, 0x01, 0xF8, 0x7F, 0x00, 0x3F, + 0x0F, 0xC0, 0x0F, 0xE1, 0xF8, 0x01, 0xFC, 0x7F, 0x00, 0x3F, 0x8F, 0xE0, + 0x07, 0xE1, 0xFC, 0x00, 0xFC, 0x3F, 0x00, 0x3F, 0x87, 0xE0, 0x07, 0xF1, + 0xFC, 0x00, 0xFE, 0x3F, 0x80, 0x1F, 0x87, 0xF0, 0x03, 0xF0, 0xFC, 0x00, + 0xFE, 0x3F, 0x80, 0x1F, 0xC7, 0xF0, 0x03, 0xF8, 0xFE, 0x00, 0x7E, 0x00, + 0x00, 0x1F, 0xE0, 0x00, 0x1F, 0xFF, 0x00, 0x1F, 0xFF, 0xE0, 0x0F, 0xFF, + 0xFC, 0x07, 0xFF, 0xFF, 0x83, 0xFC, 0x1F, 0xE1, 0xFE, 0x03, 0xFC, 0xFF, + 0x00, 0xFF, 0x3F, 0x80, 0x1F, 0xDF, 0xC0, 0x07, 0xF7, 0xF0, 0x01, 0xFD, + 0xFC, 0x00, 0x7F, 0xFE, 0x00, 0x1F, 0xFF, 0x80, 0x07, 0xFF, 0xE0, 0x03, + 0xFB, 0xF8, 0x00, 0xFE, 0xFE, 0x00, 0x3F, 0xBF, 0x80, 0x1F, 0xCF, 0xF0, + 0x0F, 0xF3, 0xFC, 0x07, 0xF8, 0x7F, 0x83, 0xFC, 0x1F, 0xFF, 0xFE, 0x03, + 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0x80, 0x0F, 0xFF, 0x80, 0x00, 0x7F, 0x00, + 0x00, 0x01, 0xFC, 0x3F, 0x00, 0x0F, 0xCF, 0xFE, 0x00, 0x7E, 0xFF, 0xF8, + 0x07, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xFF, 0x01, 0xFF, 0x87, 0xF8, 0x0F, + 0xF0, 0x1F, 0xE0, 0xFF, 0x00, 0xFF, 0x07, 0xF0, 0x03, 0xF8, 0x3F, 0x80, + 0x1F, 0xC1, 0xF8, 0x00, 0xFE, 0x0F, 0xC0, 0x07, 0xF0, 0xFE, 0x00, 0x3F, + 0x87, 0xF0, 0x01, 0xFC, 0x3F, 0x00, 0x1F, 0xC1, 0xF8, 0x00, 0xFE, 0x1F, + 0xC0, 0x07, 0xF0, 0xFE, 0x00, 0x7F, 0x07, 0xF8, 0x07, 0xF8, 0x3F, 0xC0, + 0x7F, 0x81, 0xFF, 0x87, 0xF8, 0x1F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFC, + 0x07, 0xF7, 0xFF, 0xC0, 0x3F, 0x1F, 0xF8, 0x01, 0xF8, 0x7F, 0x00, 0x1F, + 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x3F, 0x00, + 0x00, 0x03, 0xF8, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0x07, 0xE0, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00, 0x00, 0x1F, 0x87, 0xF0, + 0x0F, 0xFE, 0x7F, 0x01, 0xFF, 0xF7, 0xE0, 0x3F, 0xFF, 0x7E, 0x07, 0xFF, + 0xFF, 0xE0, 0xFF, 0x07, 0xFE, 0x1F, 0xE0, 0x3F, 0xE3, 0xFC, 0x03, 0xFC, + 0x3F, 0x80, 0x1F, 0xC7, 0xF0, 0x01, 0xFC, 0x7F, 0x00, 0x1F, 0xC7, 0xF0, + 0x01, 0xF8, 0xFE, 0x00, 0x1F, 0x8F, 0xE0, 0x03, 0xF8, 0xFE, 0x00, 0x3F, + 0x8F, 0xE0, 0x03, 0xF8, 0xFE, 0x00, 0x7F, 0x0F, 0xE0, 0x07, 0xF0, 0xFE, + 0x00, 0xFF, 0x0F, 0xF0, 0x1F, 0xF0, 0x7F, 0x87, 0xFF, 0x07, 0xFF, 0xFF, + 0xE0, 0x3F, 0xFF, 0x7E, 0x03, 0xFF, 0xEF, 0xE0, 0x1F, 0xFC, 0xFE, 0x00, + 0x7F, 0x0F, 0xC0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x1F, 0x80, + 0x00, 0x03, 0xF8, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xF8, 0x00, 0x07, + 0xF0, 0xF0, 0x7F, 0x3F, 0x07, 0xE7, 0xE0, 0x7E, 0xFE, 0x0F, 0xFF, 0xE0, + 0xFF, 0xFE, 0x0F, 0xFC, 0x00, 0xFF, 0x00, 0x0F, 0xE0, 0x01, 0xFC, 0x00, + 0x1F, 0xC0, 0x01, 0xF8, 0x00, 0x1F, 0x80, 0x03, 0xF8, 0x00, 0x3F, 0x80, + 0x03, 0xF8, 0x00, 0x3F, 0x00, 0x03, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xF0, + 0x00, 0x7F, 0x00, 0x07, 0xE0, 0x00, 0xFE, 0x00, 0x0F, 0xE0, 0x00, 0xFE, + 0x00, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0xFF, 0xF8, 0x03, 0xFF, 0xFC, 0x07, + 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0x0F, 0xE0, 0xFF, 0x1F, 0xC0, 0x7F, 0x1F, + 0xC0, 0x7F, 0x1F, 0xE0, 0x00, 0x1F, 0xFC, 0x00, 0x1F, 0xFF, 0xC0, 0x0F, + 0xFF, 0xF0, 0x07, 0xFF, 0xF8, 0x03, 0xFF, 0xFC, 0x00, 0x7F, 0xFE, 0x00, + 0x0F, 0xFE, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFE, 0xFC, 0x00, 0xFE, 0xFE, + 0x00, 0xFE, 0xFF, 0x03, 0xFC, 0x7F, 0xFF, 0xF8, 0x7F, 0xFF, 0xF8, 0x3F, + 0xFF, 0xE0, 0x1F, 0xFF, 0xC0, 0x03, 0xFE, 0x00, 0x03, 0xF0, 0x1F, 0xC0, + 0x7F, 0x01, 0xFC, 0x07, 0xE0, 0x3F, 0x80, 0xFE, 0x1F, 0xFF, 0x7F, 0xFD, + 0xFF, 0xFF, 0xFF, 0xC7, 0xF0, 0x1F, 0xC0, 0x7E, 0x01, 0xF8, 0x0F, 0xE0, + 0x3F, 0x80, 0xFE, 0x03, 0xF0, 0x0F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xE0, + 0x1F, 0x80, 0xFE, 0x03, 0xF8, 0x0F, 0xE0, 0x3F, 0xF0, 0xFF, 0xC3, 0xFF, + 0x07, 0xFC, 0x0F, 0xE0, 0x0F, 0xC0, 0x0F, 0xE1, 0xF8, 0x01, 0xFC, 0x7F, + 0x00, 0x3F, 0x0F, 0xE0, 0x0F, 0xE1, 0xFC, 0x01, 0xFC, 0x3F, 0x00, 0x3F, + 0x87, 0xE0, 0x07, 0xE1, 0xFC, 0x00, 0xFC, 0x3F, 0x80, 0x3F, 0x87, 0xF0, + 0x07, 0xF0, 0xFC, 0x00, 0xFE, 0x1F, 0x80, 0x1F, 0x87, 0xF0, 0x03, 0xF0, + 0xFE, 0x00, 0xFE, 0x1F, 0x80, 0x1F, 0xC3, 0xF0, 0x03, 0xF0, 0xFE, 0x00, + 0x7E, 0x1F, 0xC0, 0x1F, 0xC3, 0xF8, 0x07, 0xF8, 0x7F, 0x01, 0xFF, 0x0F, + 0xF0, 0x7F, 0xC1, 0xFF, 0xFF, 0xF8, 0x3F, 0xFF, 0xFF, 0x03, 0xFF, 0xEF, + 0xE0, 0x3F, 0xF9, 0xFC, 0x01, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x7F, 0x7F, + 0x00, 0x3F, 0xBF, 0x80, 0x3F, 0x8F, 0xC0, 0x1F, 0xC7, 0xE0, 0x1F, 0xC3, + 0xF0, 0x0F, 0xC1, 0xFC, 0x0F, 0xE0, 0xFE, 0x07, 0xE0, 0x7F, 0x07, 0xF0, + 0x3F, 0x83, 0xF0, 0x0F, 0xC3, 0xF8, 0x07, 0xE1, 0xF8, 0x03, 0xF1, 0xFC, + 0x01, 0xF8, 0xFC, 0x00, 0xFC, 0xFC, 0x00, 0x7E, 0x7E, 0x00, 0x3F, 0x7E, + 0x00, 0x0F, 0xBF, 0x00, 0x07, 0xFF, 0x00, 0x03, 0xFF, 0x80, 0x01, 0xFF, + 0x80, 0x00, 0xFF, 0x80, 0x00, 0x7F, 0xC0, 0x00, 0x3F, 0xC0, 0x00, 0x1F, + 0xE0, 0x00, 0x00, 0xFE, 0x03, 0xF8, 0x0F, 0xFF, 0xC0, 0x7F, 0x01, 0xFF, + 0xF8, 0x1F, 0xE0, 0x3F, 0x7F, 0x03, 0xFC, 0x0F, 0xEF, 0xE0, 0xFF, 0x81, + 0xF9, 0xFC, 0x1F, 0xF0, 0x7F, 0x3F, 0x83, 0xFE, 0x0F, 0xC3, 0xF0, 0xFF, + 0xC3, 0xF8, 0x7E, 0x1E, 0xF8, 0x7E, 0x0F, 0xC7, 0xDF, 0x1F, 0xC1, 0xF8, + 0xFB, 0xE3, 0xF0, 0x3F, 0x1E, 0x7C, 0x7E, 0x07, 0xE7, 0xCF, 0x9F, 0x80, + 0xFC, 0xF1, 0xF3, 0xF0, 0x1F, 0xBE, 0x3E, 0xFC, 0x03, 0xF7, 0x87, 0xDF, + 0x80, 0x7E, 0xF0, 0xFF, 0xE0, 0x0F, 0xFE, 0x1F, 0xFC, 0x01, 0xFF, 0x83, + 0xFF, 0x00, 0x3F, 0xF0, 0x7F, 0xE0, 0x07, 0xFC, 0x0F, 0xF8, 0x00, 0x7F, + 0x81, 0xFF, 0x00, 0x0F, 0xF0, 0x3F, 0xC0, 0x01, 0xFC, 0x07, 0xF8, 0x00, + 0x3F, 0x80, 0xFE, 0x00, 0x00, 0x03, 0xFC, 0x07, 0xF8, 0x1F, 0xE0, 0x7F, + 0x80, 0x7F, 0x03, 0xF8, 0x03, 0xF8, 0x3F, 0x80, 0x1F, 0xE3, 0xF8, 0x00, + 0x7F, 0x3F, 0x80, 0x03, 0xF9, 0xFC, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x7F, + 0xFC, 0x00, 0x01, 0xFF, 0xC0, 0x00, 0x0F, 0xFC, 0x00, 0x00, 0x7F, 0xC0, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x01, 0xFF, 0x80, 0x00, + 0x1F, 0xFE, 0x00, 0x01, 0xFF, 0xF0, 0x00, 0x1F, 0xDF, 0xC0, 0x01, 0xFC, + 0xFE, 0x00, 0x1F, 0xE7, 0xF8, 0x00, 0xFE, 0x1F, 0xC0, 0x0F, 0xE0, 0xFE, + 0x00, 0xFF, 0x07, 0xF8, 0x0F, 0xF0, 0x1F, 0xC0, 0xFF, 0x00, 0xFF, 0x00, + 0x0F, 0xE0, 0x03, 0xF0, 0x7F, 0x00, 0x3F, 0x83, 0xF8, 0x01, 0xF8, 0x1F, + 0xC0, 0x1F, 0xC0, 0xFE, 0x00, 0xFC, 0x03, 0xF8, 0x0F, 0xE0, 0x1F, 0xC0, + 0x7E, 0x00, 0xFE, 0x07, 0xE0, 0x07, 0xF0, 0x3F, 0x00, 0x3F, 0x83, 0xF0, + 0x01, 0xFC, 0x1F, 0x80, 0x0F, 0xE1, 0xF8, 0x00, 0x3F, 0x0F, 0xC0, 0x01, + 0xF8, 0xFC, 0x00, 0x0F, 0xC7, 0xC0, 0x00, 0x7F, 0x7E, 0x00, 0x03, 0xFB, + 0xE0, 0x00, 0x1F, 0xFF, 0x00, 0x00, 0xFF, 0xF0, 0x00, 0x03, 0xFF, 0x80, + 0x00, 0x1F, 0xF8, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x07, 0xFC, 0x00, 0x00, + 0x3F, 0xC0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x03, 0xF8, 0x00, + 0x01, 0xFF, 0x80, 0x00, 0x1F, 0xFC, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x07, + 0xF8, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xC0, 0xFF, + 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, 0x1F, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0x80, + 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x07, 0xF8, + 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, + 0x80, 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x07, + 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, + 0x7F, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, + 0xE0, 0xFF, 0xFF, 0xF8, 0x00, 0x00, 0x0F, 0xC0, 0x0F, 0xF0, 0x07, 0xFC, + 0x01, 0xFE, 0x00, 0xFF, 0x80, 0x3E, 0x00, 0x0F, 0x80, 0x07, 0xE0, 0x01, + 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x03, 0xE0, 0x00, 0xF8, + 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x07, 0xE0, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x3F, 0x00, 0x7F, 0x80, 0x1F, 0x80, 0x07, 0xE0, 0x03, 0xFC, 0x00, 0x3F, + 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xC0, + 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x01, + 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xF8, 0x01, 0xFE, 0x00, 0x7F, + 0x80, 0x0F, 0xE0, 0x01, 0xF8, 0x00, 0x00, 0x78, 0x03, 0xC0, 0x1C, 0x01, + 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1C, 0x01, 0xE0, 0x0F, 0x00, 0x78, + 0x03, 0xC0, 0x1C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x3C, 0x01, + 0xE0, 0x0F, 0x00, 0x78, 0x03, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, + 0x03, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0x80, 0x3C, 0x01, + 0xE0, 0x0F, 0x00, 0x70, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x70, + 0x07, 0x80, 0x3C, 0x00, 0x00, 0x7E, 0x00, 0x1F, 0xC0, 0x07, 0xF0, 0x01, + 0xFE, 0x00, 0x7F, 0x80, 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x1F, + 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x0F, 0x80, + 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xF0, 0x00, + 0xFF, 0x00, 0x1F, 0x80, 0x07, 0xE0, 0x07, 0xF8, 0x03, 0xF0, 0x00, 0xF8, + 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x1F, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x1F, + 0x80, 0x07, 0xC0, 0x01, 0xF0, 0x07, 0xFC, 0x01, 0xFE, 0x00, 0xFF, 0x80, + 0x3F, 0xC0, 0x0F, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0xFF, 0x80, 0x07, 0xFF, + 0x03, 0xDF, 0xFE, 0x0F, 0xF0, 0x7F, 0xFB, 0x80, 0xFF, 0xE0, 0x01, 0xFF, + 0x00, 0x03, 0xF0 }; + +const GFXglyph FreeSansBoldOblique24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 13, 0, 1 }, // 0x20 ' ' + { 0, 14, 34, 16, 5, -33 }, // 0x21 '!' + { 60, 18, 12, 22, 8, -33 }, // 0x22 '"' + { 87, 29, 33, 26, 2, -31 }, // 0x23 '#' + { 207, 26, 42, 26, 3, -35 }, // 0x24 '$' + { 344, 36, 34, 42, 6, -32 }, // 0x25 '%' + { 497, 29, 35, 34, 4, -33 }, // 0x26 '&' + { 624, 7, 12, 11, 8, -33 }, // 0x27 ''' + { 635, 17, 44, 16, 4, -33 }, // 0x28 '(' + { 729, 17, 44, 16, 0, -34 }, // 0x29 ')' + { 823, 15, 15, 18, 7, -33 }, // 0x2A '*' + { 852, 24, 22, 27, 4, -21 }, // 0x2B '+' + { 918, 10, 15, 13, 1, -6 }, // 0x2C ',' + { 937, 14, 6, 16, 3, -15 }, // 0x2D '-' + { 948, 8, 7, 13, 3, -6 }, // 0x2E '.' + { 955, 20, 34, 13, 0, -32 }, // 0x2F '/' + { 1040, 25, 35, 26, 4, -33 }, // 0x30 '0' + { 1150, 17, 33, 26, 8, -32 }, // 0x31 '1' + { 1221, 29, 34, 26, 1, -33 }, // 0x32 '2' + { 1345, 26, 35, 26, 3, -33 }, // 0x33 '3' + { 1459, 25, 32, 26, 3, -31 }, // 0x34 '4' + { 1559, 27, 34, 26, 3, -32 }, // 0x35 '5' + { 1674, 25, 35, 26, 4, -33 }, // 0x36 '6' + { 1784, 26, 33, 26, 6, -32 }, // 0x37 '7' + { 1892, 26, 35, 26, 3, -33 }, // 0x38 '8' + { 2006, 25, 35, 26, 4, -33 }, // 0x39 '9' + { 2116, 12, 25, 16, 5, -24 }, // 0x3A ':' + { 2154, 14, 33, 16, 3, -24 }, // 0x3B ';' + { 2212, 26, 23, 27, 4, -22 }, // 0x3C '<' + { 2287, 26, 18, 27, 3, -19 }, // 0x3D '=' + { 2346, 26, 23, 27, 1, -21 }, // 0x3E '>' + { 2421, 24, 35, 29, 8, -34 }, // 0x3F '?' + { 2526, 45, 41, 46, 3, -34 }, // 0x40 '@' + { 2757, 32, 34, 34, 1, -33 }, // 0x41 'A' + { 2893, 32, 34, 34, 4, -33 }, // 0x42 'B' + { 3029, 32, 36, 34, 5, -34 }, // 0x43 'C' + { 3173, 32, 34, 34, 4, -33 }, // 0x44 'D' + { 3309, 32, 34, 31, 4, -33 }, // 0x45 'E' + { 3445, 32, 34, 29, 3, -33 }, // 0x46 'F' + { 3581, 33, 36, 37, 5, -34 }, // 0x47 'G' + { 3730, 35, 34, 34, 3, -33 }, // 0x48 'H' + { 3879, 14, 34, 13, 3, -33 }, // 0x49 'I' + { 3939, 27, 35, 26, 3, -33 }, // 0x4A 'J' + { 4058, 37, 34, 34, 3, -33 }, // 0x4B 'K' + { 4216, 24, 34, 29, 4, -33 }, // 0x4C 'L' + { 4318, 41, 34, 39, 3, -33 }, // 0x4D 'M' + { 4493, 35, 34, 34, 3, -33 }, // 0x4E 'N' + { 4642, 34, 36, 37, 5, -34 }, // 0x4F 'O' + { 4795, 31, 34, 31, 4, -33 }, // 0x50 'P' + { 4927, 34, 37, 37, 5, -34 }, // 0x51 'Q' + { 5085, 33, 34, 34, 4, -33 }, // 0x52 'R' + { 5226, 30, 36, 31, 4, -34 }, // 0x53 'S' + { 5361, 28, 34, 29, 7, -33 }, // 0x54 'T' + { 5480, 32, 35, 34, 6, -33 }, // 0x55 'U' + { 5620, 30, 34, 31, 8, -33 }, // 0x56 'V' + { 5748, 43, 34, 44, 8, -33 }, // 0x57 'W' + { 5931, 37, 34, 31, 1, -33 }, // 0x58 'X' + { 6089, 29, 34, 31, 9, -33 }, // 0x59 'Y' + { 6213, 33, 34, 29, 1, -33 }, // 0x5A 'Z' + { 6354, 21, 43, 16, 1, -33 }, // 0x5B '[' + { 6467, 7, 36, 13, 6, -34 }, // 0x5C '\' + { 6499, 21, 43, 16, -1, -33 }, // 0x5D ']' + { 6612, 21, 20, 27, 6, -32 }, // 0x5E '^' + { 6665, 29, 4, 26, -3, 6 }, // 0x5F '_' + { 6680, 7, 7, 16, 8, -35 }, // 0x60 '`' + { 6687, 25, 26, 26, 2, -24 }, // 0x61 'a' + { 6769, 27, 35, 29, 3, -33 }, // 0x62 'b' + { 6888, 25, 26, 26, 4, -24 }, // 0x63 'c' + { 6970, 29, 35, 29, 4, -33 }, // 0x64 'd' + { 7097, 25, 26, 26, 3, -24 }, // 0x65 'e' + { 7179, 18, 34, 16, 4, -33 }, // 0x66 'f' + { 7256, 29, 35, 29, 2, -24 }, // 0x67 'g' + { 7383, 27, 34, 29, 3, -33 }, // 0x68 'h' + { 7498, 14, 34, 13, 3, -33 }, // 0x69 'i' + { 7558, 19, 44, 13, -2, -33 }, // 0x6A 'j' + { 7663, 28, 34, 26, 3, -33 }, // 0x6B 'k' + { 7782, 14, 34, 13, 3, -33 }, // 0x6C 'l' + { 7842, 40, 25, 42, 3, -24 }, // 0x6D 'm' + { 7967, 27, 25, 29, 3, -24 }, // 0x6E 'n' + { 8052, 26, 26, 29, 4, -24 }, // 0x6F 'o' + { 8137, 29, 35, 29, 1, -24 }, // 0x70 'p' + { 8264, 28, 35, 29, 3, -24 }, // 0x71 'q' + { 8387, 20, 25, 18, 3, -24 }, // 0x72 'r' + { 8450, 24, 26, 26, 3, -24 }, // 0x73 's' + { 8528, 14, 32, 16, 5, -30 }, // 0x74 't' + { 8584, 27, 26, 29, 4, -24 }, // 0x75 'u' + { 8672, 25, 25, 26, 6, -24 }, // 0x76 'v' + { 8751, 35, 25, 37, 6, -24 }, // 0x77 'w' + { 8861, 29, 25, 26, 1, -24 }, // 0x78 'x' + { 8952, 29, 35, 26, 2, -24 }, // 0x79 'y' + { 9079, 26, 25, 23, 1, -24 }, // 0x7A 'z' + { 9161, 18, 43, 18, 4, -33 }, // 0x7B '{' + { 9258, 13, 43, 13, 3, -33 }, // 0x7C '|' + { 9328, 18, 43, 18, 2, -33 }, // 0x7D '}' + { 9425, 22, 8, 27, 5, -14 } }; // 0x7E '~' + +const GFXfont FreeSansBoldOblique24pt7b PROGMEM = { + (uint8_t *)FreeSansBoldOblique24pt7bBitmaps, + (GFXglyph *)FreeSansBoldOblique24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 10119 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique9pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique9pt7b.h new file mode 100644 index 0000000..6250aca --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique9pt7b.h @@ -0,0 +1,227 @@ +const uint8_t FreeSansBoldOblique9pt7bBitmaps[] PROGMEM = { + 0x21, 0x8E, 0x73, 0x18, 0xC6, 0x21, 0x19, 0xCE, 0x00, 0xEF, 0xDF, 0xBE, + 0x68, 0x80, 0x06, 0xC1, 0x99, 0xFF, 0xBF, 0xF1, 0xB0, 0x66, 0x0C, 0xC7, + 0xFC, 0xFF, 0x8C, 0x83, 0x30, 0x64, 0x00, 0x02, 0x00, 0xF0, 0x7F, 0x1D, + 0x73, 0xEE, 0x78, 0x0F, 0x00, 0xF8, 0x0F, 0xC1, 0xBB, 0xA7, 0x74, 0xEF, + 0xF8, 0xFE, 0x04, 0x00, 0x80, 0x3C, 0x11, 0xF8, 0x8E, 0x66, 0x31, 0x90, + 0xCE, 0x83, 0xF4, 0x07, 0xB0, 0x00, 0x9E, 0x04, 0xFC, 0x26, 0x31, 0x98, + 0xC4, 0x7E, 0x20, 0xF0, 0x07, 0x80, 0xFC, 0x1D, 0xC1, 0xDC, 0x1F, 0x80, + 0xE0, 0x3E, 0x37, 0x77, 0xE3, 0xEE, 0x3C, 0xE3, 0xCF, 0xFE, 0x3C, 0xE0, + 0xFF, 0xE8, 0x06, 0x06, 0x0C, 0x18, 0x38, 0x30, 0x70, 0x60, 0xE0, 0xE0, + 0xE0, 0xE0, 0xE0, 0xE0, 0x60, 0x70, 0x30, 0x0C, 0x0E, 0x06, 0x07, 0x07, + 0x07, 0x07, 0x07, 0x07, 0x06, 0x0E, 0x0C, 0x1C, 0x18, 0x30, 0x60, 0x60, + 0x32, 0xBF, 0x9C, 0xD2, 0x40, 0x0C, 0x06, 0x07, 0x1F, 0xFF, 0xF0, 0xC0, + 0xE0, 0x60, 0x77, 0x72, 0x6C, 0xFF, 0xC0, 0xFC, 0x02, 0x02, 0x04, 0x04, + 0x08, 0x08, 0x10, 0x10, 0x20, 0x20, 0x40, 0x40, 0x80, 0x0F, 0x07, 0xE3, + 0x9D, 0xC7, 0x71, 0xDC, 0x7E, 0x1F, 0x8E, 0xE3, 0xB8, 0xEE, 0x73, 0xF8, + 0x3C, 0x00, 0x04, 0x3B, 0xF7, 0xE1, 0xC3, 0x06, 0x1C, 0x38, 0x70, 0xC1, + 0x87, 0x00, 0x0F, 0x87, 0xFC, 0xE3, 0xB8, 0x70, 0x0E, 0x03, 0x80, 0xF0, + 0x38, 0x1E, 0x07, 0x01, 0xC0, 0x7F, 0xCF, 0xF8, 0x0F, 0xC7, 0xFC, 0xE3, + 0xB8, 0x70, 0x1C, 0x0F, 0x03, 0xF0, 0x0E, 0x01, 0xDC, 0x3B, 0x8E, 0x7F, + 0x83, 0xE0, 0x03, 0xC0, 0xE0, 0x58, 0x2E, 0x13, 0x8C, 0xE6, 0x33, 0xFE, + 0xFF, 0x81, 0xC0, 0x60, 0x18, 0x0F, 0xE3, 0xFC, 0x60, 0x0C, 0x03, 0x78, + 0x7F, 0x9C, 0x70, 0x0E, 0x01, 0xDC, 0x33, 0x8E, 0x7F, 0x83, 0xE0, 0x0F, + 0x07, 0xE3, 0x9D, 0xC0, 0x7F, 0x1F, 0xEF, 0x3B, 0x8E, 0xE3, 0xB8, 0xCE, + 0x71, 0xF8, 0x3C, 0x00, 0x7F, 0xDF, 0xF0, 0x18, 0x0C, 0x06, 0x03, 0x81, + 0xC0, 0x60, 0x38, 0x0C, 0x07, 0x01, 0x80, 0x60, 0x00, 0x0F, 0x83, 0xFC, + 0xE3, 0x9C, 0x73, 0x9C, 0x3F, 0x0F, 0xE3, 0x8E, 0xE1, 0xDC, 0x3B, 0x8E, + 0x7F, 0xC3, 0xE0, 0x0F, 0x83, 0xF8, 0xE3, 0xB8, 0x77, 0x0E, 0xE1, 0xDC, + 0x7B, 0xFE, 0x3D, 0xC0, 0x33, 0x8E, 0x7F, 0x87, 0xC0, 0x77, 0x00, 0x00, + 0x0E, 0xE0, 0x39, 0xC0, 0x00, 0x01, 0xCE, 0x71, 0x19, 0x80, 0x00, 0x00, + 0x70, 0xFD, 0xF8, 0x70, 0x3F, 0x03, 0xF8, 0x1E, 0x01, 0x80, 0x7F, 0xDF, + 0xF0, 0x00, 0x00, 0xFF, 0xBF, 0xE0, 0x60, 0x1E, 0x07, 0xF0, 0x3F, 0x03, + 0x87, 0xEF, 0xC3, 0x80, 0x00, 0x00, 0x1F, 0x1F, 0xFE, 0x1F, 0x87, 0x01, + 0xC0, 0xE0, 0x70, 0x78, 0x3C, 0x0E, 0x00, 0x00, 0xE0, 0x38, 0x00, 0x00, + 0xFC, 0x00, 0xFF, 0xC0, 0xF0, 0x78, 0x70, 0x07, 0x38, 0x01, 0xCC, 0x3F, + 0x36, 0x31, 0x8D, 0x98, 0x63, 0xC4, 0x11, 0xF3, 0x0C, 0x6C, 0xC6, 0x73, + 0x3E, 0xF8, 0xE7, 0x3C, 0x1E, 0x00, 0x03, 0xFE, 0x00, 0x3F, 0x00, 0x01, + 0xE0, 0x0F, 0x00, 0xF8, 0x07, 0xC0, 0x6F, 0x03, 0x38, 0x31, 0xC3, 0x8E, + 0x1F, 0xF1, 0xFF, 0x8C, 0x1E, 0xE0, 0x76, 0x03, 0x80, 0x1F, 0xF0, 0xFF, + 0xC6, 0x0E, 0x70, 0x73, 0x87, 0x1F, 0xF0, 0xFF, 0x86, 0x0E, 0x70, 0x73, + 0x83, 0x9C, 0x38, 0xFF, 0xC7, 0xF8, 0x00, 0x07, 0xE0, 0xFF, 0x8F, 0x1E, + 0x70, 0x77, 0x00, 0x30, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x03, 0xBC, + 0x38, 0xFF, 0x83, 0xF0, 0x00, 0x1F, 0xE0, 0xFF, 0x86, 0x1E, 0x70, 0x73, + 0x83, 0x9C, 0x1C, 0xC0, 0xE6, 0x07, 0x70, 0x73, 0x83, 0x9C, 0x38, 0xFF, + 0x8F, 0xF0, 0x00, 0x1F, 0xF8, 0xFF, 0x86, 0x00, 0x70, 0x03, 0x80, 0x1F, + 0xF0, 0xFF, 0x86, 0x00, 0x70, 0x03, 0x80, 0x1C, 0x00, 0xFF, 0xC7, 0xFC, + 0x00, 0x1F, 0xF1, 0xFF, 0x18, 0x03, 0x80, 0x38, 0x03, 0xFC, 0x3F, 0xC7, + 0x00, 0x70, 0x07, 0x00, 0x70, 0x06, 0x00, 0xE0, 0x00, 0x07, 0xC1, 0xFE, + 0x38, 0x77, 0x03, 0x70, 0x0E, 0x00, 0xE1, 0xEE, 0x1E, 0xE0, 0x6E, 0x0E, + 0x70, 0xE7, 0xFC, 0x1F, 0x40, 0x1C, 0x1C, 0x60, 0x63, 0x83, 0x8E, 0x0E, + 0x38, 0x38, 0xFF, 0xC3, 0xFF, 0x1C, 0x1C, 0x70, 0x71, 0xC1, 0xC6, 0x06, + 0x18, 0x38, 0xE0, 0xE0, 0x39, 0xCE, 0x63, 0x39, 0xCE, 0x63, 0x39, 0xCE, + 0x00, 0x00, 0xC0, 0x18, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x00, 0xE0, 0x1C, + 0xE3, 0x9C, 0x73, 0x9C, 0x7F, 0x87, 0xC0, 0x1C, 0x3C, 0x71, 0xC1, 0x8E, + 0x0E, 0x70, 0x3B, 0x80, 0xFC, 0x03, 0xF0, 0x0E, 0xE0, 0x73, 0x81, 0xC7, + 0x07, 0x1C, 0x18, 0x38, 0xE0, 0xF0, 0x1C, 0x07, 0x01, 0x80, 0xE0, 0x38, + 0x0E, 0x03, 0x80, 0xC0, 0x70, 0x1C, 0x07, 0x01, 0xFF, 0x7F, 0x80, 0x1E, + 0x1F, 0x1E, 0x1E, 0x3E, 0x1E, 0x3E, 0x3E, 0x36, 0x3E, 0x36, 0x6E, 0x36, + 0x6C, 0x76, 0xCC, 0x76, 0xDC, 0x67, 0x9C, 0x67, 0x98, 0xE7, 0x18, 0xE7, + 0x18, 0x1C, 0x1C, 0x70, 0x63, 0xE1, 0x8F, 0x8E, 0x3E, 0x38, 0xDC, 0xC3, + 0x33, 0x1C, 0xEC, 0x71, 0xF1, 0xC7, 0xC6, 0x1E, 0x18, 0x38, 0xE0, 0xE0, + 0x07, 0xC0, 0xFF, 0x8E, 0x1E, 0xE0, 0x77, 0x03, 0xF0, 0x1F, 0x80, 0xFC, + 0x07, 0xE0, 0x77, 0x03, 0xBC, 0x38, 0xFF, 0x81, 0xF0, 0x00, 0x1F, 0xF0, + 0xFF, 0xC6, 0x0E, 0x70, 0x73, 0x83, 0x9C, 0x38, 0xFF, 0x87, 0xF8, 0x70, + 0x03, 0x80, 0x1C, 0x00, 0xC0, 0x0E, 0x00, 0x00, 0x07, 0xC0, 0xFF, 0x8F, + 0x1C, 0xE0, 0x77, 0x03, 0xB0, 0x1F, 0x80, 0xFC, 0x06, 0xE1, 0x77, 0x1F, + 0x3C, 0x78, 0xFF, 0xC1, 0xF6, 0x00, 0x20, 0x1F, 0xF0, 0xFF, 0xC6, 0x0E, + 0x70, 0x73, 0x83, 0x9C, 0x38, 0xFF, 0x87, 0xFC, 0x70, 0x73, 0x83, 0x9C, + 0x38, 0xC1, 0xC6, 0x0F, 0x00, 0x07, 0xE0, 0xFF, 0xC7, 0x0E, 0x70, 0x73, + 0x80, 0x1F, 0x80, 0x7F, 0x80, 0x7E, 0x00, 0x77, 0x03, 0xBC, 0x38, 0xFF, + 0xC3, 0xF8, 0x00, 0xFF, 0xDF, 0xF8, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x06, + 0x01, 0xC0, 0x38, 0x07, 0x00, 0xC0, 0x18, 0x07, 0x00, 0x38, 0x31, 0xC1, + 0x8C, 0x1C, 0xE0, 0xE7, 0x07, 0x38, 0x31, 0xC3, 0x9C, 0x1C, 0xE0, 0xE7, + 0x06, 0x38, 0x70, 0xFF, 0x03, 0xE0, 0x00, 0xE0, 0xFC, 0x1D, 0x87, 0x30, + 0xC6, 0x38, 0xC6, 0x19, 0xC3, 0xB0, 0x7E, 0x0F, 0x80, 0xF0, 0x1C, 0x03, + 0x00, 0xE1, 0xC3, 0xF1, 0xE3, 0xB8, 0xF1, 0xDC, 0x78, 0xCE, 0x6C, 0xE7, + 0x36, 0x63, 0xB3, 0x70, 0xD9, 0xB0, 0x7C, 0xD8, 0x3C, 0x78, 0x1E, 0x3C, + 0x0E, 0x1C, 0x07, 0x0E, 0x00, 0x0E, 0x1C, 0x38, 0xE0, 0xE7, 0x01, 0xD8, + 0x07, 0xE0, 0x0F, 0x00, 0x38, 0x01, 0xE0, 0x0F, 0xC0, 0x77, 0x01, 0x8E, + 0x0E, 0x38, 0x70, 0xF0, 0xE0, 0xEE, 0x39, 0xC7, 0x39, 0xC3, 0x70, 0x7C, + 0x0F, 0x80, 0xE0, 0x1C, 0x03, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x3F, 0xF3, + 0xFF, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x3C, 0x07, + 0x80, 0x70, 0x0F, 0xFC, 0xFF, 0xC0, 0x0F, 0x0F, 0x0C, 0x1C, 0x18, 0x18, + 0x18, 0x18, 0x30, 0x30, 0x30, 0x30, 0x60, 0x60, 0x60, 0x78, 0x78, 0x12, + 0x4C, 0x92, 0x49, 0x26, 0xD9, 0x20, 0x1E, 0x1E, 0x06, 0x06, 0x06, 0x0C, + 0x0C, 0x0C, 0x0C, 0x18, 0x18, 0x18, 0x18, 0x38, 0x30, 0xF0, 0xF0, 0x06, + 0x0E, 0x0E, 0x1B, 0x33, 0x33, 0x63, 0x63, 0xFF, 0xE0, 0xCC, 0x1F, 0x8F, + 0xF3, 0x1C, 0x06, 0x1F, 0x9F, 0xEE, 0x3B, 0x9C, 0xFF, 0x1D, 0xC0, 0x18, + 0x03, 0x00, 0xE0, 0x1D, 0xC3, 0xFC, 0x71, 0xDC, 0x3B, 0x87, 0x70, 0xEE, + 0x39, 0xCF, 0x7F, 0xCF, 0xE0, 0x0F, 0x0F, 0xF7, 0x1D, 0xC0, 0xE0, 0x38, + 0x0E, 0x03, 0x8E, 0x7F, 0x0F, 0x80, 0x00, 0x60, 0x06, 0x00, 0x61, 0xEE, + 0x3F, 0xE7, 0x9C, 0x71, 0xCE, 0x1C, 0xE1, 0xCE, 0x1C, 0xE3, 0x87, 0xF8, + 0x7F, 0x80, 0x1F, 0x0F, 0xE7, 0x1D, 0xC7, 0xFF, 0xFF, 0xFE, 0x03, 0x8E, + 0x7F, 0x0F, 0x80, 0x1C, 0xF3, 0x3F, 0xFD, 0xC7, 0x18, 0x63, 0x8E, 0x30, + 0xC0, 0x0F, 0x71, 0xFE, 0x3C, 0xE3, 0x8E, 0x70, 0xE7, 0x0E, 0x70, 0xC7, + 0x1C, 0x3F, 0xC3, 0xFC, 0x01, 0xCE, 0x38, 0x7F, 0x03, 0xE0, 0x18, 0x03, + 0x00, 0xE0, 0x1D, 0xE3, 0xFE, 0x71, 0xCC, 0x3B, 0x86, 0x70, 0xCC, 0x39, + 0x87, 0x30, 0xEE, 0x18, 0x39, 0xC0, 0x63, 0x39, 0xCE, 0x63, 0x39, 0xCE, + 0x00, 0x06, 0x06, 0x00, 0x0E, 0x0E, 0x0C, 0x0C, 0x1C, 0x1C, 0x1C, 0x18, + 0x18, 0x38, 0x38, 0x30, 0x70, 0xE0, 0x18, 0x03, 0x00, 0xE0, 0x1C, 0xE3, + 0x38, 0x6E, 0x1F, 0x83, 0xF0, 0x7E, 0x0E, 0xE1, 0x9C, 0x73, 0x8E, 0x38, + 0x39, 0xCE, 0x63, 0x39, 0xCE, 0x63, 0x39, 0xCE, 0x00, 0x3B, 0x9E, 0x3F, + 0xFF, 0x39, 0xC7, 0x71, 0xC6, 0x71, 0x86, 0x71, 0x8E, 0x63, 0x8E, 0x63, + 0x8C, 0xE3, 0x8C, 0xE3, 0x1C, 0x3B, 0xC7, 0xFC, 0xE3, 0xB8, 0x77, 0x0C, + 0xE1, 0x98, 0x73, 0x0E, 0xE1, 0xDC, 0x30, 0x0F, 0x87, 0xF9, 0xE7, 0xB8, + 0x7E, 0x0F, 0xC1, 0xF8, 0x77, 0x9E, 0x7F, 0x87, 0xC0, 0x1D, 0xE1, 0xFE, + 0x1C, 0x73, 0x87, 0x38, 0x73, 0x87, 0x38, 0xE3, 0x8E, 0x7F, 0xC7, 0xF8, + 0x60, 0x06, 0x00, 0x60, 0x0E, 0x00, 0x1E, 0xE7, 0xFD, 0xE7, 0x38, 0xEE, + 0x1D, 0xC3, 0xB8, 0x77, 0x1C, 0x7F, 0x8F, 0xF0, 0x0E, 0x01, 0x80, 0x30, + 0x06, 0x00, 0x3B, 0x36, 0x38, 0x70, 0x70, 0x70, 0x60, 0x60, 0xE0, 0xE0, + 0x3E, 0x3F, 0xF8, 0xFC, 0x0F, 0xC3, 0xF8, 0x3D, 0x8E, 0xFE, 0x3E, 0x00, + 0x38, 0xCF, 0xFE, 0x71, 0x86, 0x38, 0xE3, 0x8F, 0x3C, 0x31, 0xDC, 0x77, + 0x19, 0x86, 0x63, 0xB8, 0xEE, 0x33, 0x9C, 0xFF, 0x1F, 0xC0, 0xE1, 0x98, + 0xE6, 0x31, 0x9C, 0x66, 0x1B, 0x86, 0xC1, 0xF0, 0x78, 0x0E, 0x00, 0xE7, + 0x1B, 0x9C, 0xEE, 0x73, 0x3B, 0xDC, 0xEB, 0x63, 0xAD, 0x8F, 0xBC, 0x1C, + 0xF0, 0x73, 0xC1, 0xCE, 0x00, 0x1C, 0xE1, 0xCC, 0x0D, 0x80, 0xF8, 0x0F, + 0x00, 0xF0, 0x1F, 0x03, 0xB8, 0x33, 0x87, 0x38, 0x70, 0xCE, 0x38, 0xC6, + 0x19, 0xC3, 0x30, 0x66, 0x0F, 0x81, 0xF0, 0x3C, 0x03, 0x80, 0x60, 0x18, + 0x0F, 0x01, 0xC0, 0x00, 0x1F, 0xCF, 0xF0, 0x38, 0x1C, 0x0E, 0x07, 0x03, + 0x81, 0xC0, 0x7F, 0xBF, 0xE0, 0x0E, 0x38, 0x61, 0x83, 0x06, 0x0C, 0x78, + 0xF0, 0xC1, 0x83, 0x0E, 0x1C, 0x38, 0x78, 0x70, 0x18, 0xC4, 0x21, 0x18, + 0xC4, 0x21, 0x18, 0xC4, 0x23, 0x18, 0x80, 0x1C, 0x3C, 0x38, 0x70, 0xE1, + 0x83, 0x06, 0x1E, 0x5C, 0x60, 0xC1, 0x83, 0x0C, 0x38, 0xE0, 0x71, 0x8E }; + +const GFXglyph FreeSansBoldOblique9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 5, 13, 6, 2, -12 }, // 0x21 '!' + { 9, 7, 5, 9, 3, -12 }, // 0x22 '"' + { 14, 11, 12, 10, 1, -11 }, // 0x23 '#' + { 31, 11, 16, 10, 1, -13 }, // 0x24 '$' + { 53, 14, 13, 16, 2, -12 }, // 0x25 '%' + { 76, 12, 13, 13, 2, -12 }, // 0x26 '&' + { 96, 3, 5, 4, 3, -12 }, // 0x27 ''' + { 98, 8, 17, 6, 2, -12 }, // 0x28 '(' + { 115, 8, 17, 6, -2, -13 }, // 0x29 ')' + { 132, 6, 6, 7, 3, -12 }, // 0x2A '*' + { 137, 9, 8, 11, 2, -7 }, // 0x2B '+' + { 146, 4, 6, 5, 0, -2 }, // 0x2C ',' + { 149, 5, 2, 6, 1, -5 }, // 0x2D '-' + { 151, 3, 2, 5, 1, -1 }, // 0x2E '.' + { 152, 8, 13, 5, 0, -12 }, // 0x2F '/' + { 165, 10, 13, 10, 1, -12 }, // 0x30 '0' + { 182, 7, 13, 10, 3, -12 }, // 0x31 '1' + { 194, 11, 13, 10, 1, -12 }, // 0x32 '2' + { 212, 11, 13, 10, 1, -12 }, // 0x33 '3' + { 230, 10, 12, 10, 1, -11 }, // 0x34 '4' + { 245, 11, 13, 10, 1, -12 }, // 0x35 '5' + { 263, 10, 13, 10, 2, -12 }, // 0x36 '6' + { 280, 10, 13, 10, 2, -12 }, // 0x37 '7' + { 297, 11, 13, 10, 1, -12 }, // 0x38 '8' + { 315, 11, 13, 10, 1, -12 }, // 0x39 '9' + { 333, 4, 9, 6, 2, -8 }, // 0x3A ':' + { 338, 5, 12, 6, 1, -8 }, // 0x3B ';' + { 346, 10, 9, 11, 1, -8 }, // 0x3C '<' + { 358, 10, 6, 11, 1, -6 }, // 0x3D '=' + { 366, 10, 9, 11, 1, -7 }, // 0x3E '>' + { 378, 10, 13, 11, 3, -12 }, // 0x3F '?' + { 395, 18, 16, 18, 1, -13 }, // 0x40 '@' + { 431, 13, 13, 13, 0, -12 }, // 0x41 'A' + { 453, 13, 13, 13, 1, -12 }, // 0x42 'B' + { 475, 13, 13, 13, 2, -12 }, // 0x43 'C' + { 497, 13, 13, 13, 1, -12 }, // 0x44 'D' + { 519, 13, 13, 12, 1, -12 }, // 0x45 'E' + { 541, 12, 13, 11, 1, -12 }, // 0x46 'F' + { 561, 12, 13, 14, 2, -12 }, // 0x47 'G' + { 581, 14, 13, 13, 1, -12 }, // 0x48 'H' + { 604, 5, 13, 5, 1, -12 }, // 0x49 'I' + { 613, 11, 13, 10, 1, -12 }, // 0x4A 'J' + { 631, 14, 13, 13, 1, -12 }, // 0x4B 'K' + { 654, 10, 13, 11, 1, -12 }, // 0x4C 'L' + { 671, 16, 13, 15, 1, -12 }, // 0x4D 'M' + { 697, 14, 13, 13, 1, -12 }, // 0x4E 'N' + { 720, 13, 13, 14, 2, -12 }, // 0x4F 'O' + { 742, 13, 13, 12, 1, -12 }, // 0x50 'P' + { 764, 13, 14, 14, 2, -12 }, // 0x51 'Q' + { 787, 13, 13, 13, 1, -12 }, // 0x52 'R' + { 809, 13, 13, 12, 1, -12 }, // 0x53 'S' + { 831, 11, 13, 11, 3, -12 }, // 0x54 'T' + { 849, 13, 13, 13, 2, -12 }, // 0x55 'U' + { 871, 11, 13, 12, 3, -12 }, // 0x56 'V' + { 889, 17, 13, 17, 3, -12 }, // 0x57 'W' + { 917, 14, 13, 12, 0, -12 }, // 0x58 'X' + { 940, 11, 13, 12, 3, -12 }, // 0x59 'Y' + { 958, 12, 13, 11, 1, -12 }, // 0x5A 'Z' + { 978, 8, 17, 6, 0, -12 }, // 0x5B '[' + { 995, 3, 17, 5, 2, -16 }, // 0x5C '\' + { 1002, 8, 17, 6, 0, -13 }, // 0x5D ']' + { 1019, 8, 8, 11, 2, -12 }, // 0x5E '^' + { 1027, 11, 1, 10, -1, 4 }, // 0x5F '_' + { 1029, 3, 2, 6, 3, -12 }, // 0x60 '`' + { 1030, 10, 10, 10, 1, -9 }, // 0x61 'a' + { 1043, 11, 13, 11, 1, -12 }, // 0x62 'b' + { 1061, 10, 10, 10, 1, -9 }, // 0x63 'c' + { 1074, 12, 13, 11, 1, -12 }, // 0x64 'd' + { 1094, 10, 10, 10, 1, -9 }, // 0x65 'e' + { 1107, 6, 13, 6, 2, -12 }, // 0x66 'f' + { 1117, 12, 14, 11, 0, -9 }, // 0x67 'g' + { 1138, 11, 13, 11, 1, -12 }, // 0x68 'h' + { 1156, 5, 13, 5, 1, -12 }, // 0x69 'i' + { 1165, 8, 17, 5, -1, -12 }, // 0x6A 'j' + { 1182, 11, 13, 10, 1, -12 }, // 0x6B 'k' + { 1200, 5, 13, 5, 1, -12 }, // 0x6C 'l' + { 1209, 16, 10, 16, 1, -9 }, // 0x6D 'm' + { 1229, 11, 10, 11, 1, -9 }, // 0x6E 'n' + { 1243, 11, 10, 11, 1, -9 }, // 0x6F 'o' + { 1257, 12, 14, 11, 0, -9 }, // 0x70 'p' + { 1278, 11, 14, 11, 1, -9 }, // 0x71 'q' + { 1298, 8, 10, 7, 1, -9 }, // 0x72 'r' + { 1308, 9, 10, 10, 2, -9 }, // 0x73 's' + { 1320, 6, 12, 6, 2, -11 }, // 0x74 't' + { 1329, 10, 10, 11, 2, -9 }, // 0x75 'u' + { 1342, 10, 10, 10, 2, -9 }, // 0x76 'v' + { 1355, 14, 10, 14, 2, -9 }, // 0x77 'w' + { 1373, 12, 10, 10, 0, -9 }, // 0x78 'x' + { 1388, 11, 14, 10, 1, -9 }, // 0x79 'y' + { 1408, 10, 10, 9, 0, -9 }, // 0x7A 'z' + { 1421, 7, 17, 7, 2, -12 }, // 0x7B '{' + { 1436, 5, 17, 5, 1, -12 }, // 0x7C '|' + { 1447, 7, 17, 7, 0, -13 }, // 0x7D '}' + { 1462, 8, 2, 11, 2, -4 } }; // 0x7E '~' + +const GFXfont FreeSansBoldOblique9pt7b PROGMEM = { + (uint8_t *)FreeSansBoldOblique9pt7bBitmaps, + (GFXglyph *)FreeSansBoldOblique9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 2136 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansOblique12pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansOblique12pt7b.h new file mode 100644 index 0000000..efdbd8d --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansOblique12pt7b.h @@ -0,0 +1,302 @@ +const uint8_t FreeSansOblique12pt7bBitmaps[] PROGMEM = { + 0x0C, 0x61, 0x86, 0x18, 0x63, 0x0C, 0x30, 0xC2, 0x18, 0x61, 0x00, 0x00, + 0xC3, 0x00, 0xCF, 0x3C, 0xE2, 0x8A, 0x20, 0x01, 0x8C, 0x03, 0x18, 0x06, + 0x60, 0x18, 0xC0, 0x31, 0x83, 0xFF, 0x87, 0xFF, 0x03, 0x18, 0x0C, 0x60, + 0x18, 0xC0, 0x23, 0x03, 0xFF, 0x8F, 0xFF, 0x02, 0x30, 0x0C, 0x60, 0x18, + 0x80, 0x63, 0x00, 0xC6, 0x00, 0x00, 0x80, 0x3F, 0x03, 0xFC, 0x32, 0x73, + 0x91, 0x99, 0x8C, 0xCC, 0x06, 0x60, 0x3E, 0x00, 0x7E, 0x01, 0xFC, 0x0C, + 0xEC, 0x43, 0x62, 0x1B, 0x11, 0x9D, 0x9C, 0x7F, 0xC1, 0xF8, 0x02, 0x00, + 0x10, 0x01, 0x80, 0x00, 0x00, 0x01, 0x83, 0xC0, 0x60, 0xFC, 0x18, 0x30, + 0xC2, 0x0C, 0x18, 0xC1, 0x83, 0x30, 0x38, 0xCC, 0x03, 0xF1, 0x00, 0x3C, + 0x40, 0x00, 0x18, 0xF0, 0x06, 0x3F, 0x01, 0x8C, 0x30, 0x23, 0x06, 0x0C, + 0x60, 0xC3, 0x0E, 0x30, 0xC0, 0xFC, 0x10, 0x0F, 0x00, 0x01, 0xE0, 0x3F, + 0x81, 0x8C, 0x18, 0x60, 0xC3, 0x06, 0x30, 0x1F, 0x00, 0xE0, 0x1F, 0x01, + 0xDC, 0xD8, 0x6D, 0x81, 0xEC, 0x0E, 0x60, 0x73, 0x87, 0xCF, 0xE6, 0x3E, + 0x38, 0xFE, 0xA0, 0x03, 0x06, 0x04, 0x0C, 0x18, 0x18, 0x30, 0x30, 0x60, + 0x60, 0x60, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0x40, 0x60, + 0x60, 0x20, 0x04, 0x06, 0x06, 0x02, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, + 0x03, 0x03, 0x06, 0x06, 0x06, 0x0C, 0x0C, 0x18, 0x18, 0x30, 0x20, 0x60, + 0xC0, 0x0C, 0x0C, 0x49, 0x7F, 0x3C, 0x3C, 0x6C, 0x00, 0x03, 0x00, 0x30, + 0x03, 0x00, 0x30, 0xFF, 0xFF, 0xFF, 0x06, 0x00, 0x60, 0x06, 0x00, 0xC0, + 0x0C, 0x00, 0x77, 0x22, 0x6C, 0xFF, 0xF0, 0xFC, 0x00, 0x40, 0x30, 0x08, + 0x06, 0x01, 0x00, 0xC0, 0x20, 0x18, 0x04, 0x02, 0x00, 0x80, 0x40, 0x10, + 0x08, 0x02, 0x01, 0x00, 0xC0, 0x20, 0x00, 0x07, 0xC0, 0xFE, 0x1C, 0x73, + 0x83, 0x30, 0x36, 0x03, 0x60, 0x36, 0x03, 0xC0, 0x7C, 0x07, 0xC0, 0x6C, + 0x06, 0xC0, 0xEC, 0x0C, 0xE3, 0x87, 0xF0, 0x3E, 0x00, 0x02, 0x0C, 0x77, + 0xEF, 0xC1, 0x83, 0x0C, 0x18, 0x30, 0x61, 0xC3, 0x06, 0x0C, 0x18, 0x60, + 0x03, 0xF0, 0x1F, 0xE0, 0xE1, 0xC7, 0x03, 0x18, 0x0C, 0x00, 0x30, 0x01, + 0x80, 0x0E, 0x00, 0x70, 0x07, 0x80, 0x78, 0x07, 0x80, 0x38, 0x01, 0xC0, + 0x06, 0x00, 0x1F, 0xFC, 0xFF, 0xE0, 0x07, 0xC0, 0xFE, 0x1C, 0x73, 0x03, + 0x30, 0x30, 0x03, 0x00, 0xE0, 0x7C, 0x07, 0xC0, 0x0E, 0x00, 0x60, 0x06, + 0xC0, 0x6C, 0x0C, 0xE1, 0xC7, 0xF8, 0x3E, 0x00, 0x00, 0x60, 0x06, 0x00, + 0xE0, 0x1E, 0x03, 0xE0, 0x6C, 0x0C, 0xC1, 0x8C, 0x30, 0xC6, 0x1C, 0xC1, + 0x8F, 0xFF, 0xFF, 0xE0, 0x18, 0x03, 0x00, 0x30, 0x03, 0x00, 0x0F, 0xF8, + 0x7F, 0xC6, 0x00, 0x30, 0x01, 0x00, 0x1B, 0xC0, 0xFF, 0x06, 0x1C, 0x60, + 0x60, 0x03, 0x00, 0x18, 0x00, 0xC0, 0x0C, 0x60, 0x63, 0x86, 0x0F, 0xE0, + 0x3E, 0x00, 0x03, 0xC0, 0xFE, 0x1C, 0x73, 0x83, 0x30, 0x06, 0x00, 0x67, + 0x87, 0xFC, 0xF0, 0xEE, 0x06, 0xC0, 0x6C, 0x06, 0xC0, 0x4C, 0x0C, 0xE1, + 0x87, 0xF8, 0x3E, 0x00, 0x3F, 0xFB, 0xFF, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, + 0x00, 0xC0, 0x06, 0x00, 0x60, 0x06, 0x00, 0x70, 0x03, 0x00, 0x30, 0x03, + 0x80, 0x18, 0x01, 0xC0, 0x0C, 0x00, 0xE0, 0x00, 0x07, 0xC0, 0xFE, 0x1C, + 0x73, 0x03, 0x30, 0x33, 0x03, 0x38, 0x61, 0xFC, 0x3F, 0xC7, 0x0E, 0x60, + 0x6C, 0x06, 0xC0, 0x6C, 0x0C, 0xE1, 0xC7, 0xF8, 0x3E, 0x00, 0x07, 0xC1, + 0xFE, 0x38, 0x73, 0x03, 0x60, 0x36, 0x03, 0x60, 0x36, 0x07, 0x70, 0xF3, + 0xFE, 0x1E, 0x60, 0x0E, 0x00, 0xCC, 0x1C, 0xE3, 0x87, 0xF0, 0x3C, 0x00, + 0x39, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x39, 0xC0, 0x1C, 0x70, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x07, 0x1C, 0x20, 0x86, 0x30, 0x00, 0x00, 0x01, 0xC0, + 0x3C, 0x0F, 0x81, 0xE0, 0x7C, 0x03, 0x80, 0x0F, 0x00, 0x1F, 0x00, 0x3E, + 0x00, 0x38, 0x00, 0x40, 0x7F, 0xFB, 0xFF, 0x80, 0x00, 0x00, 0x0F, 0xFF, + 0x7F, 0xF0, 0x20, 0x01, 0xC0, 0x07, 0xC0, 0x0F, 0x80, 0x0F, 0x00, 0x1C, + 0x03, 0xE0, 0x78, 0x1F, 0x03, 0xC0, 0x38, 0x00, 0x00, 0x00, 0x0F, 0x87, + 0xF9, 0xC3, 0xB0, 0x3C, 0x06, 0x00, 0xC0, 0x30, 0x0C, 0x03, 0x01, 0xC0, + 0x30, 0x0C, 0x01, 0x80, 0x00, 0x00, 0x00, 0x00, 0x30, 0x06, 0x00, 0x00, + 0x3F, 0x80, 0x01, 0xFF, 0xE0, 0x0F, 0x01, 0xE0, 0x38, 0x00, 0xE0, 0xE0, + 0x00, 0xC3, 0x87, 0x81, 0xCE, 0x1F, 0xB1, 0x98, 0x71, 0xC3, 0x61, 0x83, + 0x86, 0xC6, 0x06, 0x0F, 0x0C, 0x0C, 0x3E, 0x30, 0x30, 0x6C, 0x60, 0x61, + 0xD8, 0xC1, 0x87, 0x31, 0xC7, 0x1C, 0x61, 0xF7, 0xF0, 0x63, 0xCF, 0x80, + 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xFF, 0xE0, 0x00, 0x7F, 0x00, 0x00, + 0x00, 0x38, 0x00, 0x78, 0x00, 0x7C, 0x00, 0xFC, 0x00, 0xDC, 0x01, 0xCC, + 0x01, 0x8C, 0x03, 0x8C, 0x03, 0x0C, 0x06, 0x0C, 0x0E, 0x0E, 0x0F, 0xFE, + 0x1F, 0xFE, 0x18, 0x06, 0x38, 0x06, 0x30, 0x06, 0x70, 0x06, 0x60, 0x07, + 0x0F, 0xF8, 0x1F, 0xF8, 0x60, 0x38, 0xC0, 0x31, 0x80, 0x63, 0x00, 0xCE, + 0x03, 0x18, 0x0C, 0x3F, 0xF0, 0x7F, 0xF0, 0xC0, 0x73, 0x00, 0x66, 0x00, + 0xCC, 0x01, 0x98, 0x06, 0x70, 0x1C, 0xFF, 0xF1, 0xFF, 0x80, 0x01, 0xF8, + 0x07, 0xFE, 0x0E, 0x0E, 0x1C, 0x03, 0x38, 0x03, 0x30, 0x00, 0x60, 0x00, + 0x60, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x06, + 0xC0, 0x0C, 0xE0, 0x1C, 0x70, 0x78, 0x3F, 0xF0, 0x1F, 0x80, 0x0F, 0xF8, + 0x1F, 0xFC, 0x18, 0x0E, 0x18, 0x07, 0x18, 0x03, 0x18, 0x03, 0x38, 0x03, + 0x30, 0x03, 0x30, 0x03, 0x30, 0x03, 0x70, 0x06, 0x70, 0x06, 0x60, 0x0C, + 0x60, 0x0C, 0x60, 0x18, 0xE0, 0x78, 0xFF, 0xE0, 0xFF, 0x80, 0x0F, 0xFF, + 0x1F, 0xFE, 0x18, 0x00, 0x18, 0x00, 0x18, 0x00, 0x18, 0x00, 0x38, 0x00, + 0x30, 0x00, 0x3F, 0xFC, 0x3F, 0xF8, 0x70, 0x00, 0x70, 0x00, 0x60, 0x00, + 0x60, 0x00, 0x60, 0x00, 0xE0, 0x00, 0xFF, 0xF8, 0xFF, 0xF8, 0x0F, 0xFE, + 0x3F, 0xFC, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x0E, 0x00, 0x18, + 0x00, 0x3F, 0xF0, 0x7F, 0xE1, 0xC0, 0x03, 0x80, 0x06, 0x00, 0x0C, 0x00, + 0x18, 0x00, 0x70, 0x00, 0xC0, 0x01, 0x80, 0x00, 0x01, 0xF8, 0x07, 0xFE, + 0x0E, 0x0F, 0x18, 0x03, 0x30, 0x03, 0x70, 0x00, 0x60, 0x00, 0x60, 0x00, + 0xC0, 0x7F, 0xC0, 0x7E, 0xC0, 0x02, 0xC0, 0x06, 0xC0, 0x06, 0xE0, 0x0E, + 0x60, 0x1E, 0x78, 0x3C, 0x3F, 0xE4, 0x0F, 0x84, 0x0C, 0x01, 0x8E, 0x00, + 0xC6, 0x00, 0xE3, 0x00, 0x61, 0x80, 0x30, 0xC0, 0x18, 0xE0, 0x0C, 0x60, + 0x0E, 0x3F, 0xFE, 0x1F, 0xFF, 0x1C, 0x01, 0x8E, 0x01, 0xC6, 0x00, 0xE3, + 0x00, 0x61, 0x80, 0x31, 0xC0, 0x18, 0xC0, 0x1C, 0x60, 0x0C, 0x00, 0x0C, + 0x71, 0x86, 0x18, 0x63, 0x8C, 0x30, 0xC3, 0x1C, 0x61, 0x86, 0x18, 0xE3, + 0x00, 0x00, 0x18, 0x01, 0x80, 0x0C, 0x00, 0x60, 0x03, 0x00, 0x38, 0x01, + 0x80, 0x0C, 0x00, 0x60, 0x03, 0x00, 0x38, 0x01, 0x8C, 0x0C, 0x60, 0x63, + 0x07, 0x1C, 0x70, 0x7F, 0x01, 0xF0, 0x00, 0x0C, 0x03, 0x87, 0x01, 0xC1, + 0x80, 0xE0, 0x60, 0x60, 0x18, 0x70, 0x06, 0x38, 0x03, 0x9C, 0x00, 0xCE, + 0x00, 0x37, 0x80, 0x0F, 0x70, 0x07, 0x8C, 0x01, 0xC3, 0x80, 0x60, 0x60, + 0x18, 0x1C, 0x06, 0x03, 0x03, 0x80, 0xE0, 0xC0, 0x18, 0x30, 0x07, 0x00, + 0x0C, 0x03, 0x80, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x0E, 0x01, 0x80, 0x30, + 0x06, 0x01, 0xC0, 0x38, 0x06, 0x00, 0xC0, 0x18, 0x07, 0x00, 0xFF, 0xFF, + 0xFC, 0x0E, 0x00, 0x71, 0xE0, 0x0F, 0x1E, 0x00, 0xF1, 0xE0, 0x1E, 0x1E, + 0x01, 0xE1, 0xE0, 0x36, 0x3B, 0x03, 0x63, 0x30, 0x6E, 0x33, 0x0E, 0xC3, + 0x30, 0xCC, 0x33, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x31, 0xC6, 0x33, 0x18, + 0x61, 0xE1, 0x8E, 0x1E, 0x18, 0xC1, 0xC1, 0x8C, 0x1C, 0x38, 0x0C, 0x01, + 0x8F, 0x00, 0xC7, 0x80, 0x63, 0xE0, 0x71, 0xF0, 0x30, 0xD8, 0x18, 0xEE, + 0x0C, 0x63, 0x06, 0x31, 0xC7, 0x18, 0xE3, 0x0C, 0x31, 0x8C, 0x1C, 0xC6, + 0x06, 0x63, 0x03, 0xF1, 0x80, 0xF1, 0xC0, 0x78, 0xC0, 0x3C, 0x60, 0x0E, + 0x00, 0x01, 0xF8, 0x03, 0xFF, 0x03, 0x83, 0xC3, 0x80, 0x63, 0x00, 0x3B, + 0x80, 0x0D, 0x80, 0x06, 0xC0, 0x03, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, + 0xF8, 0x00, 0x6C, 0x00, 0x36, 0x00, 0x31, 0x80, 0x30, 0xF0, 0x78, 0x3F, + 0xF0, 0x07, 0xE0, 0x00, 0x0F, 0xF8, 0x3F, 0xF8, 0x60, 0x38, 0xC0, 0x31, + 0x80, 0x63, 0x00, 0xCE, 0x03, 0x18, 0x0E, 0x3F, 0xF8, 0x7F, 0xE1, 0xC0, + 0x03, 0x80, 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x70, 0x00, 0xC0, 0x01, + 0x80, 0x00, 0x00, 0xFC, 0x01, 0xFF, 0xC0, 0xF0, 0x78, 0x70, 0x06, 0x38, + 0x01, 0xCC, 0x00, 0x36, 0x00, 0x0D, 0x80, 0x03, 0xC0, 0x00, 0xF0, 0x00, + 0x3C, 0x00, 0x1B, 0x00, 0x06, 0xC0, 0x03, 0x38, 0x1D, 0xC6, 0x03, 0xE1, + 0xE0, 0xF0, 0x3F, 0xFE, 0x03, 0xF1, 0xC0, 0x00, 0x20, 0x0F, 0xFC, 0x1F, + 0xFE, 0x18, 0x07, 0x18, 0x03, 0x18, 0x03, 0x18, 0x03, 0x38, 0x06, 0x30, + 0x0C, 0x3F, 0xF8, 0x3F, 0xF8, 0x70, 0x1C, 0x70, 0x0C, 0x60, 0x0C, 0x60, + 0x0C, 0x60, 0x18, 0xE0, 0x18, 0xC0, 0x18, 0xC0, 0x1C, 0x03, 0xF8, 0x1F, + 0xF8, 0x70, 0x38, 0xC0, 0x33, 0x00, 0x66, 0x00, 0x0C, 0x00, 0x1E, 0x00, + 0x1F, 0xC0, 0x0F, 0xF0, 0x01, 0xF0, 0x00, 0xEC, 0x00, 0xD8, 0x01, 0xB0, + 0x06, 0x70, 0x38, 0x7F, 0xE0, 0x3F, 0x00, 0xFF, 0xFF, 0xFF, 0xF0, 0x70, + 0x01, 0xC0, 0x06, 0x00, 0x18, 0x00, 0x60, 0x03, 0x80, 0x0C, 0x00, 0x30, + 0x00, 0xC0, 0x03, 0x00, 0x1C, 0x00, 0x60, 0x01, 0x80, 0x06, 0x00, 0x18, + 0x00, 0xE0, 0x00, 0x18, 0x03, 0x38, 0x03, 0x30, 0x07, 0x30, 0x06, 0x30, + 0x06, 0x70, 0x06, 0x70, 0x0E, 0x60, 0x0C, 0x60, 0x0C, 0x60, 0x0C, 0xE0, + 0x0C, 0xC0, 0x1C, 0xC0, 0x18, 0xC0, 0x18, 0xC0, 0x38, 0xE0, 0x70, 0x7F, + 0xE0, 0x1F, 0x80, 0xC0, 0x0F, 0xC0, 0x1B, 0x80, 0x73, 0x00, 0xC6, 0x03, + 0x0C, 0x06, 0x18, 0x18, 0x30, 0x70, 0x60, 0xC0, 0xE3, 0x81, 0xC6, 0x01, + 0x9C, 0x03, 0x30, 0x06, 0xE0, 0x0D, 0x80, 0x1E, 0x00, 0x3C, 0x00, 0x70, + 0x00, 0xC0, 0x70, 0x1F, 0x01, 0xC0, 0x6C, 0x0F, 0x03, 0xB0, 0x3C, 0x0C, + 0xC1, 0xF0, 0x73, 0x06, 0xC1, 0x8C, 0x3B, 0x06, 0x30, 0xC6, 0x30, 0xC7, + 0x18, 0xC3, 0x18, 0x67, 0x0C, 0xE1, 0x98, 0x33, 0x06, 0xE0, 0xDC, 0x1B, + 0x03, 0x60, 0x6C, 0x07, 0x81, 0xE0, 0x1C, 0x07, 0x80, 0x70, 0x1C, 0x01, + 0x80, 0x70, 0x00, 0x07, 0x00, 0xE0, 0xE0, 0x38, 0x0C, 0x0E, 0x01, 0xC3, + 0x80, 0x18, 0xE0, 0x03, 0x98, 0x00, 0x36, 0x00, 0x07, 0x80, 0x00, 0xF0, + 0x00, 0x1E, 0x00, 0x07, 0xC0, 0x01, 0xDC, 0x00, 0x73, 0x80, 0x1C, 0x30, + 0x03, 0x07, 0x00, 0xC0, 0x60, 0x38, 0x0E, 0x0E, 0x00, 0xC0, 0xE0, 0x06, + 0x60, 0x0C, 0x70, 0x1C, 0x70, 0x38, 0x30, 0x70, 0x38, 0x60, 0x18, 0xC0, + 0x1D, 0xC0, 0x1F, 0x80, 0x0F, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0E, 0x00, + 0x0C, 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x1C, 0x00, 0x18, 0x00, 0x0F, 0xFF, + 0x87, 0xFF, 0x80, 0x01, 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x01, + 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x01, + 0xC0, 0x01, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xFF, 0xF8, 0x7F, 0xFC, + 0x00, 0x07, 0xC1, 0xE0, 0x60, 0x18, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x1C, + 0x06, 0x01, 0x80, 0x60, 0x18, 0x0E, 0x03, 0x00, 0xC0, 0x30, 0x0C, 0x06, + 0x01, 0x80, 0x60, 0x1E, 0x07, 0x80, 0x93, 0x6C, 0x92, 0x49, 0x24, 0xDB, + 0x24, 0x07, 0x81, 0xE0, 0x18, 0x06, 0x01, 0x80, 0xC0, 0x30, 0x0C, 0x03, + 0x01, 0xC0, 0x60, 0x18, 0x06, 0x01, 0x80, 0xE0, 0x30, 0x0C, 0x03, 0x00, + 0xC0, 0x60, 0x18, 0x1E, 0x0F, 0x80, 0x03, 0x01, 0xC0, 0xD8, 0x36, 0x19, + 0x84, 0x63, 0x19, 0x83, 0x60, 0xC0, 0xFF, 0xFC, 0xE6, 0x23, 0x07, 0xC3, + 0xFC, 0xE3, 0x98, 0x30, 0x06, 0x01, 0x87, 0xF3, 0xC6, 0xC0, 0xD8, 0x3B, + 0x0E, 0x7F, 0x77, 0xCC, 0x0C, 0x00, 0x60, 0x03, 0x00, 0x30, 0x01, 0x80, + 0x0C, 0xF0, 0x7F, 0xC3, 0x87, 0x38, 0x19, 0x80, 0xCC, 0x06, 0x60, 0x32, + 0x03, 0xB0, 0x19, 0xC1, 0xCE, 0x1C, 0x7F, 0xC3, 0x7C, 0x00, 0x0F, 0x83, + 0xF8, 0xE3, 0xB8, 0x36, 0x07, 0xC0, 0x30, 0x06, 0x00, 0xC0, 0x18, 0x1B, + 0x86, 0x3F, 0xC3, 0xE0, 0x00, 0x0C, 0x00, 0x60, 0x01, 0x80, 0x06, 0x00, + 0x18, 0x3E, 0x61, 0xFF, 0x0E, 0x3C, 0x70, 0x71, 0x80, 0xCE, 0x07, 0x30, + 0x18, 0xC0, 0x63, 0x01, 0x8C, 0x0E, 0x38, 0x78, 0x7F, 0xC0, 0xFB, 0x00, + 0x07, 0xC1, 0xFE, 0x38, 0x77, 0x03, 0x60, 0x37, 0xFF, 0xFF, 0xFC, 0x00, + 0xC0, 0x0C, 0x06, 0xE1, 0xC7, 0xF8, 0x3E, 0x00, 0x07, 0x0F, 0x1C, 0x18, + 0x18, 0x7E, 0x7E, 0x30, 0x30, 0x30, 0x30, 0x60, 0x60, 0x60, 0x60, 0x60, + 0xC0, 0xC0, 0x03, 0xCC, 0x3F, 0xA1, 0xC7, 0x8E, 0x0E, 0x30, 0x38, 0xC0, + 0xC6, 0x03, 0x18, 0x0C, 0x60, 0x71, 0x81, 0xC7, 0x0E, 0x0F, 0xF8, 0x1E, + 0x60, 0x03, 0x80, 0x0C, 0x30, 0x70, 0x7F, 0x80, 0xF8, 0x00, 0x0C, 0x00, + 0xC0, 0x0C, 0x01, 0x80, 0x18, 0x01, 0x9E, 0x1F, 0xF1, 0xC7, 0x38, 0x33, + 0x03, 0x30, 0x33, 0x07, 0x30, 0x66, 0x06, 0x60, 0x66, 0x06, 0x60, 0xC6, + 0x0C, 0x18, 0xC0, 0x00, 0x18, 0xC6, 0x33, 0x18, 0xC6, 0x31, 0x98, 0xC6, + 0x00, 0x01, 0x80, 0xC0, 0x00, 0x00, 0x00, 0x18, 0x1C, 0x0C, 0x06, 0x03, + 0x01, 0x81, 0x80, 0xC0, 0x60, 0x30, 0x18, 0x18, 0x0C, 0x06, 0x03, 0x03, + 0x87, 0x83, 0x80, 0x0C, 0x00, 0x60, 0x03, 0x00, 0x30, 0x01, 0x80, 0x0C, + 0x18, 0x61, 0x83, 0x38, 0x33, 0x81, 0xB8, 0x0F, 0xC0, 0x77, 0x03, 0x18, + 0x30, 0xC1, 0x87, 0x0C, 0x18, 0x60, 0xE3, 0x03, 0x00, 0x18, 0xC6, 0x63, + 0x18, 0xC6, 0x33, 0x18, 0xC6, 0x31, 0x98, 0xC6, 0x00, 0x1B, 0xE3, 0xC3, + 0xFD, 0xFC, 0xF1, 0xE1, 0x9C, 0x18, 0x33, 0x03, 0x06, 0x60, 0xC0, 0xCC, + 0x18, 0x3B, 0x83, 0x06, 0x60, 0x60, 0xCC, 0x0C, 0x19, 0x83, 0x03, 0x30, + 0x60, 0xE6, 0x0C, 0x18, 0x1B, 0xE1, 0xFF, 0x3C, 0x73, 0x83, 0x30, 0x33, + 0x03, 0x30, 0x77, 0x06, 0x60, 0x66, 0x06, 0x60, 0x66, 0x0C, 0x60, 0xC0, + 0x07, 0xC1, 0xFE, 0x38, 0x77, 0x03, 0x60, 0x3E, 0x03, 0xC0, 0x3C, 0x06, + 0xC0, 0x6C, 0x0E, 0xE1, 0xC7, 0xF8, 0x3E, 0x00, 0x0C, 0xF0, 0x3F, 0xE0, + 0xE1, 0xC7, 0x03, 0x1C, 0x0C, 0x60, 0x31, 0x80, 0xCE, 0x07, 0x38, 0x18, + 0xE0, 0xE3, 0xC7, 0x0F, 0xF8, 0x77, 0xC1, 0x80, 0x06, 0x00, 0x18, 0x00, + 0x60, 0x03, 0x80, 0x00, 0x0F, 0x98, 0xFF, 0xCE, 0x3C, 0xE0, 0xE6, 0x03, + 0x70, 0x1B, 0x01, 0x98, 0x0C, 0xC0, 0x66, 0x07, 0x38, 0x78, 0xFF, 0x83, + 0xCC, 0x00, 0x60, 0x07, 0x00, 0x38, 0x01, 0x80, 0x0C, 0x00, 0x1B, 0x8F, + 0xCF, 0x07, 0x03, 0x01, 0x80, 0xC0, 0xE0, 0x60, 0x30, 0x18, 0x0C, 0x06, + 0x00, 0x0F, 0xC1, 0xFF, 0x30, 0x76, 0x03, 0x60, 0x07, 0x80, 0x3F, 0x80, + 0x7E, 0x00, 0x6C, 0x06, 0xE0, 0xCF, 0xF8, 0x3E, 0x00, 0x18, 0x30, 0x67, + 0xEF, 0xC6, 0x0C, 0x30, 0x60, 0xC1, 0x83, 0x0C, 0x18, 0x3C, 0x38, 0x30, + 0x33, 0x03, 0x30, 0x37, 0x06, 0x60, 0x66, 0x06, 0x60, 0x66, 0x06, 0xC0, + 0xEC, 0x0C, 0xC3, 0xCF, 0xFC, 0x7C, 0xC0, 0xC0, 0x78, 0x1B, 0x03, 0x60, + 0xC6, 0x18, 0xC6, 0x19, 0xC3, 0x30, 0x6C, 0x0D, 0x81, 0xE0, 0x3C, 0x03, + 0x00, 0xC1, 0xC3, 0xE1, 0xE1, 0xB0, 0xF0, 0xD8, 0x78, 0xCC, 0x6C, 0x66, + 0x36, 0x63, 0x33, 0x30, 0x99, 0xB0, 0x58, 0xD8, 0x2C, 0x78, 0x1C, 0x3C, + 0x0E, 0x1C, 0x06, 0x0E, 0x00, 0x0C, 0x1C, 0x30, 0xE0, 0xE3, 0x01, 0x98, + 0x07, 0xC0, 0x0E, 0x00, 0x30, 0x01, 0xE0, 0x0F, 0x80, 0x73, 0x01, 0x8C, + 0x0C, 0x38, 0x60, 0x60, 0x18, 0x0C, 0x60, 0x61, 0x83, 0x86, 0x0C, 0x1C, + 0x60, 0x31, 0x80, 0xCC, 0x03, 0x30, 0x0D, 0x80, 0x36, 0x00, 0xF0, 0x03, + 0x80, 0x06, 0x00, 0x30, 0x00, 0xC0, 0x06, 0x00, 0xF0, 0x03, 0x80, 0x00, + 0x1F, 0xF1, 0xFF, 0x00, 0x70, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, + 0x18, 0x03, 0x00, 0x60, 0x0F, 0xFC, 0xFF, 0xC0, 0x07, 0x0E, 0x18, 0x18, + 0x18, 0x18, 0x30, 0x30, 0x30, 0x30, 0x60, 0xE0, 0xE0, 0x60, 0x60, 0x60, + 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xF0, 0x60, 0x0C, 0x30, 0x82, 0x08, 0x61, + 0x84, 0x10, 0x43, 0x0C, 0x20, 0x86, 0x18, 0x41, 0x04, 0x30, 0xC2, 0x00, + 0x00, 0x06, 0x07, 0x80, 0xC0, 0x60, 0x30, 0x18, 0x0C, 0x0C, 0x06, 0x03, + 0x01, 0xC0, 0xE0, 0x60, 0x60, 0x30, 0x18, 0x0C, 0x0C, 0x06, 0x03, 0x01, + 0x83, 0x83, 0x80, 0x38, 0x0F, 0x82, 0x38, 0x83, 0xE0, 0x38 }; + +const GFXglyph FreeSansOblique12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 7, 0, 1 }, // 0x20 ' ' + { 0, 6, 18, 7, 3, -17 }, // 0x21 '!' + { 14, 6, 6, 9, 4, -16 }, // 0x22 '"' + { 19, 15, 18, 13, 1, -17 }, // 0x23 '#' + { 53, 13, 21, 13, 2, -17 }, // 0x24 '$' + { 88, 19, 17, 21, 3, -16 }, // 0x25 '%' + { 129, 13, 17, 16, 2, -16 }, // 0x26 '&' + { 157, 2, 6, 5, 4, -16 }, // 0x27 ''' + { 159, 8, 23, 8, 3, -17 }, // 0x28 '(' + { 182, 8, 23, 8, 0, -16 }, // 0x29 ')' + { 205, 8, 8, 9, 4, -17 }, // 0x2A '*' + { 213, 12, 11, 14, 2, -10 }, // 0x2B '+' + { 230, 4, 6, 7, 1, -1 }, // 0x2C ',' + { 233, 6, 2, 8, 2, -7 }, // 0x2D '-' + { 235, 3, 2, 7, 2, -1 }, // 0x2E '.' + { 236, 10, 18, 7, 0, -17 }, // 0x2F '/' + { 259, 12, 17, 13, 2, -16 }, // 0x30 '0' + { 285, 7, 17, 13, 5, -16 }, // 0x31 '1' + { 300, 14, 17, 13, 1, -16 }, // 0x32 '2' + { 330, 12, 17, 13, 2, -16 }, // 0x33 '3' + { 356, 12, 17, 13, 2, -16 }, // 0x34 '4' + { 382, 13, 17, 13, 2, -16 }, // 0x35 '5' + { 410, 12, 17, 13, 2, -16 }, // 0x36 '6' + { 436, 13, 17, 13, 3, -16 }, // 0x37 '7' + { 464, 12, 17, 13, 2, -16 }, // 0x38 '8' + { 490, 12, 17, 13, 2, -16 }, // 0x39 '9' + { 516, 5, 12, 7, 3, -11 }, // 0x3A ':' + { 524, 6, 16, 7, 2, -11 }, // 0x3B ';' + { 536, 13, 12, 14, 2, -11 }, // 0x3C '<' + { 556, 13, 6, 14, 2, -8 }, // 0x3D '=' + { 566, 13, 12, 14, 1, -10 }, // 0x3E '>' + { 586, 11, 18, 13, 4, -17 }, // 0x3F '?' + { 611, 23, 21, 24, 2, -17 }, // 0x40 '@' + { 672, 16, 18, 16, 0, -17 }, // 0x41 'A' + { 708, 15, 18, 16, 2, -17 }, // 0x42 'B' + { 742, 16, 18, 17, 2, -17 }, // 0x43 'C' + { 778, 16, 18, 17, 2, -17 }, // 0x44 'D' + { 814, 16, 18, 16, 2, -17 }, // 0x45 'E' + { 850, 15, 18, 14, 2, -17 }, // 0x46 'F' + { 884, 16, 18, 19, 3, -17 }, // 0x47 'G' + { 920, 17, 18, 17, 2, -17 }, // 0x48 'H' + { 959, 6, 18, 7, 2, -17 }, // 0x49 'I' + { 973, 13, 18, 12, 1, -17 }, // 0x4A 'J' + { 1003, 18, 18, 16, 2, -17 }, // 0x4B 'K' + { 1044, 11, 18, 13, 2, -17 }, // 0x4C 'L' + { 1069, 20, 18, 20, 2, -17 }, // 0x4D 'M' + { 1114, 17, 18, 18, 2, -17 }, // 0x4E 'N' + { 1153, 17, 18, 18, 2, -17 }, // 0x4F 'O' + { 1192, 15, 18, 15, 2, -17 }, // 0x50 'P' + { 1226, 18, 19, 19, 2, -17 }, // 0x51 'Q' + { 1269, 16, 18, 17, 2, -17 }, // 0x52 'R' + { 1305, 15, 18, 16, 2, -17 }, // 0x53 'S' + { 1339, 14, 18, 15, 4, -17 }, // 0x54 'T' + { 1371, 16, 18, 17, 3, -17 }, // 0x55 'U' + { 1407, 15, 18, 15, 4, -17 }, // 0x56 'V' + { 1441, 22, 18, 22, 4, -17 }, // 0x57 'W' + { 1491, 19, 18, 16, 0, -17 }, // 0x58 'X' + { 1534, 16, 18, 16, 4, -17 }, // 0x59 'Y' + { 1570, 17, 18, 15, 1, -17 }, // 0x5A 'Z' + { 1609, 10, 23, 7, 0, -17 }, // 0x5B '[' + { 1638, 3, 18, 7, 4, -17 }, // 0x5C '\' + { 1645, 10, 23, 7, -1, -16 }, // 0x5D ']' + { 1674, 10, 9, 11, 2, -16 }, // 0x5E '^' + { 1686, 14, 1, 13, -1, 4 }, // 0x5F '_' + { 1688, 4, 4, 8, 4, -17 }, // 0x60 '`' + { 1690, 11, 13, 13, 2, -12 }, // 0x61 'a' + { 1708, 13, 18, 13, 1, -17 }, // 0x62 'b' + { 1738, 11, 13, 12, 2, -12 }, // 0x63 'c' + { 1756, 14, 18, 13, 2, -17 }, // 0x64 'd' + { 1788, 12, 13, 13, 2, -12 }, // 0x65 'e' + { 1808, 8, 18, 6, 2, -17 }, // 0x66 'f' + { 1826, 14, 18, 13, 1, -12 }, // 0x67 'g' + { 1858, 12, 18, 13, 1, -17 }, // 0x68 'h' + { 1885, 5, 18, 5, 2, -17 }, // 0x69 'i' + { 1897, 9, 23, 6, -1, -17 }, // 0x6A 'j' + { 1923, 13, 18, 12, 1, -17 }, // 0x6B 'k' + { 1953, 5, 18, 5, 2, -17 }, // 0x6C 'l' + { 1965, 19, 13, 20, 1, -12 }, // 0x6D 'm' + { 1996, 12, 13, 13, 1, -12 }, // 0x6E 'n' + { 2016, 12, 13, 13, 2, -12 }, // 0x6F 'o' + { 2036, 14, 18, 14, 0, -12 }, // 0x70 'p' + { 2068, 13, 18, 13, 2, -12 }, // 0x71 'q' + { 2098, 9, 13, 8, 1, -12 }, // 0x72 'r' + { 2113, 12, 13, 12, 1, -12 }, // 0x73 's' + { 2133, 7, 16, 6, 2, -15 }, // 0x74 't' + { 2147, 12, 13, 13, 2, -12 }, // 0x75 'u' + { 2167, 11, 13, 12, 3, -12 }, // 0x76 'v' + { 2185, 17, 13, 17, 3, -12 }, // 0x77 'w' + { 2213, 14, 13, 12, 0, -12 }, // 0x78 'x' + { 2236, 14, 18, 11, 0, -12 }, // 0x79 'y' + { 2268, 12, 13, 12, 1, -12 }, // 0x7A 'z' + { 2288, 8, 23, 8, 3, -17 }, // 0x7B '{' + { 2311, 6, 23, 6, 1, -17 }, // 0x7C '|' + { 2329, 9, 23, 8, -1, -16 }, // 0x7D '}' + { 2355, 11, 5, 14, 3, -10 } }; // 0x7E '~' + +const GFXfont FreeSansOblique12pt7b PROGMEM = { + (uint8_t *)FreeSansOblique12pt7bBitmaps, + (GFXglyph *)FreeSansOblique12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 3034 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansOblique18pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansOblique18pt7b.h new file mode 100644 index 0000000..2a18a3f --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansOblique18pt7b.h @@ -0,0 +1,518 @@ +const uint8_t FreeSansOblique18pt7bBitmaps[] PROGMEM = { + 0x03, 0x83, 0x81, 0xC0, 0xE0, 0x70, 0x78, 0x38, 0x1C, 0x0E, 0x07, 0x07, + 0x83, 0x81, 0xC0, 0xE0, 0x60, 0x30, 0x30, 0x18, 0x0C, 0x04, 0x00, 0x00, + 0x01, 0xC0, 0xE0, 0x70, 0x78, 0x00, 0x71, 0xDC, 0x7F, 0x3F, 0x8E, 0xE3, + 0xB8, 0xEC, 0x33, 0x0C, 0xC3, 0x00, 0x00, 0x38, 0x70, 0x01, 0xC3, 0x80, + 0x0C, 0x18, 0x00, 0xE1, 0xC0, 0x06, 0x0C, 0x00, 0x70, 0xE0, 0x03, 0x87, + 0x03, 0xFF, 0xFF, 0x1F, 0xFF, 0xF0, 0xFF, 0xFF, 0x80, 0x60, 0xC0, 0x07, + 0x0E, 0x00, 0x30, 0x60, 0x03, 0x87, 0x00, 0x18, 0x30, 0x1F, 0xFF, 0xF8, + 0xFF, 0xFF, 0xC7, 0xFF, 0xFC, 0x07, 0x0E, 0x00, 0x30, 0x70, 0x03, 0x87, + 0x00, 0x1C, 0x38, 0x00, 0xC1, 0x80, 0x0E, 0x1C, 0x00, 0x60, 0xC0, 0x00, + 0x00, 0x0C, 0x00, 0x07, 0xF8, 0x01, 0xFF, 0xC0, 0x3F, 0xFE, 0x07, 0x99, + 0xF0, 0xF1, 0x87, 0x0E, 0x18, 0x71, 0xC1, 0x87, 0x1C, 0x38, 0x01, 0xC3, + 0x00, 0x1C, 0x30, 0x01, 0xE3, 0x00, 0x0F, 0xB0, 0x00, 0xFF, 0x80, 0x03, + 0xFF, 0x00, 0x0F, 0xF8, 0x00, 0x6F, 0xC0, 0x06, 0x3C, 0x00, 0xC1, 0xCE, + 0x0C, 0x1C, 0xE0, 0xC1, 0xCE, 0x0C, 0x38, 0xF1, 0xC3, 0x8F, 0x98, 0xF0, + 0x7F, 0xFE, 0x03, 0xFF, 0xC0, 0x0F, 0xF0, 0x00, 0x30, 0x00, 0x03, 0x00, + 0x00, 0x30, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x07, 0x03, 0xE0, 0x03, + 0x81, 0xFC, 0x00, 0xC0, 0xFF, 0x00, 0x60, 0x70, 0xE0, 0x38, 0x38, 0x18, + 0x1C, 0x0C, 0x06, 0x0E, 0x03, 0x01, 0x83, 0x00, 0xC0, 0xE1, 0x80, 0x38, + 0x70, 0xE0, 0x0F, 0xF8, 0x70, 0x01, 0xFC, 0x18, 0x00, 0x3E, 0x0C, 0x00, + 0x00, 0x06, 0x07, 0x80, 0x03, 0x87, 0xF8, 0x00, 0xC3, 0xFE, 0x00, 0x61, + 0xE1, 0xC0, 0x30, 0x60, 0x30, 0x1C, 0x30, 0x0C, 0x0E, 0x0C, 0x03, 0x03, + 0x03, 0x01, 0x81, 0x80, 0xE1, 0xE0, 0xC0, 0x1F, 0xF0, 0x70, 0x07, 0xF8, + 0x18, 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x07, 0xF8, 0x00, 0xFF, 0xC0, + 0x1E, 0x3C, 0x03, 0xC1, 0xC0, 0x38, 0x1C, 0x03, 0x81, 0xC0, 0x38, 0x38, + 0x03, 0xC7, 0x00, 0x1D, 0xE0, 0x01, 0xFC, 0x00, 0x1F, 0x00, 0x07, 0xF0, + 0x01, 0xF7, 0x87, 0x3C, 0x3C, 0xE7, 0x81, 0xCE, 0x70, 0x1F, 0xCE, 0x00, + 0xFC, 0xE0, 0x07, 0x8E, 0x00, 0x78, 0xF0, 0x1F, 0x8F, 0x87, 0xFC, 0x7F, + 0xF9, 0xC3, 0xFE, 0x1E, 0x1F, 0x80, 0xE0, 0x77, 0xFE, 0xEE, 0xCC, 0xC0, + 0x00, 0x30, 0x06, 0x00, 0xC0, 0x18, 0x03, 0x80, 0x30, 0x06, 0x00, 0xE0, + 0x0C, 0x01, 0xC0, 0x18, 0x03, 0x80, 0x38, 0x07, 0x00, 0x70, 0x07, 0x00, + 0x70, 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x00, + 0xE0, 0x0E, 0x00, 0xE0, 0x06, 0x00, 0x70, 0x07, 0x00, 0x30, 0x03, 0x00, + 0x18, 0x00, 0x01, 0x80, 0x0C, 0x00, 0xC0, 0x0E, 0x00, 0xE0, 0x06, 0x00, + 0x70, 0x07, 0x00, 0x70, 0x07, 0x00, 0x70, 0x07, 0x00, 0x70, 0x07, 0x00, + 0x70, 0x07, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x01, 0xC0, 0x1C, 0x03, + 0x80, 0x38, 0x03, 0x00, 0x70, 0x06, 0x00, 0xC0, 0x1C, 0x01, 0x80, 0x30, + 0x06, 0x00, 0xC0, 0x00, 0x06, 0x01, 0x84, 0x47, 0xF7, 0xFF, 0xCF, 0xC1, + 0xE0, 0xD8, 0x67, 0x18, 0xC0, 0x00, 0x70, 0x00, 0x1C, 0x00, 0x0F, 0x00, + 0x03, 0x80, 0x00, 0xE0, 0x00, 0x38, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xC0, 0x70, 0x00, 0x1C, 0x00, 0x07, 0x00, 0x01, 0xC0, 0x00, 0xE0, + 0x00, 0x38, 0x00, 0x0E, 0x00, 0x3B, 0xDC, 0x21, 0x18, 0x98, 0xFF, 0xFF, + 0xFF, 0xE0, 0x7F, 0xFE, 0x00, 0x06, 0x00, 0x18, 0x00, 0x30, 0x00, 0xC0, + 0x01, 0x80, 0x06, 0x00, 0x0C, 0x00, 0x30, 0x00, 0x60, 0x01, 0x80, 0x03, + 0x00, 0x0C, 0x00, 0x18, 0x00, 0x60, 0x00, 0xC0, 0x03, 0x00, 0x06, 0x00, + 0x18, 0x00, 0x20, 0x00, 0xC0, 0x03, 0x00, 0x06, 0x00, 0x18, 0x00, 0x30, + 0x00, 0xC0, 0x01, 0x80, 0x00, 0x00, 0x7C, 0x00, 0x7F, 0xC0, 0x7F, 0xF8, + 0x3E, 0x1E, 0x0F, 0x03, 0xC7, 0x80, 0x71, 0xC0, 0x1C, 0xE0, 0x07, 0x38, + 0x01, 0xDE, 0x00, 0x77, 0x00, 0x1D, 0xC0, 0x0F, 0x70, 0x03, 0xFC, 0x00, + 0xEE, 0x00, 0x3B, 0x80, 0x0E, 0xE0, 0x07, 0xB8, 0x01, 0xCE, 0x00, 0xF3, + 0x80, 0x38, 0xF0, 0x1E, 0x1E, 0x1F, 0x07, 0xFF, 0x80, 0xFF, 0xC0, 0x0F, + 0x80, 0x00, 0x00, 0xC0, 0x70, 0x3C, 0x3E, 0xFF, 0xBF, 0xEF, 0xF8, 0x1E, + 0x07, 0x01, 0xC0, 0x70, 0x1C, 0x0F, 0x03, 0x80, 0xE0, 0x38, 0x0E, 0x07, + 0x81, 0xC0, 0x70, 0x1C, 0x07, 0x01, 0xC0, 0xE0, 0x38, 0x00, 0x00, 0x3F, + 0x00, 0x0F, 0xFC, 0x03, 0xFF, 0xE0, 0x7C, 0x1E, 0x07, 0x80, 0xF0, 0xF0, + 0x07, 0x0E, 0x00, 0x70, 0xE0, 0x07, 0x00, 0x00, 0x70, 0x00, 0x0E, 0x00, + 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x0F, 0x80, 0x03, 0xF0, 0x00, 0xFC, 0x00, + 0x1F, 0x00, 0x07, 0xC0, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0x80, 0x00, + 0x70, 0x00, 0x07, 0x00, 0x00, 0xFF, 0xFF, 0x8F, 0xFF, 0xF0, 0xFF, 0xFF, + 0x00, 0x00, 0x7E, 0x00, 0x3F, 0xF0, 0x0F, 0xFF, 0x03, 0xC1, 0xF0, 0x70, + 0x0E, 0x1C, 0x01, 0xC3, 0x80, 0x38, 0xE0, 0x07, 0x00, 0x01, 0xC0, 0x00, + 0xF0, 0x03, 0xFC, 0x00, 0x7F, 0x00, 0x0F, 0xF0, 0x00, 0x1F, 0x00, 0x00, + 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x9C, 0x00, 0x73, 0x80, 0x1E, 0x70, 0x03, + 0x8F, 0x00, 0xF1, 0xF0, 0x7C, 0x1F, 0xFF, 0x01, 0xFF, 0xC0, 0x0F, 0xC0, + 0x00, 0x00, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x78, 0x00, 0x3E, 0x00, 0x1F, + 0x80, 0x0F, 0xE0, 0x07, 0xF0, 0x03, 0xDC, 0x01, 0xE7, 0x00, 0x71, 0xC0, + 0x38, 0xF0, 0x1C, 0x38, 0x0E, 0x0E, 0x07, 0x03, 0x83, 0x80, 0xE1, 0xC0, + 0x70, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x70, 0x00, 0x38, + 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x01, 0xFF, + 0xF0, 0x3F, 0xFF, 0x03, 0xFF, 0xE0, 0x78, 0x00, 0x07, 0x00, 0x00, 0x70, + 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0xFC, 0x01, 0xFF, 0xF0, 0x1F, + 0xFF, 0x83, 0xE0, 0x78, 0x3C, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xC0, + 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x18, 0x00, 0x03, 0x8E, 0x00, 0x78, + 0xE0, 0x0F, 0x0F, 0x81, 0xE0, 0x7F, 0xFC, 0x03, 0xFF, 0x80, 0x0F, 0xE0, + 0x00, 0x00, 0x7E, 0x00, 0x3F, 0xF0, 0x0F, 0xFF, 0x03, 0xE1, 0xF0, 0xF0, + 0x0E, 0x1C, 0x01, 0xC7, 0x00, 0x01, 0xE0, 0x00, 0x38, 0x00, 0x07, 0x1F, + 0x01, 0xCF, 0xF8, 0x3B, 0xFF, 0x87, 0xE0, 0xF8, 0xF0, 0x0F, 0x3C, 0x00, + 0xE7, 0x80, 0x1C, 0xE0, 0x03, 0x9C, 0x00, 0x73, 0x80, 0x1C, 0x70, 0x03, + 0x8F, 0x00, 0xE0, 0xF0, 0x78, 0x1F, 0xFF, 0x01, 0xFF, 0x80, 0x0F, 0xC0, + 0x00, 0x3F, 0xFF, 0xCF, 0xFF, 0xF7, 0xFF, 0xFC, 0x00, 0x0E, 0x00, 0x07, + 0x00, 0x03, 0x80, 0x00, 0xC0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, + 0x0E, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x78, 0x00, 0x1C, + 0x00, 0x0E, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xF0, 0x00, 0x38, 0x00, + 0x1E, 0x00, 0x07, 0x00, 0x03, 0xC0, 0x00, 0xE0, 0x00, 0x00, 0x00, 0x7E, + 0x00, 0x3F, 0xF0, 0x1F, 0xFF, 0x07, 0xC1, 0xF0, 0xE0, 0x0E, 0x38, 0x01, + 0xC7, 0x00, 0x38, 0xE0, 0x0E, 0x1C, 0x01, 0xC3, 0xC0, 0xF0, 0x3F, 0xFC, + 0x03, 0xFE, 0x01, 0xFF, 0xF0, 0x7C, 0x1E, 0x1E, 0x01, 0xE3, 0x80, 0x1C, + 0xE0, 0x03, 0x9C, 0x00, 0x73, 0x80, 0x0E, 0x70, 0x03, 0x8F, 0x00, 0xF1, + 0xF0, 0x7C, 0x1F, 0xFF, 0x01, 0xFF, 0xC0, 0x0F, 0xC0, 0x00, 0x00, 0x7E, + 0x00, 0x3F, 0xF0, 0x1F, 0xFF, 0x07, 0xC1, 0xE0, 0xE0, 0x1E, 0x38, 0x01, + 0xC7, 0x00, 0x39, 0xC0, 0x07, 0x38, 0x00, 0xE7, 0x00, 0x3C, 0xE0, 0x07, + 0x9E, 0x01, 0xE3, 0xE0, 0xFC, 0x3F, 0xFB, 0x83, 0xFE, 0xF0, 0x3F, 0x1C, + 0x00, 0x03, 0x80, 0x00, 0xF0, 0x00, 0x1C, 0x70, 0x07, 0x8E, 0x01, 0xE1, + 0xE0, 0xF8, 0x1F, 0xFE, 0x01, 0xFF, 0x80, 0x0F, 0xC0, 0x00, 0x0E, 0x3C, + 0x78, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, + 0xF1, 0xE3, 0x80, 0x07, 0x0F, 0x0F, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x78, 0x70, 0x10, 0x10, + 0x30, 0x20, 0xC0, 0x00, 0x00, 0x20, 0x00, 0x1C, 0x00, 0x1F, 0x80, 0x1F, + 0xC0, 0x0F, 0xC0, 0x0F, 0xE0, 0x07, 0xE0, 0x03, 0xF0, 0x00, 0xF0, 0x00, + 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF8, + 0x00, 0x0F, 0xC0, 0x00, 0x78, 0x00, 0x01, 0x00, 0x7F, 0xFF, 0xDF, 0xFF, + 0xF7, 0xFF, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0xFB, + 0xFF, 0xFE, 0xFF, 0xFF, 0x80, 0x10, 0x00, 0x03, 0xC0, 0x00, 0x7E, 0x00, + 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x3F, + 0x00, 0x01, 0xE0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0xFE, 0x00, 0x7E, 0x00, + 0x7F, 0x00, 0x3F, 0x00, 0x07, 0x00, 0x00, 0x80, 0x00, 0x00, 0x03, 0xF8, + 0x0F, 0xFC, 0x1F, 0xFE, 0x3C, 0x1F, 0x78, 0x07, 0x70, 0x07, 0xE0, 0x07, + 0xE0, 0x07, 0x00, 0x0E, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, + 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0F, 0x00, 0x0E, 0x00, 0x0E, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, + 0x3C, 0x00, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x07, + 0xFF, 0xFE, 0x00, 0x0F, 0xE0, 0x3F, 0x80, 0x0F, 0x80, 0x03, 0xE0, 0x0F, + 0x00, 0x00, 0xF8, 0x0F, 0x00, 0x00, 0x3C, 0x0F, 0x01, 0xF0, 0x0F, 0x0F, + 0x03, 0xFD, 0xC7, 0x8F, 0x03, 0xFE, 0xE1, 0xC7, 0x03, 0xC3, 0x60, 0xE7, + 0x03, 0xC0, 0xF0, 0x77, 0x83, 0xC0, 0x70, 0x3B, 0x83, 0xC0, 0x78, 0x1D, + 0xC1, 0xC0, 0x38, 0x1F, 0xC1, 0xE0, 0x1C, 0x0E, 0xE0, 0xE0, 0x1C, 0x0F, + 0x70, 0x70, 0x0E, 0x07, 0x38, 0x38, 0x0E, 0x07, 0x9C, 0x1C, 0x0F, 0x07, + 0x8E, 0x0F, 0x0F, 0x8F, 0x87, 0x03, 0xFD, 0xFF, 0x83, 0xC1, 0xFC, 0xFF, + 0x80, 0xE0, 0x7C, 0x3F, 0x00, 0x78, 0x00, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x00, 0x07, 0x80, 0x00, 0x00, 0x01, 0xF8, 0x07, 0x00, 0x00, 0x7F, 0xFF, + 0x80, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x00, 0x01, + 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x80, 0x00, 0xFF, + 0x00, 0x01, 0xDE, 0x00, 0x07, 0x9C, 0x00, 0x0E, 0x38, 0x00, 0x3C, 0x70, + 0x00, 0x70, 0xF0, 0x01, 0xC1, 0xE0, 0x07, 0x83, 0xC0, 0x0E, 0x07, 0x80, + 0x38, 0x07, 0x00, 0x70, 0x0E, 0x01, 0xFF, 0xFC, 0x03, 0xFF, 0xFC, 0x0F, + 0xFF, 0xF8, 0x1C, 0x00, 0xF0, 0x70, 0x01, 0xE1, 0xE0, 0x01, 0xC3, 0x80, + 0x03, 0x8F, 0x00, 0x07, 0x1C, 0x00, 0x0E, 0x78, 0x00, 0x1E, 0xE0, 0x00, + 0x3C, 0x07, 0xFF, 0xC0, 0x3F, 0xFF, 0x81, 0xFF, 0xFC, 0x0E, 0x00, 0xF0, + 0xF0, 0x03, 0x87, 0x00, 0x1C, 0x38, 0x00, 0xE1, 0xC0, 0x07, 0x0E, 0x00, + 0x70, 0xF0, 0x03, 0x87, 0x00, 0x78, 0x3F, 0xFF, 0x81, 0xFF, 0xF8, 0x0F, + 0xFF, 0xF0, 0xE0, 0x03, 0xC7, 0x00, 0x0E, 0x38, 0x00, 0x71, 0xC0, 0x03, + 0x9E, 0x00, 0x1C, 0xE0, 0x00, 0xE7, 0x00, 0x0E, 0x38, 0x00, 0xF1, 0xC0, + 0x0F, 0x1F, 0xFF, 0xF0, 0xFF, 0xFF, 0x07, 0xFF, 0xE0, 0x00, 0x00, 0x1F, + 0x80, 0x03, 0xFF, 0x80, 0x1F, 0xFF, 0x01, 0xF8, 0x3E, 0x07, 0x80, 0x38, + 0x38, 0x00, 0xF1, 0xC0, 0x01, 0xCF, 0x00, 0x07, 0x38, 0x00, 0x01, 0xE0, + 0x00, 0x07, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x70, 0x00, 0x03, 0x80, 0x00, + 0x0E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x7B, 0x80, 0x01, 0xCE, + 0x00, 0x0F, 0x3C, 0x00, 0x38, 0x70, 0x01, 0xE1, 0xE0, 0x0F, 0x07, 0xC0, + 0xF8, 0x0F, 0xFF, 0xC0, 0x1F, 0xFC, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xFF, + 0xC0, 0x0F, 0xFF, 0xE0, 0x1F, 0xFF, 0xE0, 0x38, 0x03, 0xE0, 0xF0, 0x03, + 0xC1, 0xC0, 0x03, 0x83, 0x80, 0x03, 0x87, 0x00, 0x07, 0x1E, 0x00, 0x0E, + 0x3C, 0x00, 0x1C, 0x70, 0x00, 0x38, 0xE0, 0x00, 0x71, 0xC0, 0x00, 0xE7, + 0x80, 0x03, 0x8F, 0x00, 0x07, 0x1C, 0x00, 0x0E, 0x38, 0x00, 0x3C, 0x70, + 0x00, 0x71, 0xE0, 0x01, 0xE3, 0x80, 0x03, 0x87, 0x00, 0x0E, 0x0E, 0x00, + 0x3C, 0x1C, 0x01, 0xF0, 0x7F, 0xFF, 0xC0, 0xFF, 0xFE, 0x01, 0xFF, 0xF0, + 0x00, 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xFC, 0x1F, 0xFF, 0xF0, 0x38, 0x00, + 0x00, 0xF0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x70, 0x00, 0x00, 0xFF, 0xFF, 0x81, + 0xFF, 0xFF, 0x07, 0xFF, 0xFE, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, + 0x00, 0x00, 0x70, 0x00, 0x01, 0xE0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, + 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x7F, 0xFF, 0xF0, 0xFF, 0xFF, + 0xC1, 0xFF, 0xFF, 0x80, 0x07, 0xFF, 0xFC, 0x1F, 0xFF, 0xF0, 0x7F, 0xFF, + 0xC1, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x03, + 0x80, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xC0, 0x00, 0x07, 0xFF, + 0xF0, 0x1F, 0xFF, 0xC0, 0xFF, 0xFF, 0x03, 0x80, 0x00, 0x0E, 0x00, 0x00, + 0x38, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1C, 0x00, 0x00, 0x70, + 0x00, 0x01, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xE0, 0x00, + 0x03, 0x80, 0x00, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x7F, 0xF8, 0x01, 0xFF, + 0xFC, 0x03, 0xE0, 0x3E, 0x07, 0x80, 0x0E, 0x0F, 0x00, 0x0F, 0x1E, 0x00, + 0x07, 0x1C, 0x00, 0x07, 0x38, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, + 0x00, 0x70, 0x00, 0x00, 0xF0, 0x07, 0xFE, 0xE0, 0x07, 0xFE, 0xE0, 0x07, + 0xFE, 0xE0, 0x00, 0x0E, 0xE0, 0x00, 0x0E, 0xE0, 0x00, 0x0E, 0xE0, 0x00, + 0x1C, 0xF0, 0x00, 0x3C, 0x70, 0x00, 0x7C, 0x78, 0x00, 0xFC, 0x3E, 0x03, + 0xDC, 0x1F, 0xFF, 0x98, 0x0F, 0xFE, 0x18, 0x03, 0xF8, 0x18, 0x07, 0x00, + 0x07, 0x83, 0x80, 0x03, 0xC1, 0xC0, 0x01, 0xC0, 0xE0, 0x00, 0xE0, 0xF0, + 0x00, 0x70, 0x70, 0x00, 0x78, 0x38, 0x00, 0x3C, 0x1C, 0x00, 0x1C, 0x1E, + 0x00, 0x0E, 0x0F, 0x00, 0x07, 0x07, 0x00, 0x07, 0x83, 0xFF, 0xFF, 0x81, + 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, 0xE0, 0xE0, 0x00, 0x70, 0x70, 0x00, 0x78, + 0x38, 0x00, 0x38, 0x1C, 0x00, 0x1C, 0x1E, 0x00, 0x0E, 0x0E, 0x00, 0x0F, + 0x07, 0x00, 0x07, 0x83, 0x80, 0x03, 0x81, 0xC0, 0x01, 0xC1, 0xE0, 0x00, + 0xE0, 0xE0, 0x00, 0xF0, 0x70, 0x00, 0x78, 0x00, 0x07, 0x0F, 0x0F, 0x0E, + 0x0E, 0x0E, 0x0E, 0x1E, 0x1C, 0x1C, 0x1C, 0x1C, 0x3C, 0x3C, 0x38, 0x38, + 0x38, 0x38, 0x78, 0x70, 0x70, 0x70, 0x70, 0xF0, 0xF0, 0xE0, 0x00, 0x01, + 0xC0, 0x00, 0x70, 0x00, 0x3C, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, + 0x00, 0x38, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x01, 0xC0, 0x00, 0x70, 0x00, + 0x1C, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x1E, + 0x1C, 0x07, 0x0E, 0x01, 0xC3, 0x80, 0x70, 0xE0, 0x3C, 0x38, 0x0E, 0x0F, + 0x0F, 0x81, 0xFF, 0xC0, 0x7F, 0xE0, 0x07, 0xE0, 0x00, 0x07, 0x00, 0x07, + 0x83, 0x80, 0x07, 0x81, 0xC0, 0x0F, 0x00, 0xE0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0x70, 0x0F, 0x00, 0x38, 0x0F, 0x00, 0x1C, 0x1F, 0x00, 0x1E, 0x1E, + 0x00, 0x0F, 0x1E, 0x00, 0x07, 0x1E, 0x00, 0x03, 0x9F, 0x00, 0x01, 0xDF, + 0xC0, 0x01, 0xFC, 0xE0, 0x00, 0xFC, 0x78, 0x00, 0x7C, 0x1C, 0x00, 0x3C, + 0x0F, 0x00, 0x1C, 0x07, 0x80, 0x1E, 0x01, 0xE0, 0x0E, 0x00, 0xF0, 0x07, + 0x00, 0x38, 0x03, 0x80, 0x1E, 0x01, 0xC0, 0x07, 0x01, 0xE0, 0x03, 0xC0, + 0xE0, 0x00, 0xE0, 0x70, 0x00, 0x78, 0x00, 0x07, 0x00, 0x07, 0x00, 0x07, + 0x00, 0x07, 0x00, 0x0F, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x1E, + 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x3C, 0x00, 0x38, + 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x78, 0x00, 0x70, 0x00, 0x70, + 0x00, 0x70, 0x00, 0x70, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x07, + 0xC0, 0x00, 0xF8, 0x3E, 0x00, 0x07, 0xC1, 0xF0, 0x00, 0x7E, 0x0F, 0x80, + 0x03, 0xF0, 0xFC, 0x00, 0x3F, 0x07, 0x70, 0x01, 0xF8, 0x3B, 0x80, 0x1D, + 0xC1, 0xDC, 0x00, 0xEE, 0x0E, 0xE0, 0x0E, 0xE0, 0xE7, 0x00, 0x77, 0x07, + 0x38, 0x07, 0x38, 0x39, 0xC0, 0x31, 0xC1, 0xCE, 0x03, 0x9E, 0x1E, 0x38, + 0x38, 0xE0, 0xE1, 0xC1, 0xC7, 0x07, 0x0E, 0x1C, 0x38, 0x38, 0x70, 0xE1, + 0xC1, 0xC3, 0x8E, 0x1E, 0x1E, 0x1C, 0x70, 0xE0, 0xE0, 0xE7, 0x07, 0x07, + 0x07, 0x38, 0x38, 0x38, 0x1F, 0x81, 0xC1, 0xC0, 0xF8, 0x1E, 0x1C, 0x07, + 0xC0, 0xE0, 0xE0, 0x3C, 0x07, 0x07, 0x01, 0xE0, 0x38, 0x00, 0x07, 0x80, + 0x03, 0x83, 0xE0, 0x01, 0xC1, 0xF0, 0x00, 0xE0, 0xF8, 0x00, 0xE0, 0xFE, + 0x00, 0x70, 0x7F, 0x00, 0x38, 0x3B, 0xC0, 0x1C, 0x1D, 0xE0, 0x1E, 0x0E, + 0x70, 0x0E, 0x0E, 0x3C, 0x07, 0x07, 0x0E, 0x03, 0x83, 0x87, 0x81, 0xC1, + 0xC3, 0xC1, 0xE1, 0xE0, 0xE0, 0xE0, 0xE0, 0x78, 0x70, 0x70, 0x1C, 0x38, + 0x38, 0x0F, 0x1C, 0x1C, 0x07, 0x9E, 0x1E, 0x01, 0xCE, 0x0E, 0x00, 0xF7, + 0x07, 0x00, 0x3B, 0x83, 0x80, 0x1F, 0xC1, 0xC0, 0x07, 0xC1, 0xC0, 0x03, + 0xE0, 0xE0, 0x01, 0xF0, 0x70, 0x00, 0x78, 0x00, 0x00, 0x1F, 0xC0, 0x00, + 0xFF, 0xF0, 0x01, 0xFF, 0xF8, 0x03, 0xE0, 0x7C, 0x07, 0x80, 0x1E, 0x0F, + 0x00, 0x0E, 0x1C, 0x00, 0x0F, 0x3C, 0x00, 0x07, 0x38, 0x00, 0x07, 0x70, + 0x00, 0x07, 0x70, 0x00, 0x07, 0x70, 0x00, 0x07, 0xE0, 0x00, 0x07, 0xE0, + 0x00, 0x0F, 0xE0, 0x00, 0x0E, 0xE0, 0x00, 0x0E, 0xE0, 0x00, 0x0E, 0xE0, + 0x00, 0x1C, 0xE0, 0x00, 0x1C, 0xF0, 0x00, 0x38, 0x70, 0x00, 0x78, 0x78, + 0x00, 0xF0, 0x3E, 0x07, 0xE0, 0x1F, 0xFF, 0xC0, 0x0F, 0xFF, 0x00, 0x03, + 0xF8, 0x00, 0x07, 0xFF, 0xE0, 0x1F, 0xFF, 0xC0, 0x7F, 0xFF, 0x81, 0xC0, + 0x1F, 0x0F, 0x00, 0x3C, 0x38, 0x00, 0x70, 0xE0, 0x01, 0xC3, 0x80, 0x07, + 0x1E, 0x00, 0x1C, 0x78, 0x00, 0xE1, 0xC0, 0x07, 0x87, 0x00, 0x3C, 0x1F, + 0xFF, 0xE0, 0xFF, 0xFF, 0x03, 0xFF, 0xF0, 0x0E, 0x00, 0x00, 0x38, 0x00, + 0x00, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1C, 0x00, 0x00, 0x70, 0x00, 0x01, + 0xC0, 0x00, 0x07, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xE0, 0x00, 0x03, 0x80, + 0x00, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x3F, 0xFC, 0x00, 0x7F, 0xFF, 0x00, + 0x7C, 0x07, 0xC0, 0x78, 0x00, 0xF0, 0x78, 0x00, 0x38, 0x78, 0x00, 0x1E, + 0x78, 0x00, 0x07, 0x38, 0x00, 0x03, 0xBC, 0x00, 0x01, 0xDC, 0x00, 0x00, + 0xEE, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0x80, 0x00, + 0x1D, 0xC0, 0x00, 0x0E, 0xE0, 0x00, 0x0F, 0x70, 0x00, 0x07, 0x38, 0x00, + 0x87, 0x9E, 0x00, 0xE7, 0x87, 0x00, 0x7F, 0x83, 0xC0, 0x1F, 0x80, 0xF8, + 0x1F, 0x80, 0x3F, 0xFF, 0xE0, 0x0F, 0xFF, 0x78, 0x01, 0xFE, 0x1E, 0x00, + 0x00, 0x07, 0x00, 0x00, 0x02, 0x00, 0x07, 0xFF, 0xF0, 0x0F, 0xFF, 0xF8, + 0x1F, 0xFF, 0xF0, 0x38, 0x00, 0xF0, 0xF0, 0x00, 0xE1, 0xC0, 0x01, 0xC3, + 0x80, 0x03, 0x87, 0x00, 0x07, 0x1E, 0x00, 0x0E, 0x3C, 0x00, 0x38, 0x70, + 0x00, 0xF0, 0xE0, 0x03, 0xC1, 0xFF, 0xFE, 0x07, 0xFF, 0xF8, 0x0F, 0xFF, + 0xF8, 0x1C, 0x00, 0x78, 0x38, 0x00, 0x70, 0x70, 0x00, 0xE1, 0xE0, 0x01, + 0xC3, 0x80, 0x03, 0x87, 0x00, 0x06, 0x0E, 0x00, 0x1C, 0x1C, 0x00, 0x38, + 0x78, 0x00, 0x70, 0xE0, 0x00, 0xE1, 0xC0, 0x01, 0xE0, 0x00, 0x3F, 0xC0, + 0x07, 0xFF, 0xC0, 0x3F, 0xFF, 0x81, 0xF0, 0x1E, 0x0F, 0x00, 0x3C, 0x38, + 0x00, 0x71, 0xC0, 0x01, 0xC7, 0x00, 0x07, 0x1C, 0x00, 0x00, 0x78, 0x00, + 0x01, 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x07, 0xFE, 0x00, 0x07, 0xFF, 0x00, + 0x03, 0xFE, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xF3, 0x80, 0x01, 0xCE, 0x00, + 0x07, 0x38, 0x00, 0x18, 0xE0, 0x00, 0xE3, 0xC0, 0x07, 0x07, 0x80, 0x7C, + 0x1F, 0xFF, 0xE0, 0x3F, 0xFE, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x1E, 0x00, + 0x01, 0xE0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x03, 0xC0, + 0x00, 0x38, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x03, 0x80, 0x00, 0x78, + 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0xF0, 0x00, 0x0F, + 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x1E, 0x00, 0x01, + 0xE0, 0x00, 0x0E, 0x00, 0x0F, 0x0E, 0x00, 0x0F, 0x0E, 0x00, 0x0E, 0x0E, + 0x00, 0x0E, 0x1E, 0x00, 0x0E, 0x1C, 0x00, 0x1E, 0x1C, 0x00, 0x1C, 0x1C, + 0x00, 0x1C, 0x3C, 0x00, 0x1C, 0x3C, 0x00, 0x1C, 0x38, 0x00, 0x3C, 0x38, + 0x00, 0x38, 0x38, 0x00, 0x38, 0x78, 0x00, 0x38, 0x70, 0x00, 0x78, 0x70, + 0x00, 0x78, 0x70, 0x00, 0x70, 0xF0, 0x00, 0x70, 0xF0, 0x00, 0x70, 0xE0, + 0x00, 0xF0, 0xE0, 0x00, 0xE0, 0xF0, 0x03, 0xE0, 0x78, 0x0F, 0xC0, 0x7F, + 0xFF, 0x80, 0x1F, 0xFE, 0x00, 0x07, 0xF0, 0x00, 0xE0, 0x00, 0x3F, 0x80, + 0x03, 0xFC, 0x00, 0x1D, 0xE0, 0x01, 0xE7, 0x00, 0x0E, 0x38, 0x00, 0xE1, + 0xC0, 0x07, 0x0E, 0x00, 0x70, 0x70, 0x07, 0x83, 0xC0, 0x38, 0x1E, 0x03, + 0xC0, 0xF0, 0x1C, 0x03, 0x81, 0xE0, 0x1C, 0x0E, 0x00, 0xE0, 0xF0, 0x07, + 0x07, 0x00, 0x3C, 0x70, 0x01, 0xE3, 0x80, 0x0F, 0x38, 0x00, 0x39, 0xC0, + 0x01, 0xDC, 0x00, 0x0E, 0xE0, 0x00, 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x1F, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0xE0, 0x03, 0x80, 0x0E, 0xE0, 0x07, 0x80, + 0x1E, 0xE0, 0x07, 0xC0, 0x1E, 0xE0, 0x0F, 0xC0, 0x1C, 0xE0, 0x0F, 0xC0, + 0x3C, 0xE0, 0x1F, 0xC0, 0x38, 0xE0, 0x1D, 0xC0, 0x78, 0xE0, 0x3D, 0xC0, + 0x70, 0xE0, 0x39, 0xC0, 0xF0, 0xE0, 0x79, 0xC0, 0xE0, 0xE0, 0x71, 0xC0, + 0xE0, 0xE0, 0xF1, 0xC1, 0xC0, 0xE0, 0xE1, 0xC1, 0xC0, 0xE1, 0xE1, 0xC3, + 0xC0, 0x61, 0xC1, 0xC3, 0x80, 0x63, 0xC1, 0xC7, 0x80, 0x63, 0x80, 0xE7, + 0x00, 0x67, 0x80, 0xEF, 0x00, 0x67, 0x00, 0xEE, 0x00, 0x7F, 0x00, 0xEE, + 0x00, 0x7E, 0x00, 0xFC, 0x00, 0x7E, 0x00, 0xFC, 0x00, 0x7C, 0x00, 0xF8, + 0x00, 0x7C, 0x00, 0xF8, 0x00, 0x78, 0x00, 0xF8, 0x00, 0x78, 0x00, 0xF0, + 0x00, 0x03, 0xC0, 0x03, 0xC0, 0x78, 0x00, 0xF0, 0x07, 0x80, 0x1C, 0x00, + 0xF0, 0x07, 0x80, 0x0F, 0x01, 0xE0, 0x01, 0xE0, 0x78, 0x00, 0x1C, 0x1E, + 0x00, 0x03, 0xC7, 0x80, 0x00, 0x39, 0xE0, 0x00, 0x07, 0xB8, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x3E, 0x00, + 0x00, 0x0F, 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xF3, 0x80, 0x00, 0x3C, + 0x78, 0x00, 0x0F, 0x0F, 0x00, 0x03, 0xC0, 0xF0, 0x00, 0x70, 0x1E, 0x00, + 0x1E, 0x01, 0xE0, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x03, 0xC0, 0x78, 0x00, + 0x78, 0x1E, 0x00, 0x0F, 0x00, 0xF0, 0x00, 0x3C, 0xE0, 0x00, 0x71, 0xE0, + 0x01, 0xE3, 0xC0, 0x07, 0x83, 0xC0, 0x1E, 0x07, 0x80, 0x78, 0x07, 0x00, + 0xE0, 0x0F, 0x03, 0xC0, 0x1E, 0x0F, 0x00, 0x1C, 0x3C, 0x00, 0x3C, 0xF0, + 0x00, 0x39, 0xC0, 0x00, 0x7F, 0x80, 0x00, 0xFE, 0x00, 0x00, 0xF8, 0x00, + 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, + 0x1C, 0x00, 0x00, 0x78, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xC0, 0x00, 0x03, + 0x80, 0x00, 0x07, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0x81, + 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0xFF, 0xFF, 0xE0, 0xFF, + 0xFF, 0xF0, 0x7F, 0xFF, 0xF8, 0x00, 0x01, 0xF8, 0x1F, 0xC0, 0xFE, 0x07, + 0x00, 0x38, 0x03, 0xC0, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x03, 0xC0, + 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, + 0x00, 0x38, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x78, 0x03, 0x80, + 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x70, 0x03, 0xF8, 0x1F, 0xC0, 0xFE, 0x00, + 0xCC, 0xCC, 0xCC, 0x46, 0x66, 0x66, 0x66, 0x66, 0x66, 0x62, 0x33, 0x33, + 0x33, 0x03, 0xF8, 0x1F, 0xC0, 0xFE, 0x00, 0x70, 0x07, 0x00, 0x38, 0x01, + 0xC0, 0x0E, 0x00, 0xF0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x0E, 0x00, 0xE0, + 0x07, 0x00, 0x38, 0x01, 0xC0, 0x0E, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, + 0xC0, 0x1E, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x1E, 0x00, 0xE0, + 0x07, 0x03, 0xF8, 0x1F, 0xC0, 0xFC, 0x00, 0x00, 0xF0, 0x03, 0xC0, 0x1F, + 0x00, 0x7C, 0x03, 0xB8, 0x1C, 0xE0, 0x63, 0x83, 0x8E, 0x1C, 0x38, 0x60, + 0x73, 0x81, 0xCC, 0x07, 0x70, 0x1F, 0x80, 0x70, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xC0, 0xF1, 0xC3, 0x86, 0x0C, 0x00, 0xFE, 0x01, 0xFF, 0xE0, 0xFF, + 0xFC, 0x3C, 0x0F, 0x1C, 0x01, 0xC0, 0x00, 0x70, 0x00, 0x1C, 0x00, 0x0E, + 0x00, 0x1F, 0x83, 0xFF, 0xE3, 0xFE, 0x39, 0xF0, 0x1E, 0xF0, 0x07, 0x38, + 0x01, 0xCE, 0x00, 0xF3, 0xC0, 0xFC, 0xFF, 0xF7, 0x9F, 0xF1, 0xE1, 0xF0, + 0x38, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0xF0, + 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x71, 0xF0, 0x0E, 0xFF, 0x83, 0xFF, + 0xF8, 0x7F, 0x0F, 0x0F, 0x80, 0xF1, 0xE0, 0x0E, 0x38, 0x01, 0xCF, 0x00, + 0x39, 0xE0, 0x07, 0x38, 0x00, 0xE7, 0x00, 0x38, 0xE0, 0x07, 0x3C, 0x00, + 0xE7, 0x80, 0x38, 0xF8, 0x0F, 0x1F, 0x87, 0xC3, 0xFF, 0xF0, 0xE7, 0xFC, + 0x1C, 0x7E, 0x00, 0x01, 0xF8, 0x07, 0xFC, 0x0F, 0xFE, 0x1E, 0x0F, 0x3C, + 0x07, 0x78, 0x07, 0x70, 0x07, 0x70, 0x00, 0xF0, 0x00, 0xE0, 0x00, 0xE0, + 0x00, 0xE0, 0x00, 0xE0, 0x0E, 0xE0, 0x1C, 0xF0, 0x3C, 0x78, 0x78, 0x7F, + 0xF0, 0x3F, 0xE0, 0x0F, 0x80, 0x00, 0x00, 0x70, 0x00, 0x0F, 0x00, 0x00, + 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x01, 0xE0, 0x1F, + 0x1C, 0x07, 0xFD, 0xC0, 0xFF, 0xDC, 0x1E, 0x0F, 0xC3, 0xC0, 0x7C, 0x38, + 0x07, 0x87, 0x00, 0x38, 0x70, 0x03, 0x8F, 0x00, 0x38, 0xE0, 0x07, 0x8E, + 0x00, 0x70, 0xE0, 0x07, 0x0E, 0x00, 0xF0, 0xE0, 0x0F, 0x0F, 0x01, 0xF0, + 0x78, 0x7E, 0x07, 0xFF, 0xE0, 0x3F, 0xEE, 0x01, 0xF8, 0xE0, 0x01, 0xF8, + 0x03, 0xFF, 0x03, 0xFF, 0xC3, 0xC1, 0xF3, 0xC0, 0x79, 0xC0, 0x1D, 0xC0, + 0x0E, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0xFF, 0xF8, 0x00, 0x1C, 0x00, 0x0E, + 0x00, 0x07, 0x00, 0x73, 0xC0, 0x78, 0xF0, 0x78, 0x7F, 0xF8, 0x1F, 0xF8, + 0x03, 0xF0, 0x00, 0x01, 0xE0, 0x7C, 0x1F, 0x83, 0x80, 0x70, 0x1C, 0x03, + 0x83, 0xFC, 0x7F, 0x8F, 0xF0, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x0F, 0x01, + 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, + 0xE0, 0x1C, 0x00, 0x00, 0xFC, 0x60, 0x7F, 0xCC, 0x1F, 0xFF, 0x87, 0xC3, + 0xF1, 0xE0, 0x3E, 0x38, 0x03, 0x8E, 0x00, 0x71, 0xC0, 0x0E, 0x38, 0x01, + 0xCE, 0x00, 0x79, 0xC0, 0x0E, 0x38, 0x01, 0xC7, 0x00, 0x78, 0xE0, 0x0F, + 0x1E, 0x03, 0xC1, 0xE1, 0xF8, 0x3F, 0xFF, 0x03, 0xFE, 0xE0, 0x1F, 0x1C, + 0x00, 0x03, 0x00, 0x00, 0xE0, 0x00, 0x18, 0x38, 0x07, 0x07, 0x83, 0xC0, + 0x7F, 0xF8, 0x0F, 0xFC, 0x00, 0x7E, 0x00, 0x00, 0x07, 0x00, 0x01, 0xC0, + 0x00, 0x70, 0x00, 0x1C, 0x00, 0x0F, 0x00, 0x03, 0x80, 0x00, 0xE0, 0x00, + 0x38, 0xFC, 0x0E, 0xFF, 0x87, 0xFF, 0xF1, 0xF8, 0x3C, 0x7C, 0x07, 0x1E, + 0x01, 0xC7, 0x00, 0x73, 0xC0, 0x1C, 0xE0, 0x0F, 0x38, 0x03, 0x8E, 0x00, + 0xE3, 0x80, 0x39, 0xE0, 0x0E, 0x70, 0x07, 0x9C, 0x01, 0xC7, 0x00, 0x71, + 0xC0, 0x1C, 0xE0, 0x07, 0x38, 0x03, 0x80, 0x07, 0x07, 0x0F, 0x0E, 0x00, + 0x00, 0x00, 0x1E, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x38, 0x38, 0x38, 0x38, + 0x38, 0x78, 0x70, 0x70, 0x70, 0x70, 0xF0, 0xE0, 0xE0, 0x00, 0x3C, 0x00, + 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1C, 0x00, + 0x70, 0x01, 0xC0, 0x0E, 0x00, 0x38, 0x00, 0xE0, 0x03, 0x80, 0x1E, 0x00, + 0x70, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, 0xE0, 0x03, 0x80, 0x0E, 0x00, + 0x38, 0x00, 0xE0, 0x07, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xC0, 0x0F, 0x00, + 0x38, 0x00, 0xE0, 0x1F, 0x80, 0x7C, 0x03, 0xE0, 0x00, 0x07, 0x00, 0x00, + 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0xF0, 0x00, 0x1C, 0x00, 0x03, + 0x80, 0x00, 0x70, 0x1E, 0x0E, 0x07, 0x83, 0xC1, 0xE0, 0x70, 0x70, 0x0E, + 0x1C, 0x01, 0xCF, 0x00, 0x3B, 0xC0, 0x0F, 0xF8, 0x01, 0xFF, 0x80, 0x3E, + 0x70, 0x07, 0x8E, 0x00, 0xE0, 0xE0, 0x38, 0x1C, 0x07, 0x03, 0xC0, 0xE0, + 0x38, 0x1C, 0x07, 0x03, 0x80, 0xF0, 0xE0, 0x0E, 0x1C, 0x01, 0xE0, 0x07, + 0x07, 0x0F, 0x0E, 0x0E, 0x0E, 0x0E, 0x1E, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, + 0x38, 0x38, 0x38, 0x38, 0x38, 0x78, 0x70, 0x70, 0x70, 0x70, 0xF0, 0xE0, + 0xE0, 0x1E, 0x7C, 0x0F, 0x83, 0xBF, 0xE7, 0xF8, 0x7F, 0xFD, 0xFF, 0x8F, + 0xC3, 0xF0, 0xF1, 0xE0, 0x3C, 0x0E, 0x38, 0x07, 0x01, 0xCF, 0x01, 0xE0, + 0x39, 0xC0, 0x38, 0x07, 0x38, 0x07, 0x00, 0xE7, 0x00, 0xE0, 0x1C, 0xE0, + 0x1C, 0x07, 0x3C, 0x07, 0x00, 0xE7, 0x00, 0xE0, 0x1C, 0xE0, 0x1C, 0x03, + 0x9C, 0x03, 0x80, 0xF3, 0x80, 0x70, 0x1C, 0x70, 0x1C, 0x03, 0x9C, 0x03, + 0x80, 0x73, 0x80, 0x70, 0x0E, 0x00, 0x1E, 0x3E, 0x07, 0x7F, 0xE1, 0xFF, + 0xF8, 0x7E, 0x0F, 0x1F, 0x01, 0xC7, 0x80, 0x73, 0xC0, 0x1C, 0xE0, 0x07, + 0x38, 0x03, 0xCE, 0x00, 0xE3, 0x80, 0x39, 0xE0, 0x0E, 0x70, 0x03, 0x9C, + 0x01, 0xC7, 0x00, 0x71, 0xC0, 0x1C, 0x70, 0x07, 0x38, 0x01, 0xCE, 0x00, + 0xE0, 0x01, 0xF8, 0x03, 0xFF, 0x03, 0xFF, 0xC3, 0xE1, 0xE3, 0xC0, 0x79, + 0xC0, 0x1D, 0xC0, 0x0E, 0xE0, 0x07, 0x70, 0x03, 0xF0, 0x01, 0xF8, 0x01, + 0xDC, 0x00, 0xEE, 0x00, 0x77, 0x00, 0x73, 0xC0, 0x78, 0xF0, 0xF8, 0x7F, + 0xF8, 0x1F, 0xF8, 0x03, 0xF0, 0x00, 0x03, 0x8F, 0x80, 0x1D, 0xFF, 0x01, + 0xFF, 0xFC, 0x0F, 0xC1, 0xE0, 0x7C, 0x07, 0x83, 0xC0, 0x1C, 0x1C, 0x00, + 0xE1, 0xE0, 0x07, 0x0E, 0x00, 0x38, 0x70, 0x01, 0xC3, 0x80, 0x1E, 0x1C, + 0x00, 0xE1, 0xE0, 0x07, 0x0F, 0x00, 0x70, 0x78, 0x07, 0x83, 0xF0, 0xF8, + 0x3F, 0xFF, 0x81, 0xDF, 0xF8, 0x0E, 0x3F, 0x00, 0x70, 0x00, 0x03, 0x80, + 0x00, 0x3C, 0x00, 0x01, 0xC0, 0x00, 0x0E, 0x00, 0x00, 0x70, 0x00, 0x03, + 0x80, 0x00, 0x00, 0x00, 0xF8, 0xF0, 0x7F, 0xEE, 0x0F, 0xFF, 0xE1, 0xF0, + 0xFE, 0x3C, 0x07, 0xE3, 0x80, 0x3E, 0x70, 0x03, 0xC7, 0x00, 0x3C, 0x70, + 0x03, 0xCE, 0x00, 0x3C, 0xE0, 0x07, 0x8E, 0x00, 0x78, 0xE0, 0x07, 0x8E, + 0x00, 0xF8, 0xF0, 0x1F, 0x87, 0x87, 0xF0, 0x7F, 0xF7, 0x03, 0xFE, 0x70, + 0x0F, 0x8F, 0x00, 0x00, 0xF0, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x0E, + 0x00, 0x01, 0xE0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x04, 0x00, 0x1E, + 0x78, 0xE7, 0xC7, 0x7C, 0x3F, 0x01, 0xF0, 0x0F, 0x00, 0xF0, 0x07, 0x00, + 0x38, 0x01, 0xC0, 0x0E, 0x00, 0xF0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x0E, + 0x00, 0x70, 0x07, 0x00, 0x38, 0x00, 0x01, 0xF8, 0x07, 0xFE, 0x0F, 0xFF, + 0x1E, 0x0F, 0x3C, 0x07, 0x38, 0x07, 0x38, 0x00, 0x3C, 0x00, 0x3F, 0x80, + 0x1F, 0xF8, 0x07, 0xFC, 0x00, 0x7E, 0x00, 0x0E, 0xE0, 0x0E, 0xE0, 0x1E, + 0xF0, 0x3C, 0x7F, 0xF8, 0x7F, 0xF0, 0x1F, 0xC0, 0x0E, 0x03, 0x80, 0xE0, + 0x38, 0x7F, 0xDF, 0xEF, 0xF8, 0x70, 0x1C, 0x0E, 0x03, 0x80, 0xE0, 0x38, + 0x1E, 0x07, 0x01, 0xC0, 0x70, 0x1C, 0x0F, 0x03, 0x80, 0xFC, 0x3F, 0x07, + 0x80, 0x1C, 0x03, 0xC7, 0x00, 0xE1, 0xC0, 0x38, 0xF0, 0x0E, 0x38, 0x03, + 0x8E, 0x00, 0xE3, 0x80, 0x70, 0xE0, 0x1C, 0x78, 0x07, 0x1C, 0x01, 0xC7, + 0x00, 0x71, 0xC0, 0x3C, 0x70, 0x0E, 0x38, 0x07, 0x8E, 0x03, 0xE3, 0x81, + 0xF8, 0xFF, 0xFE, 0x1F, 0xFF, 0x03, 0xF1, 0xC0, 0xE0, 0x07, 0xE0, 0x0F, + 0xE0, 0x0E, 0xE0, 0x1C, 0x70, 0x1C, 0x70, 0x38, 0x70, 0x38, 0x70, 0x70, + 0x70, 0xF0, 0x70, 0xE0, 0x71, 0xC0, 0x71, 0xC0, 0x33, 0x80, 0x3B, 0x80, + 0x3F, 0x00, 0x3F, 0x00, 0x3E, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0xE0, 0x1C, + 0x07, 0xE0, 0x3C, 0x0E, 0xE0, 0x3C, 0x0E, 0xE0, 0x7C, 0x1C, 0xE0, 0x7C, + 0x1C, 0xE0, 0xEC, 0x38, 0xE0, 0xEC, 0x38, 0x61, 0xCC, 0x70, 0x61, 0xCC, + 0x70, 0x63, 0x8C, 0xE0, 0x73, 0x8C, 0xE0, 0x77, 0x0C, 0xC0, 0x77, 0x0D, + 0xC0, 0x7E, 0x0D, 0x80, 0x7E, 0x0F, 0x80, 0x7C, 0x0F, 0x80, 0x7C, 0x0F, + 0x00, 0x78, 0x0F, 0x00, 0x78, 0x0E, 0x00, 0x0E, 0x00, 0xE1, 0xE0, 0x38, + 0x1C, 0x0E, 0x03, 0xC3, 0x80, 0x38, 0xE0, 0x07, 0xBC, 0x00, 0x77, 0x00, + 0x0F, 0xC0, 0x00, 0xF0, 0x00, 0x1C, 0x00, 0x07, 0xC0, 0x01, 0xF8, 0x00, + 0x77, 0x80, 0x1E, 0x70, 0x07, 0x8F, 0x00, 0xE0, 0xE0, 0x38, 0x1C, 0x0E, + 0x01, 0xC3, 0x80, 0x38, 0x00, 0x0E, 0x00, 0x70, 0xF0, 0x0F, 0x07, 0x00, + 0xE0, 0x70, 0x1C, 0x07, 0x01, 0xC0, 0x70, 0x38, 0x07, 0x03, 0x80, 0x70, + 0x70, 0x07, 0x07, 0x00, 0x70, 0xE0, 0x03, 0x9E, 0x00, 0x39, 0xC0, 0x03, + 0xB8, 0x00, 0x3B, 0x80, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xE0, 0x00, + 0x1E, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, + 0x07, 0x00, 0x00, 0xE0, 0x00, 0xFE, 0x00, 0x0F, 0xC0, 0x00, 0xF0, 0x00, + 0x00, 0x07, 0xFF, 0xC0, 0xFF, 0xF8, 0x3F, 0xFF, 0x00, 0x01, 0xC0, 0x00, + 0x70, 0x00, 0x1C, 0x00, 0x07, 0x00, 0x01, 0xC0, 0x00, 0x70, 0x00, 0x1C, + 0x00, 0x07, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, + 0x03, 0xC0, 0x00, 0x7F, 0xFE, 0x1F, 0xFF, 0xC3, 0xFF, 0xF8, 0x00, 0x00, + 0x70, 0x1F, 0x01, 0xF0, 0x3C, 0x03, 0x80, 0x38, 0x07, 0x00, 0x70, 0x07, + 0x00, 0x70, 0x07, 0x00, 0xE0, 0x0E, 0x01, 0xE0, 0x3C, 0x0F, 0x80, 0xE0, + 0x0F, 0x00, 0x78, 0x03, 0x80, 0x38, 0x03, 0x80, 0x38, 0x03, 0x80, 0x38, + 0x07, 0x00, 0x70, 0x07, 0x00, 0x70, 0x0E, 0x00, 0xF8, 0x0F, 0x80, 0x78, + 0x00, 0x01, 0x80, 0xC0, 0xC0, 0x60, 0x30, 0x18, 0x0C, 0x0C, 0x06, 0x03, + 0x01, 0x81, 0xC0, 0xC0, 0x60, 0x30, 0x18, 0x18, 0x0C, 0x06, 0x03, 0x01, + 0x81, 0x80, 0xC0, 0x60, 0x30, 0x38, 0x18, 0x0C, 0x06, 0x03, 0x03, 0x01, + 0x80, 0xC0, 0x00, 0x01, 0xE0, 0x1F, 0x01, 0xF0, 0x07, 0x00, 0xE0, 0x0E, + 0x00, 0xE0, 0x0E, 0x01, 0xC0, 0x1C, 0x01, 0xC0, 0x1C, 0x01, 0xC0, 0x1C, + 0x01, 0xE0, 0x0F, 0x00, 0x70, 0x1F, 0x03, 0xC0, 0x78, 0x07, 0x00, 0x70, + 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x01, 0xC0, 0x1C, 0x03, 0xC0, + 0xF8, 0x0F, 0x80, 0xE0, 0x00, 0x1C, 0x00, 0x3F, 0x00, 0x7F, 0x83, 0x63, + 0xC7, 0xC1, 0xFE, 0x00, 0xFC, 0x00, 0x78 }; + +const GFXglyph FreeSansOblique18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 10, 0, 1 }, // 0x20 ' ' + { 0, 9, 26, 10, 4, -25 }, // 0x21 '!' + { 30, 10, 9, 12, 6, -24 }, // 0x22 '"' + { 42, 21, 25, 19, 2, -24 }, // 0x23 '#' + { 108, 20, 31, 19, 2, -26 }, // 0x24 '$' + { 186, 26, 25, 31, 5, -24 }, // 0x25 '%' + { 268, 20, 25, 23, 3, -24 }, // 0x26 '&' + { 331, 4, 9, 7, 6, -24 }, // 0x27 ''' + { 336, 12, 33, 12, 4, -25 }, // 0x28 '(' + { 386, 12, 33, 12, -1, -24 }, // 0x29 ')' + { 436, 10, 10, 14, 6, -25 }, // 0x2A '*' + { 449, 18, 16, 20, 3, -15 }, // 0x2B '+' + { 485, 5, 8, 10, 2, -2 }, // 0x2C ',' + { 490, 9, 3, 12, 3, -10 }, // 0x2D '-' + { 494, 4, 4, 10, 3, -3 }, // 0x2E '.' + { 496, 15, 26, 10, 0, -25 }, // 0x2F '/' + { 545, 18, 25, 19, 3, -24 }, // 0x30 '0' + { 602, 10, 25, 19, 7, -24 }, // 0x31 '1' + { 634, 20, 25, 19, 2, -24 }, // 0x32 '2' + { 697, 19, 25, 19, 2, -24 }, // 0x33 '3' + { 757, 18, 25, 19, 2, -24 }, // 0x34 '4' + { 814, 20, 25, 19, 2, -24 }, // 0x35 '5' + { 877, 19, 25, 19, 3, -24 }, // 0x36 '6' + { 937, 18, 25, 19, 5, -24 }, // 0x37 '7' + { 994, 19, 25, 19, 3, -24 }, // 0x38 '8' + { 1054, 19, 25, 19, 2, -24 }, // 0x39 '9' + { 1114, 7, 19, 10, 4, -18 }, // 0x3A ':' + { 1131, 8, 24, 10, 3, -18 }, // 0x3B ';' + { 1155, 19, 17, 20, 3, -16 }, // 0x3C '<' + { 1196, 18, 9, 20, 3, -12 }, // 0x3D '=' + { 1217, 19, 17, 20, 2, -15 }, // 0x3E '>' + { 1258, 16, 26, 19, 6, -25 }, // 0x3F '?' + { 1310, 33, 31, 36, 3, -25 }, // 0x40 '@' + { 1438, 23, 26, 23, 0, -25 }, // 0x41 'A' + { 1513, 21, 26, 23, 3, -25 }, // 0x42 'B' + { 1582, 22, 26, 25, 4, -25 }, // 0x43 'C' + { 1654, 23, 26, 25, 3, -25 }, // 0x44 'D' + { 1729, 23, 26, 23, 3, -25 }, // 0x45 'E' + { 1804, 22, 26, 21, 3, -25 }, // 0x46 'F' + { 1876, 24, 26, 27, 4, -25 }, // 0x47 'G' + { 1954, 25, 26, 25, 3, -25 }, // 0x48 'H' + { 2036, 8, 26, 10, 4, -25 }, // 0x49 'I' + { 2062, 18, 26, 18, 2, -25 }, // 0x4A 'J' + { 2121, 25, 26, 23, 3, -25 }, // 0x4B 'K' + { 2203, 16, 26, 19, 3, -25 }, // 0x4C 'L' + { 2255, 29, 26, 30, 3, -25 }, // 0x4D 'M' + { 2350, 25, 26, 26, 3, -25 }, // 0x4E 'N' + { 2432, 24, 26, 27, 4, -25 }, // 0x4F 'O' + { 2510, 22, 26, 23, 3, -25 }, // 0x50 'P' + { 2582, 25, 28, 27, 4, -25 }, // 0x51 'Q' + { 2670, 23, 26, 25, 3, -25 }, // 0x52 'R' + { 2745, 22, 26, 23, 3, -25 }, // 0x53 'S' + { 2817, 20, 26, 21, 6, -25 }, // 0x54 'T' + { 2882, 24, 26, 25, 4, -25 }, // 0x55 'U' + { 2960, 21, 26, 23, 6, -25 }, // 0x56 'V' + { 3029, 32, 26, 33, 6, -25 }, // 0x57 'W' + { 3133, 27, 26, 23, 1, -25 }, // 0x58 'X' + { 3221, 23, 26, 24, 6, -25 }, // 0x59 'Y' + { 3296, 25, 26, 21, 1, -25 }, // 0x5A 'Z' + { 3378, 13, 33, 10, 1, -25 }, // 0x5B '[' + { 3432, 4, 26, 10, 5, -25 }, // 0x5C '\' + { 3445, 13, 33, 10, -1, -24 }, // 0x5D ']' + { 3499, 14, 14, 16, 3, -24 }, // 0x5E '^' + { 3524, 21, 2, 19, -2, 5 }, // 0x5F '_' + { 3530, 6, 5, 12, 6, -25 }, // 0x60 '`' + { 3534, 18, 19, 19, 2, -18 }, // 0x61 'a' + { 3577, 19, 26, 20, 2, -25 }, // 0x62 'b' + { 3639, 16, 19, 18, 3, -18 }, // 0x63 'c' + { 3677, 20, 26, 20, 3, -25 }, // 0x64 'd' + { 3742, 17, 19, 19, 3, -18 }, // 0x65 'e' + { 3783, 11, 26, 9, 2, -25 }, // 0x66 'f' + { 3819, 19, 27, 19, 2, -18 }, // 0x67 'g' + { 3884, 18, 26, 19, 2, -25 }, // 0x68 'h' + { 3943, 8, 26, 8, 2, -25 }, // 0x69 'i' + { 3969, 14, 34, 8, -2, -25 }, // 0x6A 'j' + { 4029, 19, 26, 18, 2, -25 }, // 0x6B 'k' + { 4091, 8, 26, 8, 2, -25 }, // 0x6C 'l' + { 4117, 27, 19, 29, 2, -18 }, // 0x6D 'm' + { 4182, 18, 19, 19, 2, -18 }, // 0x6E 'n' + { 4225, 17, 19, 19, 3, -18 }, // 0x6F 'o' + { 4266, 21, 26, 20, 0, -18 }, // 0x70 'p' + { 4335, 20, 27, 19, 2, -18 }, // 0x71 'q' + { 4403, 13, 19, 11, 2, -18 }, // 0x72 'r' + { 4434, 16, 19, 18, 2, -18 }, // 0x73 's' + { 4472, 10, 23, 9, 3, -22 }, // 0x74 't' + { 4501, 18, 19, 19, 3, -18 }, // 0x75 'u' + { 4544, 16, 19, 17, 4, -18 }, // 0x76 'v' + { 4582, 24, 19, 25, 4, -18 }, // 0x77 'w' + { 4639, 19, 19, 17, 1, -18 }, // 0x78 'x' + { 4685, 20, 27, 17, 0, -18 }, // 0x79 'y' + { 4753, 19, 19, 17, 1, -18 }, // 0x7A 'z' + { 4799, 12, 33, 12, 3, -25 }, // 0x7B '{' + { 4849, 9, 33, 9, 2, -25 }, // 0x7C '|' + { 4887, 12, 33, 12, 0, -24 }, // 0x7D '}' + { 4937, 16, 7, 20, 5, -15 } }; // 0x7E '~' + +const GFXfont FreeSansOblique18pt7b PROGMEM = { + (uint8_t *)FreeSansOblique18pt7bBitmaps, + (GFXglyph *)FreeSansOblique18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 5623 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansOblique24pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansOblique24pt7b.h new file mode 100644 index 0000000..4c8c8ab --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansOblique24pt7b.h @@ -0,0 +1,840 @@ +const uint8_t FreeSansOblique24pt7bBitmaps[] PROGMEM = { + 0x01, 0xE0, 0x3C, 0x0F, 0x81, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x3C, 0x07, + 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x03, + 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x38, 0x07, 0x00, 0xE0, 0x18, 0x03, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xF0, 0x1E, 0x07, 0x80, 0xF0, 0x1E, 0x00, 0x78, + 0x7B, 0xC3, 0xDE, 0x1F, 0xE1, 0xEF, 0x0F, 0x78, 0x7B, 0xC3, 0xDC, 0x1C, + 0xE0, 0xE7, 0x07, 0x30, 0x31, 0x81, 0x80, 0x00, 0x07, 0x81, 0xC0, 0x00, + 0x78, 0x3C, 0x00, 0x07, 0x03, 0xC0, 0x00, 0xF0, 0x38, 0x00, 0x0E, 0x07, + 0x80, 0x01, 0xE0, 0x70, 0x00, 0x1E, 0x0F, 0x00, 0x01, 0xC0, 0xF0, 0x00, + 0x3C, 0x0E, 0x00, 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, + 0xFE, 0x00, 0x70, 0x3C, 0x00, 0x0F, 0x03, 0x80, 0x00, 0xF0, 0x78, 0x00, + 0x0E, 0x07, 0x80, 0x01, 0xE0, 0x70, 0x00, 0x1C, 0x0F, 0x00, 0x03, 0xC0, + 0xE0, 0x00, 0x3C, 0x1E, 0x00, 0x03, 0x81, 0xE0, 0x0F, 0xFF, 0xFF, 0xE0, + 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xE0, 0x0F, 0x03, 0x80, 0x00, 0xE0, + 0x78, 0x00, 0x1E, 0x07, 0x00, 0x01, 0xC0, 0xF0, 0x00, 0x1C, 0x0F, 0x00, + 0x03, 0xC0, 0xE0, 0x00, 0x38, 0x1E, 0x00, 0x07, 0x81, 0xC0, 0x00, 0x78, + 0x3C, 0x00, 0x07, 0x03, 0xC0, 0x00, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x30, + 0x00, 0x00, 0x7F, 0x80, 0x00, 0xFF, 0xF8, 0x00, 0x7F, 0xFF, 0x00, 0x7F, + 0xFF, 0xE0, 0x1F, 0x18, 0xF8, 0x0F, 0x8E, 0x1F, 0x07, 0xC3, 0x83, 0xC1, + 0xE0, 0xE0, 0xF0, 0x70, 0x38, 0x3C, 0x3C, 0x0C, 0x0F, 0x0F, 0x07, 0x00, + 0x03, 0xC1, 0xC0, 0x00, 0xF0, 0x70, 0x00, 0x3E, 0x1C, 0x00, 0x0F, 0xE6, + 0x00, 0x01, 0xFF, 0xC0, 0x00, 0x3F, 0xFE, 0x00, 0x03, 0xFF, 0xE0, 0x00, + 0x3F, 0xFC, 0x00, 0x03, 0xFF, 0x80, 0x01, 0xC7, 0xF0, 0x00, 0x70, 0x7C, + 0x00, 0x1C, 0x0F, 0x00, 0x06, 0x03, 0xCF, 0x03, 0x80, 0xF3, 0xC0, 0xE0, + 0x3C, 0xF0, 0x38, 0x0E, 0x3C, 0x0E, 0x07, 0x8F, 0x03, 0x01, 0xE3, 0xE1, + 0xC0, 0xF0, 0xF8, 0x70, 0x78, 0x1F, 0x9C, 0xFC, 0x03, 0xFF, 0xFE, 0x00, + 0x7F, 0xFF, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x38, 0x00, 0x00, 0x0E, 0x00, + 0x00, 0x03, 0x00, 0x00, 0x01, 0xC0, 0x00, 0x00, 0x70, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x07, 0x80, 0x1F, 0x00, 0x00, 0x70, 0x07, 0xFC, 0x00, 0x0E, + 0x00, 0xFF, 0xE0, 0x01, 0xC0, 0x1E, 0x1E, 0x00, 0x3C, 0x03, 0x80, 0xF0, + 0x03, 0x80, 0x70, 0x07, 0x00, 0x70, 0x07, 0x00, 0x70, 0x0E, 0x00, 0xE0, + 0x07, 0x01, 0xC0, 0x0E, 0x00, 0x70, 0x3C, 0x00, 0xE0, 0x0E, 0x03, 0x80, + 0x0E, 0x00, 0xE0, 0x70, 0x00, 0xF0, 0x1C, 0x0E, 0x00, 0x07, 0x87, 0xC1, + 0xE0, 0x00, 0x7F, 0xF8, 0x1C, 0x00, 0x03, 0xFE, 0x03, 0x80, 0x00, 0x0F, + 0x80, 0x70, 0x00, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x00, 0x01, 0xE0, 0x1F, + 0x00, 0x00, 0x1C, 0x07, 0xFC, 0x00, 0x03, 0x80, 0xFF, 0xE0, 0x00, 0x70, + 0x1E, 0x1E, 0x00, 0x0F, 0x03, 0x80, 0xF0, 0x00, 0xE0, 0x70, 0x07, 0x00, + 0x1C, 0x07, 0x00, 0x70, 0x03, 0x80, 0xE0, 0x07, 0x00, 0x70, 0x0E, 0x00, + 0x70, 0x0F, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x1C, 0x00, + 0xF0, 0x1C, 0x03, 0x80, 0x07, 0x87, 0xC0, 0x70, 0x00, 0x7F, 0xF8, 0x07, + 0x00, 0x03, 0xFE, 0x00, 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF8, 0x00, + 0x03, 0xFF, 0x00, 0x01, 0xFF, 0xE0, 0x00, 0xF8, 0x7C, 0x00, 0x78, 0x0F, + 0x00, 0x1E, 0x03, 0xC0, 0x0F, 0x00, 0xF0, 0x03, 0xC0, 0x3C, 0x00, 0xF0, + 0x1E, 0x00, 0x3C, 0x07, 0x80, 0x0F, 0x87, 0xC0, 0x01, 0xE3, 0xE0, 0x00, + 0x7F, 0xF0, 0x00, 0x0F, 0xF8, 0x00, 0x03, 0xF8, 0x00, 0x03, 0xFC, 0x00, + 0x03, 0xFF, 0x00, 0x01, 0xFB, 0xE0, 0x70, 0xF8, 0x7C, 0x1C, 0x7C, 0x1F, + 0x0E, 0x3C, 0x03, 0xE3, 0x9E, 0x00, 0x79, 0xE7, 0x80, 0x1F, 0xF3, 0xC0, + 0x03, 0xF8, 0xF0, 0x00, 0xFE, 0x3C, 0x00, 0x1F, 0x0F, 0x00, 0x07, 0xC3, + 0xE0, 0x03, 0xF8, 0xF8, 0x03, 0xFE, 0x3F, 0x83, 0xF7, 0xC7, 0xFF, 0xF8, + 0xF0, 0xFF, 0xFC, 0x3E, 0x1F, 0xFC, 0x07, 0x81, 0xFC, 0x00, 0x00, 0x7B, + 0xDF, 0xEF, 0x7B, 0xDC, 0xE7, 0x31, 0x80, 0x00, 0x0E, 0x00, 0x38, 0x00, + 0xE0, 0x03, 0x80, 0x07, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xE0, 0x03, 0x80, + 0x0F, 0x00, 0x1C, 0x00, 0x78, 0x00, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x0E, + 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, + 0x1C, 0x00, 0x78, 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, + 0x00, 0x1C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, + 0x07, 0x00, 0x06, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x30, 0x00, + 0x70, 0x00, 0xE0, 0x00, 0xC0, 0x00, 0x00, 0x30, 0x00, 0x70, 0x00, 0xE0, + 0x00, 0xC0, 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x0E, 0x00, + 0x1C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, 0x07, + 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x70, 0x01, 0xE0, 0x03, 0x80, + 0x07, 0x00, 0x0E, 0x00, 0x3C, 0x00, 0x70, 0x00, 0xE0, 0x01, 0xC0, 0x07, + 0x00, 0x0E, 0x00, 0x3C, 0x00, 0x70, 0x01, 0xE0, 0x03, 0x80, 0x0F, 0x00, + 0x1C, 0x00, 0x78, 0x00, 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x1C, 0x00, 0x70, + 0x01, 0xC0, 0x07, 0x00, 0x00, 0x01, 0xC0, 0x07, 0x00, 0x38, 0x18, 0xE3, + 0x7B, 0xBF, 0xFF, 0xF3, 0xFF, 0x01, 0xE0, 0x1F, 0xC0, 0xF7, 0x07, 0x9E, + 0x1C, 0x38, 0x20, 0xC0, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x78, + 0x00, 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, + 0x00, 0x1C, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xE0, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, + 0x78, 0x00, 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, + 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, 0x00, 0x3E, 0x7C, 0xF9, 0xE7, + 0xC1, 0x83, 0x0C, 0x18, 0x63, 0xC6, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFE, 0x7D, 0xF7, 0xBE, 0xF8, 0x00, 0x00, 0x18, 0x00, 0x01, 0xC0, 0x00, + 0x1C, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x00, 0x70, 0x00, 0x07, 0x00, + 0x00, 0x30, 0x00, 0x03, 0x80, 0x00, 0x18, 0x00, 0x01, 0xC0, 0x00, 0x0C, + 0x00, 0x00, 0xE0, 0x00, 0x06, 0x00, 0x00, 0x70, 0x00, 0x03, 0x00, 0x00, + 0x38, 0x00, 0x01, 0x80, 0x00, 0x1C, 0x00, 0x00, 0xC0, 0x00, 0x0E, 0x00, + 0x00, 0x60, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x03, 0x80, 0x00, 0x38, + 0x00, 0x01, 0x80, 0x00, 0x1C, 0x00, 0x00, 0xC0, 0x00, 0x0E, 0x00, 0x00, + 0x60, 0x00, 0x07, 0x00, 0x00, 0x30, 0x00, 0x03, 0x80, 0x00, 0x18, 0x00, + 0x00, 0x00, 0x0F, 0xC0, 0x00, 0xFF, 0xE0, 0x03, 0xFF, 0xE0, 0x0F, 0xFF, + 0xE0, 0x3F, 0x0F, 0xC0, 0xF8, 0x07, 0x81, 0xE0, 0x0F, 0x87, 0x80, 0x0F, + 0x1F, 0x00, 0x1E, 0x3C, 0x00, 0x3C, 0x78, 0x00, 0x79, 0xE0, 0x00, 0xF3, + 0xC0, 0x01, 0xE7, 0x80, 0x07, 0xDE, 0x00, 0x0F, 0xBC, 0x00, 0x1E, 0x78, + 0x00, 0x3C, 0xF0, 0x00, 0x79, 0xE0, 0x00, 0xF7, 0x80, 0x03, 0xEF, 0x00, + 0x07, 0xDE, 0x00, 0x0F, 0x3C, 0x00, 0x1E, 0x78, 0x00, 0x7C, 0xF0, 0x00, + 0xF1, 0xE0, 0x03, 0xE3, 0xC0, 0x07, 0x87, 0xC0, 0x1F, 0x0F, 0x80, 0x7C, + 0x0F, 0xC3, 0xF0, 0x1F, 0xFF, 0xC0, 0x1F, 0xFF, 0x00, 0x1F, 0xFC, 0x00, + 0x0F, 0xC0, 0x00, 0x00, 0x18, 0x01, 0xC0, 0x1C, 0x01, 0xE0, 0x1F, 0x0F, + 0xFB, 0xFF, 0xDF, 0xFC, 0xFF, 0xE0, 0x0F, 0x00, 0x78, 0x07, 0xC0, 0x3C, + 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x07, 0xC0, 0x3C, 0x01, 0xE0, 0x0F, 0x00, + 0x78, 0x07, 0xC0, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x07, 0xC0, 0x3C, + 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x07, 0xC0, 0x3C, 0x00, 0x00, 0x03, 0xFC, + 0x00, 0x03, 0xFF, 0xE0, 0x00, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0xE0, 0x0F, + 0xC0, 0xFC, 0x03, 0xE0, 0x07, 0xC0, 0xF8, 0x00, 0xF8, 0x1F, 0x00, 0x0F, + 0x03, 0xC0, 0x01, 0xE0, 0xF8, 0x00, 0x3C, 0x1E, 0x00, 0x07, 0x80, 0x00, + 0x01, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x1F, + 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0xFC, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0xFF, + 0xFF, 0xFC, 0x3F, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFC, + 0x00, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xFE, 0x00, 0x3F, 0xFF, 0x80, 0x3F, + 0xFF, 0xE0, 0x1F, 0x81, 0xF8, 0x1F, 0x00, 0x7C, 0x1F, 0x00, 0x1E, 0x0F, + 0x00, 0x0F, 0x0F, 0x80, 0x07, 0x87, 0x80, 0x03, 0xC0, 0x00, 0x03, 0xC0, + 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x7F, 0xE0, + 0x00, 0x3F, 0xE0, 0x00, 0x1F, 0xF8, 0x00, 0x1F, 0xFE, 0x00, 0x00, 0x3F, + 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, + 0x79, 0xE0, 0x00, 0x3C, 0xF0, 0x00, 0x1E, 0x78, 0x00, 0x1E, 0x3C, 0x00, + 0x0F, 0x1E, 0x00, 0x0F, 0x0F, 0x80, 0x1F, 0x83, 0xF0, 0x3F, 0x81, 0xFF, + 0xFF, 0x80, 0x7F, 0xFF, 0x80, 0x1F, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x00, + 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7E, + 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x03, 0xFC, 0x00, 0x07, 0xBC, + 0x00, 0x0F, 0xBC, 0x00, 0x1F, 0x7C, 0x00, 0x3E, 0x78, 0x00, 0x7C, 0x78, + 0x00, 0xF8, 0x78, 0x00, 0xF0, 0x78, 0x01, 0xE0, 0xF0, 0x03, 0xC0, 0xF0, + 0x07, 0x80, 0xF0, 0x0F, 0x00, 0xF0, 0x1E, 0x01, 0xF0, 0x3C, 0x01, 0xE0, + 0x78, 0x01, 0xE0, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, + 0xFF, 0xFF, 0xFE, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, + 0x00, 0x07, 0x80, 0x00, 0x07, 0x80, 0x00, 0x07, 0x80, 0x00, 0x07, 0x80, + 0x00, 0x0F, 0x80, 0x00, 0x7F, 0xFF, 0xC0, 0x1F, 0xFF, 0xF8, 0x03, 0xFF, + 0xFF, 0x00, 0x7F, 0xFF, 0xE0, 0x1E, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, + 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x78, 0x00, + 0x00, 0x1E, 0x00, 0x00, 0x03, 0xC7, 0xE0, 0x00, 0xF7, 0xFF, 0x80, 0x1F, + 0xFF, 0xF8, 0x03, 0xFF, 0xFF, 0x80, 0xFE, 0x03, 0xF0, 0x1F, 0x00, 0x3F, + 0x03, 0xC0, 0x03, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x07, 0x80, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x70, + 0x00, 0x00, 0x1E, 0x1E, 0x00, 0x03, 0xC3, 0xC0, 0x00, 0xF0, 0x7C, 0x00, + 0x3C, 0x0F, 0x80, 0x0F, 0x80, 0xFC, 0x07, 0xE0, 0x1F, 0xFF, 0xF8, 0x01, + 0xFF, 0xFE, 0x00, 0x1F, 0xFF, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x07, + 0xE0, 0x00, 0x3F, 0xF8, 0x00, 0x7F, 0xFC, 0x00, 0xFF, 0xFE, 0x01, 0xF8, + 0x3E, 0x03, 0xE0, 0x1F, 0x07, 0xC0, 0x1F, 0x0F, 0x80, 0x0F, 0x0F, 0x00, + 0x0F, 0x1F, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x3C, 0x1F, + 0x80, 0x3C, 0x7F, 0xE0, 0x3D, 0xFF, 0xF0, 0x7B, 0xFF, 0xF8, 0x7F, 0xC1, + 0xF8, 0x7F, 0x00, 0x7C, 0x7E, 0x00, 0x7C, 0xFC, 0x00, 0x3C, 0xF8, 0x00, + 0x3C, 0xF8, 0x00, 0x3C, 0xF0, 0x00, 0x3C, 0xF0, 0x00, 0x38, 0xF0, 0x00, + 0x78, 0xF0, 0x00, 0x78, 0xF0, 0x00, 0xF0, 0xF8, 0x01, 0xF0, 0x7C, 0x03, + 0xE0, 0x7E, 0x0F, 0xC0, 0x3F, 0xFF, 0xC0, 0x3F, 0xFF, 0x80, 0x0F, 0xFE, + 0x00, 0x03, 0xF8, 0x00, 0x1F, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xE1, 0xFF, + 0xFF, 0xF8, 0xFF, 0xFF, 0xFE, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0x80, + 0x00, 0x03, 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0x80, 0x00, 0x03, + 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xC0, 0x00, 0x01, 0xE0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0x80, + 0x00, 0x03, 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, + 0x00, 0x00, 0x0F, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x01, 0xF0, 0x00, 0x00, + 0x78, 0x00, 0x00, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xFE, 0x00, 0x1F, + 0xFF, 0x80, 0x1F, 0xFF, 0xE0, 0x1F, 0x81, 0xF8, 0x1F, 0x00, 0x7C, 0x0F, + 0x00, 0x1E, 0x0F, 0x00, 0x0F, 0x07, 0x80, 0x07, 0x83, 0xC0, 0x03, 0xC1, + 0xE0, 0x03, 0xC0, 0xF8, 0x03, 0xC0, 0x7E, 0x07, 0xC0, 0x1F, 0xFF, 0xC0, + 0x07, 0xFF, 0xC0, 0x03, 0xFF, 0xE0, 0x07, 0xFF, 0xF8, 0x07, 0xE0, 0x7E, + 0x07, 0xC0, 0x0F, 0x07, 0x80, 0x07, 0xC7, 0xC0, 0x01, 0xE3, 0xC0, 0x00, + 0xF3, 0xC0, 0x00, 0x79, 0xE0, 0x00, 0x3C, 0xF0, 0x00, 0x1C, 0x78, 0x00, + 0x1E, 0x3C, 0x00, 0x0F, 0x1F, 0x00, 0x0F, 0x0F, 0xC0, 0x0F, 0x83, 0xF0, + 0x3F, 0x81, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0x80, 0x0F, 0xFF, 0x00, 0x01, + 0xFE, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0xF0, 0x01, 0xFF, 0xFC, + 0x03, 0xFF, 0xFC, 0x07, 0xF0, 0x7E, 0x07, 0xC0, 0x3E, 0x0F, 0x80, 0x1F, + 0x0F, 0x00, 0x0F, 0x1E, 0x00, 0x0F, 0x1E, 0x00, 0x0F, 0x3C, 0x00, 0x0F, + 0x3C, 0x00, 0x0F, 0x3C, 0x00, 0x1F, 0x3C, 0x00, 0x1F, 0x3C, 0x00, 0x3F, + 0x3E, 0x00, 0x7E, 0x3E, 0x00, 0xFE, 0x1F, 0x83, 0xFE, 0x1F, 0xFF, 0xFE, + 0x0F, 0xFF, 0xBC, 0x07, 0xFE, 0x3C, 0x01, 0xF8, 0x7C, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x78, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF0, 0xF0, 0x01, 0xF0, + 0xF0, 0x03, 0xE0, 0xF8, 0x07, 0xC0, 0xFC, 0x1F, 0xC0, 0x7F, 0xFF, 0x80, + 0x3F, 0xFE, 0x00, 0x1F, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xC1, 0xF0, + 0x78, 0x3E, 0x0F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7C, 0x1F, + 0x07, 0x83, 0xE0, 0xF8, 0x00, 0x03, 0xE0, 0x7C, 0x0F, 0x03, 0xE0, 0x7C, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xE0, 0x7C, 0x0F, + 0x81, 0xE0, 0x7C, 0x01, 0x80, 0x30, 0x0C, 0x01, 0x80, 0x60, 0x3C, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x70, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0xFE, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xFE, 0x00, 0x03, 0xFE, 0x00, + 0x07, 0xFC, 0x00, 0x07, 0xFC, 0x00, 0x0F, 0xF8, 0x00, 0x07, 0xF0, 0x00, + 0x03, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x1F, 0xF0, 0x00, + 0x01, 0xFF, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x0E, + 0x00, 0x00, 0x00, 0x80, 0x1F, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0xE3, 0xFF, + 0xFF, 0xF8, 0xFF, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, + 0xC7, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xF8, 0x04, 0x00, 0x00, 0x01, 0xC0, + 0x00, 0x00, 0xFC, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x03, 0xFE, 0x00, 0x00, + 0x3F, 0xE0, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x00, 0x00, + 0x3F, 0x80, 0x00, 0x7F, 0xC0, 0x00, 0xFF, 0x80, 0x00, 0xFF, 0x80, 0x01, + 0xFF, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0x38, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0xFE, + 0x00, 0x3F, 0xF8, 0x0F, 0xFF, 0xC1, 0xFF, 0xFE, 0x1F, 0x03, 0xE3, 0xE0, + 0x1F, 0x7C, 0x00, 0xF7, 0x80, 0x0F, 0x78, 0x00, 0xFF, 0x00, 0x0F, 0xF0, + 0x01, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, + 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x1F, 0x00, + 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0x80, 0x00, 0x78, 0x00, 0x0F, 0x80, + 0x00, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x1E, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xE0, 0x00, 0x3E, + 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0x80, 0x00, 0x00, 0x00, 0xFF, 0xFF, + 0x80, 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFE, + 0x00, 0x00, 0x7F, 0xE0, 0x0F, 0xF8, 0x00, 0x0F, 0xF0, 0x00, 0x1F, 0xE0, + 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x0F, 0xC0, 0x00, 0x00, 0xFC, 0x00, + 0xFC, 0x00, 0x00, 0x01, 0xF0, 0x0F, 0xC0, 0x00, 0x00, 0x0F, 0x80, 0xF8, + 0x00, 0xFC, 0x00, 0x3E, 0x0F, 0x80, 0x1F, 0xF9, 0xE1, 0xF0, 0x78, 0x03, + 0xFF, 0xCF, 0x07, 0x87, 0xC0, 0x3F, 0x0F, 0xF0, 0x3C, 0x7C, 0x03, 0xE0, + 0x3F, 0x01, 0xE3, 0xC0, 0x3E, 0x01, 0xF8, 0x0F, 0x3E, 0x03, 0xE0, 0x0F, + 0x80, 0x79, 0xE0, 0x1E, 0x00, 0x7C, 0x03, 0xDF, 0x01, 0xE0, 0x03, 0xC0, + 0x3E, 0xF0, 0x1F, 0x00, 0x3E, 0x01, 0xE7, 0x80, 0xF0, 0x01, 0xE0, 0x0F, + 0x38, 0x07, 0x80, 0x0F, 0x00, 0xFB, 0xC0, 0x78, 0x00, 0xF0, 0x07, 0x9E, + 0x03, 0xC0, 0x07, 0x80, 0x7C, 0xF0, 0x1E, 0x00, 0x78, 0x07, 0xC7, 0x80, + 0xF0, 0x07, 0xC0, 0x7E, 0x3C, 0x07, 0x80, 0x7C, 0x07, 0xE1, 0xE0, 0x3E, + 0x07, 0xE0, 0x7E, 0x0F, 0x00, 0xF8, 0x7F, 0x8F, 0xC0, 0x7C, 0x07, 0xFF, + 0x7F, 0xFC, 0x01, 0xE0, 0x1F, 0xF1, 0xFF, 0x80, 0x0F, 0x00, 0x7E, 0x0F, + 0xF0, 0x00, 0x7C, 0x00, 0x00, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x00, + 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFE, 0x00, 0xF8, 0x00, 0x00, + 0x0F, 0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0x00, 0x00, 0x00, + 0x3F, 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x1F, 0x80, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0x1F, 0xE0, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x03, 0xDF, 0x00, 0x00, 0x1E, + 0x7C, 0x00, 0x00, 0x79, 0xF0, 0x00, 0x03, 0xC7, 0xC0, 0x00, 0x0F, 0x1F, + 0x00, 0x00, 0x78, 0x3C, 0x00, 0x03, 0xE0, 0xF0, 0x00, 0x0F, 0x03, 0xE0, + 0x00, 0x78, 0x0F, 0x80, 0x01, 0xE0, 0x3E, 0x00, 0x0F, 0x00, 0xF8, 0x00, + 0x3C, 0x03, 0xE0, 0x01, 0xE0, 0x0F, 0x80, 0x0F, 0x80, 0x1E, 0x00, 0x3C, + 0x00, 0x7C, 0x01, 0xFF, 0xFF, 0xF0, 0x07, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, + 0xFF, 0x00, 0xFF, 0xFF, 0xFC, 0x07, 0xC0, 0x01, 0xF0, 0x3E, 0x00, 0x03, + 0xC0, 0xF8, 0x00, 0x0F, 0x87, 0xC0, 0x00, 0x3E, 0x1E, 0x00, 0x00, 0xF8, + 0xF8, 0x00, 0x03, 0xE3, 0xC0, 0x00, 0x0F, 0x9F, 0x00, 0x00, 0x3E, 0xF8, + 0x00, 0x00, 0x7B, 0xE0, 0x00, 0x01, 0xF0, 0x01, 0xFF, 0xFF, 0x00, 0x0F, + 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0xE0, 0x3E, 0x00, + 0x1F, 0x81, 0xE0, 0x00, 0x7C, 0x0F, 0x00, 0x01, 0xE0, 0x78, 0x00, 0x0F, + 0x03, 0xC0, 0x00, 0x78, 0x3C, 0x00, 0x03, 0xC1, 0xE0, 0x00, 0x3C, 0x0F, + 0x00, 0x01, 0xE0, 0x78, 0x00, 0x1E, 0x07, 0xC0, 0x03, 0xE0, 0x3F, 0xFF, + 0xFC, 0x01, 0xFF, 0xFF, 0xC0, 0x0F, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xFE, + 0x07, 0x80, 0x01, 0xF0, 0x3C, 0x00, 0x07, 0xC1, 0xE0, 0x00, 0x1E, 0x0F, + 0x00, 0x00, 0xF0, 0xF0, 0x00, 0x07, 0x87, 0x80, 0x00, 0x3C, 0x3C, 0x00, + 0x01, 0xE1, 0xE0, 0x00, 0x1E, 0x1F, 0x00, 0x00, 0xF0, 0xF0, 0x00, 0x0F, + 0x87, 0x80, 0x00, 0xF8, 0x3C, 0x00, 0x1F, 0x81, 0xFF, 0xFF, 0xF8, 0x1F, + 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0x00, 0x00, 0x00, + 0x01, 0xFE, 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x1F, + 0xFF, 0xFC, 0x00, 0xFE, 0x03, 0xF0, 0x07, 0xE0, 0x03, 0xE0, 0x3E, 0x00, + 0x07, 0x81, 0xF0, 0x00, 0x1E, 0x07, 0x80, 0x00, 0x3C, 0x3C, 0x00, 0x00, + 0xF1, 0xF0, 0x00, 0x03, 0xC7, 0x80, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x00, + 0xF0, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x0F, 0x00, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0x3C, 0xF0, 0x00, 0x01, 0xF3, 0xC0, 0x00, 0x07, + 0x8F, 0x80, 0x00, 0x3E, 0x3E, 0x00, 0x00, 0xF0, 0x7C, 0x00, 0x07, 0xC1, + 0xF0, 0x00, 0x3E, 0x03, 0xE0, 0x03, 0xF0, 0x0F, 0xE0, 0x3F, 0x80, 0x1F, + 0xFF, 0xFC, 0x00, 0x3F, 0xFF, 0xE0, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x3F, + 0xC0, 0x00, 0x01, 0xFF, 0xFF, 0x00, 0x03, 0xFF, 0xFF, 0x80, 0x07, 0xFF, + 0xFF, 0x80, 0x1F, 0xFF, 0xFF, 0x80, 0x3E, 0x00, 0x3F, 0x80, 0x78, 0x00, + 0x1F, 0x80, 0xF0, 0x00, 0x1F, 0x03, 0xE0, 0x00, 0x1E, 0x07, 0xC0, 0x00, + 0x3E, 0x0F, 0x00, 0x00, 0x3C, 0x1E, 0x00, 0x00, 0x78, 0x3C, 0x00, 0x00, + 0xF0, 0xF8, 0x00, 0x01, 0xE1, 0xF0, 0x00, 0x03, 0xC3, 0xC0, 0x00, 0x07, + 0x87, 0x80, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x3C, 0x3E, 0x00, 0x00, 0x78, + 0x7C, 0x00, 0x00, 0xF0, 0xF0, 0x00, 0x01, 0xE1, 0xE0, 0x00, 0x07, 0x87, + 0xC0, 0x00, 0x0F, 0x0F, 0x80, 0x00, 0x3E, 0x1E, 0x00, 0x00, 0x78, 0x3C, + 0x00, 0x01, 0xF0, 0x78, 0x00, 0x03, 0xC1, 0xF0, 0x00, 0x0F, 0x03, 0xE0, + 0x00, 0x3E, 0x07, 0x80, 0x01, 0xF8, 0x0F, 0x00, 0x0F, 0xE0, 0x1F, 0xFF, + 0xFF, 0x80, 0x7F, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0xF0, 0x01, 0xFF, 0xFF, + 0x00, 0x00, 0x01, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xFC, 0x07, 0xFF, + 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0xE0, 0x3E, 0x00, 0x00, 0x00, 0x78, 0x00, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x07, 0xC0, 0x00, + 0x00, 0x0F, 0x00, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, + 0x07, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, 0xFF, 0x80, + 0x7F, 0xFF, 0xFF, 0x00, 0xF0, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x07, + 0xC0, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x1F, 0xFF, + 0xFF, 0xE0, 0x7F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, + 0xFE, 0x00, 0x01, 0xFF, 0xFF, 0xFC, 0x07, 0xFF, 0xFF, 0xF0, 0x1F, 0xFF, + 0xFF, 0xC0, 0xFF, 0xFF, 0xFE, 0x03, 0xE0, 0x00, 0x00, 0x0F, 0x00, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x0F, + 0x80, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x03, 0xFF, + 0xFF, 0xC0, 0x0F, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xFC, 0x01, 0xFF, 0xFF, + 0xF0, 0x07, 0x80, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, + 0x03, 0xE0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x00, + 0xF0, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x3E, 0x00, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x7F, 0xC0, 0x00, 0x01, 0xFF, 0xF8, 0x00, 0x07, 0xFF, 0xFF, 0x00, 0x07, + 0xFF, 0xFF, 0xC0, 0x07, 0xF0, 0x0F, 0xF0, 0x0F, 0xC0, 0x00, 0xF8, 0x0F, + 0xC0, 0x00, 0x3E, 0x07, 0x80, 0x00, 0x1F, 0x07, 0x80, 0x00, 0x07, 0x87, + 0xC0, 0x00, 0x03, 0xC3, 0xC0, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x03, + 0xE0, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x00, + 0xF0, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x00, 0x3C, 0x00, 0x1F, 0xFF, + 0xBC, 0x00, 0x0F, 0xFF, 0xDE, 0x00, 0x0F, 0xFF, 0xEF, 0x00, 0x07, 0xFF, + 0xF7, 0x80, 0x00, 0x00, 0x73, 0xC0, 0x00, 0x00, 0x39, 0xE0, 0x00, 0x00, + 0x3C, 0xF0, 0x00, 0x00, 0x1E, 0x78, 0x00, 0x00, 0x1F, 0x3E, 0x00, 0x00, + 0x0F, 0x8F, 0x00, 0x00, 0x0F, 0x87, 0xC0, 0x00, 0x0F, 0xC3, 0xF0, 0x00, + 0x0F, 0xE0, 0xFC, 0x00, 0x1F, 0xF0, 0x7F, 0x80, 0x7F, 0x78, 0x1F, 0xFF, + 0xFE, 0x38, 0x03, 0xFF, 0xFE, 0x1C, 0x00, 0xFF, 0xFC, 0x0E, 0x00, 0x0F, + 0xF0, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0xF0, 0x00, 0x03, 0xC0, + 0x78, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x01, 0xF0, 0x3E, 0x00, 0x00, 0xF0, + 0x1E, 0x00, 0x00, 0x78, 0x0F, 0x00, 0x00, 0x3C, 0x0F, 0x80, 0x00, 0x3E, + 0x07, 0xC0, 0x00, 0x1F, 0x03, 0xC0, 0x00, 0x0F, 0x01, 0xE0, 0x00, 0x07, + 0x80, 0xF0, 0x00, 0x03, 0xC0, 0xF8, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x01, + 0xF0, 0x3C, 0x00, 0x00, 0xF0, 0x1F, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, + 0xFC, 0x0F, 0xFF, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xFE, 0x03, 0xC0, 0x00, + 0x0F, 0x01, 0xE0, 0x00, 0x07, 0x81, 0xF0, 0x00, 0x07, 0xC0, 0xF8, 0x00, + 0x03, 0xE0, 0x78, 0x00, 0x01, 0xE0, 0x3C, 0x00, 0x00, 0xF0, 0x1E, 0x00, + 0x00, 0x78, 0x1F, 0x00, 0x00, 0x7C, 0x0F, 0x80, 0x00, 0x3C, 0x07, 0x80, + 0x00, 0x1E, 0x03, 0xC0, 0x00, 0x0F, 0x01, 0xE0, 0x00, 0x0F, 0x81, 0xF0, + 0x00, 0x07, 0xC0, 0xF0, 0x00, 0x03, 0xC0, 0x78, 0x00, 0x01, 0xE0, 0x00, + 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xE0, 0x3C, 0x07, 0x81, 0xF0, 0x3E, 0x07, + 0x80, 0xF0, 0x1E, 0x07, 0xC0, 0xF8, 0x1E, 0x03, 0xC0, 0x78, 0x1F, 0x03, + 0xE0, 0x78, 0x0F, 0x01, 0xE0, 0x7C, 0x0F, 0x81, 0xE0, 0x3C, 0x07, 0x81, + 0xF0, 0x3E, 0x07, 0x80, 0xF0, 0x1E, 0x07, 0xC0, 0xF8, 0x1E, 0x00, 0x00, + 0x00, 0x07, 0x80, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x01, 0xE0, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0x80, 0x00, 0x07, + 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, + 0x78, 0x00, 0x00, 0x78, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x0F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0x80, 0x00, 0x03, 0xC0, 0xF0, + 0x01, 0xE0, 0x78, 0x00, 0xF0, 0x78, 0x00, 0xF8, 0x3C, 0x00, 0x78, 0x1E, + 0x00, 0x3C, 0x0F, 0x00, 0x3E, 0x07, 0xC0, 0x3E, 0x03, 0xF0, 0x7E, 0x00, + 0xFF, 0xFF, 0x00, 0x3F, 0xFF, 0x00, 0x0F, 0xFE, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x01, 0xE0, 0x00, 0x0F, 0xC0, 0x78, 0x00, 0x07, 0xC0, 0x1E, 0x00, + 0x03, 0xE0, 0x0F, 0x80, 0x03, 0xF0, 0x03, 0xE0, 0x01, 0xF8, 0x00, 0xF0, + 0x00, 0xFC, 0x00, 0x3C, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x3E, 0x00, 0x07, + 0xC0, 0x3F, 0x00, 0x01, 0xE0, 0x1F, 0x80, 0x00, 0x78, 0x0F, 0x80, 0x00, + 0x1E, 0x07, 0xC0, 0x00, 0x0F, 0x83, 0xE0, 0x00, 0x03, 0xE3, 0xF0, 0x00, + 0x00, 0xF1, 0xFC, 0x00, 0x00, 0x3C, 0xFF, 0x00, 0x00, 0x0F, 0x7F, 0xE0, + 0x00, 0x07, 0xFE, 0xF8, 0x00, 0x01, 0xFE, 0x1E, 0x00, 0x00, 0x7F, 0x07, + 0xC0, 0x00, 0x1F, 0x80, 0xF0, 0x00, 0x0F, 0xC0, 0x3E, 0x00, 0x03, 0xE0, + 0x07, 0x80, 0x00, 0xF0, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x7C, 0x00, 0x0F, + 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x78, 0x00, 0x1F, 0x00, 0x1E, 0x00, 0x03, 0xE0, 0x07, 0x80, 0x00, 0xF8, + 0x03, 0xE0, 0x00, 0x1F, 0x00, 0xF0, 0x00, 0x07, 0xC0, 0x3C, 0x00, 0x00, + 0xF8, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, 0xF8, + 0x00, 0x03, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, 0x01, 0xF0, 0x00, + 0x07, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x0F, + 0x80, 0x00, 0x3E, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, + 0x00, 0x7C, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, + 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF0, + 0x00, 0x07, 0xC0, 0x00, 0x1F, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, + 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, 0xE0, + 0x01, 0xF8, 0x00, 0x00, 0x7E, 0x03, 0xF8, 0x00, 0x01, 0xFC, 0x0F, 0xF0, + 0x00, 0x03, 0xF8, 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x3F, 0xC0, 0x00, 0x1F, + 0xC0, 0x7F, 0x80, 0x00, 0x7F, 0x80, 0xFF, 0x00, 0x00, 0xEF, 0x03, 0xFE, + 0x00, 0x03, 0xFE, 0x07, 0xBC, 0x00, 0x0F, 0x78, 0x0F, 0x3C, 0x00, 0x1E, + 0xF0, 0x1E, 0x78, 0x00, 0x79, 0xE0, 0x3C, 0xF0, 0x00, 0xF3, 0xC0, 0xF9, + 0xE0, 0x03, 0xCF, 0x81, 0xE3, 0xC0, 0x07, 0x9E, 0x03, 0xC7, 0x80, 0x1E, + 0x3C, 0x07, 0x8F, 0x00, 0x38, 0x78, 0x1F, 0x1E, 0x00, 0xF0, 0xF0, 0x3C, + 0x1E, 0x03, 0xC3, 0xE0, 0x78, 0x3C, 0x07, 0x87, 0x80, 0xF0, 0x78, 0x1E, + 0x0F, 0x01, 0xE0, 0xF0, 0x3C, 0x1E, 0x07, 0xC1, 0xE0, 0xF0, 0x7C, 0x0F, + 0x03, 0xC1, 0xE0, 0xF0, 0x1E, 0x07, 0x87, 0x81, 0xE0, 0x3C, 0x0F, 0x0E, + 0x03, 0xC0, 0x78, 0x0F, 0x3C, 0x07, 0x81, 0xF0, 0x1E, 0x70, 0x1F, 0x03, + 0xC0, 0x3D, 0xE0, 0x3C, 0x07, 0x80, 0x7F, 0x80, 0x78, 0x0F, 0x00, 0xFF, + 0x00, 0xF0, 0x3E, 0x01, 0xFC, 0x01, 0xE0, 0x78, 0x03, 0xF8, 0x07, 0xC0, + 0xF0, 0x07, 0xE0, 0x0F, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x01, 0xF0, + 0x00, 0x03, 0xC0, 0x7E, 0x00, 0x01, 0xF0, 0x3F, 0x80, 0x00, 0x78, 0x0F, + 0xE0, 0x00, 0x1E, 0x03, 0xFC, 0x00, 0x07, 0x80, 0xFF, 0x00, 0x03, 0xE0, + 0x3F, 0xE0, 0x00, 0xF0, 0x1F, 0xF8, 0x00, 0x3C, 0x07, 0x9E, 0x00, 0x0F, + 0x01, 0xE7, 0xC0, 0x03, 0xC0, 0x78, 0xF0, 0x01, 0xF0, 0x1E, 0x3E, 0x00, + 0x78, 0x0F, 0x87, 0x80, 0x1E, 0x03, 0xC1, 0xF0, 0x07, 0x80, 0xF0, 0x7C, + 0x01, 0xE0, 0x3C, 0x0F, 0x00, 0xF8, 0x1F, 0x03, 0xE0, 0x3C, 0x07, 0x80, + 0x78, 0x0F, 0x01, 0xE0, 0x1F, 0x03, 0xC0, 0x78, 0x07, 0xC1, 0xF0, 0x1E, + 0x00, 0xF8, 0x78, 0x0F, 0x80, 0x3E, 0x1E, 0x03, 0xC0, 0x07, 0x87, 0x80, + 0xF0, 0x01, 0xF1, 0xE0, 0x3C, 0x00, 0x3C, 0xF8, 0x0F, 0x00, 0x0F, 0xBC, + 0x07, 0xC0, 0x03, 0xEF, 0x01, 0xE0, 0x00, 0x7F, 0xC0, 0x78, 0x00, 0x1F, + 0xF0, 0x1E, 0x00, 0x03, 0xFC, 0x0F, 0x80, 0x00, 0xFE, 0x03, 0xC0, 0x00, + 0x1F, 0x80, 0xF0, 0x00, 0x07, 0xE0, 0x3C, 0x00, 0x01, 0xF8, 0x00, 0x00, + 0x00, 0xFF, 0x00, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xFC, 0x00, + 0x0F, 0xFF, 0xFF, 0x80, 0x0F, 0xF0, 0x1F, 0xC0, 0x0F, 0xC0, 0x03, 0xF0, + 0x0F, 0x80, 0x00, 0xFC, 0x0F, 0x80, 0x00, 0x3E, 0x0F, 0x80, 0x00, 0x0F, + 0x07, 0x80, 0x00, 0x07, 0xC7, 0xC0, 0x00, 0x01, 0xE3, 0xC0, 0x00, 0x00, + 0xF3, 0xC0, 0x00, 0x00, 0x79, 0xE0, 0x00, 0x00, 0x3D, 0xE0, 0x00, 0x00, + 0x1E, 0xF0, 0x00, 0x00, 0x0F, 0x78, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x03, 0xDE, 0x00, 0x00, 0x01, 0xEF, 0x00, 0x00, + 0x00, 0xF7, 0x80, 0x00, 0x00, 0xFB, 0xC0, 0x00, 0x00, 0x79, 0xE0, 0x00, + 0x00, 0x3C, 0xF0, 0x00, 0x00, 0x3E, 0x78, 0x00, 0x00, 0x1E, 0x3E, 0x00, + 0x00, 0x1F, 0x0F, 0x00, 0x00, 0x1F, 0x07, 0xC0, 0x00, 0x1F, 0x03, 0xF0, + 0x00, 0x1F, 0x00, 0xFC, 0x00, 0x3F, 0x80, 0x3F, 0x80, 0x7F, 0x80, 0x1F, + 0xFF, 0xFF, 0x00, 0x03, 0xFF, 0xFF, 0x00, 0x00, 0xFF, 0xFE, 0x00, 0x00, + 0x0F, 0xF8, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x00, 0x0F, 0xFF, 0xFE, 0x00, + 0x7F, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0xE0, 0x3E, 0x00, 0x3F, 0x81, 0xE0, + 0x00, 0x7C, 0x0F, 0x00, 0x01, 0xE0, 0xF8, 0x00, 0x0F, 0x07, 0xC0, 0x00, + 0x78, 0x3C, 0x00, 0x03, 0xC1, 0xE0, 0x00, 0x1E, 0x0F, 0x00, 0x01, 0xE0, + 0xF8, 0x00, 0x0F, 0x07, 0xC0, 0x00, 0xF8, 0x3C, 0x00, 0x0F, 0x81, 0xE0, + 0x01, 0xF8, 0x0F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFC, 0x07, 0xFF, 0xFF, + 0x80, 0x3F, 0xFF, 0xF0, 0x01, 0xE0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x01, 0xE0, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x07, 0x80, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, + 0xF0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0x00, + 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xFC, 0x00, 0x0F, 0xFF, 0xFF, + 0x80, 0x0F, 0xF0, 0x1F, 0xC0, 0x0F, 0xC0, 0x03, 0xF0, 0x0F, 0xC0, 0x00, + 0xFC, 0x0F, 0x80, 0x00, 0x3E, 0x0F, 0x80, 0x00, 0x0F, 0x07, 0x80, 0x00, + 0x07, 0xC7, 0xC0, 0x00, 0x01, 0xE3, 0xC0, 0x00, 0x00, 0xF3, 0xC0, 0x00, + 0x00, 0x79, 0xE0, 0x00, 0x00, 0x3D, 0xE0, 0x00, 0x00, 0x1E, 0xF0, 0x00, + 0x00, 0x0F, 0x78, 0x00, 0x00, 0x07, 0xB8, 0x00, 0x00, 0x03, 0xFC, 0x00, + 0x00, 0x03, 0xDE, 0x00, 0x00, 0x01, 0xEF, 0x00, 0x00, 0x00, 0xF7, 0x80, + 0x00, 0x00, 0x7B, 0xC0, 0x00, 0x00, 0x79, 0xE0, 0x00, 0x00, 0x3C, 0xF0, + 0x00, 0x00, 0x3C, 0x78, 0x00, 0x08, 0x3E, 0x3E, 0x00, 0x0E, 0x1E, 0x0F, + 0x00, 0x0F, 0x9F, 0x07, 0xC0, 0x07, 0xFF, 0x03, 0xF0, 0x01, 0xFF, 0x00, + 0xFC, 0x00, 0x7F, 0x00, 0x3F, 0x80, 0xFF, 0x80, 0x1F, 0xFF, 0xFF, 0xE0, + 0x03, 0xFF, 0xFF, 0xF8, 0x00, 0xFF, 0xFC, 0x7E, 0x00, 0x0F, 0xF0, 0x1F, + 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, + 0xC0, 0x07, 0xFF, 0xFF, 0xC0, 0x1F, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xFE, + 0x03, 0xE0, 0x00, 0xFC, 0x0F, 0x00, 0x01, 0xF0, 0x3C, 0x00, 0x03, 0xC1, + 0xF0, 0x00, 0x0F, 0x07, 0xC0, 0x00, 0x3C, 0x1E, 0x00, 0x00, 0xF0, 0x78, + 0x00, 0x03, 0xC1, 0xE0, 0x00, 0x1E, 0x0F, 0x80, 0x00, 0x78, 0x3E, 0x00, + 0x03, 0xE0, 0xF0, 0x00, 0x1F, 0x03, 0xC0, 0x01, 0xF8, 0x0F, 0xFF, 0xFF, + 0xC0, 0x7F, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0xF0, + 0x1E, 0x00, 0x07, 0xE0, 0xF8, 0x00, 0x0F, 0x83, 0xE0, 0x00, 0x1E, 0x0F, + 0x00, 0x00, 0x78, 0x3C, 0x00, 0x01, 0xE0, 0xF0, 0x00, 0x07, 0x87, 0xC0, + 0x00, 0x1E, 0x1F, 0x00, 0x00, 0xF0, 0x78, 0x00, 0x03, 0xC1, 0xE0, 0x00, + 0x0F, 0x07, 0x80, 0x00, 0x3C, 0x3E, 0x00, 0x00, 0xF0, 0xF0, 0x00, 0x03, + 0xC3, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFF, 0xFC, + 0x00, 0x1F, 0xFF, 0xF8, 0x01, 0xFF, 0xFF, 0xC0, 0x1F, 0xC0, 0x7F, 0x01, + 0xF0, 0x00, 0xFC, 0x0F, 0x00, 0x03, 0xE0, 0xF0, 0x00, 0x0F, 0x07, 0x00, + 0x00, 0x78, 0x78, 0x00, 0x03, 0xC3, 0xC0, 0x00, 0x1E, 0x1E, 0x00, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, + 0xFF, 0xE0, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x0F, 0xFF, 0xF0, 0x00, 0x0F, + 0xFF, 0xC0, 0x00, 0x07, 0xFF, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x3C, 0xF0, 0x00, 0x01, 0xE7, + 0x80, 0x00, 0x0F, 0x3C, 0x00, 0x00, 0x71, 0xE0, 0x00, 0x07, 0x8F, 0x00, + 0x00, 0x3C, 0x7C, 0x00, 0x03, 0xC1, 0xF0, 0x00, 0x7C, 0x0F, 0xE0, 0x1F, + 0xC0, 0x3F, 0xFF, 0xFC, 0x00, 0xFF, 0xFF, 0xC0, 0x03, 0xFF, 0xF8, 0x00, + 0x03, 0xFE, 0x00, 0x00, 0x7F, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0x7F, + 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFE, 0x00, 0x0F, 0x00, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x01, 0xE0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, 0x00, + 0x00, 0x78, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x78, 0x00, 0x00, 0x0F, + 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0x0F, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, + 0xE0, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x3E, 0x00, + 0x00, 0x03, 0xC0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x0F, 0x00, 0x00, 0x3C, 0x1E, + 0x00, 0x00, 0xF8, 0x7C, 0x00, 0x01, 0xF0, 0xF8, 0x00, 0x03, 0xC1, 0xE0, + 0x00, 0x07, 0x83, 0xC0, 0x00, 0x0F, 0x0F, 0x80, 0x00, 0x3E, 0x1F, 0x00, + 0x00, 0x7C, 0x3C, 0x00, 0x00, 0xF0, 0x78, 0x00, 0x01, 0xE0, 0xF0, 0x00, + 0x03, 0xC3, 0xE0, 0x00, 0x0F, 0x87, 0xC0, 0x00, 0x1F, 0x0F, 0x00, 0x00, + 0x3C, 0x1E, 0x00, 0x00, 0x78, 0x3C, 0x00, 0x01, 0xF0, 0xF8, 0x00, 0x03, + 0xE1, 0xF0, 0x00, 0x07, 0x83, 0xC0, 0x00, 0x0F, 0x07, 0x80, 0x00, 0x1E, + 0x1F, 0x00, 0x00, 0x7C, 0x3E, 0x00, 0x00, 0xF8, 0x78, 0x00, 0x01, 0xE0, + 0xF0, 0x00, 0x03, 0xC1, 0xE0, 0x00, 0x0F, 0x83, 0xC0, 0x00, 0x1E, 0x07, + 0x80, 0x00, 0x7C, 0x0F, 0x80, 0x01, 0xF0, 0x0F, 0x80, 0x07, 0xE0, 0x1F, + 0xC0, 0x7F, 0x80, 0x1F, 0xFF, 0xFE, 0x00, 0x1F, 0xFF, 0xF0, 0x00, 0x1F, + 0xFF, 0xC0, 0x00, 0x07, 0xFC, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFF, 0xC0, + 0x00, 0x0F, 0xBE, 0x00, 0x00, 0x79, 0xF0, 0x00, 0x07, 0xC7, 0x80, 0x00, + 0x3C, 0x3C, 0x00, 0x03, 0xE1, 0xE0, 0x00, 0x1E, 0x0F, 0x80, 0x01, 0xF0, + 0x7C, 0x00, 0x0F, 0x03, 0xE0, 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0x80, 0x78, + 0x00, 0x78, 0x03, 0xC0, 0x07, 0xC0, 0x1E, 0x00, 0x3C, 0x00, 0xF0, 0x03, + 0xE0, 0x07, 0xC0, 0x1E, 0x00, 0x3E, 0x01, 0xF0, 0x01, 0xF0, 0x0F, 0x00, + 0x07, 0x80, 0xF0, 0x00, 0x3C, 0x07, 0x80, 0x01, 0xE0, 0x78, 0x00, 0x0F, + 0x07, 0xC0, 0x00, 0x7C, 0x3C, 0x00, 0x03, 0xE3, 0xE0, 0x00, 0x1F, 0x1E, + 0x00, 0x00, 0xF9, 0xF0, 0x00, 0x03, 0xCF, 0x00, 0x00, 0x1E, 0xF0, 0x00, + 0x00, 0xF7, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0xF0, + 0x00, 0x1F, 0x00, 0x03, 0xDE, 0x00, 0x07, 0xE0, 0x00, 0xFB, 0xC0, 0x00, + 0xFC, 0x00, 0x1E, 0x78, 0x00, 0x3F, 0x80, 0x07, 0xCF, 0x00, 0x07, 0xF0, + 0x00, 0xF9, 0xE0, 0x01, 0xFE, 0x00, 0x3E, 0x3C, 0x00, 0x7F, 0xC0, 0x07, + 0xC7, 0x80, 0x0F, 0x78, 0x01, 0xF0, 0xF0, 0x03, 0xEF, 0x00, 0x3E, 0x1E, + 0x00, 0x79, 0xE0, 0x0F, 0x83, 0xC0, 0x1F, 0x3C, 0x01, 0xF0, 0x78, 0x03, + 0xC7, 0x80, 0x3C, 0x0F, 0x00, 0xF8, 0xF0, 0x0F, 0x80, 0xE0, 0x1E, 0x1E, + 0x01, 0xE0, 0x1C, 0x07, 0xC1, 0xC0, 0x7C, 0x03, 0x80, 0xF0, 0x3C, 0x0F, + 0x00, 0x70, 0x3E, 0x07, 0x83, 0xE0, 0x0E, 0x07, 0x80, 0xF0, 0x78, 0x01, + 0xC1, 0xF0, 0x1E, 0x1F, 0x00, 0x3C, 0x3C, 0x03, 0xC3, 0xE0, 0x07, 0x8F, + 0x80, 0x78, 0x78, 0x00, 0xF1, 0xE0, 0x0F, 0x1F, 0x00, 0x1E, 0x7C, 0x01, + 0xE3, 0xC0, 0x03, 0xCF, 0x00, 0x3C, 0xF8, 0x00, 0x7B, 0xE0, 0x07, 0x9E, + 0x00, 0x0F, 0x78, 0x00, 0xF7, 0xC0, 0x01, 0xFF, 0x00, 0x1E, 0xF0, 0x00, + 0x3F, 0xC0, 0x03, 0xFE, 0x00, 0x07, 0xF8, 0x00, 0x7F, 0x80, 0x00, 0xFE, + 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0xFC, 0x00, 0x03, 0xF0, 0x00, + 0x1F, 0x80, 0x00, 0x7E, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x7C, + 0x00, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xF0, 0x07, 0xC0, 0x00, 0x3E, 0x00, + 0x7C, 0x00, 0x07, 0xC0, 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x1F, + 0x00, 0x01, 0xF0, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x7C, 0x00, 0x00, 0xF8, + 0x0F, 0x80, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0x00, 0x7C, 0x1F, 0x00, 0x00, + 0x07, 0xC3, 0xE0, 0x00, 0x00, 0x7C, 0x7C, 0x00, 0x00, 0x03, 0xEF, 0x80, + 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, + 0x03, 0xFC, 0x00, 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x00, 0x0F, 0xBE, 0x00, + 0x00, 0x01, 0xF3, 0xE0, 0x00, 0x00, 0x3E, 0x1F, 0x00, 0x00, 0x03, 0xE1, + 0xF0, 0x00, 0x00, 0x7C, 0x0F, 0x80, 0x00, 0x0F, 0x80, 0xF8, 0x00, 0x01, + 0xF0, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x03, 0xE0, + 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x03, 0xF0, 0x03, 0xF0, 0x00, + 0x1F, 0x00, 0x7E, 0x00, 0x01, 0xF8, 0x0F, 0xC0, 0x00, 0x0F, 0x80, 0xF8, + 0x00, 0x00, 0x7D, 0xF0, 0x00, 0x03, 0xE7, 0xC0, 0x00, 0x1F, 0x1F, 0x80, + 0x00, 0xF8, 0x3E, 0x00, 0x03, 0xE0, 0xF8, 0x00, 0x1F, 0x01, 0xF0, 0x00, + 0xF8, 0x07, 0xC0, 0x07, 0xC0, 0x0F, 0x00, 0x3E, 0x00, 0x3E, 0x01, 0xF0, + 0x00, 0xF8, 0x07, 0xC0, 0x01, 0xF0, 0x3E, 0x00, 0x07, 0xC1, 0xF0, 0x00, + 0x0F, 0x0F, 0x80, 0x00, 0x3E, 0x7C, 0x00, 0x00, 0x79, 0xE0, 0x00, 0x01, + 0xFF, 0x80, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x3F, + 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x0F, 0x80, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x03, 0xC0, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, + 0x07, 0x80, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x03, + 0xE0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xFF, 0xC0, + 0x1F, 0xFF, 0xFF, 0xE0, 0x07, 0xFF, 0xFF, 0xF8, 0x03, 0xFF, 0xFF, 0xFE, + 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x07, + 0xC0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, + 0x03, 0xE0, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x01, 0xF0, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x0F, 0x80, + 0x00, 0x00, 0x07, 0xFF, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, 0xFF, 0x80, 0x7F, + 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0xF8, 0x00, 0x00, 0x7F, 0xC0, 0x1F, + 0xF0, 0x07, 0xFC, 0x01, 0xFE, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, + 0x03, 0xC0, 0x01, 0xF0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, + 0xE0, 0x00, 0xF8, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, + 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0xF8, 0x00, + 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x7C, 0x00, 0x1E, + 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x0F, 0x00, + 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x7C, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, + 0xE0, 0x00, 0x7F, 0xC0, 0x3F, 0xE0, 0x0F, 0xF8, 0x03, 0xFE, 0x00, 0xE3, + 0x8E, 0x38, 0xE1, 0x86, 0x18, 0x61, 0x87, 0x1C, 0x71, 0xC7, 0x0C, 0x30, + 0xC3, 0x0C, 0x38, 0xE3, 0x8E, 0x38, 0x61, 0x86, 0x18, 0x61, 0xC7, 0x1C, + 0x71, 0xC0, 0x00, 0x7F, 0xC0, 0x1F, 0xF0, 0x07, 0xFC, 0x03, 0xFE, 0x00, + 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x03, + 0xC0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, + 0x00, 0x78, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, + 0x3C, 0x00, 0x1F, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, + 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, 0x00, + 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x0F, 0x80, 0x03, + 0xC0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x7F, 0x80, 0x3F, 0xE0, + 0x0F, 0xF8, 0x03, 0xFE, 0x00, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x1F, 0x00, + 0x1F, 0xC0, 0x0E, 0xE0, 0x0E, 0x70, 0x0F, 0x38, 0x07, 0x1C, 0x07, 0x0E, + 0x03, 0x83, 0x83, 0x81, 0xC3, 0xC0, 0xE1, 0xC0, 0x71, 0xC0, 0x39, 0xE0, + 0x0E, 0xE0, 0x07, 0xF0, 0x03, 0xF0, 0x01, 0xC0, 0x7F, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xC0, 0xF8, 0x78, 0x3C, 0x1C, 0x0E, 0x0E, 0x07, 0x00, + 0x1F, 0xE0, 0x01, 0xFF, 0xF0, 0x07, 0xFF, 0xF0, 0x1F, 0xFF, 0xF0, 0x7E, + 0x07, 0xE1, 0xF0, 0x07, 0xC3, 0xC0, 0x07, 0x80, 0x00, 0x0F, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xF0, 0x00, 0x07, 0xE0, 0x0F, 0xFF, + 0xC0, 0xFF, 0xFF, 0x07, 0xFF, 0x9E, 0x1F, 0xC0, 0x3C, 0x7C, 0x00, 0x78, + 0xF0, 0x00, 0xF3, 0xC0, 0x03, 0xC7, 0x80, 0x07, 0x8F, 0x00, 0x1F, 0x1E, + 0x00, 0x7E, 0x3F, 0x07, 0xFC, 0x3F, 0xFF, 0x7E, 0x7F, 0xFC, 0xFC, 0x7F, + 0xF0, 0xF8, 0x3F, 0x00, 0xF0, 0x01, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x78, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x0F, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0x83, 0xE0, 0x03, 0xC7, 0xFC, + 0x01, 0xEF, 0xFF, 0x00, 0xFF, 0xFF, 0xC0, 0xF7, 0x83, 0xF0, 0x7F, 0x00, + 0xF8, 0x3F, 0x00, 0x3E, 0x1F, 0x00, 0x0F, 0x1F, 0x80, 0x07, 0x8F, 0x80, + 0x03, 0xC7, 0x80, 0x01, 0xE3, 0xC0, 0x00, 0xF1, 0xE0, 0x00, 0x79, 0xF0, + 0x00, 0x3C, 0xF0, 0x00, 0x3C, 0x78, 0x00, 0x1E, 0x3C, 0x00, 0x0F, 0x1E, + 0x00, 0x0F, 0x9F, 0x00, 0x07, 0x8F, 0xC0, 0x07, 0xC7, 0xE0, 0x07, 0xC3, + 0xF8, 0x07, 0xC1, 0xFE, 0x0F, 0xC1, 0xEF, 0xFF, 0xE0, 0xF3, 0xFF, 0xC0, + 0x78, 0xFF, 0xC0, 0x00, 0x1F, 0x80, 0x00, 0x00, 0x3F, 0x80, 0x03, 0xFF, + 0x80, 0x3F, 0xFF, 0x01, 0xFF, 0xFE, 0x0F, 0xE0, 0xF8, 0x7E, 0x01, 0xF1, + 0xF0, 0x03, 0xCF, 0x80, 0x0F, 0x3C, 0x00, 0x3D, 0xF0, 0x00, 0x07, 0x80, + 0x00, 0x1E, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x0F, 0x3C, + 0x00, 0x3C, 0xF8, 0x01, 0xE1, 0xF0, 0x0F, 0x87, 0xE0, 0xFC, 0x0F, 0xFF, + 0xE0, 0x3F, 0xFF, 0x00, 0x7F, 0xF8, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x00, + 0x03, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x01, 0xE0, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, + 0x3C, 0x00, 0x3F, 0x07, 0x80, 0x1F, 0xF8, 0xF0, 0x0F, 0xFF, 0x3E, 0x03, + 0xFF, 0xF7, 0x80, 0xFC, 0x1F, 0xF0, 0x3F, 0x00, 0xFE, 0x07, 0xC0, 0x0F, + 0xC1, 0xF0, 0x01, 0xF0, 0x3C, 0x00, 0x3E, 0x0F, 0x80, 0x07, 0xC1, 0xE0, + 0x00, 0x78, 0x3C, 0x00, 0x1F, 0x0F, 0x80, 0x03, 0xC1, 0xE0, 0x00, 0x78, + 0x3C, 0x00, 0x0F, 0x07, 0x80, 0x01, 0xE0, 0xF0, 0x00, 0x7C, 0x1E, 0x00, + 0x0F, 0x03, 0xC0, 0x03, 0xE0, 0x78, 0x00, 0x7C, 0x0F, 0x80, 0x1F, 0x80, + 0xF8, 0x07, 0xF0, 0x1F, 0x83, 0xFC, 0x03, 0xFF, 0xFF, 0x80, 0x3F, 0xFE, + 0xF0, 0x03, 0xFF, 0x1E, 0x00, 0x1F, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x80, + 0x01, 0xFF, 0xC0, 0x07, 0xFF, 0xE0, 0x3F, 0xFF, 0xC0, 0xFE, 0x0F, 0xC1, + 0xF0, 0x07, 0xC7, 0xC0, 0x0F, 0x8F, 0x00, 0x0F, 0x3C, 0x00, 0x1E, 0x78, + 0x00, 0x3D, 0xE0, 0x00, 0x7B, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xBF, 0xFF, 0xFF, 0x78, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, + 0x03, 0xC0, 0x00, 0x07, 0x80, 0x03, 0xCF, 0x80, 0x0F, 0x0F, 0x80, 0x3E, + 0x1F, 0x81, 0xF8, 0x1F, 0xFF, 0xE0, 0x1F, 0xFF, 0x80, 0x1F, 0xFC, 0x00, + 0x0F, 0xE0, 0x00, 0x00, 0x3E, 0x01, 0xFC, 0x07, 0xF8, 0x0F, 0xE0, 0x3E, + 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x07, 0xC0, 0x7F, 0xF0, 0xFF, 0xE3, + 0xFF, 0xC0, 0x78, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x3E, + 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x0F, 0x80, 0x1E, 0x00, + 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x03, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1E, + 0x00, 0x3C, 0x00, 0xF0, 0x01, 0xE0, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x07, + 0xFE, 0x3C, 0x01, 0xFF, 0xE7, 0x00, 0xFF, 0xFE, 0xE0, 0x1F, 0x83, 0xFC, + 0x07, 0xC0, 0x3F, 0x81, 0xF0, 0x03, 0xF0, 0x3C, 0x00, 0x7C, 0x0F, 0x00, + 0x0F, 0x81, 0xE0, 0x01, 0xF0, 0x78, 0x00, 0x3E, 0x0F, 0x00, 0x07, 0xC1, + 0xE0, 0x00, 0xF0, 0x38, 0x00, 0x1E, 0x0F, 0x00, 0x03, 0xC1, 0xE0, 0x00, + 0xF8, 0x3C, 0x00, 0x1F, 0x07, 0x80, 0x03, 0xC0, 0xF0, 0x00, 0xF8, 0x1E, + 0x00, 0x3F, 0x03, 0xE0, 0x07, 0xE0, 0x3E, 0x01, 0xF8, 0x07, 0xE0, 0xFF, + 0x00, 0x7F, 0xFD, 0xE0, 0x0F, 0xFF, 0x3C, 0x00, 0xFF, 0xCF, 0x00, 0x07, + 0xE1, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x0F, 0x01, 0xE0, 0x03, 0xE0, + 0x3C, 0x00, 0xF8, 0x07, 0xE0, 0x7F, 0x00, 0x7F, 0xFF, 0xC0, 0x0F, 0xFF, + 0xF0, 0x00, 0x7F, 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x01, 0xE0, 0x00, + 0x03, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x78, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x83, 0xF0, 0x0F, + 0x1F, 0xF0, 0x1E, 0xFF, 0xF0, 0x3F, 0xFF, 0xE0, 0xFF, 0x87, 0xE1, 0xFC, + 0x07, 0xC3, 0xF0, 0x07, 0x87, 0xC0, 0x0F, 0x1F, 0x00, 0x1E, 0x3E, 0x00, + 0x3C, 0x78, 0x00, 0x78, 0xF0, 0x01, 0xE1, 0xE0, 0x03, 0xC7, 0xC0, 0x07, + 0x8F, 0x00, 0x0F, 0x1E, 0x00, 0x1E, 0x3C, 0x00, 0x78, 0x78, 0x00, 0xF1, + 0xE0, 0x01, 0xE3, 0xC0, 0x03, 0xC7, 0x80, 0x0F, 0x8F, 0x00, 0x1E, 0x1E, + 0x00, 0x3C, 0x78, 0x00, 0x78, 0xF0, 0x00, 0xF1, 0xE0, 0x03, 0xC0, 0x01, + 0xE0, 0x3C, 0x0F, 0x01, 0xE0, 0x3C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xF0, 0x1E, 0x03, 0xC0, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x03, 0xC0, + 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, + 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0xF0, 0x1E, 0x00, 0x00, 0x07, + 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xC0, 0x01, 0xE0, 0x00, + 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x3C, + 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, + 0x07, 0x80, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, + 0xC0, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, + 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x01, 0xF0, 0x00, + 0x78, 0x00, 0x3E, 0x00, 0x7F, 0x80, 0x3F, 0xC0, 0x0F, 0xE0, 0x03, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x0F, + 0x00, 0x00, 0x07, 0x80, 0x00, 0x03, 0xC0, 0x0F, 0x81, 0xE0, 0x0F, 0x80, + 0xF0, 0x0F, 0x80, 0xF0, 0x1F, 0x00, 0x78, 0x1F, 0x00, 0x3C, 0x1F, 0x00, + 0x1E, 0x1F, 0x00, 0x1F, 0x1F, 0x00, 0x0F, 0x1E, 0x00, 0x07, 0xBF, 0x80, + 0x03, 0xFF, 0xC0, 0x01, 0xFD, 0xE0, 0x01, 0xFC, 0xF8, 0x00, 0xFC, 0x3C, + 0x00, 0x7C, 0x1F, 0x00, 0x3C, 0x07, 0x80, 0x1E, 0x03, 0xC0, 0x1F, 0x01, + 0xF0, 0x0F, 0x00, 0x78, 0x07, 0x80, 0x3E, 0x03, 0xC0, 0x0F, 0x01, 0xE0, + 0x07, 0x81, 0xE0, 0x03, 0xE0, 0xF0, 0x00, 0xF0, 0x78, 0x00, 0x7C, 0x00, + 0x01, 0xE0, 0x3C, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x3C, 0x07, + 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x03, + 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, + 0xF0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0xF0, 0x1E, 0x00, 0x00, + 0x07, 0xE0, 0x1F, 0x80, 0xF9, 0xFF, 0x07, 0xFC, 0x0F, 0x3F, 0xF8, 0xFF, + 0xE0, 0xF7, 0xFF, 0x9F, 0xFF, 0x0F, 0xF0, 0xFF, 0xC3, 0xF0, 0xFC, 0x07, + 0xF8, 0x1F, 0x1F, 0x80, 0x3F, 0x00, 0xF1, 0xF0, 0x03, 0xE0, 0x0F, 0x1E, + 0x00, 0x3C, 0x00, 0xF1, 0xE0, 0x03, 0xC0, 0x0F, 0x1E, 0x00, 0x3C, 0x00, + 0xF1, 0xE0, 0x07, 0x80, 0x0F, 0x3C, 0x00, 0x78, 0x01, 0xF3, 0xC0, 0x07, + 0x80, 0x1E, 0x3C, 0x00, 0x78, 0x01, 0xE3, 0xC0, 0x0F, 0x80, 0x1E, 0x3C, + 0x00, 0xF0, 0x01, 0xE7, 0xC0, 0x0F, 0x00, 0x3C, 0x78, 0x00, 0xF0, 0x03, + 0xC7, 0x80, 0x0F, 0x00, 0x3C, 0x78, 0x01, 0xE0, 0x03, 0xC7, 0x80, 0x1E, + 0x00, 0x3C, 0xF8, 0x01, 0xE0, 0x07, 0x8F, 0x00, 0x1E, 0x00, 0x78, 0xF0, + 0x01, 0xE0, 0x07, 0x8F, 0x00, 0x3C, 0x00, 0x78, 0x00, 0x07, 0xE0, 0x1F, + 0x3F, 0xF0, 0x3C, 0xFF, 0xF0, 0x7B, 0xFF, 0xE0, 0xFF, 0x07, 0xE1, 0xF8, + 0x07, 0xC7, 0xE0, 0x07, 0x8F, 0x80, 0x0F, 0x1F, 0x00, 0x1E, 0x3C, 0x00, + 0x3C, 0x78, 0x00, 0x78, 0xF0, 0x01, 0xE3, 0xC0, 0x03, 0xC7, 0x80, 0x07, + 0x8F, 0x00, 0x0F, 0x1E, 0x00, 0x3E, 0x3C, 0x00, 0x78, 0xF0, 0x00, 0xF1, + 0xE0, 0x01, 0xE3, 0xC0, 0x03, 0xC7, 0x80, 0x0F, 0x8F, 0x00, 0x1E, 0x3E, + 0x00, 0x3C, 0x78, 0x00, 0x78, 0xF0, 0x00, 0xF1, 0xE0, 0x03, 0xC0, 0x00, + 0x1F, 0x80, 0x01, 0xFF, 0xC0, 0x0F, 0xFF, 0xE0, 0x3F, 0xFF, 0xC0, 0xFE, + 0x0F, 0xC1, 0xF0, 0x0F, 0x87, 0xC0, 0x0F, 0x8F, 0x00, 0x0F, 0x3C, 0x00, + 0x1E, 0x78, 0x00, 0x3D, 0xE0, 0x00, 0x7B, 0xC0, 0x00, 0xF7, 0x80, 0x01, + 0xFE, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0x78, 0x00, 0x1E, 0xF0, 0x00, 0x3D, + 0xE0, 0x00, 0xF3, 0xC0, 0x01, 0xE7, 0x80, 0x07, 0x8F, 0x80, 0x1F, 0x0F, + 0x80, 0x7C, 0x1F, 0x83, 0xF8, 0x1F, 0xFF, 0xE0, 0x3F, 0xFF, 0x00, 0x1F, + 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x00, 0xFC, 0x00, 0x3C, 0x7F, 0xE0, + 0x07, 0xBF, 0xFE, 0x01, 0xFF, 0xFF, 0xC0, 0x3D, 0xE0, 0xFC, 0x07, 0xF0, + 0x0F, 0x80, 0xFC, 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0x07, 0xC0, 0x01, 0xE0, + 0xF8, 0x00, 0x3C, 0x1F, 0x00, 0x07, 0x83, 0xC0, 0x00, 0xF0, 0x78, 0x00, + 0x1E, 0x1F, 0x00, 0x03, 0xC3, 0xC0, 0x00, 0xF0, 0x78, 0x00, 0x1E, 0x0F, + 0x00, 0x03, 0xC3, 0xE0, 0x00, 0xF8, 0x7C, 0x00, 0x1E, 0x0F, 0x80, 0x07, + 0xC1, 0xF8, 0x01, 0xF0, 0x3F, 0x80, 0x7C, 0x0F, 0xF8, 0x3F, 0x81, 0xEF, + 0xFF, 0xE0, 0x3C, 0xFF, 0xF8, 0x07, 0x8F, 0xFC, 0x00, 0xF0, 0xFE, 0x00, + 0x3E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0x03, 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x03, + 0xC0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x3F, + 0xF8, 0xF0, 0x1F, 0xFF, 0x3C, 0x0F, 0xFF, 0xDF, 0x07, 0xE0, 0xFF, 0x83, + 0xE0, 0x1F, 0xE1, 0xF0, 0x03, 0xF8, 0x78, 0x00, 0xFE, 0x3C, 0x00, 0x1F, + 0x8F, 0x00, 0x07, 0xC7, 0x80, 0x01, 0xF1, 0xE0, 0x00, 0x7C, 0x78, 0x00, + 0x1F, 0x3C, 0x00, 0x0F, 0x8F, 0x00, 0x03, 0xE3, 0xC0, 0x00, 0xF8, 0xF0, + 0x00, 0x3E, 0x3C, 0x00, 0x1F, 0x8F, 0x00, 0x0F, 0xC3, 0xC0, 0x03, 0xF0, + 0xF8, 0x01, 0xFC, 0x1F, 0x00, 0xFF, 0x07, 0xE0, 0xFF, 0xC0, 0xFF, 0xFD, + 0xE0, 0x1F, 0xFE, 0x78, 0x03, 0xFF, 0x3E, 0x00, 0x3F, 0x0F, 0x80, 0x00, + 0x03, 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1F, 0x00, + 0x00, 0x07, 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0x87, 0xCF, 0xC3, 0xCF, 0xE1, 0xEF, + 0xE0, 0xFF, 0x80, 0x7F, 0x00, 0x7E, 0x00, 0x3F, 0x00, 0x1F, 0x00, 0x0F, + 0x00, 0x07, 0x80, 0x03, 0xC0, 0x03, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, + 0x78, 0x00, 0x3C, 0x00, 0x3E, 0x00, 0x1E, 0x00, 0x0F, 0x00, 0x07, 0x80, + 0x03, 0xC0, 0x03, 0xE0, 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x00, + 0x00, 0x3F, 0x80, 0x07, 0xFF, 0x00, 0xFF, 0xFC, 0x0F, 0xFF, 0xE0, 0xFC, + 0x1F, 0x87, 0x80, 0x3C, 0x7C, 0x01, 0xE3, 0xC0, 0x0F, 0x1E, 0x00, 0x00, + 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0xE0, 0x03, 0xFF, + 0xC0, 0x07, 0xFF, 0x80, 0x07, 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x07, 0xBC, + 0x00, 0x3D, 0xE0, 0x01, 0xEF, 0x00, 0x1F, 0x7C, 0x01, 0xF3, 0xF0, 0x1F, + 0x8F, 0xFF, 0xF8, 0x7F, 0xFF, 0x80, 0xFF, 0xF0, 0x01, 0xFE, 0x00, 0x03, + 0xC0, 0x1E, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC1, 0xFF, 0xEF, 0xFF, + 0x7F, 0xF0, 0x78, 0x03, 0xC0, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, + 0xC0, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x3C, 0x01, 0xE0, + 0x0F, 0x00, 0x78, 0x07, 0xC0, 0x3C, 0x01, 0xE0, 0x0F, 0xF0, 0x7F, 0x81, + 0xF8, 0x07, 0xC0, 0x0F, 0x00, 0x0F, 0x0F, 0x00, 0x1E, 0x0F, 0x00, 0x1E, + 0x1F, 0x00, 0x1E, 0x1E, 0x00, 0x1E, 0x1E, 0x00, 0x1E, 0x1E, 0x00, 0x3C, + 0x1E, 0x00, 0x3C, 0x3E, 0x00, 0x3C, 0x3C, 0x00, 0x3C, 0x3C, 0x00, 0x3C, + 0x3C, 0x00, 0x7C, 0x3C, 0x00, 0x78, 0x78, 0x00, 0x78, 0x78, 0x00, 0x78, + 0x78, 0x00, 0x78, 0x78, 0x00, 0xF8, 0x78, 0x00, 0xF0, 0xF0, 0x01, 0xF0, + 0xF0, 0x03, 0xF0, 0xF0, 0x07, 0xF0, 0xF8, 0x1F, 0xF0, 0xFF, 0xFF, 0xE0, + 0x7F, 0xFD, 0xE0, 0x3F, 0xF1, 0xE0, 0x1F, 0xC0, 0x00, 0xF0, 0x00, 0x7F, + 0xC0, 0x01, 0xEF, 0x00, 0x0F, 0xBC, 0x00, 0x3C, 0x78, 0x01, 0xE1, 0xE0, + 0x07, 0x87, 0x80, 0x3C, 0x1E, 0x01, 0xF0, 0x78, 0x07, 0x81, 0xE0, 0x3E, + 0x07, 0x80, 0xF0, 0x1E, 0x07, 0x80, 0x38, 0x1E, 0x00, 0xF0, 0xF0, 0x03, + 0xC7, 0xC0, 0x0F, 0x1E, 0x00, 0x3C, 0xF0, 0x00, 0xF3, 0xC0, 0x03, 0xDE, + 0x00, 0x07, 0x78, 0x00, 0x1F, 0xC0, 0x00, 0x7E, 0x00, 0x01, 0xF8, 0x00, + 0x07, 0xC0, 0x00, 0x1F, 0x00, 0x00, 0xF0, 0x07, 0xC0, 0x0F, 0x78, 0x03, + 0xE0, 0x0F, 0xBC, 0x03, 0xF0, 0x07, 0x9E, 0x01, 0xF8, 0x03, 0xCF, 0x00, + 0xFC, 0x03, 0xC7, 0x80, 0xFE, 0x01, 0xE3, 0xC0, 0x77, 0x01, 0xE0, 0xE0, + 0x7B, 0x80, 0xF0, 0x70, 0x39, 0xC0, 0xF0, 0x38, 0x3C, 0xE0, 0x78, 0x1C, + 0x1E, 0x78, 0x78, 0x0F, 0x1E, 0x3C, 0x3C, 0x07, 0x8F, 0x1E, 0x3C, 0x03, + 0xC7, 0x0F, 0x1E, 0x01, 0xE7, 0x87, 0x9E, 0x00, 0xF3, 0x81, 0xCF, 0x00, + 0x7B, 0xC0, 0xEF, 0x00, 0x3D, 0xC0, 0x77, 0x80, 0x1F, 0xE0, 0x3F, 0x80, + 0x0F, 0xF0, 0x1F, 0xC0, 0x07, 0xF0, 0x0F, 0xC0, 0x01, 0xF8, 0x07, 0xE0, + 0x00, 0xF8, 0x03, 0xE0, 0x00, 0x7C, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0xF0, + 0x00, 0x00, 0x03, 0xC0, 0x07, 0xC0, 0xF8, 0x01, 0xE0, 0x1E, 0x00, 0xF0, + 0x07, 0x80, 0x78, 0x00, 0xF0, 0x3C, 0x00, 0x3C, 0x1F, 0x00, 0x0F, 0x8F, + 0x80, 0x01, 0xE7, 0xC0, 0x00, 0x7D, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x03, + 0xF8, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, 0xC0, 0x00, + 0x07, 0xF0, 0x00, 0x03, 0xFE, 0x00, 0x01, 0xF7, 0x80, 0x00, 0xF9, 0xF0, + 0x00, 0x3C, 0x3C, 0x00, 0x1E, 0x0F, 0x80, 0x0F, 0x01, 0xE0, 0x07, 0x80, + 0x7C, 0x03, 0xE0, 0x0F, 0x01, 0xF0, 0x03, 0xE0, 0xF8, 0x00, 0x78, 0x00, + 0x03, 0xC0, 0x01, 0xE0, 0x78, 0x00, 0x78, 0x0F, 0x00, 0x0F, 0x01, 0xE0, + 0x03, 0xC0, 0x3C, 0x00, 0x78, 0x07, 0xC0, 0x1E, 0x00, 0x78, 0x07, 0xC0, + 0x0F, 0x00, 0xF0, 0x01, 0xE0, 0x3C, 0x00, 0x3C, 0x07, 0x80, 0x07, 0x81, + 0xE0, 0x00, 0xF0, 0x3C, 0x00, 0x1E, 0x0F, 0x00, 0x03, 0xC1, 0xC0, 0x00, + 0x3C, 0x78, 0x00, 0x07, 0x9E, 0x00, 0x00, 0xF3, 0xC0, 0x00, 0x1E, 0xF0, + 0x00, 0x03, 0xDE, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x0F, 0xE0, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x78, 0x00, + 0x00, 0x0F, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x1E, + 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x00, 0x01, + 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0xE0, + 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, + 0x00, 0x01, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x03, 0xE0, 0x00, 0x03, 0xE0, 0x00, 0x03, 0xE0, + 0x00, 0x03, 0xE0, 0x00, 0x03, 0xE0, 0x00, 0x03, 0xE0, 0x00, 0x03, 0xE0, + 0x00, 0x03, 0xC0, 0x00, 0x03, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, 0xE0, 0xFF, + 0xFF, 0xF0, 0x7F, 0xFF, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x7E, 0x00, 0xFE, + 0x00, 0xF0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x07, 0xC0, 0x07, 0x80, 0x07, 0x80, 0x07, 0x80, + 0x07, 0x80, 0x0F, 0x00, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0xF8, 0x00, + 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, + 0x38, 0x00, 0x38, 0x00, 0x3C, 0x00, 0x7C, 0x00, 0x78, 0x00, 0x78, 0x00, + 0x78, 0x00, 0x78, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xE0, 0x00, + 0xE0, 0x00, 0xF0, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0x7C, 0x00, 0x00, 0x70, + 0x07, 0x00, 0x60, 0x06, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0C, 0x01, 0xC0, + 0x1C, 0x01, 0xC0, 0x1C, 0x01, 0x80, 0x38, 0x03, 0x80, 0x38, 0x03, 0x00, + 0x30, 0x07, 0x00, 0x70, 0x07, 0x00, 0x60, 0x0E, 0x00, 0xE0, 0x0E, 0x00, + 0xE0, 0x0C, 0x01, 0xC0, 0x1C, 0x01, 0xC0, 0x1C, 0x01, 0x80, 0x38, 0x03, + 0x80, 0x38, 0x03, 0x00, 0x70, 0x07, 0x00, 0x70, 0x07, 0x00, 0x60, 0x0E, + 0x00, 0xE0, 0x06, 0x00, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x3F, 0x00, 0x0F, + 0x00, 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x1E, + 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x3E, 0x00, 0x3C, 0x00, 0x1C, + 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1E, 0x00, 0x0F, + 0x00, 0x07, 0x00, 0x1F, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x00, 0xF0, + 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x03, 0xE0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x07, 0x80, 0x07, 0x80, 0x07, 0x80, + 0x0F, 0x00, 0x7F, 0x00, 0x7E, 0x00, 0xF8, 0x00, 0x0F, 0x00, 0x01, 0xFE, + 0x00, 0xCF, 0xFC, 0x0E, 0xE3, 0xF0, 0xE6, 0x07, 0xFF, 0x60, 0x0F, 0xF0, + 0x00, 0x1E, 0x00 }; + +const GFXglyph FreeSansOblique24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 13, 0, 1 }, // 0x20 ' ' + { 0, 11, 34, 13, 6, -33 }, // 0x21 '!' + { 47, 13, 12, 17, 8, -32 }, // 0x22 '"' + { 67, 28, 34, 26, 3, -32 }, // 0x23 '#' + { 186, 26, 42, 26, 3, -35 }, // 0x24 '$' + { 323, 36, 34, 42, 6, -32 }, // 0x25 '%' + { 476, 26, 34, 31, 4, -32 }, // 0x26 '&' + { 587, 5, 12, 9, 8, -32 }, // 0x27 ''' + { 595, 15, 44, 16, 5, -33 }, // 0x28 '(' + { 678, 15, 44, 16, 1, -33 }, // 0x29 ')' + { 761, 14, 13, 18, 8, -33 }, // 0x2A '*' + { 784, 23, 22, 27, 5, -20 }, // 0x2B '+' + { 848, 7, 12, 13, 3, -4 }, // 0x2C ',' + { 859, 12, 4, 16, 5, -14 }, // 0x2D '-' + { 865, 6, 5, 13, 4, -4 }, // 0x2E '.' + { 869, 21, 35, 13, -1, -33 }, // 0x2F '/' + { 961, 23, 34, 26, 5, -32 }, // 0x30 '0' + { 1059, 13, 33, 26, 10, -32 }, // 0x31 '1' + { 1113, 27, 33, 26, 2, -32 }, // 0x32 '2' + { 1225, 25, 34, 26, 3, -32 }, // 0x33 '3' + { 1332, 24, 33, 26, 3, -32 }, // 0x34 '4' + { 1431, 27, 34, 26, 3, -32 }, // 0x35 '5' + { 1546, 24, 34, 26, 4, -32 }, // 0x36 '6' + { 1648, 26, 33, 26, 6, -32 }, // 0x37 '7' + { 1756, 25, 34, 26, 3, -32 }, // 0x38 '8' + { 1863, 24, 34, 26, 4, -32 }, // 0x39 '9' + { 1965, 10, 25, 13, 5, -24 }, // 0x3A ':' + { 1997, 11, 32, 13, 4, -24 }, // 0x3B ';' + { 2041, 26, 23, 27, 4, -22 }, // 0x3C '<' + { 2116, 26, 12, 27, 3, -16 }, // 0x3D '=' + { 2155, 26, 23, 27, 2, -21 }, // 0x3E '>' + { 2230, 20, 35, 26, 9, -34 }, // 0x3F '?' + { 2318, 45, 42, 48, 4, -34 }, // 0x40 '@' + { 2555, 30, 34, 31, 1, -33 }, // 0x41 'A' + { 2683, 29, 34, 31, 4, -33 }, // 0x42 'B' + { 2807, 30, 36, 33, 5, -34 }, // 0x43 'C' + { 2942, 31, 34, 33, 4, -33 }, // 0x44 'D' + { 3074, 31, 34, 31, 4, -33 }, // 0x45 'E' + { 3206, 30, 34, 28, 4, -33 }, // 0x46 'F' + { 3334, 33, 36, 37, 5, -34 }, // 0x47 'G' + { 3483, 33, 34, 34, 4, -33 }, // 0x48 'H' + { 3624, 11, 34, 13, 5, -33 }, // 0x49 'I' + { 3671, 25, 35, 24, 2, -33 }, // 0x4A 'J' + { 3781, 34, 34, 31, 4, -33 }, // 0x4B 'K' + { 3926, 22, 34, 26, 4, -33 }, // 0x4C 'L' + { 4020, 39, 34, 40, 4, -33 }, // 0x4D 'M' + { 4186, 34, 34, 34, 4, -33 }, // 0x4E 'N' + { 4331, 33, 36, 36, 5, -34 }, // 0x4F 'O' + { 4480, 29, 34, 30, 4, -33 }, // 0x50 'P' + { 4604, 33, 38, 36, 5, -34 }, // 0x51 'Q' + { 4761, 30, 34, 33, 4, -33 }, // 0x52 'R' + { 4889, 29, 36, 31, 4, -34 }, // 0x53 'S' + { 5020, 28, 34, 29, 7, -33 }, // 0x54 'T' + { 5139, 31, 35, 34, 6, -33 }, // 0x55 'U' + { 5275, 29, 34, 30, 8, -33 }, // 0x56 'V' + { 5399, 43, 34, 44, 8, -33 }, // 0x57 'W' + { 5582, 36, 34, 31, 1, -33 }, // 0x58 'X' + { 5735, 30, 34, 32, 8, -33 }, // 0x59 'Y' + { 5863, 34, 34, 29, 1, -33 }, // 0x5A 'Z' + { 6008, 18, 44, 13, 1, -33 }, // 0x5B '[' + { 6107, 6, 35, 13, 7, -33 }, // 0x5C '\' + { 6134, 18, 44, 13, -1, -33 }, // 0x5D ']' + { 6233, 17, 18, 22, 6, -32 }, // 0x5E '^' + { 6272, 29, 2, 26, -3, 7 }, // 0x5F '_' + { 6280, 8, 7, 16, 8, -34 }, // 0x60 '`' + { 6287, 23, 27, 26, 3, -25 }, // 0x61 'a' + { 6365, 25, 35, 26, 3, -33 }, // 0x62 'b' + { 6475, 22, 27, 24, 4, -25 }, // 0x63 'c' + { 6550, 27, 35, 26, 4, -33 }, // 0x64 'd' + { 6669, 23, 27, 26, 4, -25 }, // 0x65 'e' + { 6747, 15, 34, 12, 3, -33 }, // 0x66 'f' + { 6811, 27, 36, 26, 2, -25 }, // 0x67 'g' + { 6933, 23, 34, 25, 3, -33 }, // 0x68 'h' + { 7031, 11, 34, 10, 3, -33 }, // 0x69 'i' + { 7078, 18, 44, 11, -2, -33 }, // 0x6A 'j' + { 7177, 25, 34, 24, 3, -33 }, // 0x6B 'k' + { 7284, 11, 34, 10, 3, -33 }, // 0x6C 'l' + { 7331, 36, 26, 38, 3, -25 }, // 0x6D 'm' + { 7448, 23, 26, 25, 3, -25 }, // 0x6E 'n' + { 7523, 23, 27, 26, 4, -25 }, // 0x6F 'o' + { 7601, 27, 36, 26, 1, -25 }, // 0x70 'p' + { 7723, 26, 36, 26, 3, -25 }, // 0x71 'q' + { 7840, 17, 26, 15, 3, -25 }, // 0x72 'r' + { 7896, 21, 27, 24, 3, -25 }, // 0x73 's' + { 7967, 13, 32, 12, 4, -30 }, // 0x74 't' + { 8019, 24, 26, 25, 4, -24 }, // 0x75 'u' + { 8097, 22, 25, 23, 6, -24 }, // 0x76 'v' + { 8166, 33, 25, 34, 6, -24 }, // 0x77 'w' + { 8270, 26, 25, 23, 1, -24 }, // 0x78 'x' + { 8352, 27, 35, 23, 0, -24 }, // 0x79 'y' + { 8471, 25, 25, 23, 1, -24 }, // 0x7A 'z' + { 8550, 16, 44, 16, 5, -33 }, // 0x7B '{' + { 8638, 12, 44, 12, 3, -33 }, // 0x7C '|' + { 8704, 16, 44, 16, -1, -33 }, // 0x7D '}' + { 8792, 21, 7, 27, 6, -19 } }; // 0x7E '~' + +const GFXfont FreeSansOblique24pt7b PROGMEM = { + (uint8_t *)FreeSansOblique24pt7bBitmaps, + (GFXglyph *)FreeSansOblique24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 9483 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansOblique9pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansOblique9pt7b.h new file mode 100644 index 0000000..18a6cbe --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSansOblique9pt7b.h @@ -0,0 +1,220 @@ +const uint8_t FreeSansOblique9pt7bBitmaps[] PROGMEM = { + 0x10, 0x84, 0x22, 0x10, 0x84, 0x42, 0x10, 0x08, 0x00, 0xDE, 0xE5, 0x20, + 0x06, 0x40, 0x88, 0x13, 0x06, 0x43, 0xFE, 0x32, 0x04, 0x40, 0x98, 0x32, + 0x1F, 0xF0, 0x98, 0x22, 0x04, 0xC0, 0x02, 0x01, 0xF8, 0x6B, 0x99, 0x33, + 0x40, 0x68, 0x0F, 0x00, 0xF8, 0x07, 0xC1, 0x1B, 0x23, 0x64, 0x4E, 0x98, + 0xFC, 0x04, 0x00, 0x80, 0x3C, 0x08, 0xCC, 0x23, 0x18, 0x86, 0x32, 0x0C, + 0x64, 0x19, 0x90, 0x1E, 0x40, 0x01, 0x1E, 0x02, 0x66, 0x09, 0x8C, 0x23, + 0x18, 0x86, 0x62, 0x07, 0x80, 0x0F, 0x06, 0x63, 0x18, 0xC6, 0x3F, 0x07, + 0x03, 0xC1, 0xB3, 0xC7, 0xB0, 0xCC, 0x33, 0x3E, 0x79, 0x80, 0xFA, 0x04, + 0x10, 0x60, 0x83, 0x04, 0x18, 0x30, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x10, + 0x30, 0x20, 0x08, 0x18, 0x10, 0x30, 0x60, 0xC1, 0x83, 0x06, 0x18, 0x30, + 0x41, 0x82, 0x0C, 0x10, 0x40, 0x19, 0x73, 0x16, 0x48, 0x04, 0x04, 0x02, + 0x1F, 0xF0, 0x80, 0x80, 0x40, 0x20, 0x6D, 0x28, 0xF0, 0xC0, 0x01, 0x02, + 0x04, 0x04, 0x08, 0x08, 0x10, 0x10, 0x20, 0x20, 0x40, 0x40, 0x80, 0x0F, + 0x19, 0xC8, 0x6C, 0x36, 0x1A, 0x0F, 0x05, 0x86, 0xC3, 0x61, 0xB1, 0x9C, + 0x87, 0x80, 0x08, 0xCD, 0xE3, 0x18, 0xC4, 0x23, 0x18, 0xC4, 0x00, 0x07, + 0x83, 0x1C, 0x41, 0x98, 0x30, 0x06, 0x01, 0x80, 0x60, 0x38, 0x1C, 0x06, + 0x01, 0x80, 0x20, 0x0F, 0xF8, 0x0F, 0x86, 0x73, 0x0C, 0x83, 0x00, 0xC0, + 0x60, 0xE0, 0x06, 0x01, 0xB0, 0x6C, 0x13, 0x8C, 0x7C, 0x00, 0x00, 0x80, + 0xC0, 0xE0, 0xA0, 0x90, 0x98, 0x8C, 0x86, 0xFF, 0x81, 0x01, 0x80, 0xC0, + 0x60, 0x0F, 0xC3, 0x00, 0x40, 0x08, 0x03, 0x00, 0x7F, 0x1C, 0x70, 0x06, + 0x00, 0xC0, 0x1B, 0x06, 0x71, 0x87, 0xE0, 0x0F, 0x86, 0x73, 0x0D, 0x80, + 0x60, 0x1F, 0xCF, 0x3B, 0x86, 0xC1, 0xB0, 0x6C, 0x33, 0x98, 0x3C, 0x00, + 0x7F, 0xC0, 0x20, 0x10, 0x0C, 0x06, 0x01, 0x00, 0x80, 0x60, 0x10, 0x0C, + 0x02, 0x01, 0x80, 0x40, 0x00, 0x0F, 0x86, 0x73, 0x0C, 0xC3, 0x30, 0xCC, + 0x61, 0xE1, 0x86, 0x41, 0xB0, 0x6C, 0x13, 0x8C, 0x3E, 0x00, 0x0F, 0x06, + 0x73, 0x0D, 0x83, 0x60, 0xD8, 0x77, 0x3C, 0xFE, 0x01, 0x80, 0x6C, 0x33, + 0x98, 0x7C, 0x00, 0x30, 0x00, 0x00, 0x00, 0xC0, 0x18, 0x00, 0x00, 0x00, + 0x0C, 0x62, 0x11, 0x00, 0x00, 0x01, 0xC3, 0x8F, 0x0C, 0x07, 0x00, 0xE0, + 0x1E, 0x01, 0x00, 0x7F, 0xC0, 0x00, 0x03, 0xFE, 0x40, 0x3C, 0x03, 0x80, + 0x70, 0x18, 0x78, 0xE1, 0xC0, 0x00, 0x00, 0x1F, 0x30, 0xD0, 0x78, 0x30, + 0x30, 0x30, 0x30, 0x30, 0x30, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0xFE, + 0x00, 0xC0, 0xE0, 0xC0, 0x18, 0x61, 0xD3, 0x31, 0x9C, 0xD8, 0xC2, 0x36, + 0x31, 0x8F, 0x18, 0x67, 0xC6, 0x11, 0xB1, 0x8C, 0xCC, 0x67, 0x63, 0x0E, + 0xF0, 0x60, 0x00, 0x1C, 0x00, 0x01, 0x81, 0x00, 0x1F, 0xC0, 0x01, 0xC0, + 0x1C, 0x03, 0xC0, 0x24, 0x06, 0x60, 0x46, 0x0C, 0x61, 0x86, 0x1F, 0xE3, + 0x06, 0x20, 0x26, 0x03, 0x40, 0x30, 0x1F, 0xE1, 0x87, 0x30, 0x33, 0x03, + 0x30, 0x23, 0x06, 0x3F, 0xC6, 0x06, 0x60, 0x66, 0x06, 0x60, 0x66, 0x0C, + 0x7F, 0x80, 0x07, 0xC1, 0x86, 0x30, 0x32, 0x03, 0x60, 0x04, 0x00, 0xC0, + 0x0C, 0x00, 0xC0, 0x6C, 0x06, 0xC0, 0xC6, 0x18, 0x3E, 0x00, 0x1F, 0xE0, + 0xC1, 0x84, 0x06, 0x60, 0x33, 0x01, 0x98, 0x0C, 0x80, 0x64, 0x02, 0x60, + 0x33, 0x01, 0x98, 0x18, 0x81, 0x87, 0xF0, 0x00, 0x1F, 0xF1, 0x80, 0x10, + 0x03, 0x00, 0x30, 0x03, 0x00, 0x3F, 0xE2, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x04, 0x00, 0x7F, 0xC0, 0x1F, 0xF1, 0x80, 0x10, 0x03, 0x00, 0x30, 0x03, + 0x00, 0x3F, 0xC2, 0x00, 0x60, 0x06, 0x00, 0x60, 0x04, 0x00, 0x40, 0x00, + 0x07, 0xE0, 0xE1, 0x8C, 0x06, 0xC0, 0x36, 0x00, 0x60, 0x03, 0x07, 0xF8, + 0x02, 0xC0, 0x36, 0x01, 0x98, 0x1C, 0xE1, 0xC1, 0xF2, 0x00, 0x18, 0x08, + 0xC0, 0xC4, 0x06, 0x60, 0x33, 0x01, 0x18, 0x18, 0xFF, 0xC4, 0x06, 0x60, + 0x23, 0x01, 0x18, 0x18, 0x80, 0xC4, 0x06, 0x00, 0x33, 0x32, 0x26, 0x66, + 0x44, 0xCC, 0xC0, 0x00, 0xC0, 0x60, 0x18, 0x06, 0x01, 0x80, 0x60, 0x30, + 0x0C, 0x03, 0x30, 0xCC, 0x63, 0x18, 0x7C, 0x00, 0x18, 0x18, 0x60, 0xC1, + 0x0E, 0x0C, 0x60, 0x33, 0x00, 0xD8, 0x03, 0xF0, 0x0C, 0xC0, 0x61, 0x81, + 0x86, 0x06, 0x0C, 0x10, 0x30, 0x40, 0x60, 0x18, 0x0C, 0x04, 0x06, 0x03, + 0x01, 0x80, 0xC0, 0x40, 0x60, 0x30, 0x18, 0x08, 0x07, 0xF8, 0x18, 0x06, + 0x18, 0x0E, 0x18, 0x0E, 0x34, 0x1E, 0x34, 0x36, 0x34, 0x34, 0x24, 0x64, + 0x24, 0x6C, 0x64, 0xCC, 0x64, 0x8C, 0x65, 0x88, 0x43, 0x08, 0x43, 0x18, + 0x18, 0x08, 0xE0, 0x47, 0x06, 0x6C, 0x33, 0x61, 0x99, 0x08, 0x8C, 0xC4, + 0x66, 0x61, 0xB3, 0x0D, 0x18, 0x38, 0x81, 0xC4, 0x06, 0x00, 0x07, 0xC0, + 0xC3, 0x8C, 0x0E, 0xC0, 0x36, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, + 0x36, 0x01, 0xB8, 0x18, 0xE1, 0x81, 0xF0, 0x00, 0x1F, 0xE1, 0x83, 0x10, + 0x33, 0x03, 0x30, 0x33, 0x06, 0x3F, 0xC2, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x04, 0x00, 0x40, 0x00, 0x07, 0xC0, 0xC3, 0x8C, 0x0E, 0xC0, 0x36, 0x01, + 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x36, 0x09, 0xB8, 0x78, 0xE3, 0x81, + 0xF6, 0x00, 0x10, 0x1F, 0xF0, 0xC0, 0xC4, 0x06, 0x60, 0x33, 0x01, 0x18, + 0x18, 0xFF, 0x04, 0x0C, 0x60, 0x63, 0x03, 0x18, 0x18, 0x80, 0xC4, 0x06, + 0x00, 0x07, 0xC1, 0x87, 0x30, 0x33, 0x03, 0x30, 0x03, 0xC0, 0x0F, 0xC0, + 0x1E, 0x00, 0x6C, 0x06, 0xC0, 0x46, 0x0C, 0x3F, 0x00, 0xFF, 0xC3, 0x00, + 0xC0, 0x20, 0x18, 0x06, 0x01, 0x80, 0x60, 0x10, 0x0C, 0x03, 0x00, 0xC0, + 0x20, 0x00, 0x30, 0x13, 0x03, 0x20, 0x36, 0x03, 0x60, 0x26, 0x06, 0x60, + 0x64, 0x06, 0xC0, 0x6C, 0x04, 0xC0, 0xCE, 0x18, 0x3E, 0x00, 0xC0, 0x78, + 0x0B, 0x03, 0x20, 0xC4, 0x18, 0xC6, 0x18, 0x83, 0x30, 0x64, 0x0D, 0x80, + 0xA0, 0x1C, 0x03, 0x00, 0xC1, 0x83, 0xC1, 0x83, 0xC3, 0x86, 0xC2, 0x86, + 0xC6, 0x84, 0xC4, 0x8C, 0xCC, 0xC8, 0xC8, 0xD8, 0xD8, 0xD0, 0xD0, 0xF0, + 0x70, 0xE0, 0x60, 0xE0, 0x60, 0xE0, 0x0C, 0x0C, 0x30, 0x60, 0x63, 0x01, + 0x98, 0x02, 0xC0, 0x0E, 0x00, 0x38, 0x01, 0xE0, 0x0C, 0x80, 0x33, 0x01, + 0x8C, 0x0C, 0x18, 0x60, 0x60, 0xC0, 0x66, 0x0C, 0x60, 0xC2, 0x18, 0x33, + 0x03, 0x60, 0x1C, 0x01, 0x80, 0x18, 0x01, 0x80, 0x18, 0x01, 0x00, 0x30, + 0x00, 0x1F, 0xF0, 0x07, 0x00, 0xE0, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, + 0xC0, 0x18, 0x03, 0x00, 0x60, 0x0C, 0x00, 0xFF, 0xC0, 0x0E, 0x10, 0x20, + 0x41, 0x02, 0x04, 0x08, 0x20, 0x40, 0x81, 0x04, 0x08, 0x10, 0x20, 0xE0, + 0xAA, 0xA9, 0x55, 0x40, 0x0E, 0x08, 0x10, 0x20, 0x41, 0x02, 0x04, 0x08, + 0x20, 0x40, 0x81, 0x04, 0x08, 0x10, 0xE0, 0x0C, 0x18, 0x51, 0xA2, 0x4C, + 0x50, 0x80, 0xFF, 0xE0, 0xC8, 0x80, 0x0F, 0x86, 0x33, 0x0C, 0x03, 0x03, + 0xDF, 0xEE, 0x0B, 0x02, 0xC1, 0x9F, 0xE0, 0x10, 0x04, 0x01, 0x00, 0xDC, + 0x39, 0x88, 0x32, 0x0D, 0x83, 0x40, 0xD0, 0x64, 0x1B, 0x8C, 0xBC, 0x00, + 0x1F, 0x18, 0xD8, 0x6C, 0x0C, 0x06, 0x03, 0x01, 0x86, 0x66, 0x3E, 0x00, + 0x00, 0x20, 0x08, 0x01, 0x0F, 0x23, 0x14, 0xC1, 0x18, 0x26, 0x04, 0xC0, + 0x98, 0x23, 0x04, 0x71, 0x87, 0xD0, 0x0F, 0x0C, 0x76, 0x0D, 0x83, 0xFF, + 0xF0, 0x0C, 0x03, 0x06, 0x63, 0x0F, 0x80, 0x1C, 0xC2, 0x1E, 0x20, 0x84, + 0x10, 0x41, 0x04, 0x20, 0x80, 0x0F, 0x46, 0x33, 0x0C, 0xC1, 0x60, 0xD8, + 0x26, 0x09, 0x86, 0x71, 0x8F, 0xE0, 0x10, 0x04, 0xC2, 0x1F, 0x00, 0x10, + 0x04, 0x01, 0x00, 0x9F, 0x39, 0x88, 0x22, 0x09, 0x02, 0x40, 0x90, 0x44, + 0x12, 0x04, 0x81, 0x00, 0x10, 0x02, 0x22, 0x64, 0x44, 0x48, 0x80, 0x04, + 0x00, 0x01, 0x08, 0x20, 0x82, 0x08, 0x41, 0x04, 0x10, 0x42, 0x08, 0xE0, + 0x10, 0x08, 0x04, 0x04, 0x32, 0x31, 0x20, 0xA0, 0xB8, 0x6C, 0x22, 0x11, + 0x90, 0xC8, 0x30, 0x11, 0x22, 0x22, 0x64, 0x44, 0x48, 0x80, 0x2F, 0x3C, + 0x63, 0x8C, 0x86, 0x19, 0x08, 0x44, 0x10, 0x88, 0x21, 0x10, 0x82, 0x21, + 0x04, 0x82, 0x11, 0x04, 0x20, 0x00, 0x0B, 0xF3, 0x18, 0x82, 0x20, 0x90, + 0x24, 0x09, 0x04, 0x41, 0x20, 0x48, 0x10, 0x0F, 0x0C, 0x76, 0x0D, 0x83, + 0xC0, 0xF0, 0x3C, 0x1B, 0x06, 0xE3, 0x0F, 0x00, 0x17, 0xC3, 0x1C, 0x41, + 0x98, 0x32, 0x06, 0x40, 0xC8, 0x33, 0x06, 0x71, 0x8B, 0xC1, 0x00, 0x20, + 0x08, 0x01, 0x00, 0x00, 0x1E, 0xCC, 0x66, 0x09, 0x82, 0xC0, 0xB0, 0x4C, + 0x13, 0x04, 0x63, 0x0F, 0xC0, 0x20, 0x08, 0x02, 0x00, 0x80, 0x2C, 0x60, + 0x81, 0x04, 0x08, 0x10, 0x20, 0x81, 0x00, 0x1E, 0x33, 0x63, 0x60, 0x70, + 0x1E, 0x03, 0xC3, 0xC6, 0x7C, 0x22, 0xF2, 0x44, 0x44, 0xCC, 0xCE, 0x21, + 0x20, 0x90, 0x48, 0x24, 0x12, 0x13, 0x09, 0x84, 0xE6, 0x3E, 0x00, 0xC1, + 0xE1, 0xB0, 0xC8, 0xC4, 0x43, 0x61, 0xA0, 0xF0, 0x70, 0x18, 0x00, 0xC7, + 0x1E, 0x38, 0xB3, 0xCD, 0x96, 0x4C, 0xB6, 0x6D, 0xB1, 0x4D, 0x0E, 0x78, + 0x63, 0x83, 0x1C, 0x00, 0x10, 0xC3, 0x10, 0x24, 0x07, 0x80, 0xE0, 0x1C, + 0x07, 0x81, 0x90, 0x23, 0x08, 0x20, 0x30, 0x46, 0x18, 0x42, 0x08, 0xC1, + 0x10, 0x24, 0x07, 0x80, 0xE0, 0x1C, 0x03, 0x00, 0x60, 0x08, 0x03, 0x01, + 0xC0, 0x00, 0x3F, 0x80, 0x80, 0x80, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, + 0x7F, 0x00, 0x18, 0x88, 0x42, 0x10, 0x88, 0xC3, 0x18, 0x88, 0x42, 0x18, + 0xE0, 0x11, 0x22, 0x22, 0x24, 0x44, 0x4C, 0x88, 0x88, 0x00, 0x38, 0xC2, + 0x10, 0x88, 0xC6, 0x18, 0x88, 0x42, 0x10, 0x88, 0xC0, 0x70, 0x4E, 0x41, + 0xC0 }; + +const GFXglyph FreeSansOblique9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 5, 13, 5, 2, -12 }, // 0x21 '!' + { 9, 5, 4, 6, 3, -12 }, // 0x22 '"' + { 12, 11, 13, 10, 1, -12 }, // 0x23 '#' + { 30, 11, 16, 10, 1, -13 }, // 0x24 '$' + { 52, 15, 13, 16, 2, -12 }, // 0x25 '%' + { 77, 10, 13, 12, 2, -12 }, // 0x26 '&' + { 94, 2, 4, 3, 3, -12 }, // 0x27 ''' + { 95, 7, 17, 6, 2, -12 }, // 0x28 '(' + { 110, 7, 17, 6, -1, -12 }, // 0x29 ')' + { 125, 6, 5, 7, 3, -12 }, // 0x2A '*' + { 129, 9, 8, 11, 2, -7 }, // 0x2B '+' + { 138, 3, 5, 5, 1, -1 }, // 0x2C ',' + { 140, 4, 1, 6, 2, -4 }, // 0x2D '-' + { 141, 2, 1, 5, 2, 0 }, // 0x2E '.' + { 142, 8, 13, 5, 0, -12 }, // 0x2F '/' + { 155, 9, 13, 10, 2, -12 }, // 0x30 '0' + { 170, 5, 13, 10, 4, -12 }, // 0x31 '1' + { 179, 11, 13, 10, 1, -12 }, // 0x32 '2' + { 197, 10, 13, 10, 1, -12 }, // 0x33 '3' + { 214, 9, 13, 10, 1, -12 }, // 0x34 '4' + { 229, 11, 13, 10, 1, -12 }, // 0x35 '5' + { 247, 10, 13, 10, 2, -12 }, // 0x36 '6' + { 264, 10, 13, 10, 2, -12 }, // 0x37 '7' + { 281, 10, 13, 10, 1, -12 }, // 0x38 '8' + { 298, 10, 13, 10, 1, -12 }, // 0x39 '9' + { 315, 4, 9, 5, 2, -8 }, // 0x3A ':' + { 320, 5, 12, 5, 1, -8 }, // 0x3B ';' + { 328, 9, 9, 11, 2, -8 }, // 0x3C '<' + { 339, 10, 4, 11, 1, -5 }, // 0x3D '=' + { 344, 9, 9, 11, 1, -7 }, // 0x3E '>' + { 355, 9, 13, 10, 3, -12 }, // 0x3F '?' + { 370, 18, 16, 18, 1, -12 }, // 0x40 '@' + { 406, 12, 13, 12, 0, -12 }, // 0x41 'A' + { 426, 12, 13, 12, 1, -12 }, // 0x42 'B' + { 446, 12, 13, 13, 2, -12 }, // 0x43 'C' + { 466, 13, 13, 13, 1, -12 }, // 0x44 'D' + { 488, 12, 13, 12, 1, -12 }, // 0x45 'E' + { 508, 12, 13, 11, 1, -12 }, // 0x46 'F' + { 528, 13, 13, 14, 2, -12 }, // 0x47 'G' + { 550, 13, 13, 13, 1, -12 }, // 0x48 'H' + { 572, 4, 13, 5, 2, -12 }, // 0x49 'I' + { 579, 10, 13, 9, 1, -12 }, // 0x4A 'J' + { 596, 14, 13, 12, 1, -12 }, // 0x4B 'K' + { 619, 9, 13, 10, 1, -12 }, // 0x4C 'L' + { 634, 16, 13, 15, 1, -12 }, // 0x4D 'M' + { 660, 13, 13, 13, 1, -12 }, // 0x4E 'N' + { 682, 13, 13, 14, 2, -12 }, // 0x4F 'O' + { 704, 12, 13, 12, 1, -12 }, // 0x50 'P' + { 724, 13, 14, 14, 2, -12 }, // 0x51 'Q' + { 747, 13, 13, 13, 1, -12 }, // 0x52 'R' + { 769, 12, 13, 12, 1, -12 }, // 0x53 'S' + { 789, 10, 13, 11, 3, -12 }, // 0x54 'T' + { 806, 12, 13, 13, 2, -12 }, // 0x55 'U' + { 826, 11, 13, 12, 3, -12 }, // 0x56 'V' + { 844, 16, 13, 17, 3, -12 }, // 0x57 'W' + { 870, 14, 13, 12, 0, -12 }, // 0x58 'X' + { 893, 12, 13, 12, 3, -12 }, // 0x59 'Y' + { 913, 12, 13, 11, 1, -12 }, // 0x5A 'Z' + { 933, 7, 17, 5, 0, -12 }, // 0x5B '[' + { 948, 2, 13, 5, 3, -12 }, // 0x5C '\' + { 952, 7, 17, 5, 0, -12 }, // 0x5D ']' + { 967, 7, 7, 8, 2, -12 }, // 0x5E '^' + { 974, 11, 1, 10, -1, 3 }, // 0x5F '_' + { 976, 3, 3, 6, 3, -12 }, // 0x60 '`' + { 978, 10, 10, 10, 1, -9 }, // 0x61 'a' + { 991, 10, 13, 10, 1, -12 }, // 0x62 'b' + { 1008, 9, 10, 9, 1, -9 }, // 0x63 'c' + { 1020, 11, 13, 10, 1, -12 }, // 0x64 'd' + { 1038, 10, 10, 10, 1, -9 }, // 0x65 'e' + { 1051, 6, 13, 5, 1, -12 }, // 0x66 'f' + { 1061, 10, 14, 10, 0, -9 }, // 0x67 'g' + { 1079, 10, 13, 10, 1, -12 }, // 0x68 'h' + { 1096, 4, 13, 4, 1, -12 }, // 0x69 'i' + { 1103, 6, 17, 4, -1, -12 }, // 0x6A 'j' + { 1116, 9, 13, 9, 1, -12 }, // 0x6B 'k' + { 1131, 4, 13, 4, 1, -12 }, // 0x6C 'l' + { 1138, 15, 10, 15, 1, -9 }, // 0x6D 'm' + { 1157, 10, 11, 10, 1, -10 }, // 0x6E 'n' + { 1171, 10, 10, 10, 1, -9 }, // 0x6F 'o' + { 1184, 11, 14, 10, 0, -9 }, // 0x70 'p' + { 1204, 10, 14, 10, 1, -9 }, // 0x71 'q' + { 1222, 7, 10, 6, 1, -9 }, // 0x72 'r' + { 1231, 8, 10, 9, 1, -9 }, // 0x73 's' + { 1241, 4, 12, 5, 2, -11 }, // 0x74 't' + { 1247, 9, 10, 10, 2, -9 }, // 0x75 'u' + { 1259, 9, 10, 9, 2, -9 }, // 0x76 'v' + { 1271, 13, 10, 13, 2, -9 }, // 0x77 'w' + { 1288, 11, 10, 9, 0, -9 }, // 0x78 'x' + { 1302, 11, 14, 9, 0, -9 }, // 0x79 'y' + { 1322, 9, 10, 9, 1, -9 }, // 0x7A 'z' + { 1334, 5, 17, 6, 2, -12 }, // 0x7B '{' + { 1345, 4, 17, 5, 1, -12 }, // 0x7C '|' + { 1354, 5, 17, 6, 0, -12 }, // 0x7D '}' + { 1365, 9, 3, 11, 2, -7 } }; // 0x7E '~' + +const GFXfont FreeSansOblique9pt7b PROGMEM = { + (uint8_t *)FreeSansOblique9pt7bBitmaps, + (GFXglyph *)FreeSansOblique9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 2041 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerif12pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerif12pt7b.h new file mode 100644 index 0000000..48ad3da --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerif12pt7b.h @@ -0,0 +1,259 @@ +const uint8_t FreeSerif12pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFE, 0xA8, 0x3F, 0xCF, 0x3C, 0xF3, 0x8A, 0x20, 0x0C, 0x40, 0xC4, + 0x08, 0x40, 0x8C, 0x08, 0xC7, 0xFF, 0x18, 0x81, 0x88, 0x10, 0x81, 0x08, + 0xFF, 0xE1, 0x18, 0x31, 0x03, 0x10, 0x31, 0x02, 0x10, 0x04, 0x07, 0xC6, + 0x5B, 0x12, 0xC4, 0xB1, 0x0F, 0x41, 0xF0, 0x1E, 0x01, 0xE0, 0x58, 0x13, + 0x84, 0xE1, 0x3C, 0x4F, 0x96, 0x3F, 0x01, 0x00, 0x00, 0x04, 0x03, 0x83, + 0x03, 0x9F, 0x81, 0xC2, 0x20, 0x60, 0x90, 0x38, 0x24, 0x0C, 0x12, 0x03, + 0x0D, 0x00, 0xC6, 0x47, 0x9E, 0x23, 0x10, 0x09, 0x84, 0x04, 0xE1, 0x03, + 0x30, 0x40, 0x8C, 0x20, 0x43, 0x08, 0x10, 0xC4, 0x08, 0x1E, 0x00, 0x03, + 0xC0, 0x02, 0x30, 0x03, 0x08, 0x01, 0x84, 0x00, 0xC4, 0x00, 0x7C, 0xF8, + 0x1C, 0x38, 0x1E, 0x08, 0x33, 0x0C, 0x31, 0xC4, 0x10, 0x74, 0x18, 0x3A, + 0x0C, 0x0E, 0x07, 0x03, 0x83, 0xC3, 0xE2, 0x7E, 0x3E, 0xFF, 0xA0, 0x04, + 0x21, 0x08, 0x61, 0x0C, 0x30, 0xC3, 0x0C, 0x30, 0xC1, 0x04, 0x18, 0x20, + 0x40, 0x81, 0x81, 0x02, 0x04, 0x18, 0x20, 0x83, 0x0C, 0x30, 0xC3, 0x0C, + 0x30, 0x86, 0x10, 0x84, 0x20, 0x30, 0xB3, 0xD7, 0x54, 0x38, 0x7C, 0xD3, + 0x30, 0x30, 0x10, 0x04, 0x00, 0x80, 0x10, 0x02, 0x00, 0x41, 0xFF, 0xC1, + 0x00, 0x20, 0x04, 0x00, 0x80, 0x10, 0x00, 0xDF, 0x95, 0x00, 0xFC, 0xFC, + 0x06, 0x0C, 0x10, 0x60, 0xC1, 0x06, 0x0C, 0x10, 0x60, 0xC1, 0x06, 0x0C, + 0x10, 0x60, 0xC0, 0x1E, 0x0C, 0xC6, 0x19, 0x86, 0xC0, 0xB0, 0x3C, 0x0F, + 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xD8, 0x66, 0x18, 0xCC, 0x1E, + 0x00, 0x11, 0xC3, 0x0C, 0x30, 0xC3, 0x0C, 0x30, 0xC3, 0x0C, 0x30, 0xC3, + 0x0C, 0xFC, 0x1E, 0x18, 0xC4, 0x1A, 0x06, 0x01, 0x80, 0x60, 0x10, 0x0C, + 0x02, 0x01, 0x00, 0xC0, 0x60, 0x30, 0x18, 0x1F, 0xF8, 0x1E, 0x18, 0xE8, + 0x18, 0x06, 0x01, 0x00, 0x80, 0xF0, 0x7E, 0x03, 0xC0, 0x70, 0x0C, 0x03, + 0x00, 0xC0, 0x6E, 0x11, 0xF8, 0x01, 0x00, 0xC0, 0x70, 0x2C, 0x0B, 0x04, + 0xC2, 0x30, 0x8C, 0x43, 0x20, 0xC8, 0x33, 0xFF, 0x03, 0x00, 0xC0, 0x30, + 0x0C, 0x00, 0x03, 0xF1, 0x00, 0x40, 0x18, 0x0F, 0x80, 0xF8, 0x0E, 0x01, + 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x20, 0x1B, 0x8C, 0x7C, 0x00, 0x01, + 0xC3, 0xC1, 0xC0, 0xC0, 0x70, 0x18, 0x0E, 0xF3, 0xCE, 0xC1, 0xF0, 0x3C, + 0x0F, 0x03, 0xC0, 0xD8, 0x36, 0x08, 0xC6, 0x1E, 0x00, 0x3F, 0xD0, 0x38, + 0x08, 0x06, 0x01, 0x80, 0x40, 0x10, 0x0C, 0x02, 0x00, 0x80, 0x20, 0x10, + 0x04, 0x01, 0x00, 0x80, 0x20, 0x1F, 0x18, 0x6C, 0x0F, 0x03, 0xC0, 0xF8, + 0x67, 0x30, 0xF0, 0x1E, 0x09, 0xE6, 0x3B, 0x07, 0xC0, 0xF0, 0x3C, 0x0D, + 0x86, 0x1F, 0x00, 0x1E, 0x08, 0xC6, 0x1B, 0x02, 0xC0, 0xF0, 0x3C, 0x0F, + 0x03, 0xE0, 0xDC, 0x73, 0xEC, 0x06, 0x01, 0x80, 0xC0, 0x70, 0x38, 0x38, + 0x18, 0x00, 0xFC, 0x00, 0x3F, 0xCC, 0xC0, 0x00, 0x00, 0x06, 0x77, 0x12, + 0x40, 0x00, 0x00, 0x07, 0x01, 0xE0, 0x78, 0x1E, 0x07, 0x00, 0xC0, 0x0F, + 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x07, 0x00, 0x10, 0xFF, 0xF0, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0x80, 0x0E, 0x00, 0x3C, 0x00, 0xF0, + 0x03, 0xC0, 0x0F, 0x00, 0x30, 0x0E, 0x07, 0x81, 0xE0, 0x78, 0x0E, 0x00, + 0x00, 0x00, 0x7C, 0x86, 0x83, 0xC3, 0x03, 0x03, 0x06, 0x0C, 0x08, 0x08, + 0x10, 0x10, 0x00, 0x00, 0x30, 0x30, 0x30, 0x03, 0xF0, 0x06, 0x06, 0x06, + 0x00, 0x86, 0x00, 0x26, 0x0E, 0xD3, 0x0C, 0xC7, 0x0C, 0x63, 0x84, 0x31, + 0xC6, 0x18, 0xE3, 0x08, 0x71, 0x8C, 0x4C, 0xC6, 0x46, 0x3D, 0xC1, 0x80, + 0x00, 0x30, 0x10, 0x07, 0xF0, 0x00, 0x80, 0x00, 0x60, 0x00, 0x70, 0x00, + 0x38, 0x00, 0x2E, 0x00, 0x13, 0x00, 0x19, 0xC0, 0x08, 0x60, 0x04, 0x38, + 0x04, 0x0C, 0x03, 0xFF, 0x03, 0x03, 0x81, 0x00, 0xE1, 0x80, 0x70, 0xC0, + 0x3D, 0xF0, 0x3F, 0xFF, 0x83, 0x0C, 0x30, 0x63, 0x06, 0x30, 0x63, 0x06, + 0x30, 0xC3, 0xF0, 0x30, 0xE3, 0x06, 0x30, 0x33, 0x03, 0x30, 0x33, 0x07, + 0x30, 0xEF, 0xFC, 0x07, 0xE2, 0x38, 0x3C, 0xC0, 0x3B, 0x00, 0x36, 0x00, + 0x38, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x03, + 0x00, 0x06, 0x00, 0x06, 0x00, 0x47, 0x03, 0x03, 0xF8, 0xFF, 0xC0, 0x30, + 0x78, 0x30, 0x1C, 0x30, 0x0E, 0x30, 0x06, 0x30, 0x03, 0x30, 0x03, 0x30, + 0x03, 0x30, 0x03, 0x30, 0x03, 0x30, 0x03, 0x30, 0x06, 0x30, 0x06, 0x30, + 0x0C, 0x30, 0x78, 0xFF, 0xC0, 0xFF, 0xFC, 0xC0, 0x33, 0x00, 0x4C, 0x00, + 0x30, 0x00, 0xC0, 0x43, 0x03, 0x0F, 0xFC, 0x30, 0x30, 0xC0, 0x43, 0x00, + 0x0C, 0x00, 0x30, 0x08, 0xC0, 0x23, 0x03, 0xBF, 0xFE, 0xFF, 0xFC, 0xC0, + 0x33, 0x00, 0x4C, 0x00, 0x30, 0x00, 0xC0, 0x43, 0x03, 0x0F, 0xFC, 0x30, + 0x30, 0xC0, 0x43, 0x00, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x03, 0x00, 0x3F, + 0x00, 0x07, 0xE4, 0x1C, 0x3C, 0x30, 0x0C, 0x60, 0x0C, 0x60, 0x04, 0xC0, + 0x00, 0xC0, 0x00, 0xC0, 0x3F, 0xC0, 0x0C, 0xC0, 0x0C, 0xC0, 0x0C, 0x60, + 0x0C, 0x60, 0x0C, 0x30, 0x0C, 0x1C, 0x1C, 0x07, 0xE0, 0xFC, 0x3F, 0x30, + 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x3F, + 0xFC, 0x30, 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x30, + 0x0C, 0x30, 0x0C, 0xFC, 0x3F, 0xFC, 0xC3, 0x0C, 0x30, 0xC3, 0x0C, 0x30, + 0xC3, 0x0C, 0x30, 0xC3, 0x3F, 0x3F, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, + 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0xC8, 0xF0, 0xFC, 0xFE, 0x30, + 0x38, 0x30, 0x20, 0x30, 0x40, 0x30, 0x80, 0x33, 0x00, 0x36, 0x00, 0x3E, + 0x00, 0x37, 0x00, 0x33, 0x80, 0x31, 0xC0, 0x30, 0xE0, 0x30, 0x70, 0x30, + 0x38, 0x30, 0x3C, 0xFC, 0x7F, 0xFC, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, + 0x03, 0x00, 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, 0x00, + 0xC0, 0x01, 0x80, 0x03, 0x00, 0x26, 0x00, 0x8C, 0x07, 0x7F, 0xFE, 0xF8, + 0x01, 0xE7, 0x00, 0x70, 0xE0, 0x0E, 0x1E, 0x03, 0xC2, 0xC0, 0x58, 0x5C, + 0x1B, 0x09, 0x82, 0x61, 0x38, 0x4C, 0x27, 0x11, 0x84, 0x72, 0x30, 0x8E, + 0xC6, 0x10, 0xD0, 0xC2, 0x1E, 0x18, 0x41, 0x83, 0x1C, 0x30, 0x67, 0xC4, + 0x3F, 0xF0, 0x1F, 0x78, 0x0E, 0x3C, 0x04, 0x3E, 0x04, 0x2E, 0x04, 0x27, + 0x04, 0x23, 0x84, 0x23, 0xC4, 0x21, 0xE4, 0x20, 0xE4, 0x20, 0x74, 0x20, + 0x3C, 0x20, 0x1C, 0x20, 0x0C, 0x70, 0x0C, 0xF8, 0x04, 0x07, 0xC0, 0x30, + 0x60, 0xC0, 0x63, 0x00, 0x66, 0x00, 0xD8, 0x00, 0xF0, 0x01, 0xE0, 0x03, + 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1B, 0x00, 0x66, 0x00, 0xC6, 0x03, 0x06, + 0x0C, 0x03, 0xE0, 0xFF, 0x83, 0x0E, 0x30, 0x73, 0x03, 0x30, 0x33, 0x03, + 0x30, 0x63, 0x0E, 0x3F, 0x83, 0x00, 0x30, 0x03, 0x00, 0x30, 0x03, 0x00, + 0x30, 0x0F, 0xC0, 0x0F, 0xE0, 0x18, 0x30, 0x30, 0x18, 0x60, 0x0C, 0x60, + 0x0C, 0xC0, 0x06, 0xC0, 0x06, 0xC0, 0x06, 0xC0, 0x06, 0xC0, 0x06, 0xC0, + 0x06, 0x60, 0x0C, 0x60, 0x0C, 0x30, 0x18, 0x18, 0x30, 0x07, 0xC0, 0x03, + 0xC0, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1F, 0xFF, 0x80, 0x61, 0xC0, 0xC1, + 0xC1, 0x81, 0x83, 0x03, 0x06, 0x06, 0x0C, 0x1C, 0x18, 0x70, 0x3F, 0x80, + 0x67, 0x00, 0xC7, 0x01, 0x8F, 0x03, 0x0F, 0x06, 0x0E, 0x0C, 0x0E, 0x7E, + 0x0F, 0x1F, 0x46, 0x19, 0x81, 0x30, 0x27, 0x02, 0xF0, 0x0F, 0x00, 0xF8, + 0x07, 0xC0, 0x38, 0x03, 0xC0, 0x34, 0x06, 0x80, 0xDC, 0x32, 0x7C, 0xFF, + 0xFF, 0x86, 0x0E, 0x0C, 0x1C, 0x18, 0x10, 0x30, 0x00, 0x60, 0x00, 0xC0, + 0x01, 0x80, 0x03, 0x00, 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, + 0x60, 0x00, 0xC0, 0x07, 0xE0, 0xFC, 0x1F, 0x30, 0x0E, 0x30, 0x04, 0x30, + 0x04, 0x30, 0x04, 0x30, 0x04, 0x30, 0x04, 0x30, 0x04, 0x30, 0x04, 0x30, + 0x04, 0x30, 0x04, 0x30, 0x04, 0x30, 0x04, 0x18, 0x08, 0x1C, 0x18, 0x07, + 0xE0, 0xFE, 0x0F, 0x9C, 0x03, 0x0E, 0x01, 0x83, 0x00, 0x81, 0xC0, 0x40, + 0x60, 0x40, 0x38, 0x20, 0x0C, 0x30, 0x07, 0x10, 0x01, 0x98, 0x00, 0xE8, + 0x00, 0x34, 0x00, 0x1E, 0x00, 0x06, 0x00, 0x03, 0x00, 0x01, 0x00, 0xFC, + 0xFC, 0x3D, 0xE1, 0xC0, 0x63, 0x83, 0x01, 0x86, 0x0E, 0x04, 0x1C, 0x18, + 0x10, 0x70, 0x70, 0x80, 0xC3, 0xC2, 0x03, 0x8B, 0x08, 0x06, 0x6E, 0x40, + 0x1D, 0x19, 0x00, 0x74, 0x78, 0x00, 0xE1, 0xE0, 0x03, 0x83, 0x80, 0x0E, + 0x0C, 0x00, 0x10, 0x10, 0x00, 0x40, 0x40, 0x7F, 0x1F, 0x9E, 0x03, 0x07, + 0x03, 0x01, 0xC3, 0x00, 0x71, 0x00, 0x19, 0x00, 0x0F, 0x00, 0x03, 0x80, + 0x01, 0xE0, 0x01, 0xB0, 0x01, 0x9C, 0x00, 0x87, 0x00, 0x81, 0xC0, 0x80, + 0xE0, 0xC0, 0x79, 0xF8, 0x7F, 0xFE, 0x1F, 0x78, 0x0C, 0x38, 0x08, 0x1C, + 0x18, 0x0E, 0x10, 0x06, 0x20, 0x07, 0x60, 0x03, 0xC0, 0x01, 0x80, 0x01, + 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x07, + 0xE0, 0x7F, 0xFB, 0x00, 0xC8, 0x07, 0x20, 0x38, 0x01, 0xC0, 0x07, 0x00, + 0x38, 0x01, 0xC0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x0E, 0x00, 0x38, 0x05, + 0xC0, 0x3E, 0x01, 0xBF, 0xFE, 0xFE, 0x31, 0x8C, 0x63, 0x18, 0xC6, 0x31, + 0x8C, 0x63, 0x18, 0xC6, 0x31, 0xF0, 0xC1, 0x81, 0x03, 0x06, 0x04, 0x0C, + 0x18, 0x10, 0x30, 0x60, 0x40, 0xC1, 0x81, 0x03, 0x06, 0xF8, 0xC6, 0x31, + 0x8C, 0x63, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0xC7, 0xF0, 0x0C, 0x07, + 0x01, 0x60, 0xD8, 0x23, 0x18, 0xC4, 0x1B, 0x06, 0x80, 0xC0, 0xFF, 0xF0, + 0xC7, 0x0C, 0x30, 0x3E, 0x31, 0x8C, 0x30, 0x0C, 0x03, 0x07, 0xC6, 0x33, + 0x0C, 0xC3, 0x31, 0xC7, 0xB8, 0x20, 0x38, 0x06, 0x01, 0x80, 0x60, 0x18, + 0x06, 0xF1, 0xC6, 0x61, 0xD8, 0x36, 0x0D, 0x83, 0x60, 0xD8, 0x26, 0x19, + 0x84, 0x3E, 0x00, 0x1E, 0x23, 0x63, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xE1, + 0x72, 0x3C, 0x00, 0x80, 0xE0, 0x18, 0x06, 0x01, 0x80, 0x61, 0xD8, 0x8E, + 0x61, 0xB0, 0x6C, 0x1B, 0x06, 0xC1, 0xB0, 0x6E, 0x19, 0xCE, 0x3D, 0xC0, + 0x1E, 0x08, 0xE4, 0x1B, 0xFE, 0xC0, 0x30, 0x0C, 0x03, 0x81, 0x60, 0x9C, + 0x41, 0xE0, 0x0F, 0x08, 0xC4, 0x06, 0x03, 0x01, 0x81, 0xF0, 0x60, 0x30, + 0x18, 0x0C, 0x06, 0x03, 0x01, 0x80, 0xC0, 0x60, 0xFC, 0x00, 0x1F, 0x03, + 0x1F, 0x60, 0xC6, 0x0C, 0x60, 0xC3, 0x18, 0x1F, 0x02, 0x00, 0x40, 0x07, + 0xFC, 0x40, 0x24, 0x02, 0xC0, 0x2C, 0x04, 0xE0, 0x83, 0xF0, 0x30, 0x1E, + 0x00, 0xC0, 0x18, 0x03, 0x00, 0x60, 0x0D, 0xE1, 0xCE, 0x30, 0xC6, 0x18, + 0xC3, 0x18, 0x63, 0x0C, 0x61, 0x8C, 0x31, 0x86, 0x79, 0xE0, 0x31, 0x80, + 0x00, 0x09, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0xDF, 0x0C, 0x30, 0x00, 0x00, + 0x31, 0xC3, 0x0C, 0x30, 0xC3, 0x0C, 0x30, 0xC3, 0x0C, 0x30, 0xF2, 0xF0, + 0x20, 0x1C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, 0x18, 0xFB, 0x08, 0x62, + 0x0C, 0x81, 0xE0, 0x3E, 0x06, 0xE0, 0xCE, 0x18, 0xC3, 0x0E, 0xF3, 0xE0, + 0x13, 0x8C, 0x63, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0xC6, 0xF8, 0xF7, + 0x8F, 0x0E, 0x3C, 0xE3, 0x0C, 0x18, 0xC3, 0x06, 0x30, 0xC1, 0x8C, 0x30, + 0x63, 0x0C, 0x18, 0xC3, 0x06, 0x30, 0xC1, 0x8C, 0x30, 0x67, 0x9E, 0x3C, + 0xF7, 0x87, 0x18, 0xC3, 0x18, 0x63, 0x0C, 0x61, 0x8C, 0x31, 0x86, 0x30, + 0xC6, 0x19, 0xE7, 0x80, 0x1E, 0x18, 0xE4, 0x1B, 0x03, 0xC0, 0xF0, 0x3C, + 0x0F, 0x03, 0x60, 0x9C, 0x41, 0xE0, 0x77, 0x87, 0x18, 0xC3, 0x98, 0x33, + 0x06, 0x60, 0xCC, 0x19, 0x83, 0x30, 0xC7, 0x10, 0xDC, 0x18, 0x03, 0x00, + 0x60, 0x0C, 0x07, 0xE0, 0x1E, 0x8C, 0xE6, 0x1B, 0x06, 0xC1, 0xB0, 0x6C, + 0x1B, 0x06, 0xE1, 0x98, 0xE3, 0xD8, 0x06, 0x01, 0x80, 0x60, 0x18, 0x1F, + 0x37, 0x7B, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x7C, 0x7B, + 0x0E, 0x1C, 0x1E, 0x0F, 0x07, 0xC3, 0x87, 0x8A, 0xE0, 0x21, 0x8F, 0x98, + 0x61, 0x86, 0x18, 0x61, 0x86, 0x19, 0x38, 0xE3, 0x98, 0x66, 0x19, 0x86, + 0x61, 0x98, 0x66, 0x19, 0x86, 0x61, 0x9C, 0xE3, 0xDC, 0xF8, 0xEE, 0x08, + 0xC1, 0x18, 0x41, 0x88, 0x32, 0x03, 0x40, 0x68, 0x06, 0x00, 0xC0, 0x10, + 0x00, 0xF3, 0xE7, 0x61, 0x83, 0x70, 0xC2, 0x30, 0xC2, 0x30, 0xC4, 0x19, + 0x64, 0x19, 0x68, 0x0E, 0x38, 0x0E, 0x38, 0x0C, 0x30, 0x04, 0x10, 0xFB, + 0xC6, 0x30, 0x64, 0x0F, 0x00, 0xC0, 0x0C, 0x03, 0xC0, 0x98, 0x21, 0x8C, + 0x3B, 0xCF, 0x80, 0xF8, 0xEE, 0x08, 0xC1, 0x18, 0x41, 0x88, 0x31, 0x03, + 0x40, 0x68, 0x06, 0x00, 0xC0, 0x08, 0x02, 0x00, 0x40, 0x10, 0x1E, 0x03, + 0x80, 0x7F, 0x90, 0xE0, 0x30, 0x18, 0x0E, 0x03, 0x01, 0xC0, 0xE0, 0x30, + 0x5C, 0x3F, 0xF8, 0x19, 0x8C, 0x63, 0x18, 0xC6, 0x31, 0xB0, 0x63, 0x18, + 0xC6, 0x31, 0x8C, 0x61, 0x80, 0xFF, 0xFF, 0x80, 0xC3, 0x18, 0xC6, 0x31, + 0x8C, 0x63, 0x06, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0xCC, 0x00, 0x38, 0x06, + 0x62, 0x41, 0xC0 }; + +const GFXglyph FreeSerif12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 6, 0, 1 }, // 0x20 ' ' + { 0, 2, 16, 8, 3, -15 }, // 0x21 '!' + { 4, 6, 6, 10, 1, -15 }, // 0x22 '"' + { 9, 12, 16, 12, 0, -15 }, // 0x23 '#' + { 33, 10, 18, 12, 1, -16 }, // 0x24 '$' + { 56, 18, 17, 20, 1, -16 }, // 0x25 '%' + { 95, 17, 16, 19, 1, -15 }, // 0x26 '&' + { 129, 2, 6, 5, 1, -15 }, // 0x27 ''' + { 131, 6, 20, 8, 1, -15 }, // 0x28 '(' + { 146, 6, 20, 8, 1, -15 }, // 0x29 ')' + { 161, 8, 10, 12, 3, -14 }, // 0x2A '*' + { 171, 11, 11, 14, 1, -10 }, // 0x2B '+' + { 187, 3, 6, 6, 2, -2 }, // 0x2C ',' + { 190, 6, 1, 8, 1, -5 }, // 0x2D '-' + { 191, 2, 3, 6, 2, -2 }, // 0x2E '.' + { 192, 7, 17, 7, 0, -16 }, // 0x2F '/' + { 207, 10, 17, 12, 1, -16 }, // 0x30 '0' + { 229, 6, 17, 12, 3, -16 }, // 0x31 '1' + { 242, 10, 15, 12, 1, -14 }, // 0x32 '2' + { 261, 10, 16, 12, 1, -15 }, // 0x33 '3' + { 281, 10, 16, 12, 1, -15 }, // 0x34 '4' + { 301, 10, 17, 12, 1, -16 }, // 0x35 '5' + { 323, 10, 17, 12, 1, -16 }, // 0x36 '6' + { 345, 10, 16, 12, 0, -15 }, // 0x37 '7' + { 365, 10, 17, 12, 1, -16 }, // 0x38 '8' + { 387, 10, 18, 12, 1, -16 }, // 0x39 '9' + { 410, 2, 12, 6, 2, -11 }, // 0x3A ':' + { 413, 4, 15, 6, 2, -11 }, // 0x3B ';' + { 421, 12, 13, 14, 1, -12 }, // 0x3C '<' + { 441, 12, 6, 14, 1, -8 }, // 0x3D '=' + { 450, 12, 13, 14, 1, -11 }, // 0x3E '>' + { 470, 8, 17, 11, 2, -16 }, // 0x3F '?' + { 487, 17, 16, 21, 2, -15 }, // 0x40 '@' + { 521, 17, 16, 17, 0, -15 }, // 0x41 'A' + { 555, 12, 16, 15, 1, -15 }, // 0x42 'B' + { 579, 15, 16, 16, 1, -15 }, // 0x43 'C' + { 609, 16, 16, 17, 0, -15 }, // 0x44 'D' + { 641, 14, 16, 15, 0, -15 }, // 0x45 'E' + { 669, 14, 16, 14, 0, -15 }, // 0x46 'F' + { 697, 16, 16, 17, 1, -15 }, // 0x47 'G' + { 729, 16, 16, 17, 0, -15 }, // 0x48 'H' + { 761, 6, 16, 8, 1, -15 }, // 0x49 'I' + { 773, 8, 16, 9, 0, -15 }, // 0x4A 'J' + { 789, 16, 16, 17, 1, -15 }, // 0x4B 'K' + { 821, 15, 16, 15, 0, -15 }, // 0x4C 'L' + { 851, 19, 16, 21, 1, -15 }, // 0x4D 'M' + { 889, 16, 16, 17, 1, -15 }, // 0x4E 'N' + { 921, 15, 16, 17, 1, -15 }, // 0x4F 'O' + { 951, 12, 16, 14, 0, -15 }, // 0x50 'P' + { 975, 16, 20, 17, 1, -15 }, // 0x51 'Q' + { 1015, 15, 16, 16, 0, -15 }, // 0x52 'R' + { 1045, 11, 16, 13, 0, -15 }, // 0x53 'S' + { 1067, 15, 16, 15, 0, -15 }, // 0x54 'T' + { 1097, 16, 16, 17, 1, -15 }, // 0x55 'U' + { 1129, 17, 16, 17, 0, -15 }, // 0x56 'V' + { 1163, 22, 16, 23, 0, -15 }, // 0x57 'W' + { 1207, 17, 16, 17, 0, -15 }, // 0x58 'X' + { 1241, 16, 16, 17, 0, -15 }, // 0x59 'Y' + { 1273, 14, 16, 15, 1, -15 }, // 0x5A 'Z' + { 1301, 5, 20, 8, 2, -15 }, // 0x5B '[' + { 1314, 7, 17, 7, 0, -16 }, // 0x5C '\' + { 1329, 5, 20, 8, 1, -15 }, // 0x5D ']' + { 1342, 10, 9, 11, 1, -15 }, // 0x5E '^' + { 1354, 12, 1, 12, 0, 3 }, // 0x5F '_' + { 1356, 5, 4, 6, 0, -15 }, // 0x60 '`' + { 1359, 10, 11, 10, 1, -10 }, // 0x61 'a' + { 1373, 10, 17, 12, 1, -16 }, // 0x62 'b' + { 1395, 8, 11, 11, 1, -10 }, // 0x63 'c' + { 1406, 10, 17, 12, 1, -16 }, // 0x64 'd' + { 1428, 10, 11, 11, 1, -10 }, // 0x65 'e' + { 1442, 9, 17, 9, 0, -16 }, // 0x66 'f' + { 1462, 12, 16, 11, 0, -10 }, // 0x67 'g' + { 1486, 11, 17, 12, 0, -16 }, // 0x68 'h' + { 1510, 5, 16, 7, 0, -15 }, // 0x69 'i' + { 1520, 6, 21, 8, 0, -15 }, // 0x6A 'j' + { 1536, 11, 17, 12, 1, -16 }, // 0x6B 'k' + { 1560, 5, 17, 6, 0, -16 }, // 0x6C 'l' + { 1571, 18, 11, 19, 0, -10 }, // 0x6D 'm' + { 1596, 11, 11, 12, 0, -10 }, // 0x6E 'n' + { 1612, 10, 11, 12, 1, -10 }, // 0x6F 'o' + { 1626, 11, 16, 12, 0, -10 }, // 0x70 'p' + { 1648, 10, 16, 12, 1, -10 }, // 0x71 'q' + { 1668, 8, 11, 8, 0, -10 }, // 0x72 'r' + { 1679, 7, 11, 9, 1, -10 }, // 0x73 's' + { 1689, 6, 13, 7, 1, -12 }, // 0x74 't' + { 1699, 10, 11, 12, 1, -10 }, // 0x75 'u' + { 1713, 11, 11, 11, 0, -10 }, // 0x76 'v' + { 1729, 16, 11, 16, 0, -10 }, // 0x77 'w' + { 1751, 11, 11, 12, 0, -10 }, // 0x78 'x' + { 1767, 11, 16, 11, 0, -10 }, // 0x79 'y' + { 1789, 10, 11, 10, 0, -10 }, // 0x7A 'z' + { 1803, 5, 21, 12, 2, -16 }, // 0x7B '{' + { 1817, 1, 17, 5, 2, -16 }, // 0x7C '|' + { 1820, 5, 21, 12, 5, -15 }, // 0x7D '}' + { 1834, 12, 3, 12, 0, -6 } }; // 0x7E '~' + +const GFXfont FreeSerif12pt7b PROGMEM = { + (uint8_t *)FreeSerif12pt7bBitmaps, + (GFXglyph *)FreeSerif12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 2511 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerif18pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerif18pt7b.h new file mode 100644 index 0000000..7d19dd1 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerif18pt7b.h @@ -0,0 +1,429 @@ +const uint8_t FreeSerif18pt7bBitmaps[] PROGMEM = { + 0x6F, 0xFF, 0xFF, 0xFE, 0x66, 0x66, 0x66, 0x64, 0x40, 0x00, 0x6F, 0xF6, + 0xE7, 0xE7, 0xE7, 0xE7, 0xE7, 0x46, 0x42, 0x42, 0x42, 0x03, 0x06, 0x01, + 0x83, 0x00, 0xC1, 0x80, 0x61, 0xC0, 0x30, 0xC0, 0x38, 0x60, 0x18, 0x30, + 0xFF, 0xFF, 0x7F, 0xFF, 0x83, 0x06, 0x01, 0x86, 0x00, 0xC3, 0x00, 0xC1, + 0x87, 0xFF, 0xFF, 0xFF, 0xFE, 0x18, 0x30, 0x0C, 0x18, 0x06, 0x18, 0x06, + 0x0C, 0x03, 0x06, 0x01, 0x83, 0x00, 0xC1, 0x80, 0x60, 0xC0, 0x02, 0x00, + 0x10, 0x03, 0xE0, 0x64, 0xE6, 0x23, 0x61, 0x1B, 0x08, 0x58, 0x42, 0xE2, + 0x03, 0x90, 0x1F, 0x80, 0x7E, 0x00, 0xFC, 0x01, 0xF0, 0x0F, 0xC0, 0x4E, + 0x02, 0x38, 0x10, 0xE0, 0x87, 0x04, 0x3C, 0x21, 0xE1, 0x1B, 0xC9, 0xCF, + 0xFC, 0x1F, 0x80, 0x10, 0x00, 0x80, 0x07, 0x80, 0x20, 0x0F, 0xF0, 0x70, + 0x0F, 0x07, 0xD0, 0x0F, 0x02, 0x18, 0x07, 0x01, 0x18, 0x07, 0x00, 0x8C, + 0x03, 0x80, 0x4C, 0x01, 0x80, 0x44, 0x00, 0xC0, 0x26, 0x00, 0x60, 0x22, + 0x0F, 0x30, 0x33, 0x1F, 0xCC, 0x73, 0x1E, 0x37, 0xF1, 0x8E, 0x19, 0xE1, + 0x8E, 0x04, 0x00, 0x86, 0x02, 0x00, 0xC7, 0x01, 0x00, 0xC3, 0x80, 0x80, + 0x61, 0x80, 0x80, 0x60, 0xC0, 0x40, 0x30, 0x60, 0x40, 0x30, 0x38, 0xE0, + 0x30, 0x0F, 0xE0, 0x18, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x00, 0x7E, 0x00, + 0x00, 0x61, 0x80, 0x00, 0x60, 0x60, 0x00, 0x30, 0x30, 0x00, 0x18, 0x18, + 0x00, 0x0C, 0x0C, 0x00, 0x06, 0x0C, 0x00, 0x03, 0x8E, 0x00, 0x01, 0xCE, + 0x00, 0x00, 0x7C, 0x3F, 0xC0, 0x38, 0x07, 0x80, 0x3E, 0x03, 0x80, 0x77, + 0x01, 0x80, 0x73, 0xC0, 0x80, 0xF0, 0xF0, 0xC0, 0x70, 0x7C, 0xC0, 0x78, + 0x1E, 0x40, 0x3C, 0x07, 0xC0, 0x1E, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x0F, + 0xC0, 0xFF, 0x0D, 0xF0, 0xC7, 0xFC, 0x7F, 0xC1, 0xFC, 0x1F, 0x80, 0x3C, + 0x00, 0xFF, 0xFE, 0x92, 0x40, 0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0xC0, + 0xC0, 0x60, 0x70, 0x30, 0x18, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, + 0x70, 0x38, 0x0C, 0x06, 0x03, 0x80, 0xC0, 0x60, 0x18, 0x0C, 0x03, 0x00, + 0xC0, 0x30, 0x0C, 0x80, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x60, 0x18, 0x0C, + 0x07, 0x01, 0x80, 0xC0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, + 0xE0, 0x60, 0x30, 0x38, 0x18, 0x0C, 0x0C, 0x04, 0x04, 0x04, 0x04, 0x04, + 0x00, 0x0C, 0x00, 0xC0, 0x0C, 0x0C, 0x46, 0xE4, 0xF7, 0x5E, 0x1F, 0x00, + 0xC0, 0x17, 0x8E, 0x4E, 0xE4, 0xFC, 0xC6, 0x0C, 0x00, 0xC0, 0x01, 0x80, + 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, + 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, + 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x6F, 0xFF, + 0x11, 0x24, 0x80, 0xFF, 0xFF, 0x6F, 0xF6, 0x00, 0xC0, 0x60, 0x18, 0x06, + 0x03, 0x80, 0xC0, 0x30, 0x1C, 0x06, 0x01, 0x80, 0xE0, 0x30, 0x0C, 0x07, + 0x01, 0x80, 0x60, 0x38, 0x0C, 0x03, 0x01, 0xC0, 0x60, 0x18, 0x0E, 0x03, + 0x00, 0x03, 0xE0, 0x0E, 0x70, 0x1C, 0x38, 0x38, 0x1C, 0x38, 0x1C, 0x78, + 0x1E, 0x70, 0x0E, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, + 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0x70, 0x0E, 0x70, + 0x0E, 0x78, 0x1E, 0x38, 0x1C, 0x38, 0x1C, 0x1C, 0x38, 0x0C, 0x30, 0x03, + 0xC0, 0x06, 0x03, 0x83, 0xE3, 0x38, 0x0E, 0x03, 0x80, 0xE0, 0x38, 0x0E, + 0x03, 0x80, 0xE0, 0x38, 0x0E, 0x03, 0x80, 0xE0, 0x38, 0x0E, 0x03, 0x80, + 0xE0, 0x38, 0x0E, 0x03, 0x81, 0xE1, 0xFF, 0x07, 0xC0, 0x1F, 0xF0, 0x3F, + 0xF8, 0x70, 0xF8, 0x60, 0x3C, 0xC0, 0x3C, 0x80, 0x1C, 0x00, 0x1C, 0x00, + 0x1C, 0x00, 0x18, 0x00, 0x18, 0x00, 0x30, 0x00, 0x30, 0x00, 0x60, 0x00, + 0xC0, 0x00, 0x80, 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x08, 0x01, 0x10, + 0x02, 0x3F, 0xFE, 0x7F, 0xFC, 0xFF, 0xFC, 0x0F, 0xC0, 0xFF, 0x0C, 0x3C, + 0x80, 0xE4, 0x03, 0x00, 0x18, 0x00, 0xC0, 0x04, 0x00, 0x40, 0x04, 0x00, + 0xF8, 0x1F, 0xE0, 0x0F, 0x00, 0x1C, 0x00, 0xE0, 0x03, 0x00, 0x18, 0x00, + 0xC0, 0x06, 0x00, 0x60, 0x03, 0x78, 0x73, 0xFF, 0x0F, 0xC0, 0x00, 0x30, + 0x00, 0x30, 0x00, 0x70, 0x00, 0xF0, 0x00, 0xB0, 0x01, 0x30, 0x03, 0x30, + 0x06, 0x30, 0x04, 0x30, 0x08, 0x30, 0x18, 0x30, 0x10, 0x30, 0x20, 0x30, + 0x60, 0x30, 0xC0, 0x30, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x30, 0x00, 0x30, + 0x00, 0x30, 0x00, 0x30, 0x00, 0x30, 0x00, 0x30, 0x00, 0x00, 0x7F, 0xC3, + 0xFE, 0x1F, 0xE1, 0x80, 0x08, 0x00, 0xC0, 0x07, 0xC0, 0x7F, 0x81, 0xFF, + 0x00, 0xFC, 0x01, 0xE0, 0x07, 0x80, 0x1C, 0x00, 0x60, 0x03, 0x00, 0x18, + 0x00, 0xC0, 0x06, 0x00, 0x60, 0x07, 0x78, 0x73, 0xFF, 0x0F, 0xC0, 0x00, + 0x0E, 0x00, 0xF8, 0x03, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x3C, + 0x00, 0x7C, 0x00, 0x79, 0xF0, 0x7F, 0xFC, 0xF8, 0x3C, 0xF0, 0x1E, 0xF0, + 0x1F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0x70, 0x0F, 0x78, + 0x0F, 0x78, 0x0E, 0x3C, 0x1E, 0x1E, 0x3C, 0x0F, 0xF8, 0x07, 0xE0, 0x3F, + 0xFD, 0xFF, 0xF7, 0xFF, 0xF0, 0x06, 0x80, 0x18, 0x00, 0x60, 0x03, 0x00, + 0x0C, 0x00, 0x30, 0x01, 0x80, 0x06, 0x00, 0x18, 0x00, 0xE0, 0x03, 0x00, + 0x0C, 0x00, 0x70, 0x01, 0x80, 0x06, 0x00, 0x38, 0x00, 0xC0, 0x03, 0x00, + 0x1C, 0x00, 0x60, 0x00, 0x0F, 0x83, 0xFC, 0x70, 0xE6, 0x07, 0xC0, 0x3C, + 0x03, 0xC0, 0x3E, 0x03, 0x70, 0x67, 0x8C, 0x3D, 0x81, 0xF0, 0x0F, 0x81, + 0x7C, 0x21, 0xE6, 0x0E, 0xC0, 0x7C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x36, + 0x06, 0x70, 0xE3, 0xFC, 0x0F, 0x80, 0x07, 0xC0, 0x1F, 0xF0, 0x3C, 0x78, + 0x38, 0x3C, 0x78, 0x1E, 0x70, 0x1E, 0xF0, 0x0E, 0xF0, 0x0F, 0xF0, 0x0F, + 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF8, 0x0F, 0x78, 0x0F, 0x3C, 0x3F, + 0x1F, 0xEE, 0x0F, 0x9E, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x38, 0x00, 0x78, + 0x00, 0xF0, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x70, 0x00, 0x6F, 0xF6, + 0x00, 0x00, 0x00, 0x00, 0x06, 0xFF, 0x60, 0x67, 0xBC, 0xC0, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x19, 0xEF, 0x78, 0x42, 0x22, 0x20, 0x00, 0x00, 0xC0, + 0x00, 0xF0, 0x01, 0xF8, 0x01, 0xF8, 0x01, 0xF8, 0x01, 0xF0, 0x03, 0xF0, + 0x03, 0xF0, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, + 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xC0, + 0x00, 0x10, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x80, + 0x00, 0x3C, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x07, 0xC0, 0x00, 0x7C, + 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x07, 0xC0, 0x00, 0xF0, 0x00, 0xFC, + 0x00, 0xFC, 0x00, 0xF8, 0x01, 0xF8, 0x01, 0xF8, 0x01, 0xF8, 0x00, 0xF0, + 0x00, 0x30, 0x00, 0x00, 0x1F, 0x81, 0xFF, 0x18, 0x7D, 0x81, 0xEC, 0x07, + 0xF0, 0x3F, 0x81, 0xE0, 0x0F, 0x00, 0x70, 0x03, 0x80, 0x38, 0x01, 0x80, + 0x08, 0x00, 0xC0, 0x04, 0x00, 0x20, 0x02, 0x00, 0x10, 0x00, 0x80, 0x00, + 0x00, 0x00, 0x03, 0x00, 0x3C, 0x01, 0xE0, 0x07, 0x00, 0x00, 0x7F, 0x00, + 0x01, 0xFF, 0xC0, 0x07, 0x80, 0xF0, 0x0F, 0x00, 0x38, 0x1C, 0x00, 0x1C, + 0x38, 0x00, 0x0C, 0x38, 0x00, 0x06, 0x70, 0x1E, 0x02, 0x70, 0x3F, 0xE3, + 0xF0, 0x71, 0xE1, 0xE0, 0xE0, 0xC1, 0xE0, 0xC0, 0xC1, 0xE0, 0xC1, 0xC1, + 0xE1, 0x81, 0xC1, 0xE1, 0x81, 0x83, 0xE1, 0x83, 0x82, 0xE1, 0x83, 0x86, + 0x71, 0xC7, 0x8C, 0x70, 0xF9, 0xF8, 0x38, 0xF0, 0xF0, 0x3C, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x07, 0x80, 0x70, 0x03, 0xFF, 0xE0, 0x00, 0x7F, 0x00, + 0x00, 0x10, 0x00, 0x00, 0x38, 0x00, 0x00, 0x38, 0x00, 0x00, 0x38, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x5C, 0x00, 0x00, 0xDE, 0x00, 0x00, 0x8E, 0x00, + 0x01, 0x8F, 0x00, 0x01, 0x87, 0x00, 0x03, 0x07, 0x80, 0x03, 0x03, 0x80, + 0x02, 0x03, 0xC0, 0x06, 0x03, 0xC0, 0x07, 0xFF, 0xC0, 0x0F, 0xFF, 0xE0, + 0x0C, 0x01, 0xE0, 0x18, 0x00, 0xF0, 0x18, 0x00, 0xF0, 0x30, 0x00, 0x78, + 0x30, 0x00, 0x78, 0x70, 0x00, 0x7C, 0xFC, 0x01, 0xFF, 0xFF, 0xFC, 0x03, + 0xFF, 0xF8, 0x1E, 0x0F, 0xC1, 0xE0, 0x3C, 0x1E, 0x01, 0xE1, 0xE0, 0x1E, + 0x1E, 0x01, 0xE1, 0xE0, 0x1E, 0x1E, 0x03, 0xC1, 0xE0, 0x78, 0x1F, 0xFE, + 0x01, 0xFF, 0xF0, 0x1E, 0x07, 0xC1, 0xE0, 0x1E, 0x1E, 0x00, 0xF1, 0xE0, + 0x0F, 0x1E, 0x00, 0xF1, 0xE0, 0x0F, 0x1E, 0x00, 0xF1, 0xE0, 0x1E, 0x1E, + 0x07, 0xE3, 0xFF, 0xF8, 0xFF, 0xFE, 0x00, 0x00, 0xFE, 0x08, 0x0F, 0xFF, + 0x60, 0xFC, 0x1F, 0x87, 0xC0, 0x1E, 0x3C, 0x00, 0x38, 0xF0, 0x00, 0x67, + 0x80, 0x01, 0x9E, 0x00, 0x02, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x0F, + 0x00, 0x02, 0x1F, 0x00, 0x38, 0x3F, 0x03, 0x80, 0x7F, 0xFC, 0x00, 0x3F, + 0x80, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x78, 0x3F, 0x80, 0xF0, 0x0F, + 0x81, 0xE0, 0x0F, 0x83, 0xC0, 0x0F, 0x07, 0x80, 0x0F, 0x0F, 0x00, 0x1E, + 0x1E, 0x00, 0x1E, 0x3C, 0x00, 0x3C, 0x78, 0x00, 0x78, 0xF0, 0x00, 0xF1, + 0xE0, 0x01, 0xE3, 0xC0, 0x03, 0xC7, 0x80, 0x07, 0x8F, 0x00, 0x1E, 0x1E, + 0x00, 0x3C, 0x3C, 0x00, 0xF0, 0x78, 0x01, 0xE0, 0xF0, 0x0F, 0x81, 0xE0, + 0x7E, 0x07, 0xFF, 0xF0, 0x3F, 0xFF, 0x00, 0x00, 0xFF, 0xFF, 0x87, 0xFF, + 0xF8, 0x3C, 0x01, 0x83, 0xC0, 0x08, 0x3C, 0x00, 0x83, 0xC0, 0x00, 0x3C, + 0x00, 0x03, 0xC0, 0x00, 0x3C, 0x02, 0x03, 0xC0, 0x60, 0x3F, 0xFE, 0x03, + 0xFF, 0xE0, 0x3C, 0x06, 0x03, 0xC0, 0x20, 0x3C, 0x00, 0x03, 0xC0, 0x00, + 0x3C, 0x00, 0x03, 0xC0, 0x01, 0x3C, 0x00, 0x23, 0xC0, 0x06, 0x3C, 0x01, + 0xE7, 0xFF, 0xFE, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xBF, 0xFF, 0xCF, 0x00, + 0x67, 0x80, 0x13, 0xC0, 0x09, 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, + 0x02, 0x1E, 0x03, 0x0F, 0xFF, 0x87, 0xFF, 0xC3, 0xC0, 0x61, 0xE0, 0x10, + 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x0F, 0x00, 0x07, 0x80, + 0x03, 0xC0, 0x03, 0xF0, 0x03, 0xFC, 0x00, 0x00, 0xFE, 0x04, 0x07, 0xFF, + 0xB8, 0x1F, 0x03, 0xF0, 0xF8, 0x01, 0xE3, 0xE0, 0x01, 0xC7, 0x80, 0x01, + 0x9E, 0x00, 0x01, 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x03, + 0xC0, 0x00, 0x07, 0x80, 0x07, 0xFF, 0x00, 0x07, 0xDE, 0x00, 0x07, 0xBC, + 0x00, 0x0F, 0x78, 0x00, 0x1E, 0x78, 0x00, 0x3C, 0xF0, 0x00, 0x78, 0xF0, + 0x00, 0xF1, 0xF0, 0x01, 0xE1, 0xF0, 0x03, 0xC1, 0xF8, 0x1F, 0x00, 0xFF, + 0xFC, 0x00, 0x3F, 0x80, 0xFF, 0x03, 0xFD, 0xF8, 0x07, 0xE3, 0xC0, 0x0F, + 0x0F, 0x00, 0x3C, 0x3C, 0x00, 0xF0, 0xF0, 0x03, 0xC3, 0xC0, 0x0F, 0x0F, + 0x00, 0x3C, 0x3C, 0x00, 0xF0, 0xF0, 0x03, 0xC3, 0xFF, 0xFF, 0x0F, 0xFF, + 0xFC, 0x3C, 0x00, 0xF0, 0xF0, 0x03, 0xC3, 0xC0, 0x0F, 0x0F, 0x00, 0x3C, + 0x3C, 0x00, 0xF0, 0xF0, 0x03, 0xC3, 0xC0, 0x0F, 0x0F, 0x00, 0x3C, 0x3C, + 0x00, 0xF1, 0xF8, 0x07, 0xEF, 0xF0, 0x3F, 0xC0, 0xFF, 0xBF, 0x0F, 0x07, + 0x83, 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, 0xC1, 0xE0, + 0xF0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, 0xC3, 0xF3, 0xFE, 0x0F, 0xF0, + 0x7E, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, + 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, + 0x3C, 0x03, 0xC6, 0x38, 0xF3, 0x8F, 0xF0, 0x7C, 0x00, 0xFF, 0x07, 0xFC, + 0xFC, 0x03, 0xC0, 0xF0, 0x07, 0x01, 0xE0, 0x1C, 0x03, 0xC0, 0x60, 0x07, + 0x81, 0x80, 0x0F, 0x06, 0x00, 0x1E, 0x18, 0x00, 0x3C, 0x60, 0x00, 0x79, + 0x80, 0x00, 0xFF, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xDF, 0x00, 0x07, 0x8F, + 0x00, 0x0F, 0x0F, 0x00, 0x1E, 0x0F, 0x00, 0x3C, 0x0F, 0x00, 0x78, 0x0F, + 0x00, 0xF0, 0x1F, 0x01, 0xE0, 0x1F, 0x03, 0xC0, 0x1F, 0x0F, 0xC0, 0x3F, + 0x3F, 0xC1, 0xFF, 0x80, 0xFF, 0x00, 0x0F, 0xC0, 0x00, 0xF0, 0x00, 0x1E, + 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, + 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, 0x00, 0x78, + 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x07, 0x80, 0x04, 0xF0, + 0x01, 0x1E, 0x00, 0x63, 0xC0, 0x3C, 0xFF, 0xFF, 0xBF, 0xFF, 0xE0, 0xFC, + 0x00, 0x03, 0xF9, 0xF0, 0x00, 0x1F, 0x87, 0x80, 0x01, 0xF8, 0x3E, 0x00, + 0x0F, 0xC1, 0xF0, 0x00, 0x5E, 0x0B, 0xC0, 0x06, 0xF0, 0x5E, 0x00, 0x37, + 0x82, 0x78, 0x03, 0x3C, 0x13, 0xC0, 0x19, 0xE0, 0x8F, 0x01, 0x8F, 0x04, + 0x78, 0x0C, 0x78, 0x21, 0xE0, 0xC3, 0xC1, 0x0F, 0x06, 0x1E, 0x08, 0x3C, + 0x60, 0xF0, 0x41, 0xE3, 0x07, 0x82, 0x07, 0xB0, 0x3C, 0x10, 0x3D, 0x81, + 0xE0, 0x81, 0xF8, 0x0F, 0x04, 0x07, 0xC0, 0x78, 0x20, 0x3C, 0x03, 0xC1, + 0x00, 0xE0, 0x1E, 0x1C, 0x06, 0x01, 0xFB, 0xF8, 0x10, 0x1F, 0xE0, 0xFC, + 0x00, 0xFE, 0x78, 0x00, 0x70, 0x78, 0x00, 0x40, 0xF8, 0x00, 0x81, 0xF8, + 0x01, 0x02, 0xF8, 0x02, 0x04, 0xF8, 0x04, 0x08, 0xF0, 0x08, 0x11, 0xF0, + 0x10, 0x21, 0xF0, 0x20, 0x41, 0xF0, 0x40, 0x81, 0xF0, 0x81, 0x01, 0xF1, + 0x02, 0x01, 0xE2, 0x04, 0x03, 0xE4, 0x08, 0x03, 0xE8, 0x10, 0x03, 0xF0, + 0x20, 0x03, 0xE0, 0x40, 0x03, 0xC0, 0x80, 0x03, 0x81, 0x00, 0x07, 0x07, + 0x00, 0x06, 0x3F, 0x80, 0x04, 0x00, 0x00, 0xFE, 0x00, 0x07, 0xFF, 0x00, + 0x3E, 0x0F, 0x80, 0xF0, 0x07, 0x83, 0xC0, 0x07, 0x87, 0x80, 0x07, 0x1E, + 0x00, 0x0F, 0x3C, 0x00, 0x1E, 0xF0, 0x00, 0x1F, 0xE0, 0x00, 0x3F, 0xC0, + 0x00, 0x7F, 0x80, 0x00, 0xFF, 0x00, 0x01, 0xFE, 0x00, 0x03, 0xFC, 0x00, + 0x07, 0xF8, 0x00, 0x0F, 0x78, 0x00, 0x3C, 0xF0, 0x00, 0x78, 0xE0, 0x01, + 0xE1, 0xE0, 0x03, 0xC1, 0xE0, 0x0F, 0x01, 0xF0, 0x7C, 0x00, 0xFF, 0xE0, + 0x00, 0x7F, 0x00, 0xFF, 0xF8, 0x1F, 0xFF, 0x83, 0xC1, 0xF0, 0xF0, 0x1E, + 0x3C, 0x07, 0xCF, 0x00, 0xF3, 0xC0, 0x3C, 0xF0, 0x0F, 0x3C, 0x03, 0xCF, + 0x01, 0xF3, 0xC0, 0x78, 0xF0, 0x7C, 0x3F, 0xFE, 0x0F, 0xFE, 0x03, 0xC0, + 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, + 0x3C, 0x00, 0x1F, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x07, 0xFF, + 0x00, 0x3E, 0x0F, 0x80, 0xF0, 0x07, 0x83, 0xC0, 0x07, 0x87, 0x80, 0x0F, + 0x1E, 0x00, 0x0F, 0x3C, 0x00, 0x1E, 0xF0, 0x00, 0x1D, 0xE0, 0x00, 0x3F, + 0xC0, 0x00, 0x7F, 0x80, 0x00, 0xFF, 0x00, 0x01, 0xFE, 0x00, 0x03, 0xFC, + 0x00, 0x07, 0xF8, 0x00, 0x0F, 0x70, 0x00, 0x1C, 0xF0, 0x00, 0x79, 0xE0, + 0x00, 0xF1, 0xE0, 0x03, 0xC1, 0xC0, 0x07, 0x01, 0xC0, 0x1C, 0x01, 0xE0, + 0xF0, 0x00, 0x7F, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x7E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, 0xC0, 0xFF, 0xF0, + 0x03, 0xFF, 0xF0, 0x0F, 0x07, 0xC0, 0x78, 0x1E, 0x03, 0xC0, 0x78, 0x1E, + 0x03, 0xC0, 0xF0, 0x1E, 0x07, 0x80, 0xF0, 0x3C, 0x07, 0x81, 0xE0, 0x78, + 0x0F, 0x0F, 0x80, 0x7F, 0xF8, 0x03, 0xFE, 0x00, 0x1E, 0x78, 0x00, 0xF1, + 0xE0, 0x07, 0x87, 0x80, 0x3C, 0x3C, 0x01, 0xE0, 0xF0, 0x0F, 0x03, 0xC0, + 0x78, 0x0F, 0x03, 0xC0, 0x7C, 0x3F, 0x01, 0xF3, 0xFC, 0x07, 0xE0, 0x07, + 0x84, 0x1F, 0xFC, 0x3C, 0x3E, 0x30, 0x0E, 0x70, 0x06, 0x70, 0x06, 0x70, + 0x02, 0x78, 0x00, 0x7C, 0x00, 0x3F, 0x00, 0x1F, 0xC0, 0x0F, 0xE0, 0x03, + 0xF8, 0x00, 0xFC, 0x00, 0x3E, 0x00, 0x1F, 0x80, 0x0F, 0x80, 0x0F, 0xC0, + 0x0F, 0xE0, 0x0F, 0x70, 0x1E, 0x78, 0x3C, 0x4F, 0xF8, 0x43, 0xF0, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xF0, 0x7C, 0x0F, 0x03, 0x80, 0xF0, 0x10, + 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, + 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, + 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, + 0x00, 0x00, 0xF0, 0x00, 0x1F, 0x80, 0x03, 0xFC, 0x00, 0xFF, 0x01, 0xFD, + 0xF8, 0x01, 0xC3, 0xC0, 0x02, 0x0F, 0x00, 0x08, 0x3C, 0x00, 0x20, 0xF0, + 0x00, 0x83, 0xC0, 0x02, 0x0F, 0x00, 0x08, 0x3C, 0x00, 0x20, 0xF0, 0x00, + 0x83, 0xC0, 0x02, 0x0F, 0x00, 0x08, 0x3C, 0x00, 0x20, 0xF0, 0x00, 0x83, + 0xC0, 0x02, 0x0F, 0x00, 0x08, 0x3C, 0x00, 0x20, 0xF0, 0x00, 0x81, 0xE0, + 0x04, 0x07, 0x80, 0x30, 0x0F, 0x81, 0x80, 0x1F, 0xFC, 0x00, 0x1F, 0xC0, + 0x00, 0xFF, 0xC0, 0x7F, 0x3E, 0x00, 0x1E, 0x1E, 0x00, 0x0C, 0x0E, 0x00, + 0x18, 0x0F, 0x00, 0x18, 0x07, 0x00, 0x10, 0x07, 0x80, 0x30, 0x07, 0x80, + 0x30, 0x03, 0xC0, 0x60, 0x03, 0xC0, 0x60, 0x01, 0xE0, 0x40, 0x01, 0xE0, + 0xC0, 0x00, 0xF0, 0xC0, 0x00, 0xF1, 0x80, 0x00, 0x71, 0x80, 0x00, 0x7B, + 0x00, 0x00, 0x3B, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x1E, + 0x00, 0x00, 0x0C, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x08, 0x00, 0xFF, 0x9F, + 0xF0, 0x3F, 0x9F, 0x03, 0xE0, 0x07, 0x07, 0x80, 0xF0, 0x03, 0x03, 0xC0, + 0x78, 0x01, 0x80, 0xE0, 0x1E, 0x00, 0x80, 0x78, 0x0F, 0x00, 0xC0, 0x1C, + 0x03, 0x80, 0x60, 0x0F, 0x01, 0xE0, 0x20, 0x07, 0x81, 0xF0, 0x30, 0x01, + 0xC0, 0xBC, 0x18, 0x00, 0xF0, 0xDE, 0x08, 0x00, 0x78, 0x67, 0x0C, 0x00, + 0x1E, 0x23, 0xC4, 0x00, 0x0F, 0x31, 0xE6, 0x00, 0x03, 0x90, 0x7B, 0x00, + 0x01, 0xF8, 0x3D, 0x00, 0x00, 0xFC, 0x0F, 0x80, 0x00, 0x3C, 0x07, 0xC0, + 0x00, 0x1E, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0xE0, 0x00, 0x03, 0x00, 0x70, + 0x00, 0x01, 0x80, 0x10, 0x00, 0x00, 0x80, 0x08, 0x00, 0x7F, 0xE0, 0xFF, + 0x0F, 0xC0, 0x1E, 0x03, 0xE0, 0x0E, 0x00, 0xF0, 0x06, 0x00, 0x3C, 0x06, + 0x00, 0x0F, 0x06, 0x00, 0x07, 0x86, 0x00, 0x01, 0xE6, 0x00, 0x00, 0x7B, + 0x00, 0x00, 0x3F, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x03, + 0xF0, 0x00, 0x03, 0x78, 0x00, 0x01, 0x9E, 0x00, 0x01, 0x87, 0x80, 0x01, + 0x83, 0xE0, 0x01, 0x80, 0xF0, 0x01, 0x80, 0x3C, 0x01, 0x80, 0x1F, 0x01, + 0xC0, 0x07, 0xC1, 0xE0, 0x03, 0xF3, 0xFE, 0x0F, 0xFE, 0xFF, 0xC0, 0xFF, + 0x7E, 0x00, 0x1C, 0x1E, 0x00, 0x18, 0x1F, 0x00, 0x30, 0x0F, 0x00, 0x60, + 0x07, 0x80, 0x60, 0x03, 0xC0, 0xC0, 0x03, 0xE1, 0x80, 0x01, 0xE1, 0x80, + 0x00, 0xF3, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0x7E, 0x00, 0x01, 0xFF, 0x80, 0x3F, 0xFF, 0xF1, 0xFF, 0xFF, 0x9C, + 0x00, 0x78, 0xC0, 0x07, 0x84, 0x00, 0x38, 0x00, 0x03, 0xC0, 0x00, 0x3C, + 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, + 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, + 0x07, 0x00, 0x00, 0x78, 0x00, 0x47, 0x80, 0x06, 0x78, 0x00, 0x33, 0x80, + 0x07, 0x3F, 0xFF, 0xFB, 0xFF, 0xFF, 0xC0, 0xFF, 0x83, 0x06, 0x0C, 0x18, + 0x30, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x06, + 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x07, 0xF0, 0xC0, 0x18, 0x06, 0x01, + 0x80, 0x70, 0x0C, 0x03, 0x00, 0xE0, 0x18, 0x06, 0x01, 0xC0, 0x30, 0x0C, + 0x03, 0x80, 0x60, 0x18, 0x07, 0x00, 0xC0, 0x30, 0x0E, 0x01, 0x80, 0x60, + 0x1C, 0x03, 0xFE, 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x18, + 0x30, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x06, + 0x0C, 0x1F, 0xF0, 0x03, 0x80, 0x0F, 0x00, 0x1F, 0x00, 0x76, 0x00, 0xCE, + 0x03, 0x8C, 0x06, 0x1C, 0x1C, 0x18, 0x30, 0x30, 0xE0, 0x31, 0x80, 0x67, + 0x00, 0x6C, 0x00, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xC0, 0xE0, 0x70, + 0x18, 0x0C, 0x03, 0x1F, 0x03, 0x8C, 0x38, 0x31, 0xC1, 0x8E, 0x0C, 0x00, + 0x60, 0x0F, 0x01, 0x98, 0x30, 0xC3, 0x86, 0x38, 0x31, 0xC1, 0x8E, 0x0C, + 0x78, 0xE5, 0xFB, 0xCF, 0x0C, 0x00, 0x00, 0x38, 0x00, 0xF8, 0x00, 0x38, + 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x39, + 0xF0, 0x3B, 0xFC, 0x3C, 0x3E, 0x38, 0x0E, 0x38, 0x0F, 0x38, 0x07, 0x38, + 0x07, 0x38, 0x07, 0x38, 0x07, 0x38, 0x07, 0x38, 0x06, 0x38, 0x0E, 0x38, + 0x0C, 0x3C, 0x1C, 0x1F, 0xF0, 0x07, 0xE0, 0x07, 0xE0, 0x7F, 0xE3, 0x87, + 0xD8, 0x0F, 0x60, 0x1B, 0x00, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x03, 0x00, + 0x0E, 0x00, 0x3C, 0x01, 0x78, 0x19, 0xFF, 0xC3, 0xFE, 0x03, 0xE0, 0x00, + 0x00, 0x00, 0x1C, 0x00, 0x7C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, + 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x07, 0x9C, 0x1F, 0xDC, 0x38, 0x7C, 0x70, + 0x3C, 0x70, 0x1C, 0x60, 0x1C, 0xE0, 0x1C, 0xE0, 0x1C, 0xE0, 0x1C, 0xE0, + 0x1C, 0xE0, 0x1C, 0xF0, 0x1C, 0x70, 0x1C, 0x7C, 0x3E, 0x3F, 0xDF, 0x0F, + 0x90, 0x0F, 0x81, 0xFF, 0x08, 0x3C, 0x80, 0xE7, 0xFF, 0x7F, 0xFF, 0x00, + 0x18, 0x00, 0xC0, 0x07, 0x00, 0x38, 0x03, 0xE0, 0x37, 0x83, 0x3F, 0xF0, + 0xFF, 0x03, 0xF0, 0x01, 0xF0, 0x3F, 0xC3, 0x8E, 0x18, 0x00, 0xC0, 0x0E, + 0x00, 0x70, 0x03, 0x80, 0x1C, 0x03, 0xFE, 0x1F, 0xF0, 0x38, 0x01, 0xC0, + 0x0E, 0x00, 0x70, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, + 0xC0, 0x0E, 0x00, 0x70, 0x07, 0xC0, 0xFF, 0x80, 0x0F, 0xC0, 0x1F, 0xFF, + 0x38, 0xFF, 0x70, 0x70, 0x70, 0x70, 0x70, 0x30, 0x70, 0x30, 0x70, 0x30, + 0x38, 0x20, 0x1C, 0x60, 0x0F, 0x80, 0x10, 0x00, 0x20, 0x00, 0x60, 0x00, + 0x7F, 0xE0, 0x3F, 0xFC, 0x1F, 0xFE, 0x20, 0x06, 0x40, 0x02, 0xC0, 0x02, + 0xC0, 0x04, 0xF0, 0x18, 0x7F, 0xF0, 0x1F, 0x80, 0x00, 0x00, 0x38, 0x00, + 0xF8, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, + 0x38, 0x00, 0x38, 0xF0, 0x3B, 0xF8, 0x3E, 0x3C, 0x3C, 0x1C, 0x38, 0x1C, + 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, + 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x7C, 0x3E, 0xFE, 0x7F, 0x18, 0x3C, + 0x3C, 0x18, 0x00, 0x00, 0x00, 0x00, 0x04, 0x3C, 0x7C, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x3C, 0xFF, 0x03, 0x03, + 0xC1, 0xE0, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x83, 0xC3, 0xE0, 0x70, + 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, + 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x37, 0x3B, 0xF8, 0xF8, 0x00, 0x00, + 0x1C, 0x00, 0x3E, 0x00, 0x07, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, + 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x3F, 0x8E, 0x0F, 0x07, 0x06, 0x03, + 0x86, 0x01, 0xC4, 0x00, 0xE4, 0x00, 0x7E, 0x00, 0x3F, 0x80, 0x1D, 0xC0, + 0x0E, 0x70, 0x07, 0x1C, 0x03, 0x8F, 0x01, 0xC3, 0xC0, 0xE0, 0xF0, 0xF8, + 0x3C, 0xFE, 0x7F, 0x80, 0x00, 0x1C, 0x7C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1C, 0x1C, 0x3C, 0xFF, 0x38, 0xF0, 0x7C, 0x3E, 0xFE, 0x7F, 0x83, + 0xE3, 0xF0, 0xE0, 0xE0, 0x70, 0x1C, 0x38, 0x1C, 0x07, 0x0E, 0x07, 0x01, + 0xC3, 0x81, 0xC0, 0x70, 0xE0, 0x70, 0x1C, 0x38, 0x1C, 0x07, 0x0E, 0x07, + 0x01, 0xC3, 0x81, 0xC0, 0x70, 0xE0, 0x70, 0x1C, 0x38, 0x1C, 0x07, 0x0E, + 0x07, 0x01, 0xC3, 0x81, 0xE0, 0x73, 0xF9, 0xFC, 0x7F, 0x38, 0xF0, 0xFB, + 0xF8, 0x3E, 0x3C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, + 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, + 0x1C, 0x78, 0x3C, 0xFE, 0x7F, 0x07, 0xE0, 0x1F, 0xF8, 0x3C, 0x7C, 0x78, + 0x3E, 0x70, 0x1E, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, + 0x0F, 0xF8, 0x0F, 0x78, 0x0E, 0x7C, 0x1C, 0x3E, 0x3C, 0x0F, 0xF0, 0x07, + 0xC0, 0x18, 0xF0, 0xFB, 0xFC, 0x3E, 0x1E, 0x38, 0x0E, 0x38, 0x0F, 0x38, + 0x07, 0x38, 0x07, 0x38, 0x07, 0x38, 0x07, 0x38, 0x07, 0x38, 0x06, 0x38, + 0x0E, 0x38, 0x0C, 0x3E, 0x1C, 0x3B, 0xF8, 0x39, 0xE0, 0x38, 0x00, 0x38, + 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x7C, 0x00, 0xFF, + 0x00, 0x07, 0xC4, 0x1F, 0xEC, 0x3C, 0x3C, 0x70, 0x1C, 0x70, 0x1C, 0x60, + 0x1C, 0xE0, 0x1C, 0xE0, 0x1C, 0xE0, 0x1C, 0xE0, 0x1C, 0xE0, 0x1C, 0xF0, + 0x1C, 0x70, 0x1C, 0x78, 0x3C, 0x3F, 0xDC, 0x1F, 0x1C, 0x00, 0x1C, 0x00, + 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x3E, 0x00, + 0xFF, 0x19, 0xFF, 0x7C, 0xF3, 0x9C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, + 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x1F, 0x07, 0xF0, 0x3E, + 0x58, 0x7C, 0x0F, 0x03, 0xC0, 0x7C, 0x07, 0x80, 0xF8, 0x1F, 0x81, 0xF8, + 0x1E, 0x03, 0xC0, 0xF0, 0x3E, 0x1A, 0x7C, 0x10, 0x30, 0x70, 0xFE, 0xFE, + 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x79, + 0x7E, 0x3C, 0xF8, 0x7C, 0x38, 0x3C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, + 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, + 0x38, 0x1C, 0x38, 0x1C, 0x3C, 0x7C, 0x1F, 0xDF, 0x0F, 0x18, 0xFE, 0x1F, + 0x7C, 0x06, 0x38, 0x04, 0x1C, 0x04, 0x1C, 0x0C, 0x0E, 0x08, 0x0E, 0x18, + 0x07, 0x10, 0x07, 0x10, 0x07, 0x20, 0x03, 0xA0, 0x03, 0xE0, 0x01, 0xC0, + 0x01, 0xC0, 0x00, 0x80, 0x00, 0x80, 0xFC, 0x7F, 0x1F, 0x78, 0x3C, 0x06, + 0x38, 0x1C, 0x04, 0x38, 0x1C, 0x04, 0x1C, 0x1C, 0x0C, 0x1C, 0x0E, 0x08, + 0x1C, 0x1E, 0x18, 0x0E, 0x17, 0x10, 0x0E, 0x37, 0x10, 0x07, 0x23, 0x30, + 0x07, 0x63, 0xA0, 0x07, 0x43, 0xE0, 0x03, 0xC1, 0xC0, 0x03, 0x81, 0xC0, + 0x01, 0x80, 0x80, 0x01, 0x00, 0x80, 0x7F, 0x7E, 0x1E, 0x0C, 0x07, 0x8C, + 0x01, 0xC4, 0x00, 0x76, 0x00, 0x3E, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x03, + 0xE0, 0x01, 0x70, 0x01, 0x1C, 0x01, 0x8F, 0x01, 0x83, 0x80, 0x80, 0xE0, + 0xC0, 0x79, 0xF0, 0xFF, 0xFE, 0x0F, 0x7C, 0x06, 0x38, 0x06, 0x1C, 0x04, + 0x1C, 0x0C, 0x0E, 0x0C, 0x0E, 0x08, 0x0F, 0x18, 0x07, 0x10, 0x07, 0x90, + 0x03, 0xB0, 0x03, 0xA0, 0x01, 0xE0, 0x01, 0xE0, 0x00, 0xC0, 0x00, 0xC0, + 0x00, 0x80, 0x00, 0x80, 0x01, 0x80, 0x01, 0x00, 0x03, 0x00, 0x7E, 0x00, + 0x7C, 0x00, 0x78, 0x00, 0x7F, 0xF9, 0xFF, 0xE6, 0x07, 0x10, 0x38, 0x00, + 0xE0, 0x07, 0x00, 0x38, 0x01, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xE0, 0x07, + 0x01, 0x38, 0x0D, 0xC0, 0x3F, 0xFF, 0xBF, 0xFE, 0x07, 0x0E, 0x1C, 0x18, + 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x30, 0x60, 0x60, + 0x10, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x1C, + 0x0E, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x70, 0x38, 0x18, + 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x08, 0x06, 0x06, + 0x08, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x38, + 0x70, 0xE0, 0x3E, 0x00, 0x7F, 0x87, 0xE3, 0xFE, 0x00, 0x7C }; + +const GFXglyph FreeSerif18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 9, 0, 1 }, // 0x20 ' ' + { 0, 4, 24, 12, 5, -23 }, // 0x21 '!' + { 12, 8, 9, 14, 3, -23 }, // 0x22 '"' + { 21, 17, 23, 17, 0, -22 }, // 0x23 '#' + { 70, 13, 27, 17, 2, -24 }, // 0x24 '$' + { 114, 25, 23, 29, 2, -22 }, // 0x25 '%' + { 186, 25, 25, 27, 1, -24 }, // 0x26 '&' + { 265, 3, 9, 7, 2, -23 }, // 0x27 ''' + { 269, 9, 30, 12, 2, -23 }, // 0x28 '(' + { 303, 9, 30, 12, 1, -22 }, // 0x29 ')' + { 337, 12, 14, 18, 3, -23 }, // 0x2A '*' + { 358, 16, 18, 20, 2, -17 }, // 0x2B '+' + { 394, 4, 9, 9, 2, -3 }, // 0x2C ',' + { 399, 8, 2, 12, 1, -8 }, // 0x2D '-' + { 401, 4, 4, 9, 2, -3 }, // 0x2E '.' + { 403, 10, 24, 10, 0, -23 }, // 0x2F '/' + { 433, 16, 24, 18, 1, -23 }, // 0x30 '0' + { 481, 10, 24, 18, 3, -23 }, // 0x31 '1' + { 511, 16, 24, 17, 1, -23 }, // 0x32 '2' + { 559, 13, 24, 17, 2, -23 }, // 0x33 '3' + { 598, 16, 23, 18, 0, -22 }, // 0x34 '4' + { 644, 13, 24, 17, 2, -23 }, // 0x35 '5' + { 683, 16, 24, 18, 1, -23 }, // 0x36 '6' + { 731, 14, 23, 18, 1, -22 }, // 0x37 '7' + { 772, 12, 25, 18, 2, -24 }, // 0x38 '8' + { 810, 16, 26, 17, 1, -24 }, // 0x39 '9' + { 862, 4, 17, 9, 2, -16 }, // 0x3A ':' + { 871, 5, 22, 9, 2, -16 }, // 0x3B ';' + { 885, 18, 18, 20, 1, -17 }, // 0x3C '<' + { 926, 18, 9, 20, 1, -12 }, // 0x3D '=' + { 947, 18, 18, 20, 1, -17 }, // 0x3E '>' + { 988, 13, 25, 16, 2, -24 }, // 0x3F '?' + { 1029, 24, 25, 30, 3, -24 }, // 0x40 '@' + { 1104, 24, 23, 25, 1, -22 }, // 0x41 'A' + { 1173, 20, 23, 22, 1, -22 }, // 0x42 'B' + { 1231, 22, 24, 23, 1, -23 }, // 0x43 'C' + { 1297, 23, 23, 25, 1, -22 }, // 0x44 'D' + { 1364, 20, 23, 21, 2, -22 }, // 0x45 'E' + { 1422, 17, 23, 20, 2, -22 }, // 0x46 'F' + { 1471, 23, 24, 25, 1, -23 }, // 0x47 'G' + { 1540, 22, 23, 25, 2, -22 }, // 0x48 'H' + { 1604, 9, 23, 11, 2, -22 }, // 0x49 'I' + { 1630, 12, 23, 13, 0, -22 }, // 0x4A 'J' + { 1665, 23, 23, 25, 2, -22 }, // 0x4B 'K' + { 1732, 19, 23, 21, 2, -22 }, // 0x4C 'L' + { 1787, 29, 23, 31, 1, -22 }, // 0x4D 'M' + { 1871, 23, 23, 25, 1, -22 }, // 0x4E 'N' + { 1938, 23, 24, 25, 1, -23 }, // 0x4F 'O' + { 2007, 18, 23, 20, 1, -22 }, // 0x50 'P' + { 2059, 23, 30, 25, 1, -23 }, // 0x51 'Q' + { 2146, 21, 23, 23, 2, -22 }, // 0x52 'R' + { 2207, 16, 24, 19, 1, -23 }, // 0x53 'S' + { 2255, 20, 23, 21, 1, -22 }, // 0x54 'T' + { 2313, 22, 23, 25, 2, -22 }, // 0x55 'U' + { 2377, 24, 23, 25, 0, -22 }, // 0x56 'V' + { 2446, 33, 23, 33, 0, -22 }, // 0x57 'W' + { 2541, 25, 23, 25, 0, -22 }, // 0x58 'X' + { 2613, 24, 23, 25, 1, -22 }, // 0x59 'Y' + { 2682, 21, 23, 21, 0, -22 }, // 0x5A 'Z' + { 2743, 7, 28, 12, 3, -22 }, // 0x5B '[' + { 2768, 10, 24, 10, 0, -23 }, // 0x5C '\' + { 2798, 7, 28, 12, 2, -22 }, // 0x5D ']' + { 2823, 15, 13, 16, 1, -22 }, // 0x5E '^' + { 2848, 18, 2, 17, 0, 3 }, // 0x5F '_' + { 2853, 8, 6, 9, 1, -23 }, // 0x60 '`' + { 2859, 13, 16, 15, 2, -15 }, // 0x61 'a' + { 2885, 16, 25, 17, 1, -24 }, // 0x62 'b' + { 2935, 14, 16, 16, 1, -15 }, // 0x63 'c' + { 2963, 16, 25, 17, 1, -24 }, // 0x64 'd' + { 3013, 13, 16, 16, 1, -15 }, // 0x65 'e' + { 3039, 13, 25, 13, 0, -24 }, // 0x66 'f' + { 3080, 16, 24, 16, 1, -15 }, // 0x67 'g' + { 3128, 16, 25, 17, 1, -24 }, // 0x68 'h' + { 3178, 8, 24, 10, 0, -23 }, // 0x69 'i' + { 3202, 9, 32, 12, 0, -23 }, // 0x6A 'j' + { 3238, 17, 25, 18, 1, -24 }, // 0x6B 'k' + { 3292, 8, 25, 9, 0, -24 }, // 0x6C 'l' + { 3317, 26, 16, 27, 1, -15 }, // 0x6D 'm' + { 3369, 16, 16, 17, 1, -15 }, // 0x6E 'n' + { 3401, 16, 16, 17, 1, -15 }, // 0x6F 'o' + { 3433, 16, 24, 17, 1, -15 }, // 0x70 'p' + { 3481, 16, 24, 17, 1, -15 }, // 0x71 'q' + { 3529, 11, 16, 12, 1, -15 }, // 0x72 'r' + { 3551, 10, 16, 13, 1, -15 }, // 0x73 's' + { 3571, 8, 19, 10, 2, -18 }, // 0x74 't' + { 3590, 16, 16, 17, 1, -15 }, // 0x75 'u' + { 3622, 16, 16, 16, 0, -15 }, // 0x76 'v' + { 3654, 24, 16, 24, 0, -15 }, // 0x77 'w' + { 3702, 17, 16, 17, 0, -15 }, // 0x78 'x' + { 3736, 16, 24, 16, 0, -15 }, // 0x79 'y' + { 3784, 14, 16, 15, 0, -15 }, // 0x7A 'z' + { 3812, 8, 30, 17, 3, -23 }, // 0x7B '{' + { 3842, 2, 24, 7, 2, -23 }, // 0x7C '|' + { 3848, 8, 30, 17, 6, -22 }, // 0x7D '}' + { 3878, 16, 4, 17, 1, -10 } }; // 0x7E '~' + +const GFXfont FreeSerif18pt7b PROGMEM = { + (uint8_t *)FreeSerif18pt7bBitmaps, + (GFXglyph *)FreeSerif18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 4558 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerif24pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerif24pt7b.h new file mode 100644 index 0000000..99ff3f4 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerif24pt7b.h @@ -0,0 +1,690 @@ +const uint8_t FreeSerif24pt7bBitmaps[] PROGMEM = { + 0x77, 0xBF, 0xFF, 0xFF, 0xFF, 0xFB, 0x9C, 0xE7, 0x39, 0xCE, 0x61, 0x08, + 0x42, 0x10, 0x84, 0x00, 0x00, 0xEF, 0xFF, 0xEE, 0x60, 0x6F, 0x0F, 0xF0, + 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0x60, 0x66, 0x06, 0x60, 0x66, 0x06, 0x60, + 0x66, 0x06, 0x00, 0xE0, 0x70, 0x01, 0xC0, 0xE0, 0x03, 0x81, 0xC0, 0x07, + 0x03, 0x80, 0x0E, 0x06, 0x00, 0x18, 0x0C, 0x00, 0x30, 0x38, 0x00, 0xE0, + 0x70, 0x01, 0xC0, 0xE0, 0x03, 0x81, 0xC1, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, + 0xF0, 0x18, 0x0C, 0x00, 0x70, 0x38, 0x00, 0xE0, 0x70, 0x01, 0xC0, 0xE0, + 0x03, 0x81, 0xC0, 0x07, 0x03, 0x80, 0x0C, 0x06, 0x07, 0xFF, 0xFF, 0xEF, + 0xFF, 0xFF, 0xC0, 0xE0, 0x70, 0x01, 0xC0, 0xE0, 0x03, 0x81, 0xC0, 0x06, + 0x03, 0x80, 0x0C, 0x06, 0x00, 0x38, 0x1C, 0x00, 0x70, 0x38, 0x00, 0xE0, + 0x70, 0x01, 0xC0, 0xE0, 0x03, 0x81, 0xC0, 0x00, 0x00, 0x40, 0x00, 0x08, + 0x00, 0x01, 0x00, 0x01, 0xFC, 0x01, 0xE4, 0xF8, 0x70, 0x87, 0x9C, 0x10, + 0x77, 0x02, 0x06, 0xE0, 0x40, 0xDC, 0x08, 0x0B, 0x81, 0x00, 0x78, 0x20, + 0x07, 0x84, 0x00, 0xFC, 0x80, 0x0F, 0xF0, 0x00, 0xFE, 0x00, 0x07, 0xF0, + 0x00, 0x7F, 0x80, 0x03, 0xFC, 0x00, 0x3F, 0xC0, 0x05, 0xFC, 0x00, 0x8F, + 0x80, 0x10, 0xF8, 0x02, 0x0F, 0x00, 0x40, 0xF0, 0x08, 0x1E, 0x01, 0x03, + 0xE0, 0x20, 0x7C, 0x04, 0x0F, 0xC0, 0x83, 0xBC, 0x10, 0xE3, 0xE2, 0x78, + 0x3F, 0xFE, 0x00, 0xFE, 0x00, 0x01, 0x00, 0x00, 0x20, 0x00, 0x04, 0x00, + 0x01, 0xF0, 0x00, 0xC0, 0x03, 0xFC, 0x01, 0xE0, 0x03, 0xC7, 0x81, 0xE0, + 0x03, 0xC0, 0x7F, 0x60, 0x03, 0xC0, 0x20, 0x70, 0x01, 0xE0, 0x10, 0x30, + 0x01, 0xE0, 0x08, 0x38, 0x00, 0xE0, 0x04, 0x18, 0x00, 0xF0, 0x02, 0x1C, + 0x00, 0x78, 0x02, 0x0C, 0x00, 0x38, 0x01, 0x0E, 0x00, 0x1C, 0x01, 0x86, + 0x00, 0x0E, 0x00, 0x86, 0x00, 0x07, 0x00, 0x87, 0x03, 0xE1, 0x80, 0xC3, + 0x07, 0xFC, 0xE1, 0xC3, 0x87, 0xC6, 0x3F, 0xC1, 0x87, 0x81, 0x8F, 0x81, + 0xC7, 0x80, 0x40, 0x00, 0xC3, 0xC0, 0x20, 0x00, 0xE3, 0xC0, 0x10, 0x00, + 0x61, 0xC0, 0x08, 0x00, 0x61, 0xE0, 0x04, 0x00, 0x70, 0xF0, 0x06, 0x00, + 0x30, 0x70, 0x02, 0x00, 0x38, 0x38, 0x03, 0x00, 0x18, 0x1C, 0x01, 0x00, + 0x1C, 0x0E, 0x01, 0x80, 0x0C, 0x07, 0x01, 0x80, 0x0E, 0x01, 0xC3, 0x80, + 0x06, 0x00, 0x7F, 0x80, 0x06, 0x00, 0x1F, 0x00, 0x07, 0x00, 0x00, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x00, 0x70, 0xE0, 0x00, + 0x00, 0xE0, 0x60, 0x00, 0x00, 0xC0, 0x30, 0x00, 0x01, 0xC0, 0x30, 0x00, + 0x01, 0xC0, 0x30, 0x00, 0x01, 0xC0, 0x30, 0x00, 0x01, 0xC0, 0x70, 0x00, + 0x01, 0xE0, 0xE0, 0x00, 0x01, 0xE1, 0xC0, 0x00, 0x00, 0xF3, 0x80, 0x00, + 0x00, 0xFF, 0x0F, 0xFC, 0x00, 0xFC, 0x03, 0xF0, 0x00, 0xF8, 0x01, 0xE0, + 0x01, 0xFC, 0x01, 0xC0, 0x07, 0x7C, 0x01, 0xC0, 0x0F, 0x3E, 0x01, 0x80, + 0x1E, 0x3E, 0x03, 0x00, 0x3C, 0x1F, 0x03, 0x00, 0x7C, 0x1F, 0x06, 0x00, + 0x78, 0x0F, 0x86, 0x00, 0x78, 0x07, 0xCC, 0x00, 0xF8, 0x07, 0xE8, 0x00, + 0xF8, 0x03, 0xF8, 0x00, 0xF8, 0x01, 0xF0, 0x00, 0xF8, 0x01, 0xF8, 0x00, + 0xFC, 0x00, 0xFC, 0x01, 0xFC, 0x01, 0xFE, 0x01, 0x7E, 0x03, 0xBF, 0x86, + 0x7F, 0x0F, 0x1F, 0xFE, 0x3F, 0xFC, 0x0F, 0xF8, 0x0F, 0xE0, 0x03, 0xF0, + 0x6F, 0xFF, 0xFF, 0x66, 0x66, 0x66, 0x00, 0x10, 0x02, 0x00, 0xC0, 0x18, + 0x03, 0x00, 0x60, 0x0E, 0x00, 0xC0, 0x1C, 0x03, 0x80, 0x38, 0x03, 0x80, + 0x78, 0x07, 0x00, 0x70, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, + 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x07, 0x00, 0x70, 0x07, 0x80, + 0x38, 0x03, 0x80, 0x38, 0x01, 0xC0, 0x0C, 0x00, 0xC0, 0x06, 0x00, 0x30, + 0x01, 0x80, 0x0C, 0x00, 0x60, 0x03, 0xC0, 0x06, 0x00, 0x30, 0x01, 0x80, + 0x0C, 0x00, 0x60, 0x07, 0x00, 0x30, 0x03, 0x80, 0x1C, 0x01, 0xC0, 0x1C, + 0x01, 0xE0, 0x0E, 0x00, 0xE0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0E, 0x00, 0xE0, 0x1E, + 0x01, 0xC0, 0x1C, 0x01, 0xC0, 0x38, 0x03, 0x00, 0x70, 0x0E, 0x00, 0xC0, + 0x18, 0x03, 0x00, 0x40, 0x08, 0x00, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, + 0x43, 0x86, 0xE1, 0x0F, 0xF1, 0x1F, 0xF9, 0x3E, 0x3D, 0x78, 0x07, 0xC0, + 0x01, 0x00, 0x07, 0xC0, 0x19, 0x30, 0xF9, 0x1E, 0xF1, 0x0F, 0xE1, 0x07, + 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0x00, 0x38, 0x00, 0x00, + 0x70, 0x00, 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, + 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, + 0x00, 0x00, 0xE0, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x07, 0x00, + 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, + 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, + 0x0E, 0x00, 0x00, 0x73, 0xEF, 0xFF, 0x7C, 0x10, 0x42, 0x08, 0xC6, 0x00, + 0xFF, 0xFF, 0xFC, 0x77, 0xFF, 0xF7, 0x00, 0x00, 0x1C, 0x00, 0xE0, 0x03, + 0x80, 0x0E, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, 0x38, 0x00, 0xE0, 0x03, + 0x80, 0x1C, 0x00, 0x70, 0x01, 0xC0, 0x0E, 0x00, 0x38, 0x01, 0xE0, 0x07, + 0x00, 0x1C, 0x00, 0xF0, 0x03, 0x80, 0x0E, 0x00, 0x78, 0x01, 0xC0, 0x07, + 0x00, 0x3C, 0x00, 0xE0, 0x03, 0x80, 0x1E, 0x00, 0x70, 0x01, 0xC0, 0x0F, + 0x00, 0x38, 0x00, 0x00, 0xFC, 0x00, 0x0E, 0x1C, 0x00, 0x70, 0x38, 0x03, + 0x80, 0x70, 0x1E, 0x01, 0xE0, 0xF0, 0x03, 0x83, 0xC0, 0x0F, 0x0F, 0x00, + 0x3C, 0x7C, 0x00, 0xF9, 0xE0, 0x01, 0xE7, 0x80, 0x07, 0xBE, 0x00, 0x1F, + 0xF8, 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0x80, 0x07, 0xFE, 0x00, 0x1F, 0xF8, + 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0x80, 0x07, 0xFE, 0x00, 0x1F, 0xF8, 0x00, + 0x7F, 0xE0, 0x01, 0xF7, 0x80, 0x07, 0x9E, 0x00, 0x1E, 0x7C, 0x00, 0xF8, + 0xF0, 0x03, 0xC3, 0xC0, 0x0F, 0x07, 0x00, 0x38, 0x1E, 0x01, 0xE0, 0x38, + 0x07, 0x00, 0x70, 0x38, 0x00, 0xE1, 0xC0, 0x00, 0xFC, 0x00, 0x00, 0x80, + 0x1C, 0x03, 0xE0, 0x7F, 0x0C, 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xF0, 0x07, + 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xF0, + 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1E, 0x00, + 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x3F, + 0x0F, 0xFF, 0x01, 0xF8, 0x00, 0x3F, 0xF0, 0x07, 0xFF, 0xE0, 0x70, 0x3F, + 0x83, 0x00, 0x7C, 0x30, 0x01, 0xF1, 0x00, 0x0F, 0x98, 0x00, 0x3C, 0x80, + 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0x80, 0x00, 0x1C, + 0x00, 0x01, 0xC0, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00, + 0x70, 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, + 0x03, 0x00, 0x00, 0x30, 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, 0x43, 0x00, + 0x02, 0x30, 0x00, 0x23, 0xFF, 0xFF, 0x3F, 0xFF, 0xF3, 0xFF, 0xFF, 0x80, + 0x03, 0xF8, 0x03, 0xFF, 0x01, 0x83, 0xE0, 0x80, 0x3C, 0x40, 0x0F, 0x10, + 0x01, 0xC8, 0x00, 0x70, 0x00, 0x1C, 0x00, 0x06, 0x00, 0x03, 0x00, 0x00, + 0x80, 0x00, 0xC0, 0x00, 0x78, 0x00, 0x7F, 0x80, 0x7F, 0xF0, 0x01, 0xFE, + 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x01, 0xC0, + 0x00, 0x70, 0x00, 0x1C, 0x00, 0x07, 0x00, 0x01, 0x80, 0x00, 0x60, 0x00, + 0x30, 0x00, 0x0C, 0x70, 0x06, 0x3F, 0x07, 0x0F, 0xFF, 0x00, 0xFF, 0x00, + 0x00, 0x03, 0x00, 0x00, 0x38, 0x00, 0x01, 0xC0, 0x00, 0x1E, 0x00, 0x01, + 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xDC, 0x00, 0x0C, 0xE0, 0x00, 0x47, 0x00, + 0x06, 0x38, 0x00, 0x61, 0xC0, 0x06, 0x0E, 0x00, 0x30, 0x70, 0x03, 0x03, + 0x80, 0x30, 0x1C, 0x01, 0x80, 0xE0, 0x18, 0x07, 0x01, 0x80, 0x38, 0x08, + 0x01, 0xC0, 0xC0, 0x0E, 0x0C, 0x00, 0x70, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xE0, 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00, 0x38, 0x00, 0x01, 0xC0, 0x00, + 0x0E, 0x00, 0x00, 0x70, 0x00, 0x03, 0x80, 0x00, 0x1C, 0x00, 0x00, 0x00, + 0x40, 0x7F, 0xF8, 0x1F, 0xFE, 0x03, 0xFF, 0xC0, 0xC0, 0x00, 0x18, 0x00, + 0x06, 0x00, 0x00, 0xC0, 0x00, 0x1C, 0x00, 0x07, 0xF8, 0x00, 0xFF, 0xC0, + 0x3F, 0xFE, 0x00, 0xFF, 0xE0, 0x01, 0xFE, 0x00, 0x0F, 0xE0, 0x00, 0x7C, + 0x00, 0x07, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x1C, + 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x30, + 0x00, 0x0E, 0x00, 0x01, 0x80, 0x00, 0x71, 0xE0, 0x1C, 0x3F, 0x07, 0x07, + 0xFF, 0x80, 0x3F, 0x80, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x0F, + 0x80, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, + 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, + 0x07, 0xC7, 0xE0, 0x3E, 0xFF, 0xC3, 0xF8, 0x3F, 0x1F, 0x80, 0x7C, 0xF8, + 0x03, 0xF7, 0xC0, 0x0F, 0xBE, 0x00, 0x7F, 0xF0, 0x01, 0xFF, 0x80, 0x0F, + 0xFC, 0x00, 0x7F, 0xE0, 0x03, 0xFF, 0x00, 0x1F, 0x78, 0x00, 0xFB, 0xE0, + 0x07, 0x9F, 0x00, 0x3C, 0x78, 0x03, 0xE3, 0xE0, 0x1E, 0x0F, 0x81, 0xE0, + 0x3E, 0x1E, 0x00, 0xFF, 0xE0, 0x00, 0xFC, 0x00, 0x3F, 0xFF, 0xF3, 0xFF, + 0xFF, 0x3F, 0xFF, 0xE7, 0x00, 0x0E, 0x40, 0x00, 0xEC, 0x00, 0x1C, 0x80, + 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x03, 0x80, + 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x00, 0xE0, + 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x38, + 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x07, + 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x1E, 0x00, 0x01, + 0xC0, 0x00, 0x03, 0xF0, 0x03, 0xFF, 0x03, 0xC1, 0xE0, 0xC0, 0x1C, 0x70, + 0x07, 0x18, 0x00, 0xEE, 0x00, 0x3B, 0x80, 0x0E, 0xF0, 0x03, 0xBC, 0x00, + 0xE7, 0x80, 0x71, 0xF0, 0x38, 0x3E, 0x1C, 0x07, 0xEE, 0x00, 0xFE, 0x00, + 0x1F, 0xC0, 0x03, 0xF8, 0x03, 0xFF, 0x01, 0xC7, 0xE0, 0xE0, 0xFC, 0x70, + 0x0F, 0x98, 0x01, 0xEE, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x01, 0xF8, 0x00, + 0x7E, 0x00, 0x1F, 0xC0, 0x07, 0x70, 0x03, 0x9E, 0x00, 0xE3, 0xE0, 0xF0, + 0x7F, 0xF0, 0x07, 0xF0, 0x00, 0x01, 0xF8, 0x00, 0x3F, 0xF0, 0x03, 0xC3, + 0xE0, 0x3C, 0x0F, 0x83, 0xC0, 0x3C, 0x3E, 0x00, 0xF1, 0xE0, 0x07, 0xCF, + 0x00, 0x3E, 0xF8, 0x00, 0xF7, 0xC0, 0x07, 0xFE, 0x00, 0x3F, 0xF0, 0x01, + 0xFF, 0x80, 0x0F, 0xFC, 0x00, 0x7F, 0xF0, 0x03, 0xEF, 0x80, 0x1F, 0x7C, + 0x00, 0xF9, 0xF0, 0x0F, 0xC7, 0xE1, 0xFC, 0x1F, 0xF9, 0xE0, 0x3F, 0x1F, + 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x78, 0x00, 0x07, 0xC0, 0x00, + 0x7C, 0x00, 0x03, 0xC0, 0x00, 0x3C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, + 0x0F, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x00, 0x77, 0xFF, 0xF7, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xBF, 0xFF, 0xB8, 0x39, 0xF7, + 0xDF, 0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x73, 0xEF, + 0xFF, 0x7C, 0x10, 0x42, 0x08, 0xC6, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x07, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x07, + 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xE0, + 0x00, 0x3F, 0x80, 0x00, 0xFE, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xF8, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0x3F, 0x80, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0x00, 0x00, 0x01, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0xE0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x07, + 0xF8, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, + 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFE, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xE0, + 0x0F, 0xFE, 0x0C, 0x1F, 0x88, 0x03, 0xEC, 0x01, 0xF7, 0x00, 0x7F, 0xC0, + 0x3F, 0xE0, 0x1F, 0x70, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xC0, 0x01, 0xE0, + 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x70, 0x00, 0x70, 0x00, 0x30, 0x00, 0x10, + 0x00, 0x18, 0x00, 0x08, 0x00, 0x04, 0x00, 0x06, 0x00, 0x02, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x3E, 0x00, + 0x1F, 0x00, 0x0F, 0x80, 0x03, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x3F, + 0xFF, 0x00, 0x00, 0xFC, 0x07, 0xC0, 0x01, 0xE0, 0x00, 0xE0, 0x07, 0xC0, + 0x00, 0x30, 0x0F, 0x00, 0x00, 0x18, 0x1E, 0x00, 0x00, 0x0C, 0x1E, 0x00, + 0x00, 0x04, 0x3C, 0x00, 0xF8, 0x06, 0x3C, 0x01, 0xFD, 0xC2, 0x78, 0x03, + 0xC7, 0xC3, 0x78, 0x07, 0x07, 0x81, 0xF0, 0x0E, 0x03, 0x81, 0xF0, 0x0E, + 0x03, 0x81, 0xF0, 0x1C, 0x07, 0x81, 0xF0, 0x1C, 0x07, 0x01, 0xF0, 0x38, + 0x07, 0x01, 0xF0, 0x38, 0x07, 0x03, 0xF0, 0x38, 0x0F, 0x02, 0xF0, 0x38, + 0x0E, 0x02, 0xF0, 0x38, 0x1E, 0x04, 0x78, 0x38, 0x1E, 0x0C, 0x78, 0x1C, + 0x6E, 0x18, 0x38, 0x1F, 0xC7, 0xF0, 0x3C, 0x0F, 0x03, 0xE0, 0x1E, 0x00, + 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x07, 0xC0, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x60, 0x00, 0xFC, 0x03, 0xE0, 0x00, 0x3F, + 0xFF, 0x80, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, + 0x80, 0x00, 0x00, 0x03, 0x80, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x07, + 0xC0, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x0D, + 0xF0, 0x00, 0x00, 0x0D, 0xF0, 0x00, 0x00, 0x18, 0xF0, 0x00, 0x00, 0x18, + 0xF8, 0x00, 0x00, 0x38, 0x78, 0x00, 0x00, 0x30, 0x7C, 0x00, 0x00, 0x30, + 0x7C, 0x00, 0x00, 0x60, 0x3E, 0x00, 0x00, 0x60, 0x3E, 0x00, 0x00, 0xE0, + 0x1E, 0x00, 0x00, 0xC0, 0x1F, 0x00, 0x00, 0xC0, 0x1F, 0x00, 0x01, 0x80, + 0x0F, 0x80, 0x01, 0xFF, 0xFF, 0x80, 0x03, 0xFF, 0xFF, 0xC0, 0x03, 0x00, + 0x07, 0xC0, 0x07, 0x00, 0x07, 0xC0, 0x06, 0x00, 0x03, 0xE0, 0x06, 0x00, + 0x03, 0xE0, 0x0E, 0x00, 0x01, 0xF0, 0x0C, 0x00, 0x01, 0xF0, 0x1C, 0x00, + 0x01, 0xF8, 0x3C, 0x00, 0x01, 0xF8, 0x7E, 0x00, 0x01, 0xFC, 0xFF, 0x80, + 0x0F, 0xFF, 0xFF, 0xFF, 0xE0, 0x03, 0xFF, 0xFF, 0x80, 0x1F, 0x01, 0xF8, + 0x03, 0xE0, 0x0F, 0x80, 0x7C, 0x00, 0xF8, 0x0F, 0x80, 0x1F, 0x81, 0xF0, + 0x01, 0xF0, 0x3E, 0x00, 0x3E, 0x07, 0xC0, 0x07, 0xC0, 0xF8, 0x00, 0xF8, + 0x1F, 0x00, 0x1F, 0x03, 0xE0, 0x07, 0xC0, 0x7C, 0x01, 0xF0, 0x0F, 0x80, + 0xFC, 0x01, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0xC0, 0x07, 0xC0, 0x7F, 0x00, + 0xF8, 0x01, 0xF0, 0x1F, 0x00, 0x1F, 0x03, 0xE0, 0x03, 0xE0, 0x7C, 0x00, + 0x3E, 0x0F, 0x80, 0x07, 0xC1, 0xF0, 0x00, 0xF8, 0x3E, 0x00, 0x1F, 0x07, + 0xC0, 0x03, 0xE0, 0xF8, 0x00, 0xF8, 0x1F, 0x00, 0x1F, 0x03, 0xE0, 0x07, + 0xC0, 0x7C, 0x07, 0xF0, 0x1F, 0xFF, 0xFC, 0x3F, 0xFF, 0xFC, 0x00, 0x00, + 0x1F, 0xF0, 0x20, 0x07, 0xFF, 0xEE, 0x01, 0xF8, 0x1F, 0xE0, 0x3E, 0x00, + 0x7E, 0x07, 0x80, 0x01, 0xE0, 0xF0, 0x00, 0x1E, 0x1F, 0x00, 0x00, 0xE3, + 0xE0, 0x00, 0x06, 0x3C, 0x00, 0x00, 0x67, 0xC0, 0x00, 0x02, 0x7C, 0x00, + 0x00, 0x27, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x80, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x01, 0xF0, 0x00, + 0x02, 0x0F, 0x80, 0x00, 0xE0, 0x7E, 0x00, 0x1C, 0x03, 0xF8, 0x0F, 0x00, + 0x0F, 0xFF, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0xFF, 0xFF, 0xC0, 0x00, 0x7F, + 0xFF, 0xF8, 0x00, 0x3E, 0x03, 0xFC, 0x00, 0x7C, 0x00, 0xFC, 0x00, 0xF8, + 0x00, 0x7E, 0x01, 0xF0, 0x00, 0x7E, 0x03, 0xE0, 0x00, 0x7C, 0x07, 0xC0, + 0x00, 0x7C, 0x0F, 0x80, 0x00, 0xF8, 0x1F, 0x00, 0x00, 0xF8, 0x3E, 0x00, + 0x01, 0xF0, 0x7C, 0x00, 0x03, 0xF0, 0xF8, 0x00, 0x03, 0xE1, 0xF0, 0x00, + 0x07, 0xC3, 0xE0, 0x00, 0x0F, 0x87, 0xC0, 0x00, 0x1F, 0x0F, 0x80, 0x00, + 0x3E, 0x1F, 0x00, 0x00, 0x7C, 0x3E, 0x00, 0x00, 0xF8, 0x7C, 0x00, 0x01, + 0xF0, 0xF8, 0x00, 0x07, 0xC1, 0xF0, 0x00, 0x0F, 0x83, 0xE0, 0x00, 0x1E, + 0x07, 0xC0, 0x00, 0x7C, 0x0F, 0x80, 0x01, 0xF0, 0x1F, 0x00, 0x03, 0xE0, + 0x3E, 0x00, 0x1F, 0x80, 0x7C, 0x00, 0x7C, 0x00, 0xF8, 0x0F, 0xF0, 0x07, + 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xF0, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0x07, + 0xFF, 0xFF, 0xE0, 0x7C, 0x00, 0x1C, 0x0F, 0x80, 0x01, 0x81, 0xF0, 0x00, + 0x30, 0x3E, 0x00, 0x02, 0x07, 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x20, 0x0F, 0x80, 0x04, + 0x01, 0xF0, 0x01, 0x80, 0x3E, 0x00, 0x70, 0x07, 0xFF, 0xFE, 0x00, 0xFF, + 0xFF, 0xC0, 0x1F, 0x00, 0x38, 0x03, 0xE0, 0x03, 0x00, 0x7C, 0x00, 0x20, + 0x0F, 0x80, 0x04, 0x01, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x07, 0xC0, + 0x00, 0x00, 0xF8, 0x00, 0x03, 0x1F, 0x00, 0x00, 0x43, 0xE0, 0x00, 0x18, + 0x7C, 0x00, 0x07, 0x0F, 0x80, 0x01, 0xC1, 0xF0, 0x00, 0xF8, 0x7F, 0xFF, + 0xFF, 0x3F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0x1F, + 0x00, 0x07, 0x1F, 0x00, 0x03, 0x1F, 0x00, 0x03, 0x1F, 0x00, 0x01, 0x1F, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, + 0x00, 0x08, 0x1F, 0x00, 0x08, 0x1F, 0x00, 0x18, 0x1F, 0x00, 0x38, 0x1F, + 0xFF, 0xF8, 0x1F, 0xFF, 0xF8, 0x1F, 0x00, 0x38, 0x1F, 0x00, 0x18, 0x1F, + 0x00, 0x08, 0x1F, 0x00, 0x08, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x3F, 0x80, 0x00, 0xFF, + 0xF0, 0x00, 0x00, 0x0F, 0xF0, 0x08, 0x00, 0xFF, 0xFE, 0x70, 0x07, 0xE0, + 0x1F, 0xE0, 0x1F, 0x00, 0x0F, 0xC0, 0x78, 0x00, 0x07, 0x81, 0xE0, 0x00, + 0x07, 0x07, 0xC0, 0x00, 0x0E, 0x1F, 0x00, 0x00, 0x0C, 0x3E, 0x00, 0x00, + 0x08, 0xF8, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, + 0x7C, 0x00, 0x03, 0xFF, 0xF8, 0x00, 0x01, 0xFD, 0xF0, 0x00, 0x01, 0xF3, + 0xE0, 0x00, 0x03, 0xE7, 0xC0, 0x00, 0x07, 0xCF, 0x80, 0x00, 0x0F, 0x8F, + 0x80, 0x00, 0x1F, 0x1F, 0x00, 0x00, 0x3E, 0x3E, 0x00, 0x00, 0x7C, 0x3E, + 0x00, 0x00, 0xF8, 0x7C, 0x00, 0x01, 0xF0, 0x7C, 0x00, 0x03, 0xE0, 0xFC, + 0x00, 0x07, 0xC0, 0xFC, 0x00, 0x0F, 0x80, 0x7C, 0x00, 0x3F, 0x00, 0x7F, + 0x01, 0xFC, 0x00, 0x3F, 0xFF, 0xC0, 0x00, 0x0F, 0xF8, 0x00, 0xFF, 0xE0, + 0x1F, 0xFC, 0xFE, 0x00, 0x1F, 0xC1, 0xF0, 0x00, 0x3E, 0x07, 0xC0, 0x00, + 0xF8, 0x1F, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0x3E, + 0x07, 0xC0, 0x00, 0xF8, 0x1F, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x0F, 0x81, + 0xF0, 0x00, 0x3E, 0x07, 0xC0, 0x00, 0xF8, 0x1F, 0x00, 0x03, 0xE0, 0x7C, + 0x00, 0x0F, 0x81, 0xFF, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xF8, 0x1F, 0x00, + 0x03, 0xE0, 0x7C, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0x3E, 0x07, 0xC0, 0x00, + 0xF8, 0x1F, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0x3E, + 0x07, 0xC0, 0x00, 0xF8, 0x1F, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x0F, 0x81, + 0xF0, 0x00, 0x3E, 0x07, 0xC0, 0x00, 0xF8, 0x1F, 0x00, 0x03, 0xE0, 0xFE, + 0x00, 0x1F, 0xCF, 0xFE, 0x01, 0xFF, 0xC0, 0xFF, 0xF8, 0xFE, 0x03, 0xE0, + 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, + 0xE0, 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, + 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, + 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x0F, 0xE3, 0xFF, 0xE0, 0x0F, 0xFF, + 0x80, 0xFE, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, + 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, + 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x7C, + 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, + 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3C, 0x0E, 0x1E, 0x0F, 0x8F, 0x07, + 0xCF, 0x01, 0xFF, 0x00, 0x7E, 0x00, 0xFF, 0xF8, 0x3F, 0xFC, 0x3F, 0xC0, + 0x07, 0xE0, 0x0F, 0x80, 0x07, 0x80, 0x0F, 0x80, 0x07, 0x00, 0x0F, 0x80, + 0x0E, 0x00, 0x0F, 0x80, 0x1C, 0x00, 0x0F, 0x80, 0x38, 0x00, 0x0F, 0x80, + 0x70, 0x00, 0x0F, 0x80, 0xE0, 0x00, 0x0F, 0x81, 0xC0, 0x00, 0x0F, 0x83, + 0x80, 0x00, 0x0F, 0x87, 0x00, 0x00, 0x0F, 0x9E, 0x00, 0x00, 0x0F, 0xBC, + 0x00, 0x00, 0x0F, 0xFE, 0x00, 0x00, 0x0F, 0xFF, 0x00, 0x00, 0x0F, 0xDF, + 0x80, 0x00, 0x0F, 0x8F, 0xC0, 0x00, 0x0F, 0x87, 0xE0, 0x00, 0x0F, 0x83, + 0xF0, 0x00, 0x0F, 0x81, 0xF8, 0x00, 0x0F, 0x80, 0xFC, 0x00, 0x0F, 0x80, + 0x7E, 0x00, 0x0F, 0x80, 0x3F, 0x00, 0x0F, 0x80, 0x3F, 0x80, 0x0F, 0x80, + 0x1F, 0x80, 0x0F, 0x80, 0x0F, 0xC0, 0x0F, 0x80, 0x07, 0xE0, 0x0F, 0x80, + 0x07, 0xF0, 0x1F, 0xC0, 0x07, 0xFC, 0xFF, 0xF8, 0x3F, 0xFF, 0xFF, 0xF0, + 0x00, 0x0F, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x7C, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, + 0x00, 0x7C, 0x00, 0x01, 0x1F, 0x00, 0x00, 0xC7, 0xC0, 0x00, 0x21, 0xF0, + 0x00, 0x18, 0x7C, 0x00, 0x0E, 0x1F, 0x00, 0x1F, 0x8F, 0xFF, 0xFF, 0xCF, + 0xFF, 0xFF, 0xF0, 0xFF, 0x80, 0x00, 0x03, 0xFE, 0x7F, 0x80, 0x00, 0x07, + 0xF0, 0x3F, 0x00, 0x00, 0x1F, 0xC0, 0x7E, 0x00, 0x00, 0x3F, 0x80, 0xFE, + 0x00, 0x00, 0xFF, 0x01, 0xFC, 0x00, 0x01, 0xBE, 0x03, 0x7C, 0x00, 0x03, + 0x7C, 0x06, 0xF8, 0x00, 0x0E, 0xF8, 0x0D, 0xF8, 0x00, 0x19, 0xF0, 0x19, + 0xF0, 0x00, 0x73, 0xE0, 0x33, 0xF0, 0x00, 0xC7, 0xC0, 0x63, 0xE0, 0x03, + 0x8F, 0x80, 0xC7, 0xE0, 0x06, 0x1F, 0x01, 0x87, 0xC0, 0x1C, 0x3E, 0x03, + 0x0F, 0xC0, 0x30, 0x7C, 0x06, 0x0F, 0x80, 0x60, 0xF8, 0x0C, 0x1F, 0x81, + 0x81, 0xF0, 0x18, 0x1F, 0x03, 0x03, 0xE0, 0x30, 0x3F, 0x0C, 0x07, 0xC0, + 0x60, 0x3E, 0x18, 0x0F, 0x80, 0xC0, 0x7C, 0x70, 0x1F, 0x01, 0x80, 0x7C, + 0xC0, 0x3E, 0x03, 0x00, 0xFB, 0x80, 0x7C, 0x06, 0x00, 0xFE, 0x00, 0xF8, + 0x0C, 0x01, 0xFC, 0x01, 0xF0, 0x18, 0x03, 0xF0, 0x03, 0xE0, 0x30, 0x03, + 0xE0, 0x07, 0xC0, 0x60, 0x07, 0x80, 0x0F, 0x81, 0xE0, 0x07, 0x00, 0x1F, + 0x07, 0xE0, 0x0C, 0x00, 0xFF, 0x3F, 0xF0, 0x08, 0x07, 0xFF, 0x80, 0xFF, + 0x00, 0x03, 0xFF, 0x3F, 0x80, 0x00, 0xFC, 0x1F, 0xC0, 0x00, 0x78, 0x0F, + 0xC0, 0x00, 0x30, 0x0F, 0xE0, 0x00, 0x30, 0x0F, 0xF0, 0x00, 0x30, 0x0D, + 0xF8, 0x00, 0x30, 0x0D, 0xFC, 0x00, 0x30, 0x0C, 0xFC, 0x00, 0x30, 0x0C, + 0x7E, 0x00, 0x30, 0x0C, 0x3F, 0x00, 0x30, 0x0C, 0x1F, 0x80, 0x30, 0x0C, + 0x1F, 0xC0, 0x30, 0x0C, 0x0F, 0xE0, 0x30, 0x0C, 0x07, 0xE0, 0x30, 0x0C, + 0x03, 0xF0, 0x30, 0x0C, 0x01, 0xF8, 0x30, 0x0C, 0x01, 0xFC, 0x30, 0x0C, + 0x00, 0xFE, 0x30, 0x0C, 0x00, 0x7E, 0x30, 0x0C, 0x00, 0x3F, 0x30, 0x0C, + 0x00, 0x1F, 0xB0, 0x0C, 0x00, 0x0F, 0xF0, 0x0C, 0x00, 0x0F, 0xF0, 0x0C, + 0x00, 0x07, 0xF0, 0x0C, 0x00, 0x03, 0xF0, 0x0C, 0x00, 0x01, 0xF0, 0x0C, + 0x00, 0x00, 0xF0, 0x1E, 0x00, 0x00, 0xF0, 0x3F, 0x00, 0x00, 0x70, 0xFF, + 0xC0, 0x00, 0x30, 0x00, 0x00, 0x00, 0x10, 0x00, 0x1F, 0xE0, 0x00, 0x03, + 0xFF, 0xF0, 0x00, 0x1F, 0x03, 0xE0, 0x01, 0xF0, 0x03, 0xE0, 0x0F, 0x80, + 0x07, 0xC0, 0x7C, 0x00, 0x0F, 0x01, 0xE0, 0x00, 0x1E, 0x0F, 0x80, 0x00, + 0x7C, 0x3C, 0x00, 0x00, 0xF1, 0xF0, 0x00, 0x03, 0xE7, 0xC0, 0x00, 0x0F, + 0x9E, 0x00, 0x00, 0x1E, 0xF8, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0x01, 0xFF, + 0x80, 0x00, 0x07, 0xFE, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x7F, 0xE0, + 0x00, 0x01, 0xFF, 0x80, 0x00, 0x07, 0xFE, 0x00, 0x00, 0x1F, 0xF8, 0x00, + 0x00, 0x7D, 0xF0, 0x00, 0x03, 0xE7, 0xC0, 0x00, 0x0F, 0x9F, 0x00, 0x00, + 0x3E, 0x3C, 0x00, 0x00, 0xF0, 0xF8, 0x00, 0x07, 0xC1, 0xE0, 0x00, 0x1E, + 0x07, 0xC0, 0x00, 0xF8, 0x0F, 0x80, 0x07, 0xC0, 0x1F, 0x00, 0x3E, 0x00, + 0x1F, 0x03, 0xE0, 0x00, 0x3F, 0xFF, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0xFF, + 0xFF, 0x00, 0x7F, 0xFF, 0x80, 0x7C, 0x1F, 0xC0, 0xF8, 0x07, 0xC1, 0xF0, + 0x07, 0xC3, 0xE0, 0x0F, 0x87, 0xC0, 0x0F, 0x8F, 0x80, 0x1F, 0x1F, 0x00, + 0x3E, 0x3E, 0x00, 0x7C, 0x7C, 0x00, 0xF8, 0xF8, 0x01, 0xF1, 0xF0, 0x07, + 0xC3, 0xE0, 0x0F, 0x87, 0xC0, 0x3E, 0x0F, 0x81, 0xF8, 0x1F, 0xFF, 0xC0, + 0x3F, 0xFE, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, + 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x07, 0xF0, + 0x00, 0x3F, 0xFC, 0x00, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFF, 0xF8, + 0x00, 0x07, 0xC0, 0xF8, 0x00, 0x3E, 0x00, 0x7C, 0x00, 0xF8, 0x00, 0x7C, + 0x03, 0xE0, 0x00, 0x7C, 0x07, 0x80, 0x00, 0x78, 0x1F, 0x00, 0x00, 0xF8, + 0x3C, 0x00, 0x00, 0xF0, 0xF8, 0x00, 0x01, 0xF1, 0xF0, 0x00, 0x03, 0xE3, + 0xC0, 0x00, 0x03, 0xCF, 0x80, 0x00, 0x07, 0xDF, 0x00, 0x00, 0x0F, 0xBE, + 0x00, 0x00, 0x1F, 0x7C, 0x00, 0x00, 0x3E, 0xF8, 0x00, 0x00, 0x7D, 0xF0, + 0x00, 0x00, 0xFB, 0xE0, 0x00, 0x01, 0xF7, 0xC0, 0x00, 0x03, 0xEF, 0x80, + 0x00, 0x07, 0xCF, 0x00, 0x00, 0x1F, 0x1F, 0x00, 0x00, 0x3E, 0x3E, 0x00, + 0x00, 0x7C, 0x3C, 0x00, 0x01, 0xF0, 0x7C, 0x00, 0x03, 0xE0, 0x78, 0x00, + 0x0F, 0x80, 0x78, 0x00, 0x1E, 0x00, 0x78, 0x00, 0x78, 0x00, 0x7C, 0x03, + 0xE0, 0x00, 0x3F, 0x3F, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x03, 0xF8, + 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x1F, + 0x03, 0xF8, 0x01, 0xF0, 0x0F, 0x80, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x03, + 0xE0, 0x1F, 0x00, 0x3E, 0x01, 0xF0, 0x03, 0xE0, 0x1F, 0x00, 0x3E, 0x01, + 0xF0, 0x03, 0xE0, 0x1F, 0x00, 0x3E, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, + 0x7C, 0x01, 0xF0, 0x0F, 0x80, 0x1F, 0x07, 0xF0, 0x01, 0xFF, 0xFC, 0x00, + 0x1F, 0xFE, 0x00, 0x01, 0xF1, 0xF0, 0x00, 0x1F, 0x1F, 0x80, 0x01, 0xF0, + 0xF8, 0x00, 0x1F, 0x07, 0xC0, 0x01, 0xF0, 0x3E, 0x00, 0x1F, 0x03, 0xF0, + 0x01, 0xF0, 0x1F, 0x80, 0x1F, 0x00, 0xFC, 0x01, 0xF0, 0x07, 0xC0, 0x1F, + 0x00, 0x7E, 0x01, 0xF0, 0x03, 0xF0, 0x1F, 0x00, 0x1F, 0x83, 0xF8, 0x00, + 0xFC, 0xFF, 0xF0, 0x0F, 0xF0, 0x03, 0xF0, 0x20, 0x7F, 0xF3, 0x07, 0xC1, + 0xF8, 0x78, 0x03, 0xC3, 0x80, 0x0E, 0x3C, 0x00, 0x31, 0xE0, 0x01, 0xCF, + 0x00, 0x06, 0x7C, 0x00, 0x33, 0xE0, 0x01, 0x9F, 0x80, 0x00, 0x7E, 0x00, + 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xE0, 0x00, 0xFF, 0xC0, 0x01, + 0xFF, 0x00, 0x07, 0xFE, 0x00, 0x0F, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0x7F, + 0x00, 0x01, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0xFE, 0x00, + 0x07, 0xF8, 0x00, 0x3F, 0xC0, 0x01, 0xEF, 0x00, 0x1F, 0x3C, 0x01, 0xF1, + 0xF8, 0x1F, 0x0C, 0xFF, 0xF0, 0x40, 0xFE, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xC0, 0x7C, 0x07, 0xF0, 0x0F, 0x80, 0x3C, 0x01, 0xF0, + 0x07, 0x00, 0x3E, 0x00, 0x60, 0x07, 0xC0, 0x08, 0x00, 0xF8, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, + 0x00, 0x01, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x07, + 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x7F, 0xFC, 0x00, 0xFF, 0xF8, 0x03, 0xFF, 0x3F, 0xE0, 0x00, + 0xFC, 0x0F, 0x80, 0x00, 0x78, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x20, 0x07, 0xC0, 0x00, + 0x60, 0x07, 0xC0, 0x00, 0x60, 0x03, 0xE0, 0x00, 0xC0, 0x03, 0xF0, 0x01, + 0xC0, 0x01, 0xFC, 0x07, 0x80, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x0F, 0xF8, + 0x00, 0xFF, 0xF8, 0x01, 0xFF, 0x3F, 0xC0, 0x00, 0x7E, 0x0F, 0x80, 0x00, + 0x3C, 0x0F, 0xC0, 0x00, 0x38, 0x07, 0xC0, 0x00, 0x38, 0x07, 0xC0, 0x00, + 0x30, 0x03, 0xE0, 0x00, 0x70, 0x03, 0xE0, 0x00, 0x60, 0x01, 0xF0, 0x00, + 0x60, 0x01, 0xF0, 0x00, 0xE0, 0x01, 0xF8, 0x00, 0xC0, 0x00, 0xF8, 0x01, + 0xC0, 0x00, 0xF8, 0x01, 0x80, 0x00, 0x7C, 0x01, 0x80, 0x00, 0x7C, 0x03, + 0x80, 0x00, 0x3E, 0x03, 0x00, 0x00, 0x3E, 0x07, 0x00, 0x00, 0x1F, 0x06, + 0x00, 0x00, 0x1F, 0x06, 0x00, 0x00, 0x1F, 0x8E, 0x00, 0x00, 0x0F, 0x8C, + 0x00, 0x00, 0x0F, 0x9C, 0x00, 0x00, 0x07, 0xD8, 0x00, 0x00, 0x07, 0xD8, + 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x00, 0xE0, + 0x00, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x00, 0x40, 0x00, 0xFF, 0xF1, 0xFF, + 0xF0, 0x1F, 0xF3, 0xF8, 0x07, 0xF8, 0x00, 0x7C, 0x1F, 0x80, 0x3F, 0x00, + 0x03, 0x80, 0xF8, 0x01, 0xF0, 0x00, 0x30, 0x0F, 0x80, 0x1F, 0x00, 0x03, + 0x00, 0x7C, 0x00, 0xF8, 0x00, 0x30, 0x07, 0xC0, 0x0F, 0x80, 0x06, 0x00, + 0x3E, 0x00, 0x7C, 0x00, 0x60, 0x03, 0xE0, 0x07, 0xC0, 0x06, 0x00, 0x3E, + 0x00, 0x7C, 0x00, 0xC0, 0x01, 0xF0, 0x07, 0xE0, 0x0C, 0x00, 0x1F, 0x00, + 0xFE, 0x01, 0xC0, 0x01, 0xF0, 0x0D, 0xE0, 0x18, 0x00, 0x0F, 0x80, 0xDF, + 0x01, 0x80, 0x00, 0xF8, 0x19, 0xF0, 0x30, 0x00, 0x07, 0xC1, 0x8F, 0x83, + 0x00, 0x00, 0x7C, 0x38, 0xF8, 0x30, 0x00, 0x07, 0xC3, 0x0F, 0x86, 0x00, + 0x00, 0x3E, 0x30, 0x7C, 0x60, 0x00, 0x03, 0xE7, 0x07, 0xCE, 0x00, 0x00, + 0x3E, 0x60, 0x3E, 0xC0, 0x00, 0x01, 0xF6, 0x03, 0xEC, 0x00, 0x00, 0x1F, + 0xE0, 0x3F, 0xC0, 0x00, 0x01, 0xFC, 0x01, 0xF8, 0x00, 0x00, 0x0F, 0xC0, + 0x1F, 0x80, 0x00, 0x00, 0xF8, 0x01, 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x0F, + 0x00, 0x00, 0x00, 0x78, 0x00, 0xF0, 0x00, 0x00, 0x07, 0x00, 0x07, 0x00, + 0x00, 0x00, 0x70, 0x00, 0x60, 0x00, 0x00, 0x03, 0x00, 0x06, 0x00, 0x00, + 0x00, 0x20, 0x00, 0x20, 0x00, 0x7F, 0xFE, 0x03, 0xFF, 0x8F, 0xF8, 0x00, + 0x7E, 0x01, 0xFC, 0x00, 0x1C, 0x00, 0x7E, 0x00, 0x1C, 0x00, 0x1F, 0x00, + 0x0C, 0x00, 0x07, 0xC0, 0x0E, 0x00, 0x03, 0xF0, 0x0E, 0x00, 0x00, 0xF8, + 0x0E, 0x00, 0x00, 0x3E, 0x06, 0x00, 0x00, 0x1F, 0x86, 0x00, 0x00, 0x07, + 0xC7, 0x00, 0x00, 0x01, 0xF7, 0x00, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x00, + 0x3F, 0x00, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x03, 0x9F, 0x00, 0x00, + 0x01, 0x8F, 0xC0, 0x00, 0x01, 0x83, 0xF0, 0x00, 0x01, 0xC0, 0xF8, 0x00, + 0x01, 0xC0, 0x7E, 0x00, 0x01, 0xC0, 0x1F, 0x80, 0x01, 0xC0, 0x07, 0xC0, + 0x00, 0xC0, 0x03, 0xF0, 0x00, 0xE0, 0x00, 0xFC, 0x00, 0xE0, 0x00, 0x7F, + 0x00, 0xF0, 0x00, 0x1F, 0x80, 0xFC, 0x00, 0x1F, 0xF3, 0xFF, 0x80, 0x7F, + 0xFE, 0xFF, 0xF8, 0x03, 0xFF, 0x3F, 0xE0, 0x00, 0x7C, 0x1F, 0xC0, 0x00, + 0x78, 0x0F, 0xC0, 0x00, 0x70, 0x07, 0xE0, 0x00, 0x60, 0x03, 0xF0, 0x00, + 0xE0, 0x01, 0xF0, 0x01, 0xC0, 0x01, 0xF8, 0x01, 0x80, 0x00, 0xFC, 0x03, + 0x80, 0x00, 0x7C, 0x07, 0x00, 0x00, 0x7E, 0x06, 0x00, 0x00, 0x3F, 0x0E, + 0x00, 0x00, 0x1F, 0x1C, 0x00, 0x00, 0x1F, 0x98, 0x00, 0x00, 0x0F, 0xF8, + 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x07, 0xF0, + 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x3F, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0xF8, + 0xF0, 0x00, 0x3E, 0x38, 0x00, 0x0F, 0x86, 0x00, 0x03, 0xF0, 0xC0, 0x00, + 0x7C, 0x10, 0x00, 0x1F, 0x02, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF8, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xFC, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF8, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x7E, + 0x00, 0x01, 0x0F, 0x80, 0x00, 0x63, 0xF0, 0x00, 0x0C, 0xFC, 0x00, 0x03, + 0xBF, 0x00, 0x00, 0xE7, 0xC0, 0x00, 0x7D, 0xFF, 0xFF, 0xFF, 0xBF, 0xFF, + 0xFF, 0xF0, 0xFF, 0xF0, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, + 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, + 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, + 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0F, 0x07, 0xFC, 0xE0, 0x01, 0xC0, + 0x07, 0x00, 0x1C, 0x00, 0x38, 0x00, 0xE0, 0x03, 0x80, 0x07, 0x00, 0x1C, + 0x00, 0x70, 0x00, 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x1C, 0x00, 0x70, 0x01, + 0xC0, 0x03, 0x80, 0x0E, 0x00, 0x38, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, + 0x0E, 0x00, 0x38, 0x00, 0xE0, 0x01, 0xC0, 0x07, 0x00, 0x1E, 0x00, 0x38, + 0x00, 0xE0, 0x03, 0xC0, 0x07, 0xFF, 0x83, 0xC0, 0xE0, 0x70, 0x38, 0x1C, + 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, + 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, + 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x3F, 0xFC, + 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0x80, 0x03, 0xDC, + 0x00, 0x39, 0xC0, 0x07, 0x9E, 0x00, 0x70, 0xE0, 0x0F, 0x0F, 0x00, 0xE0, + 0x70, 0x1E, 0x07, 0x81, 0xC0, 0x38, 0x3C, 0x03, 0xC3, 0x80, 0x1C, 0x78, + 0x01, 0xE7, 0x00, 0x0E, 0xF0, 0x00, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xE0, 0x3C, 0x0F, 0x81, 0xF0, 0x1E, 0x03, 0xC0, 0x38, 0x07, 0x03, + 0xF0, 0x07, 0x0E, 0x03, 0x81, 0xC1, 0xE0, 0x30, 0x78, 0x0E, 0x1E, 0x03, + 0x83, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x3E, 0x00, 0x73, 0x80, 0x70, 0xE0, + 0x70, 0x38, 0x38, 0x0E, 0x1C, 0x03, 0x8F, 0x00, 0xE3, 0xC0, 0x38, 0xF0, + 0x0E, 0x3E, 0x07, 0x8F, 0xC3, 0xE1, 0xFF, 0x3F, 0x1F, 0x07, 0x80, 0x06, + 0x00, 0x01, 0xF0, 0x00, 0x3F, 0x80, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, + 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, + 0x00, 0x07, 0x80, 0x00, 0x3C, 0x7E, 0x01, 0xEF, 0xFC, 0x0F, 0xC3, 0xF0, + 0x7C, 0x07, 0x83, 0xC0, 0x3E, 0x1E, 0x00, 0xF0, 0xF0, 0x07, 0xC7, 0x80, + 0x1E, 0x3C, 0x00, 0xF1, 0xE0, 0x07, 0x8F, 0x00, 0x3C, 0x78, 0x01, 0xE3, + 0xC0, 0x0F, 0x1E, 0x00, 0x70, 0xF0, 0x03, 0x87, 0x80, 0x38, 0x3C, 0x01, + 0xC1, 0xE0, 0x1C, 0x0F, 0xC1, 0xC0, 0x1F, 0xFC, 0x00, 0x3F, 0x80, 0x01, + 0xFC, 0x00, 0xFF, 0xE0, 0x38, 0x3E, 0x0E, 0x03, 0xE3, 0x80, 0x7C, 0xE0, + 0x07, 0x18, 0x00, 0x03, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x80, + 0x00, 0x70, 0x00, 0x0E, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x1B, 0xC0, + 0x02, 0x7C, 0x01, 0x87, 0xE0, 0x60, 0x7F, 0xF8, 0x07, 0xFE, 0x00, 0x3F, + 0x00, 0x00, 0x00, 0x60, 0x00, 0x0F, 0x80, 0x00, 0xFE, 0x00, 0x00, 0x78, + 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, + 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x7C, 0x78, 0x07, 0xFD, + 0xE0, 0x3C, 0x3F, 0x81, 0xC0, 0x3E, 0x0E, 0x00, 0xF8, 0x38, 0x01, 0xE1, + 0xE0, 0x07, 0x87, 0x00, 0x1E, 0x3C, 0x00, 0x78, 0xF0, 0x01, 0xE3, 0xC0, + 0x07, 0x8F, 0x00, 0x1E, 0x3C, 0x00, 0x78, 0xF0, 0x01, 0xE3, 0xE0, 0x07, + 0x87, 0x80, 0x1E, 0x1F, 0x00, 0x78, 0x3E, 0x03, 0xE0, 0xFC, 0x1F, 0xF0, + 0xFF, 0xDF, 0x00, 0xFC, 0x60, 0x03, 0xF8, 0x03, 0xFF, 0x01, 0xC1, 0xE0, + 0xC0, 0x3C, 0x70, 0x0F, 0x98, 0x01, 0xE7, 0xFF, 0xFB, 0xFF, 0xFE, 0xE0, + 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xF0, 0x00, 0x3C, 0x00, + 0x1F, 0x00, 0x05, 0xE0, 0x02, 0x7C, 0x01, 0x8F, 0xC1, 0xC3, 0xFF, 0xE0, + 0x7F, 0xF0, 0x07, 0xF0, 0x00, 0x00, 0x7E, 0x00, 0xFF, 0xC0, 0xE3, 0xE0, + 0x60, 0x70, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x1E, 0x00, 0x0F, 0x00, + 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x07, 0xFF, 0x83, 0xFF, 0xC0, 0x3C, + 0x00, 0x1E, 0x00, 0x0F, 0x00, 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x00, + 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x0F, 0x00, 0x07, 0x80, + 0x03, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x3F, + 0x00, 0xFF, 0xF0, 0x00, 0x01, 0xF8, 0x00, 0x3F, 0xF0, 0x03, 0xC7, 0xFE, + 0x3C, 0x1F, 0xF1, 0xC0, 0x70, 0x1E, 0x03, 0xC0, 0xF0, 0x0E, 0x07, 0x80, + 0x70, 0x3C, 0x03, 0x81, 0xE0, 0x1C, 0x07, 0x80, 0xC0, 0x3E, 0x0E, 0x00, + 0x78, 0xE0, 0x01, 0xFC, 0x00, 0x18, 0x00, 0x01, 0x80, 0x00, 0x18, 0x00, + 0x01, 0xE0, 0x00, 0x0F, 0xFF, 0xC0, 0x3F, 0xFF, 0x80, 0xFF, 0xFE, 0x0C, + 0x00, 0x38, 0xC0, 0x00, 0x4C, 0x00, 0x02, 0x60, 0x00, 0x17, 0x00, 0x01, + 0x38, 0x00, 0x09, 0xE0, 0x00, 0x87, 0xC0, 0x38, 0x1F, 0xFF, 0x00, 0x3F, + 0xC0, 0x00, 0x06, 0x00, 0x00, 0xF8, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0x80, + 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, + 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x87, 0xE0, 0x1E, + 0x7F, 0xC0, 0x7B, 0x0F, 0x81, 0xF8, 0x1E, 0x07, 0x80, 0x3C, 0x1E, 0x00, + 0xF0, 0x78, 0x03, 0xC1, 0xE0, 0x0F, 0x07, 0x80, 0x3C, 0x1E, 0x00, 0xF0, + 0x78, 0x03, 0xC1, 0xE0, 0x0F, 0x07, 0x80, 0x3C, 0x1E, 0x00, 0xF0, 0x78, + 0x03, 0xC1, 0xE0, 0x0F, 0x07, 0x80, 0x3C, 0x1E, 0x00, 0xF0, 0x78, 0x03, + 0xC3, 0xF0, 0x1F, 0x9F, 0xF1, 0xFF, 0x0E, 0x03, 0xE0, 0x7C, 0x0F, 0x80, + 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x70, + 0x7E, 0x1F, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, + 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x07, + 0xE7, 0xFF, 0x00, 0xE0, 0x1F, 0x01, 0xF0, 0x1F, 0x00, 0xE0, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x70, 0x3F, 0x07, + 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, + 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, + 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xE0, 0x0E, 0xE0, + 0xEF, 0x1C, 0xFF, 0x87, 0xE0, 0x06, 0x00, 0x00, 0x7C, 0x00, 0x03, 0xF8, + 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x80, + 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x78, 0x00, + 0x00, 0xF0, 0x7F, 0xE1, 0xE0, 0x3E, 0x03, 0xC0, 0x70, 0x07, 0x81, 0x80, + 0x0F, 0x06, 0x00, 0x1E, 0x18, 0x00, 0x3C, 0x60, 0x00, 0x79, 0x80, 0x00, + 0xFF, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xDE, 0x00, 0x07, 0x9E, 0x00, 0x0F, + 0x3E, 0x00, 0x1E, 0x3E, 0x00, 0x3C, 0x3E, 0x00, 0x78, 0x3C, 0x00, 0xF0, + 0x3C, 0x01, 0xE0, 0x7C, 0x03, 0xC0, 0x7C, 0x0F, 0xC0, 0xFE, 0x7F, 0xE3, + 0xFF, 0x03, 0x03, 0xE1, 0xFC, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, + 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, + 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x01, + 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x07, 0xE7, 0xFF, 0x1E, 0x1F, 0x01, + 0xF8, 0x1F, 0xCF, 0xF0, 0xFF, 0x80, 0xFF, 0x0F, 0x70, 0xF8, 0x0F, 0x81, + 0xF8, 0x0F, 0x01, 0xE0, 0x1E, 0x00, 0xF0, 0x3C, 0x03, 0xC0, 0x1E, 0x07, + 0x80, 0x78, 0x03, 0xC0, 0xF0, 0x0F, 0x00, 0x78, 0x1E, 0x01, 0xE0, 0x0F, + 0x03, 0xC0, 0x3C, 0x01, 0xE0, 0x78, 0x07, 0x80, 0x3C, 0x0F, 0x00, 0xF0, + 0x07, 0x81, 0xE0, 0x1E, 0x00, 0xF0, 0x3C, 0x03, 0xC0, 0x1E, 0x07, 0x80, + 0x78, 0x03, 0xC0, 0xF0, 0x0F, 0x00, 0x78, 0x1E, 0x01, 0xE0, 0x0F, 0x03, + 0xC0, 0x3C, 0x01, 0xE0, 0x78, 0x07, 0x80, 0x3C, 0x1F, 0x81, 0xF8, 0x0F, + 0xCF, 0xFC, 0xFF, 0xC7, 0xFE, 0x1E, 0x1F, 0x83, 0xF9, 0xFF, 0x03, 0xFC, + 0x3E, 0x07, 0xC0, 0x7C, 0x1E, 0x00, 0xF0, 0x78, 0x03, 0xC1, 0xE0, 0x0F, + 0x07, 0x80, 0x3C, 0x1E, 0x00, 0xF0, 0x78, 0x03, 0xC1, 0xE0, 0x0F, 0x07, + 0x80, 0x3C, 0x1E, 0x00, 0xF0, 0x78, 0x03, 0xC1, 0xE0, 0x0F, 0x07, 0x80, + 0x3C, 0x1E, 0x00, 0xF0, 0x78, 0x03, 0xC1, 0xE0, 0x0F, 0x0F, 0xC0, 0x7E, + 0x7F, 0xC3, 0xFC, 0x01, 0xFE, 0x00, 0x1F, 0xFE, 0x00, 0xF0, 0x7C, 0x0F, + 0x80, 0xF8, 0x3C, 0x01, 0xF1, 0xE0, 0x03, 0xE7, 0x80, 0x0F, 0xBE, 0x00, + 0x3F, 0xF8, 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0x80, 0x07, 0xFE, 0x00, 0x1F, + 0xF8, 0x00, 0x7F, 0xF0, 0x01, 0xE7, 0xC0, 0x07, 0x9F, 0x80, 0x3E, 0x3E, + 0x00, 0xF0, 0x7C, 0x07, 0x80, 0xF8, 0x3C, 0x01, 0xFF, 0xE0, 0x00, 0xFC, + 0x00, 0x0E, 0x3F, 0x07, 0xF7, 0xFE, 0x07, 0xE0, 0xF8, 0x3E, 0x03, 0xE1, + 0xE0, 0x0F, 0x0F, 0x00, 0x7C, 0x78, 0x03, 0xE3, 0xC0, 0x0F, 0x1E, 0x00, + 0x78, 0xF0, 0x03, 0xC7, 0x80, 0x1E, 0x3C, 0x00, 0xF1, 0xE0, 0x07, 0x8F, + 0x00, 0x38, 0x78, 0x03, 0xC3, 0xC0, 0x1E, 0x1E, 0x00, 0xE0, 0xF8, 0x0E, + 0x07, 0xE0, 0xE0, 0x3D, 0xFE, 0x01, 0xE7, 0xC0, 0x0F, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, + 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x1F, 0x80, 0x03, 0xFF, 0x80, 0x00, 0x01, + 0xF8, 0x20, 0x3F, 0xF3, 0x03, 0xC1, 0xF8, 0x3C, 0x07, 0xC3, 0xC0, 0x1E, + 0x1C, 0x00, 0xF1, 0xE0, 0x07, 0x8E, 0x00, 0x3C, 0xF0, 0x01, 0xE7, 0x80, + 0x0F, 0x3C, 0x00, 0x79, 0xE0, 0x03, 0xCF, 0x00, 0x1E, 0x78, 0x00, 0xF3, + 0xE0, 0x07, 0x9F, 0x00, 0x3C, 0x7C, 0x01, 0xE3, 0xE0, 0x1F, 0x0F, 0xC1, + 0xF8, 0x3F, 0xF3, 0xC0, 0x7E, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, + 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, + 0xC0, 0x00, 0x1E, 0x00, 0x03, 0xF8, 0x00, 0x7F, 0xE0, 0x06, 0x3C, 0xFC, + 0xFE, 0xFA, 0x78, 0xF8, 0x71, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, 0x00, + 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, + 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x01, 0xF8, 0x0F, 0xFC, + 0x00, 0x1F, 0x91, 0x87, 0x98, 0x1D, 0xC0, 0x6E, 0x03, 0x70, 0x0B, 0xC0, + 0x5F, 0x80, 0x7E, 0x01, 0xFC, 0x07, 0xF0, 0x0F, 0xE0, 0x3F, 0x00, 0x7E, + 0x01, 0xF0, 0x07, 0xC0, 0x3E, 0x01, 0xF8, 0x0D, 0xE0, 0xC8, 0xF8, 0x00, + 0x04, 0x00, 0xC0, 0x0C, 0x01, 0xC0, 0x3C, 0x07, 0xFC, 0xFF, 0xC3, 0xC0, + 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, + 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xE2, + 0x1F, 0xC0, 0xF8, 0xFC, 0x0F, 0xE1, 0xF0, 0x0F, 0x83, 0xC0, 0x1E, 0x0F, + 0x00, 0x78, 0x3C, 0x01, 0xE0, 0xF0, 0x07, 0x83, 0xC0, 0x1E, 0x0F, 0x00, + 0x78, 0x3C, 0x01, 0xE0, 0xF0, 0x07, 0x83, 0xC0, 0x1E, 0x0F, 0x00, 0x78, + 0x3C, 0x01, 0xE0, 0xF0, 0x07, 0x83, 0xC0, 0x1E, 0x0F, 0x00, 0x78, 0x3C, + 0x01, 0xE0, 0xF8, 0x0F, 0x81, 0xF0, 0xFF, 0x03, 0xFE, 0x7F, 0x07, 0xE1, + 0xC0, 0xFF, 0x81, 0xFC, 0xFC, 0x01, 0xC1, 0xE0, 0x07, 0x07, 0x80, 0x18, + 0x0F, 0x00, 0x60, 0x3C, 0x01, 0x00, 0x78, 0x0C, 0x01, 0xE0, 0x30, 0x07, + 0x81, 0x80, 0x0F, 0x06, 0x00, 0x3C, 0x10, 0x00, 0x78, 0xC0, 0x01, 0xE3, + 0x00, 0x03, 0x98, 0x00, 0x0F, 0x60, 0x00, 0x3D, 0x00, 0x00, 0x7C, 0x00, + 0x01, 0xF0, 0x00, 0x03, 0x80, 0x00, 0x0E, 0x00, 0x00, 0x30, 0x00, 0x00, + 0x40, 0x00, 0xFF, 0x8F, 0xF8, 0x3F, 0x7E, 0x07, 0xE0, 0x0E, 0x3E, 0x03, + 0xC0, 0x0C, 0x1E, 0x03, 0xE0, 0x0C, 0x1E, 0x01, 0xE0, 0x0C, 0x1E, 0x01, + 0xE0, 0x18, 0x0F, 0x00, 0xF0, 0x18, 0x0F, 0x01, 0xF0, 0x10, 0x07, 0x81, + 0xF0, 0x30, 0x07, 0x81, 0x78, 0x30, 0x07, 0x83, 0x78, 0x60, 0x03, 0xC3, + 0x38, 0x60, 0x03, 0xC6, 0x3C, 0x40, 0x01, 0xC6, 0x3C, 0xC0, 0x01, 0xEC, + 0x1E, 0xC0, 0x01, 0xEC, 0x1F, 0x80, 0x00, 0xF8, 0x0F, 0x80, 0x00, 0xF8, + 0x0F, 0x00, 0x00, 0x70, 0x0F, 0x00, 0x00, 0x70, 0x07, 0x00, 0x00, 0x60, + 0x06, 0x00, 0x00, 0x20, 0x02, 0x00, 0x7F, 0xE7, 0xF0, 0x7E, 0x0F, 0x00, + 0xF8, 0x38, 0x01, 0xE0, 0xC0, 0x07, 0xC6, 0x00, 0x0F, 0x30, 0x00, 0x1E, + 0xC0, 0x00, 0x7E, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x07, 0xC0, + 0x00, 0x3F, 0x00, 0x00, 0xDE, 0x00, 0x06, 0x7C, 0x00, 0x30, 0xF0, 0x01, + 0xC1, 0xE0, 0x06, 0x07, 0xC0, 0x30, 0x0F, 0x01, 0xC0, 0x1E, 0x0F, 0x00, + 0xFC, 0xFE, 0x07, 0xFC, 0xFF, 0xC0, 0xFC, 0xFC, 0x01, 0xE1, 0xE0, 0x03, + 0x07, 0x80, 0x18, 0x0F, 0x00, 0x60, 0x3C, 0x01, 0x80, 0x78, 0x0C, 0x01, + 0xE0, 0x30, 0x03, 0xC0, 0xC0, 0x0F, 0x06, 0x00, 0x3E, 0x18, 0x00, 0x78, + 0x40, 0x01, 0xF3, 0x00, 0x03, 0xCC, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0x80, + 0x00, 0x7C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x06, 0x00, 0x00, + 0x18, 0x00, 0x00, 0x40, 0x00, 0x03, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x60, + 0x00, 0x01, 0x80, 0x00, 0x0C, 0x00, 0x0F, 0xF0, 0x00, 0x7F, 0x80, 0x01, + 0xFC, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7F, 0xFF, 0x9F, 0xFF, 0xE6, 0x00, + 0xF1, 0x00, 0x78, 0x40, 0x3E, 0x00, 0x0F, 0x00, 0x07, 0x80, 0x03, 0xE0, + 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x07, 0x80, 0x03, + 0xE0, 0x01, 0xF0, 0x04, 0x78, 0x01, 0x3E, 0x00, 0xDF, 0x00, 0x37, 0x80, + 0x1F, 0xFF, 0xFE, 0xFF, 0xFF, 0x80, 0x01, 0xE0, 0x78, 0x1C, 0x07, 0x80, + 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, + 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x70, 0x1C, 0x0E, 0x00, 0x70, + 0x07, 0x00, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, + 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x01, 0xC0, + 0x1E, 0x00, 0xE0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xE0, 0x0F, 0x00, 0x70, 0x0F, 0x00, 0xE0, 0x1C, 0x03, + 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, + 0x70, 0x0E, 0x01, 0xC0, 0x1C, 0x01, 0xC0, 0x0E, 0x07, 0x01, 0xC0, 0x70, + 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, + 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x3C, 0x07, 0x03, 0xC0, 0xF0, 0x00, + 0x1F, 0x80, 0x00, 0xFF, 0x80, 0xC7, 0x0F, 0x87, 0xB8, 0x0F, 0xFC, 0x00, + 0x07, 0xC0 }; + +const GFXglyph FreeSerif24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 12, 0, 1 }, // 0x20 ' ' + { 0, 5, 32, 16, 6, -31 }, // 0x21 '!' + { 20, 12, 12, 19, 4, -31 }, // 0x22 '"' + { 38, 23, 31, 23, 0, -30 }, // 0x23 '#' + { 128, 19, 37, 24, 2, -33 }, // 0x24 '$' + { 216, 33, 32, 39, 3, -30 }, // 0x25 '%' + { 348, 32, 33, 37, 2, -31 }, // 0x26 '&' + { 480, 4, 12, 9, 3, -31 }, // 0x27 ''' + { 486, 12, 40, 16, 2, -31 }, // 0x28 '(' + { 546, 12, 40, 16, 2, -30 }, // 0x29 ')' + { 606, 16, 19, 24, 4, -30 }, // 0x2A '*' + { 644, 23, 23, 27, 2, -22 }, // 0x2B '+' + { 711, 6, 11, 12, 2, -4 }, // 0x2C ',' + { 720, 11, 2, 16, 2, -10 }, // 0x2D '-' + { 723, 5, 5, 12, 3, -3 }, // 0x2E '.' + { 727, 14, 32, 14, 0, -30 }, // 0x2F '/' + { 783, 22, 33, 23, 1, -31 }, // 0x30 '0' + { 874, 13, 32, 24, 5, -31 }, // 0x31 '1' + { 926, 21, 31, 23, 1, -30 }, // 0x32 '2' + { 1008, 18, 32, 23, 2, -30 }, // 0x33 '3' + { 1080, 21, 31, 24, 1, -30 }, // 0x34 '4' + { 1162, 19, 33, 24, 2, -31 }, // 0x35 '5' + { 1241, 21, 33, 23, 2, -31 }, // 0x36 '6' + { 1328, 20, 31, 24, 1, -30 }, // 0x37 '7' + { 1406, 18, 33, 23, 3, -31 }, // 0x38 '8' + { 1481, 21, 33, 24, 1, -31 }, // 0x39 '9' + { 1568, 5, 22, 12, 4, -20 }, // 0x3A ':' + { 1582, 6, 27, 12, 3, -20 }, // 0x3B ';' + { 1603, 24, 25, 27, 1, -24 }, // 0x3C '<' + { 1678, 24, 11, 27, 1, -16 }, // 0x3D '=' + { 1711, 24, 25, 27, 2, -23 }, // 0x3E '>' + { 1786, 17, 32, 21, 3, -31 }, // 0x3F '?' + { 1854, 32, 33, 41, 4, -31 }, // 0x40 '@' + { 1986, 32, 32, 34, 1, -31 }, // 0x41 'A' + { 2114, 27, 31, 30, 0, -30 }, // 0x42 'B' + { 2219, 28, 33, 31, 2, -31 }, // 0x43 'C' + { 2335, 31, 31, 34, 1, -30 }, // 0x44 'D' + { 2456, 27, 31, 29, 2, -30 }, // 0x45 'E' + { 2561, 24, 31, 27, 2, -30 }, // 0x46 'F' + { 2654, 31, 33, 35, 2, -31 }, // 0x47 'G' + { 2782, 30, 31, 34, 2, -30 }, // 0x48 'H' + { 2899, 13, 31, 15, 1, -30 }, // 0x49 'I' + { 2950, 17, 32, 18, 0, -30 }, // 0x4A 'J' + { 3018, 32, 31, 33, 1, -30 }, // 0x4B 'K' + { 3142, 26, 31, 29, 2, -30 }, // 0x4C 'L' + { 3243, 39, 31, 41, 1, -30 }, // 0x4D 'M' + { 3395, 32, 32, 34, 1, -30 }, // 0x4E 'N' + { 3523, 30, 33, 34, 2, -31 }, // 0x4F 'O' + { 3647, 23, 31, 27, 2, -30 }, // 0x50 'P' + { 3737, 31, 40, 34, 2, -31 }, // 0x51 'Q' + { 3892, 28, 31, 31, 2, -30 }, // 0x52 'R' + { 4001, 21, 33, 25, 2, -31 }, // 0x53 'S' + { 4088, 27, 31, 28, 1, -30 }, // 0x54 'T' + { 4193, 32, 32, 34, 1, -30 }, // 0x55 'U' + { 4321, 32, 32, 33, 0, -30 }, // 0x56 'V' + { 4449, 44, 32, 45, 0, -30 }, // 0x57 'W' + { 4625, 33, 31, 34, 0, -30 }, // 0x58 'X' + { 4753, 32, 31, 33, 0, -30 }, // 0x59 'Y' + { 4877, 27, 31, 29, 1, -30 }, // 0x5A 'Z' + { 4982, 9, 38, 16, 4, -30 }, // 0x5B '[' + { 5025, 14, 32, 14, 0, -30 }, // 0x5C '\' + { 5081, 9, 38, 16, 3, -30 }, // 0x5D ']' + { 5124, 20, 17, 22, 1, -30 }, // 0x5E '^' + { 5167, 24, 2, 23, 0, 5 }, // 0x5F '_' + { 5173, 10, 8, 12, 1, -31 }, // 0x60 '`' + { 5183, 18, 21, 20, 1, -20 }, // 0x61 'a' + { 5231, 21, 32, 24, 1, -31 }, // 0x62 'b' + { 5315, 19, 21, 21, 1, -20 }, // 0x63 'c' + { 5365, 22, 32, 23, 1, -31 }, // 0x64 'd' + { 5453, 18, 21, 21, 1, -20 }, // 0x65 'e' + { 5501, 17, 33, 18, 0, -32 }, // 0x66 'f' + { 5572, 21, 31, 22, 1, -20 }, // 0x67 'g' + { 5654, 22, 32, 23, 0, -31 }, // 0x68 'h' + { 5742, 11, 32, 13, 0, -31 }, // 0x69 'i' + { 5786, 12, 42, 16, 0, -31 }, // 0x6A 'j' + { 5849, 23, 32, 24, 1, -31 }, // 0x6B 'k' + { 5941, 11, 32, 12, 0, -31 }, // 0x6C 'l' + { 5985, 35, 21, 37, 1, -20 }, // 0x6D 'm' + { 6077, 22, 21, 23, 0, -20 }, // 0x6E 'n' + { 6135, 22, 21, 23, 1, -20 }, // 0x6F 'o' + { 6193, 21, 31, 24, 1, -20 }, // 0x70 'p' + { 6275, 21, 31, 23, 1, -20 }, // 0x71 'q' + { 6357, 15, 21, 16, 1, -20 }, // 0x72 'r' + { 6397, 13, 21, 17, 2, -20 }, // 0x73 's' + { 6432, 12, 26, 13, 1, -25 }, // 0x74 't' + { 6471, 22, 21, 23, 1, -20 }, // 0x75 'u' + { 6529, 22, 22, 22, 0, -20 }, // 0x76 'v' + { 6590, 32, 22, 32, 0, -20 }, // 0x77 'w' + { 6678, 22, 21, 23, 0, -20 }, // 0x78 'x' + { 6736, 22, 31, 22, 0, -20 }, // 0x79 'y' + { 6822, 18, 21, 20, 1, -20 }, // 0x7A 'z' + { 6870, 11, 41, 23, 5, -31 }, // 0x7B '{' + { 6927, 3, 32, 9, 3, -30 }, // 0x7C '|' + { 6939, 11, 41, 23, 7, -31 }, // 0x7D '}' + { 6996, 22, 5, 23, 1, -13 } }; // 0x7E '~' + +const GFXfont FreeSerif24pt7b PROGMEM = { + (uint8_t *)FreeSerif24pt7bBitmaps, + (GFXglyph *)FreeSerif24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 7682 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerif9pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerif9pt7b.h new file mode 100644 index 0000000..cdb20c7 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerif9pt7b.h @@ -0,0 +1,195 @@ +const uint8_t FreeSerif9pt7bBitmaps[] PROGMEM = { + 0xFF, 0xEA, 0x03, 0xDE, 0xF7, 0x20, 0x11, 0x09, 0x04, 0x82, 0x4F, 0xF9, + 0x10, 0x89, 0xFF, 0x24, 0x12, 0x09, 0x0C, 0x80, 0x10, 0x7C, 0xD6, 0xD2, + 0xD0, 0xF0, 0x38, 0x1E, 0x17, 0x93, 0x93, 0xD6, 0x7C, 0x10, 0x38, 0x43, + 0x3C, 0x39, 0x21, 0x8A, 0x0C, 0x50, 0x65, 0x39, 0xCB, 0x20, 0xB9, 0x05, + 0x88, 0x4C, 0x44, 0x64, 0x21, 0xC0, 0x0E, 0x00, 0xC8, 0x06, 0x40, 0x32, + 0x01, 0xA0, 0x07, 0x78, 0x31, 0x87, 0x88, 0x46, 0x86, 0x34, 0x30, 0xC1, + 0xC7, 0x17, 0xCF, 0x00, 0xFE, 0x08, 0x88, 0x84, 0x63, 0x18, 0xC6, 0x10, + 0x82, 0x08, 0x20, 0x82, 0x08, 0x21, 0x0C, 0x63, 0x18, 0xC4, 0x22, 0x22, + 0x00, 0x63, 0x9A, 0xDC, 0x72, 0xB6, 0x08, 0x08, 0x04, 0x02, 0x01, 0x0F, + 0xF8, 0x40, 0x20, 0x10, 0x08, 0x00, 0xD8, 0xF0, 0xF0, 0x08, 0x84, 0x22, + 0x10, 0x8C, 0x42, 0x31, 0x00, 0x1C, 0x31, 0x98, 0xD8, 0x3C, 0x1E, 0x0F, + 0x07, 0x83, 0xC1, 0xE0, 0xD8, 0xC4, 0x61, 0xC0, 0x13, 0x8C, 0x63, 0x18, + 0xC6, 0x31, 0x8C, 0x67, 0x80, 0x3C, 0x4E, 0x86, 0x06, 0x06, 0x04, 0x0C, + 0x08, 0x10, 0x20, 0x41, 0xFE, 0x3C, 0xC6, 0x06, 0x04, 0x1C, 0x3E, 0x07, + 0x03, 0x03, 0x03, 0x06, 0xF8, 0x04, 0x18, 0x71, 0x64, 0xC9, 0xA3, 0x46, + 0xFE, 0x18, 0x30, 0x60, 0x0F, 0x10, 0x20, 0x3C, 0x0E, 0x07, 0x03, 0x03, + 0x03, 0x02, 0x04, 0xF8, 0x07, 0x1C, 0x30, 0x60, 0x60, 0xDC, 0xE6, 0xC3, + 0xC3, 0xC3, 0x43, 0x66, 0x3C, 0x7F, 0x82, 0x02, 0x02, 0x04, 0x04, 0x04, + 0x08, 0x08, 0x08, 0x10, 0x10, 0x3C, 0x8F, 0x1E, 0x3E, 0x4F, 0x06, 0x36, + 0xC7, 0x8F, 0x1B, 0x33, 0xC0, 0x3C, 0x66, 0xC2, 0xC3, 0xC3, 0xC3, 0xC3, + 0x63, 0x3F, 0x06, 0x06, 0x0C, 0x38, 0x60, 0xF0, 0x0F, 0xD8, 0x00, 0x03, + 0x28, 0x01, 0x87, 0x0E, 0x1C, 0x0C, 0x03, 0x80, 0x70, 0x0E, 0x00, 0x80, + 0xFF, 0x80, 0x00, 0x00, 0x0F, 0xF8, 0x80, 0x1C, 0x01, 0xC0, 0x1C, 0x01, + 0xC0, 0xE0, 0xE0, 0xE0, 0xC0, 0x00, 0x79, 0x1A, 0x18, 0x30, 0x60, 0x83, + 0x04, 0x10, 0x20, 0x40, 0x03, 0x00, 0x0F, 0x83, 0x8C, 0x60, 0x26, 0x02, + 0xC7, 0x9C, 0xC9, 0xD8, 0x9D, 0x99, 0xD9, 0x26, 0xEC, 0x60, 0x03, 0x04, + 0x0F, 0x80, 0x02, 0x00, 0x10, 0x01, 0xC0, 0x16, 0x00, 0x98, 0x04, 0xC0, + 0x43, 0x03, 0xF8, 0x20, 0x61, 0x03, 0x18, 0x1D, 0xE1, 0xF0, 0xFF, 0x86, + 0x1C, 0xC1, 0x98, 0x33, 0x0C, 0x7E, 0x0C, 0x31, 0x83, 0x30, 0x66, 0x0C, + 0xC3, 0x7F, 0xC0, 0x1F, 0x26, 0x1D, 0x81, 0xE0, 0x1C, 0x01, 0x80, 0x30, + 0x06, 0x00, 0xC0, 0x0C, 0x00, 0xC1, 0x8F, 0xC0, 0xFF, 0x03, 0x1C, 0x30, + 0x63, 0x07, 0x30, 0x33, 0x03, 0x30, 0x33, 0x03, 0x30, 0x33, 0x06, 0x30, + 0xCF, 0xF0, 0xFF, 0x98, 0x26, 0x01, 0x80, 0x61, 0x1F, 0xC6, 0x11, 0x80, + 0x60, 0x18, 0x16, 0x0F, 0xFE, 0xFF, 0xB0, 0x58, 0x0C, 0x06, 0x13, 0xF9, + 0x84, 0xC0, 0x60, 0x30, 0x18, 0x1E, 0x00, 0x1F, 0x23, 0x0E, 0x60, 0x26, + 0x00, 0xC0, 0x0C, 0x0F, 0xC0, 0x6C, 0x06, 0xC0, 0x66, 0x06, 0x30, 0x60, + 0xF8, 0xF1, 0xEC, 0x19, 0x83, 0x30, 0x66, 0x0C, 0xFF, 0x98, 0x33, 0x06, + 0x60, 0xCC, 0x19, 0x83, 0x78, 0xF0, 0xF6, 0x66, 0x66, 0x66, 0x66, 0x6F, + 0x3C, 0x61, 0x86, 0x18, 0x61, 0x86, 0x18, 0x6D, 0xBC, 0xF3, 0xE6, 0x08, + 0x61, 0x06, 0x20, 0x64, 0x07, 0x80, 0x6C, 0x06, 0x60, 0x63, 0x06, 0x18, + 0x60, 0xCF, 0x3F, 0xF0, 0x18, 0x06, 0x01, 0x80, 0x60, 0x18, 0x06, 0x01, + 0x80, 0x60, 0x18, 0x16, 0x0B, 0xFE, 0xF0, 0x0E, 0x70, 0x38, 0xE0, 0x71, + 0xE1, 0x62, 0xC2, 0xC5, 0xC9, 0x89, 0x93, 0x13, 0x26, 0x23, 0x8C, 0x47, + 0x18, 0x84, 0x33, 0x88, 0xF0, 0xE0, 0xEE, 0x09, 0xC1, 0x2C, 0x25, 0xC4, + 0x9C, 0x91, 0x92, 0x1A, 0x41, 0xC8, 0x19, 0x03, 0x70, 0x20, 0x1F, 0x06, + 0x31, 0x83, 0x20, 0x2C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x68, 0x09, + 0x83, 0x18, 0xC1, 0xF0, 0xFE, 0x31, 0x98, 0x6C, 0x36, 0x1B, 0x19, 0xF8, + 0xC0, 0x60, 0x30, 0x18, 0x1E, 0x00, 0x1F, 0x06, 0x31, 0x83, 0x20, 0x2C, + 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x68, 0x19, 0x83, 0x18, 0xC0, 0xE0, + 0x0E, 0x00, 0xE0, 0x07, 0xFE, 0x0C, 0x61, 0x86, 0x30, 0xC6, 0x18, 0xC6, + 0x1F, 0x83, 0x70, 0x67, 0x0C, 0x71, 0x87, 0x78, 0x70, 0x1D, 0x31, 0x98, + 0x4C, 0x07, 0x80, 0xE0, 0x1C, 0x07, 0x01, 0xA0, 0xD8, 0xCB, 0xC0, 0xFF, + 0xF8, 0xCE, 0x18, 0x83, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, + 0xC0, 0x18, 0x07, 0x80, 0xF0, 0xEC, 0x09, 0x81, 0x30, 0x26, 0x04, 0xC0, + 0x98, 0x13, 0x02, 0x60, 0x4C, 0x08, 0xC2, 0x0F, 0x80, 0xF8, 0x77, 0x02, + 0x30, 0x23, 0x04, 0x18, 0x41, 0x84, 0x0C, 0x80, 0xC8, 0x07, 0x00, 0x70, + 0x02, 0x00, 0x20, 0xFB, 0xE7, 0xB0, 0xC0, 0x8C, 0x20, 0x86, 0x18, 0x41, + 0x8C, 0x40, 0xCB, 0x20, 0x65, 0x90, 0x1A, 0x70, 0x0E, 0x38, 0x03, 0x1C, + 0x01, 0x04, 0x00, 0x82, 0x00, 0xFC, 0xF9, 0x83, 0x06, 0x10, 0x19, 0x00, + 0xD0, 0x03, 0x00, 0x1C, 0x01, 0x30, 0x11, 0xC1, 0x86, 0x08, 0x19, 0xE3, + 0xF0, 0xF8, 0xF6, 0x06, 0x30, 0x41, 0x88, 0x1D, 0x00, 0xD0, 0x06, 0x00, + 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, 0xF0, 0x3F, 0xCC, 0x11, 0x06, 0x01, + 0x80, 0x70, 0x0C, 0x03, 0x00, 0xE0, 0x38, 0x06, 0x05, 0xC1, 0x7F, 0xE0, + 0xFB, 0x6D, 0xB6, 0xDB, 0x6D, 0xB8, 0x82, 0x10, 0x82, 0x10, 0x86, 0x10, + 0x86, 0x10, 0xED, 0xB6, 0xDB, 0x6D, 0xB6, 0xF8, 0x18, 0x1C, 0x34, 0x26, + 0x62, 0x42, 0xC1, 0xFF, 0x80, 0x84, 0x20, 0x79, 0x98, 0x30, 0xE6, 0xD9, + 0xB3, 0x3F, 0x20, 0x70, 0x18, 0x0C, 0x06, 0x03, 0x71, 0xCC, 0xC3, 0x61, + 0xB0, 0xD8, 0x6C, 0x63, 0xE0, 0x3C, 0xCF, 0x06, 0x0C, 0x18, 0x18, 0x9E, + 0x01, 0x03, 0x80, 0xC0, 0x60, 0x31, 0xD9, 0x9D, 0x86, 0xC3, 0x61, 0xB0, + 0xCC, 0x63, 0xF0, 0x3C, 0x46, 0xFE, 0xC0, 0xC0, 0xE1, 0x62, 0x3C, 0x1E, + 0x41, 0x83, 0x06, 0x1E, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x0F, 0x00, 0x3C, + 0x19, 0xF6, 0x31, 0x8C, 0x1E, 0x08, 0x04, 0x01, 0xFC, 0x40, 0xB0, 0x2E, + 0x11, 0xF8, 0x20, 0x70, 0x18, 0x0C, 0x06, 0x03, 0x71, 0xCC, 0xC6, 0x63, + 0x31, 0x98, 0xCC, 0x6F, 0x78, 0x60, 0x02, 0xE6, 0x66, 0x66, 0xF0, 0x18, + 0x00, 0x33, 0x8C, 0x63, 0x18, 0xC6, 0x31, 0x8B, 0x80, 0x20, 0x70, 0x18, + 0x0C, 0x06, 0x03, 0x3D, 0x88, 0xD8, 0x78, 0x36, 0x19, 0x8C, 0x6F, 0x78, + 0x2E, 0x66, 0x66, 0x66, 0x66, 0x66, 0xF0, 0xEE, 0x71, 0xCE, 0x66, 0x31, + 0x98, 0xC6, 0x63, 0x19, 0x8C, 0x66, 0x31, 0xBD, 0xEF, 0xEE, 0x39, 0x98, + 0xCC, 0x66, 0x33, 0x19, 0x8D, 0xEF, 0x3E, 0x31, 0xB0, 0x78, 0x3C, 0x1E, + 0x0D, 0x8C, 0x7C, 0xEE, 0x39, 0x98, 0x6C, 0x36, 0x1B, 0x0D, 0x8C, 0xFC, + 0x60, 0x30, 0x18, 0x1E, 0x00, 0x3D, 0x31, 0xB0, 0xD8, 0x6C, 0x36, 0x1B, + 0x8C, 0xFE, 0x03, 0x01, 0x80, 0xC0, 0xF0, 0x6D, 0xC6, 0x18, 0x61, 0x86, + 0x3C, 0x76, 0x38, 0x58, 0x3E, 0x38, 0xFE, 0x27, 0x98, 0xC6, 0x31, 0x8C, + 0x38, 0xE7, 0x31, 0x98, 0xCC, 0x66, 0x33, 0x19, 0x8C, 0x7F, 0xF3, 0x61, + 0x22, 0x32, 0x14, 0x1C, 0x08, 0x08, 0xEF, 0x36, 0x61, 0x62, 0x22, 0x32, + 0x35, 0x41, 0x9C, 0x18, 0x81, 0x08, 0xF7, 0x12, 0x0E, 0x03, 0x01, 0xC1, + 0x21, 0x09, 0xCF, 0xF3, 0x61, 0x62, 0x32, 0x34, 0x14, 0x1C, 0x08, 0x08, + 0x08, 0x10, 0xE0, 0xFD, 0x18, 0x60, 0x83, 0x0C, 0x70, 0xFE, 0x19, 0x8C, + 0x63, 0x18, 0xC4, 0x61, 0x8C, 0x63, 0x18, 0xC3, 0xFF, 0xF0, 0xC3, 0x18, + 0xC6, 0x31, 0x84, 0x33, 0x18, 0xC6, 0x31, 0x98, 0x70, 0x24, 0xC1, 0xC0 }; + +const GFXglyph FreeSerif9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 2, 12, 6, 2, -11 }, // 0x21 '!' + { 3, 5, 4, 7, 1, -11 }, // 0x22 '"' + { 6, 9, 12, 9, 0, -11 }, // 0x23 '#' + { 20, 8, 14, 9, 1, -12 }, // 0x24 '$' + { 34, 13, 12, 15, 1, -11 }, // 0x25 '%' + { 54, 13, 13, 14, 1, -12 }, // 0x26 '&' + { 76, 2, 4, 4, 1, -11 }, // 0x27 ''' + { 77, 5, 15, 6, 1, -11 }, // 0x28 '(' + { 87, 5, 15, 6, 0, -11 }, // 0x29 ')' + { 97, 6, 8, 9, 3, -11 }, // 0x2A '*' + { 103, 9, 9, 10, 0, -8 }, // 0x2B '+' + { 114, 2, 3, 4, 2, 0 }, // 0x2C ',' + { 115, 4, 1, 6, 1, -3 }, // 0x2D '-' + { 116, 2, 2, 5, 1, -1 }, // 0x2E '.' + { 117, 5, 12, 5, 0, -11 }, // 0x2F '/' + { 125, 9, 13, 9, 0, -12 }, // 0x30 '0' + { 140, 5, 13, 9, 2, -12 }, // 0x31 '1' + { 149, 8, 12, 9, 1, -11 }, // 0x32 '2' + { 161, 8, 12, 9, 0, -11 }, // 0x33 '3' + { 173, 7, 12, 9, 1, -11 }, // 0x34 '4' + { 184, 8, 12, 9, 0, -11 }, // 0x35 '5' + { 196, 8, 13, 9, 1, -12 }, // 0x36 '6' + { 209, 8, 12, 9, 0, -11 }, // 0x37 '7' + { 221, 7, 13, 9, 1, -12 }, // 0x38 '8' + { 233, 8, 14, 9, 1, -12 }, // 0x39 '9' + { 247, 2, 8, 5, 1, -7 }, // 0x3A ':' + { 249, 3, 10, 5, 1, -7 }, // 0x3B ';' + { 253, 9, 9, 10, 1, -8 }, // 0x3C '<' + { 264, 9, 5, 10, 1, -6 }, // 0x3D '=' + { 270, 10, 9, 10, 0, -8 }, // 0x3E '>' + { 282, 7, 13, 8, 1, -12 }, // 0x3F '?' + { 294, 12, 13, 16, 2, -12 }, // 0x40 '@' + { 314, 13, 12, 13, 0, -11 }, // 0x41 'A' + { 334, 11, 12, 11, 0, -11 }, // 0x42 'B' + { 351, 11, 12, 12, 1, -11 }, // 0x43 'C' + { 368, 12, 12, 13, 0, -11 }, // 0x44 'D' + { 386, 10, 12, 11, 1, -11 }, // 0x45 'E' + { 401, 9, 12, 10, 1, -11 }, // 0x46 'F' + { 415, 12, 12, 13, 1, -11 }, // 0x47 'G' + { 433, 11, 12, 13, 1, -11 }, // 0x48 'H' + { 450, 4, 12, 6, 1, -11 }, // 0x49 'I' + { 456, 6, 12, 7, 0, -11 }, // 0x4A 'J' + { 465, 12, 12, 13, 1, -11 }, // 0x4B 'K' + { 483, 10, 12, 11, 1, -11 }, // 0x4C 'L' + { 498, 15, 12, 16, 0, -11 }, // 0x4D 'M' + { 521, 11, 12, 13, 1, -11 }, // 0x4E 'N' + { 538, 11, 13, 13, 1, -12 }, // 0x4F 'O' + { 556, 9, 12, 10, 1, -11 }, // 0x50 'P' + { 570, 11, 16, 13, 1, -12 }, // 0x51 'Q' + { 592, 11, 12, 12, 1, -11 }, // 0x52 'R' + { 609, 9, 12, 10, 0, -11 }, // 0x53 'S' + { 623, 11, 12, 11, 0, -11 }, // 0x54 'T' + { 640, 11, 12, 13, 1, -11 }, // 0x55 'U' + { 657, 12, 12, 13, 0, -11 }, // 0x56 'V' + { 675, 17, 12, 17, 0, -11 }, // 0x57 'W' + { 701, 13, 12, 13, 0, -11 }, // 0x58 'X' + { 721, 12, 12, 13, 0, -11 }, // 0x59 'Y' + { 739, 11, 12, 11, 0, -11 }, // 0x5A 'Z' + { 756, 3, 15, 6, 2, -11 }, // 0x5B '[' + { 762, 5, 12, 5, 0, -11 }, // 0x5C '\' + { 770, 3, 15, 6, 1, -11 }, // 0x5D ']' + { 776, 8, 7, 8, 0, -11 }, // 0x5E '^' + { 783, 9, 1, 9, 0, 2 }, // 0x5F '_' + { 785, 4, 3, 5, 0, -11 }, // 0x60 '`' + { 787, 7, 8, 8, 1, -7 }, // 0x61 'a' + { 794, 9, 13, 9, 0, -12 }, // 0x62 'b' + { 809, 7, 8, 8, 0, -7 }, // 0x63 'c' + { 816, 9, 13, 9, 0, -12 }, // 0x64 'd' + { 831, 8, 8, 8, 0, -7 }, // 0x65 'e' + { 839, 7, 13, 7, 1, -12 }, // 0x66 'f' + { 851, 10, 12, 8, 0, -7 }, // 0x67 'g' + { 866, 9, 13, 9, 0, -12 }, // 0x68 'h' + { 881, 4, 11, 5, 1, -10 }, // 0x69 'i' + { 887, 5, 15, 6, 0, -10 }, // 0x6A 'j' + { 897, 9, 13, 9, 1, -12 }, // 0x6B 'k' + { 912, 4, 13, 5, 1, -12 }, // 0x6C 'l' + { 919, 14, 8, 14, 0, -7 }, // 0x6D 'm' + { 933, 9, 8, 9, 0, -7 }, // 0x6E 'n' + { 942, 9, 8, 9, 0, -7 }, // 0x6F 'o' + { 951, 9, 12, 9, 0, -7 }, // 0x70 'p' + { 965, 9, 12, 9, 0, -7 }, // 0x71 'q' + { 979, 6, 8, 6, 0, -7 }, // 0x72 'r' + { 985, 6, 8, 7, 1, -7 }, // 0x73 's' + { 991, 5, 9, 5, 0, -8 }, // 0x74 't' + { 997, 9, 8, 9, 0, -7 }, // 0x75 'u' + { 1006, 8, 8, 8, 0, -7 }, // 0x76 'v' + { 1014, 12, 8, 12, 0, -7 }, // 0x77 'w' + { 1026, 9, 8, 9, 0, -7 }, // 0x78 'x' + { 1035, 8, 12, 8, 0, -7 }, // 0x79 'y' + { 1047, 7, 8, 7, 1, -7 }, // 0x7A 'z' + { 1054, 5, 16, 9, 1, -12 }, // 0x7B '{' + { 1064, 1, 12, 4, 1, -11 }, // 0x7C '|' + { 1066, 5, 16, 9, 3, -11 }, // 0x7D '}' + { 1076, 9, 3, 9, 0, -5 } }; // 0x7E '~' + +const GFXfont FreeSerif9pt7b PROGMEM = { + (uint8_t *)FreeSerif9pt7bBitmaps, + (GFXglyph *)FreeSerif9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 1752 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBold12pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBold12pt7b.h new file mode 100644 index 0000000..1d49981 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBold12pt7b.h @@ -0,0 +1,271 @@ +const uint8_t FreeSerifBold12pt7bBitmaps[] PROGMEM = { + 0x7F, 0xFF, 0x77, 0x66, 0x22, 0x00, 0x6F, 0xF7, 0xE3, 0xF1, 0xF8, 0xFC, + 0x7E, 0x3A, 0x09, 0x04, 0x0C, 0x40, 0xCC, 0x0C, 0xC0, 0x8C, 0x18, 0xC7, + 0xFF, 0x18, 0xC1, 0x88, 0x19, 0x81, 0x98, 0xFF, 0xE3, 0x18, 0x31, 0x83, + 0x18, 0x33, 0x03, 0x30, 0x08, 0x01, 0x00, 0xFC, 0x24, 0xEC, 0x8D, 0x90, + 0xBA, 0x07, 0xC0, 0x7E, 0x07, 0xF0, 0x7F, 0x07, 0xF0, 0x9F, 0x11, 0xE2, + 0x3E, 0x46, 0xE9, 0xC7, 0xC0, 0x20, 0x04, 0x00, 0x1E, 0x0C, 0x0E, 0x7F, + 0x07, 0x10, 0x83, 0xC4, 0x40, 0xE1, 0x30, 0x38, 0x88, 0x0E, 0x26, 0x03, + 0x91, 0x1E, 0x78, 0x8E, 0x40, 0x27, 0x10, 0x11, 0xC4, 0x0C, 0xE1, 0x02, + 0x38, 0x81, 0x0E, 0x20, 0x43, 0x90, 0x20, 0x78, 0x03, 0xE0, 0x01, 0x9E, + 0x00, 0xE3, 0x80, 0x38, 0xE0, 0x0F, 0x30, 0x03, 0xF0, 0x00, 0x78, 0x7C, + 0x1F, 0x06, 0x1B, 0xE1, 0x1C, 0x7C, 0x8F, 0x1F, 0x23, 0xC3, 0xF0, 0xF8, + 0x7C, 0x3E, 0x0F, 0x97, 0xC7, 0xFC, 0xFE, 0x3E, 0xFF, 0xFE, 0x90, 0x00, + 0x31, 0x0C, 0x31, 0x86, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x86, 0x18, 0x60, + 0xC1, 0x02, 0x04, 0x03, 0x06, 0x0C, 0x30, 0x61, 0x87, 0x1C, 0x71, 0xC7, + 0x1C, 0x71, 0x86, 0x38, 0xC2, 0x10, 0x80, 0x1C, 0x6E, 0xFA, 0xEF, 0xF1, + 0xC7, 0xFF, 0xAF, 0xBB, 0x1C, 0x04, 0x00, 0x06, 0x00, 0x60, 0x06, 0x00, + 0x60, 0x06, 0x0F, 0xFF, 0xFF, 0xF0, 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, + 0x60, 0x6F, 0xF7, 0x11, 0x24, 0xFF, 0xFF, 0xC0, 0x6F, 0xF6, 0x03, 0x07, + 0x06, 0x06, 0x0C, 0x0C, 0x0C, 0x18, 0x18, 0x18, 0x30, 0x30, 0x30, 0x60, + 0x60, 0x60, 0xC0, 0x0E, 0x07, 0x71, 0xC7, 0x38, 0xEF, 0x1D, 0xE3, 0xFC, + 0x7F, 0x8F, 0xF1, 0xFE, 0x3F, 0xC7, 0xF8, 0xF7, 0x1C, 0xE3, 0x8E, 0xE0, + 0xF8, 0x06, 0x0F, 0x1F, 0x83, 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, 0x0F, + 0x07, 0x83, 0xC1, 0xE0, 0xF0, 0xF9, 0xFF, 0x0F, 0x03, 0xFC, 0x7F, 0xC4, + 0x3E, 0x01, 0xE0, 0x1E, 0x01, 0xE0, 0x1C, 0x03, 0x80, 0x30, 0x06, 0x00, + 0xC1, 0x18, 0x13, 0xFE, 0x7F, 0xEF, 0xFE, 0x1F, 0x0C, 0xFA, 0x0F, 0x01, + 0xE0, 0x38, 0x0E, 0x03, 0xE0, 0x3E, 0x03, 0xE0, 0x3C, 0x03, 0x80, 0x70, + 0x0D, 0xC1, 0xBC, 0x43, 0xF0, 0x03, 0x80, 0xE0, 0x78, 0x3E, 0x17, 0x89, + 0xE2, 0x79, 0x1E, 0x87, 0xA1, 0xEF, 0xFF, 0xFF, 0xFF, 0xC1, 0xE0, 0x78, + 0x1E, 0x3F, 0xE7, 0xF8, 0xFF, 0x10, 0x04, 0x00, 0xF8, 0x1F, 0xC7, 0xFC, + 0x1F, 0xC0, 0x78, 0x07, 0x00, 0x60, 0x0D, 0xC1, 0x3C, 0x43, 0xF0, 0x00, + 0xE0, 0xF0, 0x38, 0x1E, 0x07, 0x80, 0xF0, 0x3F, 0xE7, 0x9E, 0xF1, 0xFE, + 0x3F, 0xC7, 0xF8, 0xF7, 0x1E, 0xE3, 0x8E, 0x60, 0xF8, 0x7F, 0xEF, 0xFD, + 0xFF, 0xA0, 0x68, 0x0C, 0x03, 0x80, 0x60, 0x0C, 0x03, 0x00, 0x60, 0x0C, + 0x03, 0x00, 0x60, 0x1C, 0x03, 0x00, 0x60, 0x1F, 0x0E, 0x73, 0x87, 0x70, + 0xEF, 0x1D, 0xF3, 0x1F, 0x81, 0xF8, 0x1F, 0xCC, 0xFB, 0x8F, 0xF0, 0xFE, + 0x1F, 0xC3, 0x9C, 0xF1, 0xF8, 0x1F, 0x06, 0x71, 0xC7, 0x78, 0xEF, 0x1F, + 0xE3, 0xFC, 0x7F, 0x8F, 0x79, 0xE7, 0xFC, 0x0F, 0x01, 0xC0, 0x78, 0x1C, + 0x0F, 0x07, 0x00, 0x6F, 0xF6, 0x00, 0x06, 0xFF, 0x60, 0x6F, 0xF6, 0x00, + 0x06, 0xFF, 0x71, 0x22, 0xC0, 0x00, 0x04, 0x00, 0x70, 0x07, 0xC0, 0xFC, + 0x0F, 0x80, 0xF8, 0x0F, 0x80, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, + 0x00, 0x1F, 0x00, 0x1C, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0x00, 0x03, 0x80, 0x0F, + 0x80, 0x0F, 0x80, 0x0F, 0x80, 0x0F, 0x80, 0x0F, 0x80, 0x1F, 0x01, 0xF0, + 0x1F, 0x03, 0xF0, 0x3E, 0x00, 0xE0, 0x02, 0x00, 0x00, 0x3E, 0x11, 0xEC, + 0x3F, 0x8F, 0xE3, 0xC0, 0xF0, 0x78, 0x18, 0x08, 0x02, 0x00, 0x00, 0x00, + 0x1C, 0x07, 0x81, 0xE0, 0x30, 0x03, 0xF0, 0x0E, 0x18, 0x18, 0x04, 0x30, + 0x66, 0x70, 0xDB, 0x61, 0x99, 0xE3, 0x19, 0xE3, 0x31, 0xE6, 0x31, 0xE6, + 0x31, 0xE6, 0xF2, 0x66, 0xB2, 0x73, 0x3C, 0x38, 0x00, 0x1E, 0x04, 0x03, + 0xF8, 0x00, 0x80, 0x00, 0xC0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x3E, 0x00, + 0x1F, 0x00, 0x1B, 0xC0, 0x09, 0xE0, 0x0C, 0xF8, 0x04, 0x3C, 0x02, 0x1F, + 0x03, 0xFF, 0x81, 0x03, 0xC1, 0x80, 0xF0, 0x80, 0x7D, 0xF0, 0xFF, 0xFF, + 0xC0, 0xF3, 0xC3, 0xC7, 0x8F, 0x1E, 0x3C, 0x78, 0xF1, 0xE3, 0xCE, 0x0F, + 0xF0, 0x3C, 0x70, 0xF0, 0xE3, 0xC3, 0xCF, 0x0F, 0x3C, 0x3C, 0xF0, 0xE3, + 0xC7, 0xBF, 0xF8, 0x07, 0xE2, 0x38, 0x7C, 0xE0, 0x3B, 0xC0, 0x37, 0x00, + 0x7E, 0x00, 0x7C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x03, + 0x80, 0x07, 0x80, 0x27, 0x00, 0xC7, 0x86, 0x03, 0xF0, 0xFF, 0xE0, 0x1E, + 0x1E, 0x0F, 0x07, 0x87, 0x81, 0xE3, 0xC0, 0xF1, 0xE0, 0x3C, 0xF0, 0x1E, + 0x78, 0x0F, 0x3C, 0x07, 0x9E, 0x03, 0xCF, 0x01, 0xE7, 0x80, 0xE3, 0xC0, + 0xF1, 0xE0, 0xF0, 0xF0, 0xE1, 0xFF, 0xC0, 0xFF, 0xFC, 0x78, 0x38, 0xF0, + 0x31, 0xE0, 0x23, 0xC4, 0x07, 0x88, 0x0F, 0x30, 0x1F, 0xE0, 0x3C, 0xC0, + 0x78, 0x80, 0xF1, 0x01, 0xE0, 0x23, 0xC0, 0x47, 0x81, 0x8F, 0x07, 0x7F, + 0xFE, 0xFF, 0xFC, 0xF0, 0x73, 0xC0, 0xCF, 0x01, 0x3C, 0x40, 0xF1, 0x03, + 0xCC, 0x0F, 0xF0, 0x3C, 0xC0, 0xF1, 0x03, 0xC4, 0x0F, 0x00, 0x3C, 0x00, + 0xF0, 0x03, 0xC0, 0x3F, 0xC0, 0x07, 0xE2, 0x1C, 0x3E, 0x38, 0x0E, 0x78, + 0x06, 0x70, 0x06, 0xF0, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF0, + 0x7F, 0xF0, 0x1E, 0x70, 0x1E, 0x78, 0x1E, 0x38, 0x1E, 0x1E, 0x1E, 0x07, + 0xF0, 0xFE, 0xFF, 0x78, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0x78, + 0x3C, 0x78, 0x3C, 0x7F, 0xFC, 0x78, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0x78, + 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0xFE, 0xFF, 0xFF, 0x3C, 0x3C, + 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, + 0xFF, 0x0F, 0xF0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, + 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0xE3, 0xCE, + 0x38, 0xE3, 0x83, 0xE0, 0xFE, 0x7F, 0x3C, 0x0E, 0x1E, 0x04, 0x0F, 0x04, + 0x07, 0x84, 0x03, 0xCC, 0x01, 0xEE, 0x00, 0xFF, 0x00, 0x7F, 0xC0, 0x3C, + 0xF0, 0x1E, 0x7C, 0x0F, 0x1F, 0x07, 0x87, 0xC3, 0xC1, 0xF1, 0xE0, 0x7D, + 0xFC, 0xFF, 0xFE, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, 0xE0, + 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x01, 0x78, + 0x0D, 0xE0, 0x67, 0x83, 0xBF, 0xFE, 0xFC, 0x01, 0xF3, 0xC0, 0x3E, 0x3E, + 0x03, 0xE2, 0xE0, 0x5E, 0x2F, 0x05, 0xE2, 0xF0, 0x5E, 0x27, 0x09, 0xE2, + 0x78, 0x9E, 0x23, 0x91, 0xE2, 0x3D, 0x1E, 0x23, 0xF1, 0xE2, 0x1E, 0x1E, + 0x21, 0xE1, 0xE2, 0x0C, 0x1E, 0x20, 0xC1, 0xEF, 0x88, 0x3F, 0xF8, 0x1E, + 0xF8, 0x18, 0xF8, 0x11, 0xF8, 0x22, 0xF8, 0x45, 0xF0, 0x89, 0xF1, 0x11, + 0xF2, 0x21, 0xF4, 0x41, 0xF8, 0x81, 0xF1, 0x01, 0xE2, 0x03, 0xC4, 0x03, + 0x8C, 0x03, 0x7C, 0x02, 0x07, 0xF0, 0x0F, 0x1E, 0x0E, 0x03, 0x8F, 0x01, + 0xE7, 0x00, 0x77, 0x80, 0x3F, 0xC0, 0x1F, 0xE0, 0x0F, 0xF0, 0x07, 0xF8, + 0x03, 0xFC, 0x01, 0xEE, 0x00, 0xE7, 0x80, 0xF1, 0xC0, 0x70, 0x70, 0x70, + 0x0F, 0xE0, 0xFF, 0x87, 0x9E, 0x78, 0xF7, 0x8F, 0x78, 0xF7, 0x8F, 0x78, + 0xF7, 0x9E, 0x7F, 0x87, 0x80, 0x78, 0x07, 0x80, 0x78, 0x07, 0x80, 0x78, + 0x0F, 0xE0, 0x07, 0xF0, 0x0F, 0x1E, 0x0E, 0x07, 0x8F, 0x01, 0xE7, 0x00, + 0xF7, 0x80, 0x3F, 0xC0, 0x1F, 0xE0, 0x0F, 0xF0, 0x07, 0xF8, 0x03, 0xFC, + 0x01, 0xEE, 0x00, 0xE7, 0x00, 0xF1, 0xC0, 0x70, 0x70, 0x70, 0x1C, 0xF0, + 0x03, 0xE0, 0x01, 0xF8, 0x00, 0x3E, 0x00, 0x07, 0xE0, 0xFF, 0xE0, 0x3C, + 0x78, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x38, 0x3C, + 0x70, 0x3F, 0xC0, 0x3D, 0xE0, 0x3C, 0xF0, 0x3C, 0xF8, 0x3C, 0x78, 0x3C, + 0x3C, 0x3C, 0x3E, 0xFF, 0x1F, 0x1F, 0x27, 0x0E, 0x60, 0x6E, 0x06, 0xF0, + 0x2F, 0x80, 0x7F, 0x07, 0xFC, 0x1F, 0xE0, 0x7E, 0x01, 0xF8, 0x07, 0xC0, + 0x7C, 0x06, 0xF0, 0xC9, 0xF8, 0xFF, 0xFF, 0xC7, 0x9F, 0x0F, 0x1C, 0x1E, + 0x10, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, + 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x07, 0xF8, 0xFE, + 0x1E, 0xF0, 0x09, 0xE0, 0x13, 0xC0, 0x27, 0x80, 0x4F, 0x00, 0x9E, 0x01, + 0x3C, 0x02, 0x78, 0x04, 0xF0, 0x09, 0xE0, 0x13, 0xC0, 0x27, 0x80, 0x47, + 0x81, 0x07, 0x84, 0x07, 0xF0, 0xFF, 0x0F, 0x9E, 0x03, 0x0F, 0x00, 0x83, + 0xC0, 0x81, 0xE0, 0x40, 0xF8, 0x60, 0x3C, 0x20, 0x1E, 0x10, 0x07, 0x90, + 0x03, 0xC8, 0x00, 0xF4, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x0E, 0x00, 0x07, + 0x00, 0x01, 0x80, 0x00, 0x80, 0x00, 0xFE, 0x7F, 0x9E, 0xF8, 0x3C, 0x08, + 0xF0, 0x78, 0x31, 0xE0, 0xF0, 0x41, 0xE0, 0xF0, 0x83, 0xC3, 0xE3, 0x07, + 0x85, 0xC4, 0x07, 0x93, 0xC8, 0x0F, 0x27, 0xB0, 0x0E, 0x47, 0x40, 0x1F, + 0x0F, 0x80, 0x3E, 0x1F, 0x00, 0x38, 0x1C, 0x00, 0x70, 0x38, 0x00, 0xE0, + 0x30, 0x00, 0x80, 0x40, 0xFF, 0x9F, 0x9F, 0x07, 0x07, 0x83, 0x03, 0xE3, + 0x00, 0xF9, 0x00, 0x3D, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xE0, 0x00, + 0xF8, 0x00, 0xBE, 0x00, 0x8F, 0x00, 0x83, 0xC0, 0xC1, 0xF0, 0xE0, 0xFD, + 0xF8, 0xFF, 0xFF, 0x1F, 0x7C, 0x06, 0x3C, 0x04, 0x3E, 0x0C, 0x1E, 0x08, + 0x0F, 0x10, 0x0F, 0x30, 0x07, 0xA0, 0x07, 0xC0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x0F, 0xF0, 0x7F, 0xFC, + 0xE0, 0xF1, 0x83, 0xE2, 0x07, 0x84, 0x1E, 0x00, 0x7C, 0x00, 0xF0, 0x03, + 0xC0, 0x0F, 0x80, 0x1E, 0x00, 0x7C, 0x08, 0xF0, 0x13, 0xC0, 0x6F, 0x81, + 0x9E, 0x07, 0x7F, 0xFE, 0xFF, 0x39, 0xCE, 0x73, 0x9C, 0xE7, 0x39, 0xCE, + 0x73, 0x9C, 0xE7, 0x39, 0xF0, 0xC0, 0x60, 0x60, 0x60, 0x30, 0x30, 0x30, + 0x18, 0x18, 0x18, 0x0C, 0x0C, 0x0C, 0x06, 0x06, 0x06, 0x03, 0xF9, 0xCE, + 0x73, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9C, 0xE7, 0x39, 0xCF, 0xF0, 0x0C, + 0x07, 0x81, 0xE0, 0xCC, 0x33, 0x18, 0x66, 0x1B, 0x87, 0xC0, 0xC0, 0xFF, + 0xF0, 0xC7, 0x1C, 0x30, 0x1F, 0x0E, 0x71, 0xCF, 0x39, 0xE0, 0x3C, 0x1F, + 0x8E, 0xF3, 0x9E, 0xF3, 0xDE, 0x79, 0xFF, 0x80, 0xF8, 0x07, 0x80, 0x78, + 0x07, 0x80, 0x78, 0x07, 0xB8, 0x7D, 0xE7, 0x8E, 0x78, 0xF7, 0x8F, 0x78, + 0xF7, 0x8F, 0x78, 0xF7, 0x8E, 0x79, 0xC4, 0x78, 0x1F, 0x1D, 0xDC, 0xFE, + 0x7F, 0x07, 0x83, 0xC1, 0xE0, 0x78, 0x3C, 0x47, 0xC0, 0x03, 0xE0, 0x1E, + 0x01, 0xE0, 0x1E, 0x01, 0xE1, 0xDE, 0x7B, 0xE7, 0x1E, 0xF1, 0xEF, 0x1E, + 0xF1, 0xEF, 0x1E, 0xF1, 0xE7, 0x1E, 0x7B, 0xE1, 0xDF, 0x1F, 0x0C, 0x67, + 0x1B, 0xC7, 0xFF, 0xFC, 0x0F, 0x03, 0xC0, 0x78, 0x4E, 0x21, 0xF0, 0x1E, + 0x3B, 0x7B, 0x78, 0x78, 0xFC, 0x78, 0x78, 0x78, 0x78, 0x78, 0x78, 0x78, + 0x78, 0x78, 0xFC, 0x3E, 0x0E, 0x7F, 0xCE, 0x79, 0xEF, 0x3C, 0xE7, 0x0F, + 0xC1, 0x00, 0x60, 0x1C, 0x03, 0xFE, 0x7F, 0xE3, 0xFF, 0x80, 0xF0, 0x33, + 0xFC, 0xF8, 0x07, 0x80, 0x78, 0x07, 0x80, 0x78, 0x07, 0xB8, 0x7D, 0xE7, + 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xEF, + 0xFF, 0x31, 0xE7, 0x8C, 0x03, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, + 0xBF, 0x06, 0x0F, 0x0F, 0x06, 0x00, 0x1F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0xCF, 0xCE, 0x7C, 0xF8, 0x03, + 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0xF9, 0xE1, 0x8F, 0x10, 0x79, + 0x03, 0xD8, 0x1F, 0xE0, 0xF7, 0x87, 0x9E, 0x3C, 0x71, 0xE3, 0xDF, 0xBF, + 0xF9, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0xBF, + 0xFB, 0xCF, 0x0F, 0xBE, 0x79, 0xE7, 0x8F, 0x3C, 0xF1, 0xE7, 0x9E, 0x3C, + 0xF3, 0xC7, 0x9E, 0x78, 0xF3, 0xCF, 0x1E, 0x79, 0xE3, 0xCF, 0x3C, 0x7B, + 0xFF, 0xDF, 0x80, 0xFB, 0x87, 0xDE, 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, + 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0xFF, 0xF0, 0x1F, 0x07, 0x71, 0xC7, + 0x78, 0xFF, 0x1F, 0xE3, 0xFC, 0x7F, 0x8F, 0x71, 0xC7, 0x70, 0x7C, 0x00, + 0xFB, 0x87, 0xDE, 0x78, 0xE7, 0x8F, 0x78, 0xF7, 0x8F, 0x78, 0xF7, 0x8F, + 0x78, 0xE7, 0x9E, 0x7F, 0x87, 0x80, 0x78, 0x07, 0x80, 0x78, 0x0F, 0xC0, + 0x1E, 0x23, 0x9E, 0x71, 0xEF, 0x1E, 0xF1, 0xEF, 0x1E, 0xF1, 0xEF, 0x1E, + 0x71, 0xE7, 0x9E, 0x1F, 0xE0, 0x1E, 0x01, 0xE0, 0x1E, 0x01, 0xE0, 0x3F, + 0xF9, 0xDF, 0xF7, 0xDD, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1E, + 0x0F, 0xC0, 0x3D, 0x43, 0xC3, 0xE0, 0xFC, 0x7E, 0x1F, 0x87, 0x83, 0xC2, + 0xBC, 0x08, 0x18, 0x38, 0x78, 0xFC, 0x78, 0x78, 0x78, 0x78, 0x78, 0x78, + 0x78, 0x78, 0x79, 0x3E, 0xFB, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, + 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x3F, 0xF0, 0xFC, 0xEF, 0x08, + 0xE1, 0x1E, 0x41, 0xC8, 0x3D, 0x03, 0xC0, 0x78, 0x0E, 0x00, 0xC0, 0x10, + 0x00, 0xFD, 0xF7, 0xBC, 0x71, 0x9E, 0x38, 0x87, 0x1E, 0x43, 0xCF, 0x40, + 0xEB, 0xA0, 0x7C, 0xF0, 0x1C, 0x70, 0x0E, 0x38, 0x06, 0x08, 0x01, 0x04, + 0x00, 0xFC, 0xF7, 0x84, 0x3C, 0x81, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x80, + 0xBC, 0x13, 0xC2, 0x1E, 0xFB, 0xF0, 0xFC, 0xEF, 0x08, 0xE1, 0x1E, 0x43, + 0xC8, 0x3A, 0x07, 0xC0, 0x78, 0x0E, 0x01, 0xC0, 0x18, 0x02, 0x00, 0x41, + 0xC8, 0x3A, 0x03, 0x80, 0xFF, 0xB1, 0xE8, 0x70, 0x3C, 0x1E, 0x07, 0x83, + 0xC1, 0xE0, 0x78, 0xBC, 0x2F, 0xF8, 0x07, 0x0E, 0x1C, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1C, 0x1C, 0x1C, 0xE0, 0x18, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1E, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xE0, 0x70, 0x38, 0x38, + 0x38, 0x38, 0x38, 0x38, 0x38, 0x18, 0x07, 0x38, 0x38, 0x38, 0x38, 0x38, + 0x38, 0x38, 0x38, 0x70, 0xE0, 0x70, 0x1F, 0x8B, 0x3F, 0x01, 0xC0 }; + +const GFXglyph FreeSerifBold12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 6, 0, 1 }, // 0x20 ' ' + { 0, 4, 16, 8, 2, -15 }, // 0x21 '!' + { 8, 9, 7, 13, 2, -15 }, // 0x22 '"' + { 16, 12, 16, 12, 0, -15 }, // 0x23 '#' + { 40, 11, 20, 12, 1, -17 }, // 0x24 '$' + { 68, 18, 16, 24, 3, -15 }, // 0x25 '%' + { 104, 18, 16, 20, 1, -15 }, // 0x26 '&' + { 140, 3, 7, 7, 2, -15 }, // 0x27 ''' + { 143, 6, 21, 8, 1, -16 }, // 0x28 '(' + { 159, 6, 21, 8, 1, -16 }, // 0x29 ')' + { 175, 9, 10, 12, 2, -15 }, // 0x2A '*' + { 187, 12, 12, 16, 2, -11 }, // 0x2B '+' + { 205, 4, 8, 6, 1, -3 }, // 0x2C ',' + { 209, 6, 3, 8, 1, -6 }, // 0x2D '-' + { 212, 4, 4, 6, 1, -3 }, // 0x2E '.' + { 214, 8, 17, 7, -1, -15 }, // 0x2F '/' + { 231, 11, 16, 12, 1, -15 }, // 0x30 '0' + { 253, 9, 16, 12, 1, -15 }, // 0x31 '1' + { 271, 12, 16, 12, 0, -15 }, // 0x32 '2' + { 295, 11, 16, 12, 1, -15 }, // 0x33 '3' + { 317, 10, 16, 12, 1, -15 }, // 0x34 '4' + { 337, 11, 16, 12, 1, -15 }, // 0x35 '5' + { 359, 11, 16, 12, 1, -15 }, // 0x36 '6' + { 381, 11, 16, 12, 0, -15 }, // 0x37 '7' + { 403, 11, 16, 12, 1, -15 }, // 0x38 '8' + { 425, 11, 16, 12, 1, -15 }, // 0x39 '9' + { 447, 4, 11, 8, 2, -10 }, // 0x3A ':' + { 453, 4, 15, 8, 2, -10 }, // 0x3B ';' + { 461, 14, 14, 16, 1, -12 }, // 0x3C '<' + { 486, 14, 8, 16, 1, -9 }, // 0x3D '=' + { 500, 14, 14, 16, 1, -12 }, // 0x3E '>' + { 525, 10, 16, 12, 1, -15 }, // 0x3F '?' + { 545, 16, 16, 22, 3, -15 }, // 0x40 '@' + { 577, 17, 16, 17, 0, -15 }, // 0x41 'A' + { 611, 14, 16, 16, 1, -15 }, // 0x42 'B' + { 639, 15, 16, 17, 1, -15 }, // 0x43 'C' + { 669, 17, 16, 18, 0, -15 }, // 0x44 'D' + { 703, 15, 16, 16, 1, -15 }, // 0x45 'E' + { 733, 14, 16, 15, 1, -15 }, // 0x46 'F' + { 761, 16, 16, 19, 1, -15 }, // 0x47 'G' + { 793, 16, 16, 19, 2, -15 }, // 0x48 'H' + { 825, 8, 16, 9, 1, -15 }, // 0x49 'I' + { 841, 12, 18, 12, 0, -15 }, // 0x4A 'J' + { 868, 17, 16, 19, 2, -15 }, // 0x4B 'K' + { 902, 14, 16, 16, 2, -15 }, // 0x4C 'L' + { 930, 20, 16, 23, 1, -15 }, // 0x4D 'M' + { 970, 15, 16, 17, 1, -15 }, // 0x4E 'N' + { 1000, 17, 16, 19, 1, -15 }, // 0x4F 'O' + { 1034, 12, 16, 15, 2, -15 }, // 0x50 'P' + { 1058, 17, 20, 19, 1, -15 }, // 0x51 'Q' + { 1101, 16, 16, 17, 1, -15 }, // 0x52 'R' + { 1133, 12, 16, 14, 1, -15 }, // 0x53 'S' + { 1157, 15, 16, 15, 0, -15 }, // 0x54 'T' + { 1187, 15, 16, 17, 1, -15 }, // 0x55 'U' + { 1217, 17, 17, 17, 0, -15 }, // 0x56 'V' + { 1254, 23, 16, 24, 0, -15 }, // 0x57 'W' + { 1300, 17, 16, 17, 0, -15 }, // 0x58 'X' + { 1334, 16, 16, 17, 1, -15 }, // 0x59 'Y' + { 1366, 15, 16, 16, 0, -15 }, // 0x5A 'Z' + { 1396, 5, 20, 8, 2, -15 }, // 0x5B '[' + { 1409, 8, 17, 7, -1, -15 }, // 0x5C '\' + { 1426, 5, 20, 8, 2, -15 }, // 0x5D ']' + { 1439, 10, 9, 14, 2, -15 }, // 0x5E '^' + { 1451, 12, 1, 12, 0, 4 }, // 0x5F '_' + { 1453, 5, 4, 8, 0, -16 }, // 0x60 '`' + { 1456, 11, 11, 12, 1, -10 }, // 0x61 'a' + { 1472, 12, 16, 13, 1, -15 }, // 0x62 'b' + { 1496, 9, 11, 10, 1, -10 }, // 0x63 'c' + { 1509, 12, 16, 13, 1, -15 }, // 0x64 'd' + { 1533, 10, 11, 11, 1, -10 }, // 0x65 'e' + { 1547, 8, 16, 9, 1, -15 }, // 0x66 'f' + { 1563, 11, 16, 12, 1, -10 }, // 0x67 'g' + { 1585, 12, 16, 13, 1, -15 }, // 0x68 'h' + { 1609, 6, 16, 7, 1, -15 }, // 0x69 'i' + { 1621, 8, 21, 10, 0, -15 }, // 0x6A 'j' + { 1642, 13, 16, 13, 1, -15 }, // 0x6B 'k' + { 1668, 6, 16, 7, 1, -15 }, // 0x6C 'l' + { 1680, 19, 11, 20, 1, -10 }, // 0x6D 'm' + { 1707, 12, 11, 13, 1, -10 }, // 0x6E 'n' + { 1724, 11, 11, 12, 1, -10 }, // 0x6F 'o' + { 1740, 12, 16, 13, 1, -10 }, // 0x70 'p' + { 1764, 12, 16, 13, 1, -10 }, // 0x71 'q' + { 1788, 10, 11, 10, 1, -10 }, // 0x72 'r' + { 1802, 8, 11, 10, 1, -10 }, // 0x73 's' + { 1813, 8, 15, 8, 1, -14 }, // 0x74 't' + { 1828, 12, 11, 14, 1, -10 }, // 0x75 'u' + { 1845, 11, 11, 12, 0, -10 }, // 0x76 'v' + { 1861, 17, 11, 17, 0, -10 }, // 0x77 'w' + { 1885, 12, 11, 12, 0, -10 }, // 0x78 'x' + { 1902, 11, 16, 12, 0, -10 }, // 0x79 'y' + { 1924, 10, 11, 11, 1, -10 }, // 0x7A 'z' + { 1938, 8, 21, 9, 0, -16 }, // 0x7B '{' + { 1959, 2, 17, 5, 2, -15 }, // 0x7C '|' + { 1964, 8, 21, 9, 2, -16 }, // 0x7D '}' + { 1985, 11, 4, 12, 1, -7 } }; // 0x7E '~' + +const GFXfont FreeSerifBold12pt7b PROGMEM = { + (uint8_t *)FreeSerifBold12pt7bBitmaps, + (GFXglyph *)FreeSerifBold12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 2663 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBold18pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBold18pt7b.h new file mode 100644 index 0000000..11d3c7e --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBold18pt7b.h @@ -0,0 +1,462 @@ +const uint8_t FreeSerifBold18pt7bBitmaps[] PROGMEM = { + 0x7B, 0xEF, 0xFF, 0xFF, 0xF7, 0x9E, 0x71, 0xC7, 0x0C, 0x20, 0x82, 0x00, + 0x00, 0x07, 0x3E, 0xFF, 0xFF, 0xDC, 0x60, 0x37, 0x83, 0xFC, 0x1F, 0xE0, + 0xFF, 0x07, 0xB8, 0x3D, 0xC0, 0xCC, 0x06, 0x20, 0x31, 0x01, 0x80, 0x03, + 0x8E, 0x00, 0xC3, 0x80, 0x30, 0xE0, 0x1C, 0x38, 0x07, 0x0E, 0x01, 0xC3, + 0x87, 0xFF, 0xFD, 0xFF, 0xFF, 0x7F, 0xFF, 0xC1, 0x87, 0x00, 0xE1, 0xC0, + 0x38, 0x70, 0x0E, 0x1C, 0x03, 0x86, 0x0F, 0xFF, 0xF3, 0xFF, 0xFC, 0xFF, + 0xFF, 0x07, 0x0E, 0x01, 0xC3, 0x80, 0x70, 0xE0, 0x1C, 0x30, 0x07, 0x0C, + 0x01, 0x87, 0x00, 0x61, 0xC0, 0x02, 0x00, 0x04, 0x00, 0x08, 0x00, 0xFF, + 0x03, 0x27, 0x8C, 0x47, 0x38, 0x86, 0x71, 0x0C, 0xF2, 0x09, 0xF4, 0x03, + 0xF8, 0x03, 0xF8, 0x07, 0xFC, 0x03, 0xFC, 0x03, 0xFE, 0x01, 0xFE, 0x03, + 0xFC, 0x04, 0xFC, 0x08, 0xFA, 0x10, 0xF4, 0x21, 0xEC, 0x43, 0xD8, 0x8F, + 0x3D, 0x3C, 0x3F, 0xF0, 0x1F, 0x00, 0x08, 0x00, 0x10, 0x00, 0x03, 0xC0, + 0x18, 0x01, 0xFE, 0x0F, 0x00, 0x7C, 0xFF, 0xC0, 0x1F, 0x0F, 0x90, 0x07, + 0xC1, 0x06, 0x00, 0xF0, 0x21, 0x80, 0x3E, 0x04, 0x30, 0x07, 0x81, 0x8C, + 0x00, 0xF0, 0x21, 0x80, 0x1E, 0x0C, 0x60, 0x03, 0xC1, 0x18, 0x1E, 0x3C, + 0xE3, 0x0F, 0xE7, 0xF8, 0xC3, 0xE6, 0x3C, 0x18, 0xF8, 0x40, 0x06, 0x3E, + 0x08, 0x01, 0x87, 0x81, 0x00, 0x31, 0xF0, 0x20, 0x0C, 0x3E, 0x04, 0x01, + 0x87, 0x81, 0x00, 0x60, 0xF0, 0x60, 0x18, 0x1E, 0x08, 0x03, 0x03, 0xC7, + 0x00, 0xC0, 0x3F, 0xC0, 0x18, 0x03, 0xE0, 0x00, 0x7E, 0x00, 0x00, 0x7F, + 0xE0, 0x00, 0x38, 0xF8, 0x00, 0x1E, 0x1F, 0x00, 0x07, 0x83, 0xC0, 0x01, + 0xF0, 0xF0, 0x00, 0x7C, 0x38, 0x00, 0x1F, 0x9C, 0x00, 0x03, 0xFC, 0x00, + 0x00, 0xFE, 0x0F, 0xF0, 0x3F, 0x80, 0xF0, 0x1F, 0xF0, 0x18, 0x1C, 0xFE, + 0x0C, 0x0E, 0x1F, 0xC3, 0x07, 0x87, 0xF1, 0x81, 0xE0, 0xFE, 0x40, 0xF8, + 0x1F, 0xF0, 0x3F, 0x07, 0xF8, 0x0F, 0xC0, 0xFE, 0x03, 0xF8, 0x1F, 0xC0, + 0xFE, 0x07, 0xF8, 0x9F, 0xE3, 0xFF, 0xE7, 0xFF, 0x9F, 0xF0, 0xFF, 0xC3, + 0xF8, 0x0F, 0x80, 0x3C, 0x00, 0x6F, 0xFF, 0xFF, 0x66, 0x66, 0x00, 0x81, + 0x81, 0x81, 0x81, 0x80, 0xC0, 0xE0, 0x70, 0x70, 0x38, 0x3C, 0x1E, 0x0F, + 0x07, 0x83, 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x0E, 0x07, 0x03, 0x80, 0xE0, + 0x70, 0x18, 0x06, 0x01, 0x00, 0x40, 0x10, 0x04, 0x80, 0x30, 0x0C, 0x03, + 0x00, 0xC0, 0x60, 0x38, 0x1C, 0x07, 0x03, 0x81, 0xC0, 0xF0, 0x78, 0x3C, + 0x1E, 0x0F, 0x07, 0x83, 0xC1, 0xE0, 0xE0, 0x70, 0x38, 0x38, 0x1C, 0x0C, + 0x0C, 0x06, 0x04, 0x04, 0x04, 0x00, 0x03, 0x00, 0x1E, 0x00, 0x78, 0x1D, + 0xE6, 0xFB, 0x3D, 0xED, 0xF3, 0xFF, 0x01, 0xC0, 0x7F, 0xF3, 0xED, 0xFF, + 0x33, 0xD9, 0xE6, 0x07, 0x80, 0x1E, 0x00, 0x30, 0x00, 0x00, 0xE0, 0x00, + 0x1C, 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, + 0x38, 0x00, 0x07, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, + 0x70, 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, + 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x73, 0xEF, 0xFF, 0xFD, 0xF0, + 0xC2, 0x18, 0xC6, 0x30, 0xFF, 0xFF, 0xFF, 0xFF, 0x7B, 0xFF, 0xFF, 0xFD, + 0xE0, 0x00, 0xE0, 0x3C, 0x07, 0x00, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x1C, + 0x07, 0x00, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x1C, + 0x07, 0x00, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x00, + 0x03, 0xC0, 0x0E, 0x70, 0x1E, 0x78, 0x3C, 0x3C, 0x3C, 0x3C, 0x7C, 0x3E, + 0x7C, 0x3E, 0x7C, 0x3E, 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, + 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3E, 0x7C, 0x3E, + 0x7C, 0x3E, 0x3C, 0x3C, 0x3C, 0x3C, 0x1E, 0x78, 0x0E, 0x70, 0x03, 0xC0, + 0x00, 0xC0, 0x3C, 0x0F, 0xC3, 0xFC, 0x4F, 0xC0, 0xFC, 0x0F, 0xC0, 0xFC, + 0x0F, 0xC0, 0xFC, 0x0F, 0xC0, 0xFC, 0x0F, 0xC0, 0xFC, 0x0F, 0xC0, 0xFC, + 0x0F, 0xC0, 0xFC, 0x0F, 0xC0, 0xFC, 0x0F, 0xC0, 0xFC, 0x1F, 0xEF, 0xFF, + 0x03, 0xE0, 0x0F, 0xF8, 0x1F, 0xFC, 0x3F, 0xFC, 0x30, 0xFE, 0x60, 0x7E, + 0x40, 0x3E, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x78, + 0x00, 0x70, 0x00, 0xE0, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x06, 0x01, + 0x0C, 0x03, 0x1F, 0xFF, 0x1F, 0xFF, 0x3F, 0xFE, 0x7F, 0xFE, 0xFF, 0xFE, + 0x03, 0xF0, 0x0F, 0xF8, 0x3F, 0xFC, 0x21, 0xFE, 0x40, 0xFE, 0x00, 0x7E, + 0x00, 0x7E, 0x00, 0x7C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xFC, 0x03, 0xFE, + 0x00, 0x7E, 0x00, 0x3F, 0x00, 0x1F, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0F, + 0x00, 0x0E, 0x70, 0x0E, 0xFC, 0x1C, 0xFE, 0x38, 0x7F, 0xE0, 0x3F, 0x80, + 0x00, 0x38, 0x00, 0xF0, 0x03, 0xE0, 0x07, 0xC0, 0x1F, 0x80, 0x5F, 0x00, + 0xBE, 0x02, 0x7C, 0x08, 0xF8, 0x31, 0xF0, 0x43, 0xE1, 0x07, 0xC4, 0x0F, + 0x88, 0x1F, 0x20, 0x3E, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, + 0x07, 0xC0, 0x0F, 0x80, 0x1F, 0x00, 0x3E, 0x00, 0x7C, 0x0F, 0xFE, 0x1F, + 0xF8, 0x7F, 0xF0, 0xFF, 0xE1, 0x80, 0x03, 0x00, 0x0C, 0x00, 0x18, 0x00, + 0x3F, 0x80, 0xFF, 0xC1, 0xFF, 0xC3, 0xFF, 0xC3, 0xFF, 0x80, 0x3F, 0x80, + 0x0F, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x18, 0x00, 0x37, 0x80, 0x4F, 0x81, + 0x9F, 0xC6, 0x3F, 0xF8, 0x1F, 0x80, 0x00, 0x07, 0x00, 0x7C, 0x01, 0xF0, + 0x03, 0xC0, 0x0F, 0x80, 0x1F, 0x00, 0x1F, 0x00, 0x3E, 0x00, 0x7E, 0x00, + 0x7F, 0xF0, 0x7F, 0xFC, 0xFC, 0x7E, 0xFC, 0x7E, 0xFC, 0x3F, 0xFC, 0x3F, + 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, 0x7C, 0x3F, 0x7C, 0x3E, 0x3C, 0x3E, + 0x3E, 0x3C, 0x1E, 0x78, 0x07, 0xE0, 0x7F, 0xFF, 0x7F, 0xFE, 0x7F, 0xFE, + 0xFF, 0xFE, 0xFF, 0xFC, 0xC0, 0x1C, 0x80, 0x18, 0x80, 0x38, 0x00, 0x38, + 0x00, 0x70, 0x00, 0x70, 0x00, 0x70, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, + 0x01, 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x03, 0x80, 0x03, 0x80, 0x07, 0x80, + 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x0F, 0xE0, 0x38, 0x78, 0x70, 0x3C, + 0xF0, 0x1E, 0xF0, 0x1E, 0xF8, 0x1E, 0xF8, 0x1E, 0xFE, 0x3C, 0x7F, 0xB0, + 0x7F, 0xE0, 0x3F, 0xF0, 0x0F, 0xF8, 0x1F, 0xFC, 0x39, 0xFE, 0x70, 0xFF, + 0xF0, 0x3F, 0xF0, 0x3F, 0xF0, 0x1F, 0xF0, 0x1F, 0xF0, 0x1E, 0x78, 0x3E, + 0x7C, 0x7C, 0x3F, 0xF8, 0x0F, 0xE0, 0x07, 0xE0, 0x1E, 0x78, 0x3C, 0x7C, + 0x7C, 0x3C, 0x7C, 0x3E, 0xFC, 0x3E, 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, + 0xFC, 0x3F, 0xFC, 0x3F, 0x7E, 0x3F, 0x7E, 0x3F, 0x3F, 0xFE, 0x0F, 0xFE, + 0x00, 0x7E, 0x00, 0x7C, 0x00, 0xF8, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xC0, + 0x0F, 0x80, 0x3E, 0x00, 0xE0, 0x00, 0x7B, 0xFF, 0xFF, 0xFD, 0xE0, 0x00, + 0x00, 0x07, 0xBF, 0xFF, 0xFF, 0xDE, 0x39, 0xFB, 0xF7, 0xEF, 0xC7, 0x00, + 0x00, 0x00, 0x01, 0xE7, 0xEF, 0xFF, 0xFF, 0xBF, 0x06, 0x08, 0x30, 0xC2, + 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x0F, 0x80, 0x07, 0xF0, + 0x03, 0xFC, 0x01, 0xFE, 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x3F, 0x80, 0x1F, + 0xC0, 0x03, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0xFE, 0x00, 0x07, 0xF0, 0x00, + 0x3F, 0x80, 0x01, 0xFE, 0x00, 0x0F, 0xE0, 0x00, 0x7C, 0x00, 0x01, 0x80, + 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x18, 0x00, 0x03, + 0xE0, 0x00, 0x7F, 0x00, 0x07, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0xFE, 0x00, + 0x07, 0xF0, 0x00, 0x3F, 0x80, 0x01, 0xFC, 0x00, 0x3F, 0x80, 0x1F, 0xC0, + 0x0F, 0xE0, 0x07, 0xF0, 0x07, 0xF8, 0x03, 0xFC, 0x00, 0xFE, 0x00, 0x1F, + 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xC0, 0xFF, 0xC7, 0x1F, + 0xB8, 0x3E, 0xF0, 0xFF, 0xC3, 0xFF, 0x0F, 0xD8, 0x3F, 0x00, 0xF8, 0x07, + 0xC0, 0x1E, 0x00, 0x60, 0x03, 0x00, 0x08, 0x00, 0x20, 0x00, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x70, 0x03, 0xE0, 0x1F, 0x80, 0x7E, 0x01, 0xF8, 0x01, + 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFF, 0xE0, 0x07, 0xC0, 0xF0, 0x0F, 0x00, + 0x38, 0x1E, 0x00, 0x0C, 0x3C, 0x07, 0x06, 0x38, 0x1F, 0x72, 0x78, 0x3C, + 0xF3, 0x78, 0x78, 0xE1, 0xF0, 0x70, 0xE1, 0xF0, 0xF0, 0xE1, 0xF0, 0xE0, + 0xC1, 0xF1, 0xE1, 0xC1, 0xF1, 0xC1, 0xC1, 0xF1, 0xC3, 0x82, 0xF1, 0xC3, + 0x86, 0x71, 0xC7, 0x8C, 0x79, 0xFB, 0xF8, 0x78, 0xF1, 0xF0, 0x3C, 0x00, + 0x00, 0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0xC0, 0x78, 0x03, 0xFF, + 0xE0, 0x00, 0x7F, 0x80, 0x00, 0x10, 0x00, 0x00, 0x38, 0x00, 0x00, 0x38, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0xFE, 0x00, 0x01, 0xBF, 0x00, 0x01, 0xBF, 0x00, 0x01, 0x1F, + 0x00, 0x03, 0x1F, 0x80, 0x02, 0x1F, 0x80, 0x06, 0x0F, 0xC0, 0x06, 0x0F, + 0xC0, 0x04, 0x07, 0xE0, 0x0F, 0xFF, 0xE0, 0x0F, 0xFF, 0xE0, 0x18, 0x03, + 0xF0, 0x18, 0x03, 0xF0, 0x30, 0x01, 0xF8, 0x30, 0x01, 0xF8, 0x70, 0x01, + 0xFC, 0xFE, 0x0F, 0xFF, 0xFF, 0xFE, 0x07, 0xFF, 0xFE, 0x0F, 0xE1, 0xF8, + 0x3F, 0x07, 0xC1, 0xF8, 0x3F, 0x0F, 0xC1, 0xF8, 0x7E, 0x0F, 0xC3, 0xF0, + 0x7E, 0x1F, 0x87, 0xE0, 0xFC, 0x7C, 0x07, 0xFF, 0x00, 0x3F, 0xFF, 0x01, + 0xF8, 0xFE, 0x0F, 0xC1, 0xF8, 0x7E, 0x0F, 0xC3, 0xF0, 0x3F, 0x1F, 0x81, + 0xF8, 0xFC, 0x0F, 0xC7, 0xE0, 0x7E, 0x3F, 0x03, 0xF1, 0xF8, 0x3F, 0x0F, + 0xC3, 0xF0, 0xFF, 0xFF, 0x1F, 0xFF, 0xC0, 0x00, 0x7E, 0x04, 0x07, 0xFF, + 0x18, 0x1F, 0x07, 0xF0, 0x7C, 0x03, 0xE1, 0xF0, 0x03, 0xC7, 0xC0, 0x03, + 0x9F, 0x80, 0x03, 0x3F, 0x00, 0x06, 0x7C, 0x00, 0x05, 0xF8, 0x00, 0x03, + 0xF0, 0x00, 0x07, 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x1F, 0x80, 0x00, 0x3F, + 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x01, 0xF8, + 0x00, 0x01, 0xF0, 0x00, 0x23, 0xF0, 0x00, 0xC3, 0xF0, 0x07, 0x03, 0xF0, + 0x3C, 0x01, 0xFF, 0xE0, 0x00, 0xFF, 0x00, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, + 0x00, 0x7E, 0x1F, 0x80, 0xFC, 0x1F, 0x81, 0xF8, 0x1F, 0x83, 0xF0, 0x1F, + 0x07, 0xE0, 0x3F, 0x0F, 0xC0, 0x7E, 0x1F, 0x80, 0x7E, 0x3F, 0x00, 0xFC, + 0x7E, 0x01, 0xF8, 0xFC, 0x03, 0xF1, 0xF8, 0x07, 0xE3, 0xF0, 0x0F, 0xC7, + 0xE0, 0x1F, 0x8F, 0xC0, 0x3F, 0x1F, 0x80, 0x7C, 0x3F, 0x01, 0xF8, 0x7E, + 0x03, 0xE0, 0xFC, 0x0F, 0x81, 0xF8, 0x1F, 0x03, 0xF0, 0xFC, 0x0F, 0xFF, + 0xE0, 0x7F, 0xFF, 0x00, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0x0F, 0xC0, 0x78, + 0x7E, 0x01, 0xC3, 0xF0, 0x06, 0x1F, 0x80, 0x10, 0xFC, 0x10, 0x87, 0xE0, + 0x80, 0x3F, 0x0C, 0x01, 0xF8, 0xE0, 0x0F, 0xFF, 0x00, 0x7F, 0xF8, 0x03, + 0xF1, 0xC0, 0x1F, 0x86, 0x00, 0xFC, 0x10, 0x07, 0xE0, 0x80, 0x3F, 0x00, + 0x09, 0xF8, 0x00, 0xCF, 0xC0, 0x0C, 0x7E, 0x00, 0x63, 0xF0, 0x0F, 0x1F, + 0x81, 0xFB, 0xFF, 0xFF, 0xDF, 0xFF, 0xFC, 0xFF, 0xFF, 0xEF, 0xFF, 0xFC, + 0xFC, 0x0F, 0x9F, 0x80, 0x73, 0xF0, 0x06, 0x7E, 0x00, 0x4F, 0xC1, 0x09, + 0xF8, 0x20, 0x3F, 0x0C, 0x07, 0xE3, 0x80, 0xFF, 0xF0, 0x1F, 0xFE, 0x03, + 0xF1, 0xC0, 0x7E, 0x18, 0x0F, 0xC1, 0x01, 0xF8, 0x20, 0x3F, 0x00, 0x07, + 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x1F, + 0xE0, 0x07, 0xFF, 0x00, 0x00, 0x7E, 0x02, 0x01, 0xFF, 0xE3, 0x01, 0xF0, + 0x3F, 0x81, 0xF0, 0x07, 0xC1, 0xF0, 0x01, 0xE1, 0xF0, 0x00, 0x71, 0xF8, + 0x00, 0x18, 0xFC, 0x00, 0x0C, 0x7C, 0x00, 0x02, 0x7E, 0x00, 0x00, 0x3F, + 0x00, 0x00, 0x1F, 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03, + 0xF0, 0x0F, 0xFF, 0xF8, 0x01, 0xFE, 0x7C, 0x00, 0x7E, 0x3F, 0x00, 0x3F, + 0x1F, 0x80, 0x1F, 0x87, 0xC0, 0x0F, 0xC1, 0xF0, 0x07, 0xE0, 0xFC, 0x03, + 0xF0, 0x1F, 0x83, 0xF0, 0x07, 0xFF, 0xE0, 0x00, 0x7F, 0x80, 0x00, 0xFF, + 0xC3, 0xFF, 0x7F, 0x81, 0xFE, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, + 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, + 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0xFF, 0xFC, 0x3F, 0xFF, 0xFC, 0x3F, + 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, + 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, + 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x7F, 0x81, 0xFE, 0xFF, 0xC3, 0xFF, 0xFF, + 0xEF, 0xF0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x07, + 0xE0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x07, 0xE0, + 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x1F, 0xE7, 0xFF, 0x07, 0xFF, 0x01, 0xFE, + 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, + 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, + 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, + 0x70, 0xFC, 0xF8, 0xFC, 0xF8, 0xF8, 0xF0, 0xF8, 0x71, 0xF0, 0x7F, 0xE0, + 0x1F, 0x80, 0xFF, 0xC3, 0xFF, 0x3F, 0xC0, 0x3E, 0x0F, 0xC0, 0x1C, 0x07, + 0xE0, 0x18, 0x03, 0xF0, 0x18, 0x01, 0xF8, 0x18, 0x00, 0xFC, 0x18, 0x00, + 0x7E, 0x18, 0x00, 0x3F, 0x18, 0x00, 0x1F, 0x9C, 0x00, 0x0F, 0xDF, 0x00, + 0x07, 0xFF, 0xC0, 0x03, 0xFF, 0xF0, 0x01, 0xF9, 0xF8, 0x00, 0xFC, 0xFE, + 0x00, 0x7E, 0x3F, 0x80, 0x3F, 0x0F, 0xE0, 0x1F, 0x83, 0xF8, 0x0F, 0xC0, + 0xFC, 0x07, 0xE0, 0x7F, 0x03, 0xF0, 0x1F, 0xC1, 0xF8, 0x07, 0xF1, 0xFE, + 0x03, 0xFD, 0xFF, 0x8F, 0xFF, 0xFF, 0xE0, 0x03, 0xFC, 0x00, 0x0F, 0xC0, + 0x00, 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, + 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0x7E, 0x00, + 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x01, 0x3F, + 0x00, 0x19, 0xF8, 0x00, 0xCF, 0xC0, 0x0C, 0x7E, 0x00, 0x63, 0xF0, 0x0F, + 0x1F, 0x81, 0xFB, 0xFF, 0xFF, 0xDF, 0xFF, 0xFE, 0xFF, 0x80, 0x03, 0xFE, + 0x7F, 0x00, 0x07, 0xF8, 0x7E, 0x00, 0x0F, 0xE0, 0xFE, 0x00, 0x3F, 0xC1, + 0x7C, 0x00, 0x5F, 0x82, 0xFC, 0x01, 0xBF, 0x05, 0xF8, 0x02, 0x7E, 0x09, + 0xF8, 0x0C, 0xFC, 0x13, 0xF0, 0x11, 0xF8, 0x23, 0xE0, 0x23, 0xF0, 0x47, + 0xE0, 0xC7, 0xE0, 0x87, 0xC1, 0x0F, 0xC1, 0x0F, 0xC6, 0x1F, 0x82, 0x0F, + 0x88, 0x3F, 0x04, 0x1F, 0xB0, 0x7E, 0x08, 0x3F, 0x60, 0xFC, 0x10, 0x3E, + 0x81, 0xF8, 0x20, 0x7F, 0x03, 0xF0, 0x40, 0x7C, 0x07, 0xE0, 0x80, 0xF8, + 0x0F, 0xC1, 0x00, 0xE0, 0x1F, 0x82, 0x01, 0xC0, 0x3F, 0x0E, 0x03, 0x80, + 0xFF, 0x7F, 0x82, 0x03, 0xFF, 0xFE, 0x00, 0xFE, 0xFE, 0x00, 0x70, 0xFE, + 0x00, 0x40, 0xFE, 0x00, 0x81, 0xFC, 0x01, 0x03, 0xFC, 0x02, 0x05, 0xFC, + 0x04, 0x09, 0xFC, 0x08, 0x11, 0xFC, 0x10, 0x23, 0xF8, 0x20, 0x43, 0xF8, + 0x40, 0x83, 0xF8, 0x81, 0x03, 0xF9, 0x02, 0x03, 0xFA, 0x04, 0x03, 0xF4, + 0x08, 0x07, 0xF8, 0x10, 0x07, 0xF0, 0x20, 0x07, 0xE0, 0x40, 0x07, 0xC0, + 0x80, 0x07, 0x81, 0x00, 0x0F, 0x02, 0x00, 0x0E, 0x0E, 0x00, 0x0C, 0x7F, + 0x00, 0x08, 0x00, 0x7F, 0x00, 0x01, 0xFF, 0xF0, 0x01, 0xF0, 0x7C, 0x01, + 0xF0, 0x1F, 0x01, 0xF0, 0x07, 0xC1, 0xF0, 0x01, 0xF1, 0xF8, 0x00, 0xFC, + 0xFC, 0x00, 0x7E, 0x7C, 0x00, 0x1F, 0x7E, 0x00, 0x0F, 0xFF, 0x00, 0x07, + 0xFF, 0x80, 0x03, 0xFF, 0xC0, 0x01, 0xFF, 0xE0, 0x00, 0xFF, 0xF0, 0x00, + 0x7F, 0xF8, 0x00, 0x3F, 0x7C, 0x00, 0x1F, 0x3E, 0x00, 0x1F, 0x9F, 0x80, + 0x0F, 0xC7, 0xC0, 0x07, 0xC1, 0xF0, 0x07, 0xC0, 0xFC, 0x07, 0xE0, 0x3F, + 0x07, 0xC0, 0x07, 0xFF, 0xC0, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0xFC, 0x0F, + 0xFF, 0xE0, 0xFC, 0x7E, 0x1F, 0x87, 0xE3, 0xF0, 0x7E, 0x7E, 0x0F, 0xCF, + 0xC1, 0xF9, 0xF8, 0x3F, 0x3F, 0x07, 0xE7, 0xE0, 0xFC, 0xFC, 0x3F, 0x1F, + 0x8F, 0xC3, 0xFF, 0xF0, 0x7F, 0xF8, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, + 0x00, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, + 0x00, 0x1F, 0xE0, 0x07, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x01, 0xFF, 0xF0, + 0x01, 0xF0, 0x7C, 0x01, 0xF0, 0x1F, 0x01, 0xF0, 0x07, 0xC1, 0xF0, 0x01, + 0xF1, 0xF8, 0x00, 0xFC, 0xFC, 0x00, 0x7E, 0x7C, 0x00, 0x1F, 0x7E, 0x00, + 0x0F, 0xFF, 0x00, 0x07, 0xFF, 0x80, 0x03, 0xFF, 0xC0, 0x01, 0xFF, 0xE0, + 0x00, 0xFF, 0xF0, 0x00, 0x7F, 0xF8, 0x00, 0x3F, 0x7C, 0x00, 0x1F, 0x3E, + 0x00, 0x0F, 0x9F, 0x80, 0x0F, 0xC7, 0xC0, 0x07, 0xC1, 0xF0, 0x07, 0xC0, + 0x78, 0x03, 0xC0, 0x1E, 0x07, 0xC0, 0x03, 0xFF, 0x80, 0x00, 0x7F, 0x00, + 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFF, + 0xF8, 0x00, 0x0F, 0xE0, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0x00, 0xFC, 0x3F, + 0x01, 0xF8, 0x3F, 0x03, 0xF0, 0x3F, 0x07, 0xE0, 0x7E, 0x0F, 0xC0, 0xFC, + 0x1F, 0x81, 0xF8, 0x3F, 0x03, 0xF0, 0x7E, 0x07, 0xC0, 0xFC, 0x1F, 0x81, + 0xF8, 0x7E, 0x03, 0xFF, 0xF0, 0x07, 0xFF, 0xC0, 0x0F, 0xDF, 0xC0, 0x1F, + 0x9F, 0x80, 0x3F, 0x1F, 0x80, 0x7E, 0x3F, 0x80, 0xFC, 0x3F, 0x81, 0xF8, + 0x3F, 0x03, 0xF0, 0x7F, 0x07, 0xE0, 0x7F, 0x1F, 0xE0, 0x7F, 0x7F, 0xE0, + 0xFF, 0x07, 0xC2, 0x1F, 0xF2, 0x3C, 0x3E, 0x70, 0x0E, 0xF0, 0x06, 0xF0, + 0x06, 0xF0, 0x02, 0xF8, 0x00, 0xFE, 0x00, 0xFF, 0x80, 0x7F, 0xE0, 0x3F, + 0xF8, 0x1F, 0xFC, 0x0F, 0xFE, 0x03, 0xFE, 0x00, 0xFF, 0x00, 0x3F, 0x80, + 0x1F, 0xC0, 0x0F, 0xC0, 0x0F, 0xE0, 0x0E, 0xF0, 0x1E, 0xF8, 0x3C, 0x9F, + 0xF8, 0x87, 0xE0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x7E, 0x3F, 0x83, + 0xF0, 0x7C, 0x1F, 0x81, 0xC0, 0xFC, 0x06, 0x07, 0xE0, 0x20, 0x3F, 0x00, + 0x01, 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x1F, + 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF8, 0x00, + 0x0F, 0xC0, 0x00, 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, + 0x00, 0x0F, 0xF0, 0x01, 0xFF, 0xE0, 0xFF, 0xC1, 0xFD, 0xFE, 0x01, 0xC3, + 0xF0, 0x02, 0x0F, 0xC0, 0x08, 0x3F, 0x00, 0x20, 0xFC, 0x00, 0x83, 0xF0, + 0x02, 0x0F, 0xC0, 0x08, 0x3F, 0x00, 0x20, 0xFC, 0x00, 0x83, 0xF0, 0x02, + 0x0F, 0xC0, 0x08, 0x3F, 0x00, 0x20, 0xFC, 0x00, 0x83, 0xF0, 0x02, 0x0F, + 0xC0, 0x08, 0x3F, 0x00, 0x20, 0xFC, 0x00, 0x83, 0xF0, 0x02, 0x0F, 0xC0, + 0x18, 0x1F, 0x80, 0x40, 0x7E, 0x03, 0x00, 0xFC, 0x18, 0x01, 0xFF, 0xC0, + 0x00, 0xFC, 0x00, 0xFF, 0xF0, 0x7F, 0x3F, 0xC0, 0x1E, 0x1F, 0x80, 0x0C, + 0x1F, 0x80, 0x08, 0x0F, 0xC0, 0x18, 0x0F, 0xC0, 0x18, 0x07, 0xE0, 0x10, + 0x07, 0xE0, 0x30, 0x07, 0xE0, 0x20, 0x03, 0xF0, 0x60, 0x03, 0xF0, 0x60, + 0x01, 0xF8, 0x40, 0x01, 0xF8, 0xC0, 0x00, 0xF8, 0x80, 0x00, 0xFC, 0x80, + 0x00, 0xFD, 0x80, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3E, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x1C, 0x00, + 0x00, 0x0C, 0x00, 0xFF, 0xE7, 0xFF, 0x0F, 0xCF, 0xE0, 0x7F, 0x00, 0xE1, + 0xF8, 0x0F, 0xC0, 0x30, 0x7E, 0x03, 0xF0, 0x0C, 0x1F, 0x80, 0x7C, 0x02, + 0x03, 0xE0, 0x1F, 0x81, 0x80, 0xFC, 0x07, 0xE0, 0x60, 0x3F, 0x03, 0xF8, + 0x10, 0x07, 0xC0, 0xBF, 0x0C, 0x01, 0xF8, 0x2F, 0xC3, 0x00, 0x7E, 0x19, + 0xF0, 0x80, 0x0F, 0x84, 0x7C, 0x60, 0x03, 0xF3, 0x0F, 0x98, 0x00, 0xFC, + 0xC3, 0xE4, 0x00, 0x1F, 0x20, 0xFB, 0x00, 0x07, 0xF8, 0x1F, 0xC0, 0x00, + 0xFC, 0x07, 0xE0, 0x00, 0x3F, 0x01, 0xF8, 0x00, 0x0F, 0xC0, 0x3E, 0x00, + 0x01, 0xE0, 0x0F, 0x00, 0x00, 0x78, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x70, + 0x00, 0x03, 0x00, 0x18, 0x00, 0x00, 0xC0, 0x06, 0x00, 0x00, 0x20, 0x00, + 0x80, 0x00, 0xFF, 0xF3, 0xFE, 0x7F, 0x80, 0x78, 0x3F, 0x80, 0x70, 0x1F, + 0xC0, 0x60, 0x0F, 0xC0, 0xC0, 0x0F, 0xE1, 0x80, 0x07, 0xF1, 0x00, 0x03, + 0xF3, 0x00, 0x03, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0x80, 0x00, + 0x9F, 0x80, 0x01, 0x8F, 0xC0, 0x03, 0x0F, 0xE0, 0x06, 0x07, 0xE0, 0x06, + 0x07, 0xF0, 0x0C, 0x03, 0xF8, 0x1C, 0x03, 0xF8, 0x3C, 0x03, 0xFC, 0xFF, + 0x0F, 0xFF, 0xFF, 0xF0, 0xFF, 0x7F, 0x80, 0x1E, 0x3F, 0x80, 0x1C, 0x1F, + 0x80, 0x18, 0x1F, 0xC0, 0x10, 0x0F, 0xC0, 0x30, 0x07, 0xE0, 0x20, 0x07, + 0xE0, 0x60, 0x03, 0xF0, 0xC0, 0x03, 0xF0, 0x80, 0x01, 0xF9, 0x80, 0x01, + 0xFF, 0x00, 0x00, 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFF, 0x00, 0x01, + 0xFF, 0x80, 0x7F, 0xFF, 0xF3, 0xFF, 0xFF, 0x9F, 0x01, 0xF8, 0xE0, 0x1F, + 0x86, 0x01, 0xFC, 0x20, 0x0F, 0xC1, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, + 0x7E, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x80, + 0x01, 0xF8, 0x00, 0x1F, 0x80, 0x01, 0xFC, 0x01, 0x0F, 0xC0, 0x18, 0xFC, + 0x00, 0xC7, 0xE0, 0x06, 0x7E, 0x00, 0x77, 0xF0, 0x07, 0x3F, 0x00, 0xFB, + 0xFF, 0xFF, 0xDF, 0xFF, 0xFE, 0xFF, 0xFF, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xFF, 0xFF, 0xE0, 0x1E, + 0x01, 0xC0, 0x38, 0x07, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x1C, 0x03, 0x80, + 0x70, 0x07, 0x00, 0xE0, 0x1C, 0x01, 0xC0, 0x38, 0x07, 0x00, 0x70, 0x0E, + 0x01, 0xC0, 0x1C, 0x03, 0x80, 0x70, 0x0F, 0x00, 0xE0, 0xFF, 0xFF, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0xFF, 0xFF, 0x03, 0x80, 0x0F, 0x00, 0x1F, 0x00, 0x7E, 0x00, 0xEE, 0x03, + 0x9C, 0x07, 0x1C, 0x1C, 0x38, 0x38, 0x38, 0xE0, 0x71, 0xC0, 0x77, 0x00, + 0xEE, 0x00, 0xE0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xE0, 0xF0, + 0x78, 0x3C, 0x0E, 0x07, 0x0F, 0xE0, 0x3F, 0xF0, 0x78, 0xF8, 0x78, 0x7C, + 0x78, 0x7C, 0x38, 0x7C, 0x00, 0x7C, 0x03, 0xFC, 0x1E, 0x7C, 0x7C, 0x7C, + 0xFC, 0x7C, 0xFC, 0x7C, 0xFC, 0xFC, 0xFF, 0xFD, 0x7F, 0x7F, 0x3C, 0x3C, + 0xFC, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1F, + 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0xF8, 0x1F, 0x7F, 0x87, 0xE3, + 0xF1, 0xF0, 0x7E, 0x7C, 0x0F, 0x9F, 0x03, 0xF7, 0xC0, 0xFD, 0xF0, 0x3F, + 0x7C, 0x0F, 0xDF, 0x03, 0xF7, 0xC0, 0xFD, 0xF0, 0x3E, 0x7C, 0x1F, 0x1F, + 0x8F, 0xC6, 0x7F, 0xC1, 0x07, 0xC0, 0x07, 0xC0, 0x7F, 0xC3, 0xC7, 0x9F, + 0x1E, 0x78, 0x7B, 0xE1, 0xCF, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, + 0x80, 0x3F, 0x00, 0x7C, 0x00, 0xFC, 0x61, 0xFF, 0x03, 0xF0, 0x00, 0x7F, + 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xC0, + 0x01, 0xF0, 0x00, 0x7C, 0x07, 0x9F, 0x07, 0xF7, 0xC3, 0xE3, 0xF1, 0xF8, + 0x7C, 0x7C, 0x1F, 0x3F, 0x07, 0xCF, 0xC1, 0xF3, 0xF0, 0x7C, 0xFC, 0x1F, + 0x3F, 0x07, 0xCF, 0xC1, 0xF1, 0xF0, 0x7C, 0x7E, 0x1F, 0x0F, 0x8F, 0xC1, + 0xFD, 0xFC, 0x3E, 0x70, 0x0F, 0xC0, 0x7F, 0xC3, 0xC7, 0x1E, 0x1E, 0xF8, + 0x7B, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0xC0, 0x1F, + 0x03, 0x7E, 0x18, 0xFF, 0xC1, 0xFE, 0x03, 0xF0, 0x0F, 0x83, 0xF8, 0xF3, + 0xBE, 0xF7, 0xDC, 0xF8, 0x1F, 0x03, 0xE0, 0xFF, 0x1F, 0xE1, 0xF0, 0x3E, + 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, + 0xC0, 0xF8, 0x1F, 0x07, 0xF8, 0x0F, 0xC0, 0x1F, 0xFF, 0xDF, 0x1F, 0xFF, + 0x07, 0x8F, 0x83, 0xE7, 0xC1, 0xF3, 0xE0, 0xF9, 0xF0, 0x7C, 0x78, 0x3C, + 0x1E, 0x3E, 0x03, 0xFC, 0x03, 0x00, 0x07, 0x00, 0x07, 0x80, 0x03, 0xFF, + 0xF1, 0xFF, 0xFE, 0x7F, 0xFF, 0x8F, 0xFF, 0xF8, 0x01, 0xFC, 0x00, 0x7F, + 0x00, 0x73, 0xFF, 0xF0, 0x7F, 0xC0, 0xFC, 0x00, 0x3E, 0x00, 0x1F, 0x00, + 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x7C, + 0x7C, 0x3E, 0xFF, 0x1F, 0xCF, 0xCF, 0x83, 0xE7, 0xC1, 0xF3, 0xE0, 0xF9, + 0xF0, 0x7C, 0xF8, 0x3E, 0x7C, 0x1F, 0x3E, 0x0F, 0x9F, 0x07, 0xCF, 0x83, + 0xE7, 0xC1, 0xF3, 0xE0, 0xF9, 0xF0, 0x7D, 0xFC, 0x7F, 0x39, 0xFB, 0xF7, + 0xE7, 0x80, 0x00, 0x00, 0xFC, 0xF9, 0xF3, 0xE7, 0xCF, 0x9F, 0x3E, 0x7C, + 0xF9, 0xF3, 0xE7, 0xCF, 0x9F, 0x7F, 0x03, 0xC0, 0xFC, 0x1F, 0x83, 0xF0, + 0x3C, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, + 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, + 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7D, 0xCF, 0xF9, 0xEE, 0x7C, 0xFF, 0x0F, + 0x80, 0xFC, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x7F, 0x9F, 0x07, 0x87, + 0xC1, 0x81, 0xF0, 0xC0, 0x7C, 0x60, 0x1F, 0x30, 0x07, 0xDE, 0x01, 0xFF, + 0xC0, 0x7F, 0xF0, 0x1F, 0x3E, 0x07, 0xCF, 0xC1, 0xF1, 0xF8, 0x7C, 0x3E, + 0x1F, 0x07, 0xC7, 0xC1, 0xFB, 0xF9, 0xFF, 0xFC, 0xF9, 0xF3, 0xE7, 0xCF, + 0x9F, 0x3E, 0x7C, 0xF9, 0xF3, 0xE7, 0xCF, 0x9F, 0x3E, 0x7C, 0xF9, 0xF3, + 0xE7, 0xCF, 0x9F, 0x7F, 0xFC, 0x7C, 0x1F, 0x0F, 0xBF, 0xCF, 0xF1, 0xF8, + 0xFF, 0x3F, 0x3E, 0x0F, 0x83, 0xE7, 0xC1, 0xF0, 0x7C, 0xF8, 0x3E, 0x0F, + 0x9F, 0x07, 0xC1, 0xF3, 0xE0, 0xF8, 0x3E, 0x7C, 0x1F, 0x07, 0xCF, 0x83, + 0xE0, 0xF9, 0xF0, 0x7C, 0x1F, 0x3E, 0x0F, 0x83, 0xE7, 0xC1, 0xF0, 0x7C, + 0xF8, 0x3E, 0x0F, 0x9F, 0x07, 0xC1, 0xF7, 0xF1, 0xFC, 0x7F, 0xFC, 0x7C, + 0x3E, 0xFF, 0x1F, 0xCF, 0xCF, 0x83, 0xE7, 0xC1, 0xF3, 0xE0, 0xF9, 0xF0, + 0x7C, 0xF8, 0x3E, 0x7C, 0x1F, 0x3E, 0x0F, 0x9F, 0x07, 0xCF, 0x83, 0xE7, + 0xC1, 0xF3, 0xE0, 0xF9, 0xF0, 0x7D, 0xFC, 0x7F, 0x07, 0xF0, 0x0F, 0xFE, + 0x0F, 0x8F, 0x8F, 0x87, 0xE7, 0xC1, 0xF7, 0xE0, 0xFF, 0xF0, 0x7F, 0xF8, + 0x3F, 0xFC, 0x1F, 0xFE, 0x0F, 0xFF, 0x07, 0xEF, 0x83, 0xE7, 0xC1, 0xF1, + 0xF1, 0xF0, 0x7F, 0xF0, 0x0F, 0xE0, 0xFE, 0x7C, 0x07, 0xDF, 0xE0, 0xFE, + 0x3E, 0x1F, 0x07, 0xE3, 0xE0, 0x7C, 0x7C, 0x0F, 0xCF, 0x81, 0xF9, 0xF0, + 0x3F, 0x3E, 0x07, 0xE7, 0xC0, 0xFC, 0xF8, 0x1F, 0x9F, 0x03, 0xE3, 0xE0, + 0xFC, 0x7E, 0x3F, 0x0F, 0xBF, 0xC1, 0xF3, 0xE0, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7E, 0x00, 0x1F, 0xE0, + 0x00, 0x07, 0xC1, 0x0F, 0xF9, 0x8F, 0xCD, 0xCF, 0xC3, 0xE7, 0xC1, 0xF7, + 0xE0, 0xFB, 0xF0, 0x7D, 0xF8, 0x3E, 0xFC, 0x1F, 0x7E, 0x0F, 0xBF, 0x07, + 0xDF, 0x83, 0xE7, 0xE1, 0xF1, 0xF1, 0xF8, 0x7F, 0x7C, 0x1F, 0x3E, 0x00, + 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x01, 0xF8, + 0x01, 0xFE, 0xFC, 0x73, 0xEF, 0xDF, 0xFE, 0xFC, 0xF7, 0xC3, 0xBE, 0x01, + 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x3E, + 0x01, 0xF0, 0x1F, 0xE0, 0x1E, 0x23, 0xFE, 0x70, 0xEE, 0x06, 0xE0, 0x2F, + 0x80, 0xFF, 0x07, 0xFC, 0x3F, 0xE0, 0xFF, 0x81, 0xF8, 0x07, 0xC0, 0x7E, + 0x0E, 0xBF, 0xC8, 0xF8, 0x04, 0x03, 0x01, 0xC0, 0xF0, 0x7C, 0x3F, 0xEF, + 0xF9, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, + 0x7C, 0x5F, 0x37, 0xF8, 0xFE, 0x1E, 0x00, 0xFC, 0x7F, 0x1F, 0x07, 0xC7, + 0xC1, 0xF1, 0xF0, 0x7C, 0x7C, 0x1F, 0x1F, 0x07, 0xC7, 0xC1, 0xF1, 0xF0, + 0x7C, 0x7C, 0x1F, 0x1F, 0x07, 0xC7, 0xC1, 0xF1, 0xF0, 0x7C, 0x7C, 0x1F, + 0x1F, 0x8F, 0xC3, 0xFD, 0xFC, 0x7C, 0x60, 0xFF, 0x9F, 0xBF, 0x83, 0x0F, + 0x81, 0x87, 0xE0, 0x81, 0xF0, 0x40, 0xF8, 0x40, 0x3E, 0x20, 0x1F, 0x30, + 0x07, 0xD0, 0x03, 0xF8, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3C, 0x00, 0x0E, + 0x00, 0x07, 0x00, 0x01, 0x00, 0xFF, 0x3F, 0xCF, 0x7E, 0x1F, 0x06, 0x3E, + 0x0F, 0x06, 0x3E, 0x0F, 0x84, 0x1F, 0x0F, 0x8C, 0x1F, 0x1F, 0x88, 0x0F, + 0x17, 0xC8, 0x0F, 0x97, 0xD8, 0x0F, 0xB3, 0xD0, 0x07, 0xE3, 0xF0, 0x07, + 0xE3, 0xE0, 0x03, 0xC1, 0xE0, 0x03, 0xC1, 0xE0, 0x03, 0x81, 0xC0, 0x01, + 0x80, 0xC0, 0x01, 0x80, 0x80, 0xFF, 0x3F, 0x7E, 0x0C, 0x3E, 0x08, 0x3F, + 0x18, 0x1F, 0x30, 0x0F, 0xE0, 0x0F, 0xC0, 0x07, 0xE0, 0x03, 0xE0, 0x03, + 0xF0, 0x05, 0xF8, 0x0C, 0xF8, 0x18, 0xFC, 0x30, 0x7E, 0x70, 0x7E, 0xFC, + 0xFF, 0xFF, 0x3F, 0x7E, 0x0C, 0x7C, 0x0C, 0x3E, 0x08, 0x3E, 0x08, 0x1E, + 0x18, 0x1F, 0x10, 0x0F, 0x30, 0x0F, 0xA0, 0x0F, 0xA0, 0x07, 0xE0, 0x07, + 0xC0, 0x03, 0xC0, 0x03, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x00, 0x01, + 0x00, 0x61, 0x00, 0xF2, 0x00, 0xF6, 0x00, 0xFC, 0x00, 0x78, 0x00, 0x7F, + 0xFD, 0xFF, 0xF7, 0x0F, 0xD0, 0x3E, 0x01, 0xF0, 0x0F, 0xC0, 0x3E, 0x01, + 0xF0, 0x0F, 0xC0, 0x3E, 0x01, 0xF8, 0x0F, 0xC1, 0x3E, 0x05, 0xF8, 0x7F, + 0xFF, 0xFF, 0xFF, 0x01, 0xE0, 0xF8, 0x3E, 0x07, 0x80, 0xF0, 0x1E, 0x03, + 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x07, 0x87, + 0x80, 0x1E, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, + 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF8, 0x0F, 0x80, 0x78, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xF0, 0x0F, 0x80, 0xF0, + 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, + 0x01, 0xE0, 0x3C, 0x03, 0xC0, 0x0F, 0x0F, 0x03, 0xC0, 0x78, 0x0F, 0x01, + 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x03, 0xE0, + 0xF8, 0x3C, 0x00, 0x3E, 0x00, 0x7F, 0xC6, 0xFF, 0xFF, 0x61, 0xFE, 0x00, + 0x7C }; + +const GFXglyph FreeSerifBold18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 9, 0, 1 }, // 0x20 ' ' + { 0, 6, 24, 12, 3, -23 }, // 0x21 '!' + { 18, 13, 10, 19, 3, -23 }, // 0x22 '"' + { 35, 18, 24, 17, 0, -23 }, // 0x23 '#' + { 89, 15, 28, 17, 1, -25 }, // 0x24 '$' + { 142, 27, 24, 35, 4, -23 }, // 0x25 '%' + { 223, 26, 25, 29, 2, -23 }, // 0x26 '&' + { 305, 4, 10, 10, 3, -23 }, // 0x27 ''' + { 310, 9, 30, 12, 2, -23 }, // 0x28 '(' + { 344, 9, 30, 12, 1, -23 }, // 0x29 ')' + { 378, 14, 15, 18, 2, -23 }, // 0x2A '*' + { 405, 19, 19, 24, 2, -17 }, // 0x2B '+' + { 451, 6, 12, 9, 1, -5 }, // 0x2C ',' + { 460, 8, 4, 12, 2, -9 }, // 0x2D '-' + { 464, 6, 6, 9, 1, -5 }, // 0x2E '.' + { 469, 11, 25, 10, -1, -23 }, // 0x2F '/' + { 504, 16, 24, 18, 1, -23 }, // 0x30 '0' + { 552, 12, 24, 18, 3, -23 }, // 0x31 '1' + { 588, 16, 24, 17, 1, -23 }, // 0x32 '2' + { 636, 16, 24, 18, 0, -23 }, // 0x33 '3' + { 684, 15, 24, 18, 1, -23 }, // 0x34 '4' + { 729, 15, 24, 18, 1, -23 }, // 0x35 '5' + { 774, 16, 24, 18, 1, -23 }, // 0x36 '6' + { 822, 16, 24, 17, 1, -23 }, // 0x37 '7' + { 870, 16, 24, 17, 1, -23 }, // 0x38 '8' + { 918, 16, 24, 18, 1, -23 }, // 0x39 '9' + { 966, 6, 16, 12, 3, -15 }, // 0x3A ':' + { 978, 7, 22, 12, 2, -15 }, // 0x3B ';' + { 998, 19, 20, 24, 2, -18 }, // 0x3C '<' + { 1046, 19, 12, 24, 2, -14 }, // 0x3D '=' + { 1075, 19, 20, 24, 3, -18 }, // 0x3E '>' + { 1123, 14, 24, 18, 2, -23 }, // 0x3F '?' + { 1165, 24, 25, 33, 4, -23 }, // 0x40 '@' + { 1240, 24, 24, 25, 1, -23 }, // 0x41 'A' + { 1312, 21, 24, 23, 1, -23 }, // 0x42 'B' + { 1375, 23, 25, 25, 1, -23 }, // 0x43 'C' + { 1447, 23, 24, 26, 1, -23 }, // 0x44 'D' + { 1516, 21, 24, 23, 2, -23 }, // 0x45 'E' + { 1579, 19, 24, 22, 2, -23 }, // 0x46 'F' + { 1636, 25, 25, 27, 1, -23 }, // 0x47 'G' + { 1715, 24, 24, 27, 2, -23 }, // 0x48 'H' + { 1787, 11, 24, 14, 2, -23 }, // 0x49 'I' + { 1820, 16, 27, 18, 0, -23 }, // 0x4A 'J' + { 1874, 25, 24, 27, 2, -23 }, // 0x4B 'K' + { 1949, 21, 24, 23, 2, -23 }, // 0x4C 'L' + { 2012, 31, 24, 33, 1, -23 }, // 0x4D 'M' + { 2105, 23, 24, 25, 1, -23 }, // 0x4E 'N' + { 2174, 25, 25, 27, 1, -23 }, // 0x4F 'O' + { 2253, 19, 24, 22, 2, -23 }, // 0x50 'P' + { 2310, 25, 30, 27, 1, -23 }, // 0x51 'Q' + { 2404, 23, 24, 25, 2, -23 }, // 0x52 'R' + { 2473, 16, 25, 20, 2, -23 }, // 0x53 'S' + { 2523, 21, 24, 23, 1, -23 }, // 0x54 'T' + { 2586, 22, 25, 25, 2, -23 }, // 0x55 'U' + { 2655, 24, 24, 25, 0, -23 }, // 0x56 'V' + { 2727, 34, 25, 34, 0, -23 }, // 0x57 'W' + { 2834, 24, 24, 25, 1, -23 }, // 0x58 'X' + { 2906, 24, 24, 25, 1, -23 }, // 0x59 'Y' + { 2978, 21, 24, 23, 1, -23 }, // 0x5A 'Z' + { 3041, 8, 29, 12, 2, -23 }, // 0x5B '[' + { 3070, 11, 25, 10, -1, -23 }, // 0x5C '\' + { 3105, 8, 29, 12, 2, -23 }, // 0x5D ']' + { 3134, 15, 13, 20, 3, -23 }, // 0x5E '^' + { 3159, 18, 3, 17, 0, 3 }, // 0x5F '_' + { 3166, 8, 6, 12, 0, -23 }, // 0x60 '`' + { 3172, 16, 16, 18, 1, -15 }, // 0x61 'a' + { 3204, 18, 24, 19, 1, -23 }, // 0x62 'b' + { 3258, 14, 16, 15, 1, -15 }, // 0x63 'c' + { 3286, 18, 24, 19, 1, -23 }, // 0x64 'd' + { 3340, 14, 16, 16, 1, -15 }, // 0x65 'e' + { 3368, 11, 24, 14, 2, -23 }, // 0x66 'f' + { 3401, 17, 23, 17, 1, -15 }, // 0x67 'g' + { 3450, 17, 24, 19, 1, -23 }, // 0x68 'h' + { 3501, 7, 24, 10, 2, -23 }, // 0x69 'i' + { 3522, 11, 31, 14, 0, -23 }, // 0x6A 'j' + { 3565, 18, 24, 19, 1, -23 }, // 0x6B 'k' + { 3619, 7, 24, 10, 1, -23 }, // 0x6C 'l' + { 3640, 27, 16, 29, 1, -15 }, // 0x6D 'm' + { 3694, 17, 16, 19, 1, -15 }, // 0x6E 'n' + { 3728, 17, 16, 18, 1, -15 }, // 0x6F 'o' + { 3762, 19, 23, 19, 0, -15 }, // 0x70 'p' + { 3817, 17, 23, 19, 1, -15 }, // 0x71 'q' + { 3866, 13, 16, 15, 1, -15 }, // 0x72 'r' + { 3892, 12, 16, 14, 1, -15 }, // 0x73 's' + { 3916, 10, 21, 12, 1, -20 }, // 0x74 't' + { 3943, 18, 16, 20, 1, -15 }, // 0x75 'u' + { 3979, 17, 16, 17, 0, -15 }, // 0x76 'v' + { 4013, 24, 16, 25, 0, -15 }, // 0x77 'w' + { 4061, 16, 16, 18, 1, -15 }, // 0x78 'x' + { 4093, 16, 23, 17, 0, -15 }, // 0x79 'y' + { 4139, 14, 16, 16, 0, -15 }, // 0x7A 'z' + { 4167, 11, 31, 14, 1, -24 }, // 0x7B '{' + { 4210, 3, 25, 8, 2, -23 }, // 0x7C '|' + { 4220, 11, 31, 14, 3, -24 }, // 0x7D '}' + { 4263, 16, 5, 18, 1, -11 } }; // 0x7E '~' + +const GFXfont FreeSerifBold18pt7b PROGMEM = { + (uint8_t *)FreeSerifBold18pt7bBitmaps, + (GFXglyph *)FreeSerifBold18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 4945 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBold24pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBold24pt7b.h new file mode 100644 index 0000000..0eb2d0b --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBold24pt7b.h @@ -0,0 +1,759 @@ +const uint8_t FreeSerifBold24pt7bBitmaps[] PROGMEM = { + 0x3C, 0x7E, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7E, 0x7E, 0x7C, 0x7C, + 0x3C, 0x3C, 0x38, 0x38, 0x38, 0x38, 0x18, 0x10, 0x10, 0x10, 0x00, 0x00, + 0x00, 0x00, 0x3C, 0x7E, 0xFF, 0xFF, 0xFF, 0xFF, 0x7E, 0x3C, 0x70, 0x07, + 0x7C, 0x07, 0xFE, 0x03, 0xFF, 0x01, 0xFF, 0x80, 0xFF, 0xC0, 0x7F, 0xC0, + 0x3E, 0xE0, 0x0E, 0x70, 0x07, 0x38, 0x03, 0x9C, 0x01, 0xC4, 0x00, 0xE2, + 0x00, 0x20, 0x00, 0xF0, 0x70, 0x01, 0xC0, 0xE0, 0x03, 0x81, 0xC0, 0x0F, + 0x07, 0x80, 0x1E, 0x0F, 0x00, 0x3C, 0x1E, 0x00, 0x78, 0x3C, 0x00, 0xF0, + 0x78, 0x01, 0xC0, 0xE0, 0x03, 0x81, 0xC0, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, + 0xF3, 0xFF, 0xFF, 0xE0, 0x78, 0x3C, 0x00, 0xF0, 0x78, 0x01, 0xC0, 0xE0, + 0x03, 0x81, 0xC0, 0x0F, 0x07, 0x80, 0x1E, 0x0F, 0x00, 0x3C, 0x1E, 0x0F, + 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0x03, 0x81, 0xC0, 0x0F, + 0x07, 0x80, 0x1E, 0x0F, 0x00, 0x3C, 0x1E, 0x00, 0x78, 0x3C, 0x00, 0xF0, + 0x78, 0x01, 0xE0, 0xE0, 0x03, 0x81, 0xC0, 0x07, 0x07, 0x80, 0x1E, 0x0F, + 0x00, 0x00, 0x60, 0x00, 0x03, 0x00, 0x00, 0x18, 0x00, 0x00, 0xC0, 0x00, + 0x7F, 0xF0, 0x0F, 0x37, 0xE0, 0xE1, 0x8F, 0x8E, 0x0C, 0x3C, 0x70, 0x60, + 0xE7, 0x83, 0x03, 0x3C, 0x18, 0x19, 0xF0, 0xC0, 0x4F, 0xC6, 0x02, 0x7F, + 0xF0, 0x03, 0xFF, 0x80, 0x0F, 0xFE, 0x00, 0x3F, 0xFC, 0x00, 0xFF, 0xF0, + 0x03, 0xFF, 0xE0, 0x0F, 0xFF, 0x80, 0x1F, 0xFE, 0x00, 0x3F, 0xF8, 0x01, + 0xFF, 0xC0, 0x0C, 0xFF, 0x00, 0x63, 0xFA, 0x03, 0x0F, 0xD0, 0x18, 0x3E, + 0x80, 0xC1, 0xF6, 0x06, 0x0F, 0xB8, 0x30, 0x79, 0xC1, 0x87, 0xCF, 0x0C, + 0x3C, 0x7E, 0x67, 0xC0, 0xFF, 0xF8, 0x00, 0xFE, 0x00, 0x00, 0xC0, 0x00, + 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0x80, 0x00, 0x00, 0x00, 0x00, 0x30, + 0x00, 0x3E, 0x00, 0x0C, 0x00, 0x0F, 0xF0, 0x03, 0x80, 0x07, 0xE7, 0x03, + 0xE0, 0x01, 0xF8, 0x7F, 0xFC, 0x00, 0x3E, 0x07, 0xF7, 0x00, 0x0F, 0xC0, + 0x80, 0xE0, 0x03, 0xF0, 0x10, 0x38, 0x00, 0x7E, 0x02, 0x07, 0x00, 0x0F, + 0x80, 0x41, 0xC0, 0x03, 0xF0, 0x10, 0x30, 0x00, 0x7E, 0x02, 0x0E, 0x00, + 0x0F, 0x80, 0xC1, 0x80, 0x01, 0xF0, 0x10, 0x70, 0x00, 0x3E, 0x06, 0x1C, + 0x00, 0x07, 0xC1, 0x83, 0x80, 0x00, 0x7C, 0x60, 0xE0, 0x1F, 0x07, 0xF8, + 0x18, 0x0F, 0xF8, 0x7C, 0x07, 0x07, 0xF1, 0x00, 0x00, 0xC1, 0xF8, 0x10, + 0x00, 0x38, 0x3F, 0x02, 0x00, 0x06, 0x0F, 0xC0, 0x40, 0x01, 0xC3, 0xF0, + 0x08, 0x00, 0x30, 0x7E, 0x01, 0x00, 0x0E, 0x1F, 0x80, 0x40, 0x03, 0x83, + 0xF0, 0x08, 0x00, 0x60, 0x7E, 0x01, 0x00, 0x1C, 0x0F, 0x80, 0x40, 0x03, + 0x01, 0xF0, 0x18, 0x00, 0xE0, 0x3E, 0x02, 0x00, 0x18, 0x03, 0xC0, 0xC0, + 0x07, 0x00, 0x7C, 0x70, 0x00, 0xC0, 0x07, 0xFC, 0x00, 0x38, 0x00, 0x7E, + 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x0F, 0xFE, 0x00, 0x00, 0x07, 0x8F, + 0xE0, 0x00, 0x03, 0xC1, 0xF8, 0x00, 0x00, 0xF0, 0x3F, 0x00, 0x00, 0x7C, + 0x07, 0xC0, 0x00, 0x1F, 0x01, 0xF0, 0x00, 0x07, 0xE0, 0x7C, 0x00, 0x01, + 0xF8, 0x1E, 0x00, 0x00, 0x7F, 0x07, 0x80, 0x00, 0x1F, 0xE3, 0x80, 0x00, + 0x03, 0xFF, 0xC0, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x00, 0x1F, 0xE0, 0x3F, + 0xF0, 0x07, 0xFC, 0x01, 0xF0, 0x07, 0xFF, 0x00, 0x78, 0x07, 0xBF, 0xE0, + 0x1C, 0x03, 0x87, 0xFC, 0x07, 0x01, 0xE0, 0xFF, 0x81, 0x80, 0xF0, 0x3F, + 0xE0, 0xC0, 0x7C, 0x07, 0xFC, 0x30, 0x1F, 0x00, 0xFF, 0x98, 0x0F, 0xC0, + 0x3F, 0xFC, 0x03, 0xF0, 0x07, 0xFF, 0x00, 0xFE, 0x00, 0xFF, 0x80, 0x3F, + 0x80, 0x3F, 0xF0, 0x0F, 0xF0, 0x07, 0xFE, 0x03, 0xFC, 0x00, 0xFF, 0x81, + 0x7F, 0x80, 0x3F, 0xF8, 0xDF, 0xF0, 0x1F, 0xFF, 0xE3, 0xFF, 0x0E, 0xFF, + 0xF8, 0xFF, 0xFE, 0x1F, 0xFC, 0x0F, 0xFE, 0x03, 0xFE, 0x00, 0xFE, 0x00, + 0x3E, 0x00, 0x77, 0xFF, 0xFF, 0xFF, 0xEE, 0x73, 0x9C, 0xE2, 0x00, 0x00, + 0x00, 0x03, 0x00, 0x60, 0x1C, 0x03, 0x80, 0x70, 0x06, 0x00, 0xE0, 0x1C, + 0x01, 0xC0, 0x3C, 0x03, 0xC0, 0x78, 0x07, 0x80, 0x78, 0x07, 0x80, 0xF8, + 0x0F, 0x80, 0xF8, 0x0F, 0x80, 0xF8, 0x0F, 0x80, 0xF8, 0x0F, 0x80, 0xF8, + 0x0F, 0x80, 0x78, 0x07, 0x80, 0x78, 0x03, 0xC0, 0x3C, 0x01, 0xC0, 0x1C, + 0x00, 0xE0, 0x0E, 0x00, 0x70, 0x03, 0x00, 0x18, 0x00, 0xC0, 0x03, 0x00, + 0x10, 0x00, 0x0C, 0x00, 0x60, 0x03, 0x00, 0x18, 0x00, 0xC0, 0x06, 0x00, + 0x70, 0x03, 0x80, 0x38, 0x03, 0xC0, 0x3C, 0x03, 0xE0, 0x1E, 0x01, 0xE0, + 0x1E, 0x01, 0xF0, 0x1F, 0x01, 0xF0, 0x1F, 0x01, 0xF0, 0x1F, 0x01, 0xF0, + 0x1F, 0x01, 0xF0, 0x1F, 0x01, 0xE0, 0x1E, 0x01, 0xE0, 0x3C, 0x03, 0xC0, + 0x38, 0x03, 0x80, 0x70, 0x07, 0x00, 0xE0, 0x0C, 0x01, 0x80, 0x30, 0x0C, + 0x00, 0x80, 0x00, 0x01, 0xC0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, + 0x03, 0xE0, 0x3C, 0x78, 0xEF, 0x9C, 0x7B, 0xF7, 0x3F, 0xFE, 0xDF, 0x8F, + 0xFF, 0xC0, 0x7F, 0x00, 0x3F, 0xC0, 0x7E, 0xBF, 0x3F, 0x77, 0xEF, 0x9C, + 0xFF, 0xC7, 0x1E, 0x63, 0xE3, 0x80, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, + 0x01, 0xC0, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, + 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x0F, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, + 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x07, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0x3C, 0x7E, 0xFE, 0xFF, 0xFF, 0xFF, 0x7F, 0x07, 0x06, 0x06, 0x0C, + 0x18, 0x30, 0x60, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x3C, + 0x7E, 0xFF, 0xFF, 0xFF, 0xFF, 0x7E, 0x3C, 0x00, 0x1E, 0x00, 0x7C, 0x00, + 0xF0, 0x01, 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x7C, 0x00, 0xF0, + 0x01, 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x7C, 0x00, 0xF0, 0x01, + 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x7C, 0x00, 0xF0, 0x01, 0xE0, + 0x03, 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0xF0, 0x01, 0xE0, 0x03, + 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0xF0, 0x00, 0x00, 0xFC, 0x00, + 0x0F, 0x3C, 0x00, 0x78, 0x78, 0x03, 0xE1, 0xF0, 0x1F, 0x03, 0xE0, 0x7C, + 0x0F, 0x83, 0xF0, 0x3F, 0x0F, 0xC0, 0xFC, 0x7F, 0x03, 0xF9, 0xFC, 0x0F, + 0xE7, 0xF0, 0x3F, 0xBF, 0xC0, 0xFE, 0xFF, 0x03, 0xFF, 0xFC, 0x0F, 0xFF, + 0xF0, 0x3F, 0xFF, 0xC0, 0xFF, 0xFF, 0x03, 0xFF, 0xFC, 0x0F, 0xFF, 0xF0, + 0x3F, 0xFF, 0xC0, 0xFF, 0xFF, 0x03, 0xFF, 0xFC, 0x0F, 0xFF, 0xF0, 0x3F, + 0x9F, 0xC0, 0xFE, 0x7F, 0x03, 0xF9, 0xFC, 0x0F, 0xE3, 0xF0, 0x3F, 0x0F, + 0xC0, 0xFC, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x80, 0xF8, 0x7C, 0x01, 0xE1, + 0xE0, 0x03, 0xCF, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x18, 0x00, 0x1E, 0x00, + 0x1F, 0x80, 0x1F, 0xE0, 0x1F, 0xF8, 0x1D, 0xFE, 0x00, 0x3F, 0x80, 0x0F, + 0xE0, 0x03, 0xF8, 0x00, 0xFE, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x03, 0xF8, + 0x00, 0xFE, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x03, 0xF8, 0x00, 0xFE, 0x00, + 0x3F, 0x80, 0x0F, 0xE0, 0x03, 0xF8, 0x00, 0xFE, 0x00, 0x3F, 0x80, 0x0F, + 0xE0, 0x03, 0xF8, 0x00, 0xFE, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x03, 0xF8, + 0x00, 0xFE, 0x00, 0x7F, 0x80, 0x3F, 0xF8, 0xFF, 0xFF, 0xC0, 0x00, 0xFC, + 0x00, 0x1F, 0xF8, 0x03, 0xFF, 0xE0, 0x3F, 0xFF, 0x81, 0xFF, 0xFC, 0x1C, + 0x1F, 0xF1, 0xC0, 0x7F, 0x8C, 0x01, 0xFC, 0x40, 0x0F, 0xE0, 0x00, 0x3F, + 0x00, 0x01, 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, + 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x00, + 0x00, 0x70, 0x00, 0x07, 0x80, 0x00, 0x38, 0x00, 0x03, 0x80, 0x00, 0x38, + 0x01, 0x03, 0x80, 0x18, 0x38, 0x00, 0x81, 0x80, 0x1C, 0x1F, 0xFF, 0xE1, + 0xFF, 0xFF, 0x1F, 0xFF, 0xF9, 0xFF, 0xFF, 0x9F, 0xFF, 0xFC, 0xFF, 0xFF, + 0xE0, 0x00, 0xFE, 0x00, 0x3F, 0xFC, 0x03, 0xFF, 0xF0, 0x30, 0xFF, 0xC2, + 0x01, 0xFE, 0x30, 0x0F, 0xF1, 0x00, 0x3F, 0x80, 0x01, 0xFC, 0x00, 0x0F, + 0xE0, 0x00, 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x01, 0xF0, 0x00, + 0x1F, 0xC0, 0x03, 0xFF, 0x00, 0x3F, 0xFC, 0x00, 0x7F, 0xF0, 0x00, 0xFF, + 0x80, 0x03, 0xFE, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0x80, 0x00, 0xFC, 0x00, + 0x07, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0x80, 0x00, 0x3C, + 0x00, 0x01, 0xC7, 0x80, 0x0E, 0x7F, 0x00, 0xE3, 0xFC, 0x06, 0x1F, 0xF8, + 0xE0, 0x7F, 0xFC, 0x00, 0xFF, 0x00, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x1E, + 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xE0, 0x00, + 0xFF, 0x00, 0x0D, 0xF8, 0x00, 0xEF, 0xC0, 0x06, 0x7E, 0x00, 0x63, 0xF0, + 0x07, 0x1F, 0x80, 0x30, 0xFC, 0x03, 0x07, 0xE0, 0x38, 0x3F, 0x03, 0x81, + 0xF8, 0x18, 0x0F, 0xC1, 0xC0, 0x7E, 0x1C, 0x03, 0xF0, 0xC0, 0x1F, 0x8E, + 0x00, 0xFC, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xC0, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, + 0x07, 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF8, 0x00, 0x0F, 0xC0, 0x07, 0xFF, + 0xF0, 0x7F, 0xFF, 0x0F, 0xFF, 0xE0, 0xFF, 0xFE, 0x0F, 0xFF, 0xE1, 0xFF, + 0xFC, 0x18, 0x00, 0x01, 0x80, 0x00, 0x18, 0x00, 0x03, 0x00, 0x00, 0x3F, + 0x80, 0x03, 0xFF, 0x80, 0x7F, 0xFE, 0x07, 0xFF, 0xF0, 0x7F, 0xFF, 0x87, + 0xFF, 0xFC, 0x7F, 0xFF, 0xC0, 0x07, 0xFC, 0x00, 0x1F, 0xE0, 0x00, 0x7E, + 0x00, 0x03, 0xE0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x00, + 0xC0, 0x00, 0x0C, 0x78, 0x00, 0x8F, 0xE0, 0x18, 0xFF, 0x87, 0x0F, 0xFF, + 0xE0, 0x7F, 0xF8, 0x01, 0xFE, 0x00, 0x00, 0x00, 0x38, 0x00, 0x1F, 0x00, + 0x07, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, + 0x00, 0xFC, 0x00, 0x0F, 0xE0, 0x00, 0xFE, 0x00, 0x0F, 0xF0, 0x00, 0x7F, + 0x00, 0x07, 0xF8, 0x00, 0x3F, 0xFF, 0x01, 0xFF, 0xFE, 0x1F, 0xF1, 0xFC, + 0xFF, 0x07, 0xE7, 0xF8, 0x3F, 0xBF, 0xC1, 0xFD, 0xFE, 0x07, 0xFF, 0xF0, + 0x3F, 0xFF, 0x81, 0xFF, 0xFC, 0x0F, 0xFF, 0xE0, 0x7F, 0xFF, 0x03, 0xFB, + 0xF8, 0x1F, 0xDF, 0xC0, 0xFE, 0xFE, 0x07, 0xE3, 0xF0, 0x3F, 0x1F, 0xC1, + 0xF0, 0x7E, 0x0F, 0x01, 0xF0, 0xF8, 0x03, 0xC7, 0x00, 0x07, 0xE0, 0x00, + 0x3F, 0xFF, 0xF9, 0xFF, 0xFF, 0xDF, 0xFF, 0xFE, 0xFF, 0xFF, 0xE7, 0xFF, + 0xFF, 0x3F, 0xFF, 0xF9, 0x80, 0x07, 0x98, 0x00, 0x3C, 0xC0, 0x03, 0xE4, + 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, + 0xC0, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, + 0x07, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x01, 0xF0, + 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x07, 0xC0, 0x00, 0x3C, 0x00, 0x01, + 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, + 0x01, 0xFE, 0x00, 0x38, 0x7C, 0x07, 0x80, 0xF0, 0x78, 0x07, 0xC3, 0xC0, + 0x1F, 0x3E, 0x00, 0xF9, 0xF0, 0x07, 0xCF, 0xC0, 0x3E, 0x7E, 0x01, 0xF3, + 0xF8, 0x0F, 0x1F, 0xE0, 0xF8, 0x7F, 0xC7, 0x83, 0xFF, 0xF0, 0x0F, 0xFE, + 0x00, 0x7F, 0xFC, 0x01, 0xFF, 0xF0, 0x03, 0xFF, 0xC0, 0x1F, 0xFF, 0x03, + 0xBF, 0xFC, 0x7C, 0x7F, 0xE7, 0xC1, 0xFF, 0x3E, 0x07, 0xFF, 0xE0, 0x1F, + 0xFF, 0x00, 0x7F, 0xF8, 0x03, 0xFF, 0xC0, 0x0F, 0xFE, 0x00, 0x7F, 0xF0, + 0x03, 0xE7, 0x80, 0x1F, 0x3E, 0x01, 0xF0, 0xF8, 0x0F, 0x83, 0xE1, 0xF8, + 0x0F, 0xFF, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x1C, 0x3C, 0x00, + 0xF0, 0x78, 0x07, 0x81, 0xF8, 0x3E, 0x07, 0xE1, 0xF8, 0x0F, 0xC7, 0xE0, + 0x3F, 0x3F, 0x80, 0xFE, 0xFE, 0x03, 0xFB, 0xF8, 0x0F, 0xFF, 0xE0, 0x3F, + 0xFF, 0x80, 0xFF, 0xFE, 0x03, 0xFF, 0xF8, 0x0F, 0xFF, 0xE0, 0x3F, 0xDF, + 0xC0, 0xFF, 0x7F, 0x03, 0xFC, 0xFC, 0x0F, 0xF3, 0xFC, 0x7F, 0x83, 0xFF, + 0xFE, 0x07, 0xF7, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0x00, 0x03, 0xF8, + 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x00, 0x03, 0xF8, 0x00, 0x0F, 0xC0, 0x00, + 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x01, 0xF0, 0x00, 0x3F, 0x00, + 0x03, 0x80, 0x00, 0x00, 0x3C, 0x7E, 0xFF, 0xFF, 0xFF, 0xFF, 0x7E, 0x3C, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3C, 0x7E, 0xFF, 0xFF, + 0xFF, 0xFF, 0x7E, 0x3C, 0x3C, 0x3F, 0x3F, 0xDF, 0xEF, 0xF7, 0xF9, 0xF8, + 0x78, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78, 0x7F, 0x7F, + 0xBF, 0xFF, 0xFF, 0xFB, 0xFC, 0xFE, 0x07, 0x03, 0x01, 0x81, 0x81, 0x81, + 0x83, 0x81, 0x00, 0x00, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, + 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0xFF, 0xC0, 0x01, 0xFF, 0x80, 0x01, + 0xFF, 0x80, 0x01, 0xFF, 0x80, 0x01, 0xFF, 0x80, 0x01, 0xFF, 0x80, 0x01, + 0xFF, 0x80, 0x01, 0xFF, 0x80, 0x00, 0xFF, 0x80, 0x00, 0x3F, 0xE0, 0x00, + 0x07, 0xFE, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0x7F, + 0xE0, 0x00, 0x07, 0xFF, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x03, 0xFF, 0x00, + 0x00, 0x3F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x03, + 0xC0, 0x00, 0x00, 0x30, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, + 0xC0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x03, 0xFC, 0x00, + 0x00, 0xFF, 0xC0, 0x00, 0x0F, 0xFC, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x0F, + 0xFE, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0x7F, 0xE0, + 0x00, 0x07, 0xFE, 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x1F, 0xF0, 0x00, 0x1F, + 0xF8, 0x00, 0x1F, 0xF8, 0x00, 0x1F, 0xF8, 0x00, 0x1F, 0xF8, 0x00, 0x1F, + 0xF8, 0x00, 0x1F, 0xF8, 0x00, 0x1F, 0xF8, 0x00, 0x3F, 0xF0, 0x00, 0x0F, + 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x30, 0x00, 0x00, + 0x00, 0x07, 0xF0, 0x07, 0xFF, 0x03, 0x87, 0xE1, 0xC0, 0xFC, 0xF0, 0x3F, + 0xBE, 0x07, 0xEF, 0xC1, 0xFF, 0xF0, 0x7F, 0xFC, 0x1F, 0xDF, 0x07, 0xF7, + 0x81, 0xFC, 0x00, 0xFE, 0x00, 0x3F, 0x80, 0x1F, 0xC0, 0x07, 0xE0, 0x03, + 0xE0, 0x00, 0xF0, 0x00, 0x70, 0x00, 0x18, 0x00, 0x04, 0x00, 0x01, 0x00, + 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x3C, 0x00, 0x1F, 0x80, 0x0F, 0xF0, 0x03, 0xFC, 0x00, 0xFF, 0x00, 0x3F, + 0xC0, 0x07, 0xE0, 0x00, 0xF0, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x1F, + 0xFF, 0xC0, 0x00, 0x1F, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x1E, 0x00, 0x3C, + 0x00, 0x03, 0x80, 0x3C, 0x00, 0x00, 0xE0, 0x3C, 0x00, 0x00, 0x30, 0x3E, + 0x00, 0x00, 0x0C, 0x3E, 0x00, 0x3C, 0x37, 0x1F, 0x00, 0x7E, 0xF1, 0x9F, + 0x00, 0x7C, 0xF8, 0xCF, 0x80, 0x78, 0x7C, 0x37, 0xC0, 0x7C, 0x3C, 0x1F, + 0xC0, 0x3C, 0x1E, 0x0F, 0xE0, 0x3C, 0x0F, 0x07, 0xF0, 0x3E, 0x0F, 0x03, + 0xF8, 0x1E, 0x07, 0x81, 0xFC, 0x0F, 0x03, 0xC0, 0xFE, 0x0F, 0x03, 0xE0, + 0x7F, 0x07, 0x81, 0xE0, 0x6F, 0x83, 0xC1, 0xF0, 0x37, 0xC1, 0xE1, 0x78, + 0x31, 0xF0, 0xF9, 0xBC, 0x18, 0xF8, 0x3F, 0x9E, 0x38, 0x3C, 0x0F, 0x0F, + 0xF8, 0x1F, 0x00, 0x01, 0xF0, 0x07, 0x80, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x07, 0xC0, + 0x00, 0xC0, 0x01, 0xF8, 0x03, 0xE0, 0x00, 0x3F, 0xFF, 0xC0, 0x00, 0x03, + 0xFF, 0x00, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x03, 0x80, 0x00, 0x00, + 0x03, 0x80, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, + 0x07, 0xE0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, + 0x0F, 0xF0, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, + 0x37, 0xF8, 0x00, 0x00, 0x33, 0xF8, 0x00, 0x00, 0x33, 0xFC, 0x00, 0x00, + 0x61, 0xFC, 0x00, 0x00, 0x61, 0xFE, 0x00, 0x00, 0xC1, 0xFE, 0x00, 0x00, + 0xC0, 0xFF, 0x00, 0x00, 0xC0, 0xFF, 0x00, 0x01, 0x80, 0x7F, 0x00, 0x01, + 0x80, 0x7F, 0x80, 0x03, 0x80, 0x7F, 0x80, 0x03, 0xFF, 0xFF, 0xC0, 0x03, + 0xFF, 0xFF, 0xC0, 0x07, 0x00, 0x3F, 0xC0, 0x06, 0x00, 0x1F, 0xE0, 0x0E, + 0x00, 0x1F, 0xE0, 0x0C, 0x00, 0x0F, 0xF0, 0x0C, 0x00, 0x0F, 0xF0, 0x1C, + 0x00, 0x0F, 0xF8, 0x1C, 0x00, 0x0F, 0xF8, 0x7E, 0x00, 0x0F, 0xFC, 0xFF, + 0x80, 0x7F, 0xFF, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xE0, 0x1F, 0xF8, + 0x7F, 0x00, 0xFF, 0x03, 0xFC, 0x0F, 0xF0, 0x3F, 0xC0, 0xFF, 0x01, 0xFE, + 0x0F, 0xF0, 0x1F, 0xE0, 0xFF, 0x01, 0xFE, 0x0F, 0xF0, 0x1F, 0xE0, 0xFF, + 0x01, 0xFE, 0x0F, 0xF0, 0x1F, 0xC0, 0xFF, 0x03, 0xFC, 0x0F, 0xF0, 0x3F, + 0x00, 0xFF, 0x0F, 0xC0, 0x0F, 0xFF, 0xE0, 0x00, 0xFF, 0xFF, 0xC0, 0x0F, + 0xF0, 0xFF, 0x00, 0xFF, 0x03, 0xFC, 0x0F, 0xF0, 0x1F, 0xE0, 0xFF, 0x01, + 0xFE, 0x0F, 0xF0, 0x0F, 0xF0, 0xFF, 0x00, 0xFF, 0x0F, 0xF0, 0x0F, 0xF0, + 0xFF, 0x00, 0xFF, 0x0F, 0xF0, 0x0F, 0xF0, 0xFF, 0x00, 0xFF, 0x0F, 0xF0, + 0x0F, 0xE0, 0xFF, 0x01, 0xFE, 0x0F, 0xF0, 0x1F, 0xC0, 0xFF, 0x87, 0xF0, + 0x3F, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0x00, 0x00, 0x0F, 0xF0, 0x08, 0x01, + 0xFF, 0xF0, 0x60, 0x0F, 0xC1, 0xF9, 0x80, 0xFC, 0x01, 0xFE, 0x07, 0xE0, + 0x01, 0xF8, 0x3F, 0x00, 0x03, 0xE1, 0xFC, 0x00, 0x07, 0x87, 0xE0, 0x00, + 0x1E, 0x3F, 0x80, 0x00, 0x38, 0xFE, 0x00, 0x00, 0x67, 0xF8, 0x00, 0x01, + 0x9F, 0xC0, 0x00, 0x02, 0x7F, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x0F, + 0xF0, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x03, 0xFC, + 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x00, 0xFF, 0x00, + 0x00, 0x03, 0xFC, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x1F, 0xE0, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0x87, 0xF0, 0x00, 0x07, 0x0F, 0xE0, 0x00, 0x38, 0x1F, 0x80, 0x01, 0xC0, + 0x3F, 0x00, 0x1E, 0x00, 0x7F, 0x01, 0xE0, 0x00, 0x7F, 0xFF, 0x00, 0x00, + 0x3F, 0xE0, 0x00, 0xFF, 0xFF, 0xE0, 0x00, 0x3F, 0xFF, 0xFE, 0x00, 0x0F, + 0xF8, 0x7F, 0x80, 0x0F, 0xF0, 0x1F, 0xC0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, + 0xF0, 0x07, 0xF0, 0x0F, 0xF0, 0x03, 0xF8, 0x0F, 0xF0, 0x03, 0xFC, 0x0F, + 0xF0, 0x01, 0xFC, 0x0F, 0xF0, 0x01, 0xFE, 0x0F, 0xF0, 0x01, 0xFE, 0x0F, + 0xF0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, + 0xF0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, + 0xF0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, + 0xF0, 0x00, 0xFE, 0x0F, 0xF0, 0x00, 0xFE, 0x0F, 0xF0, 0x01, 0xFE, 0x0F, + 0xF0, 0x01, 0xFC, 0x0F, 0xF0, 0x01, 0xFC, 0x0F, 0xF0, 0x03, 0xF8, 0x0F, + 0xF0, 0x03, 0xF0, 0x0F, 0xF0, 0x07, 0xE0, 0x0F, 0xF0, 0x0F, 0xC0, 0x0F, + 0xF8, 0x3F, 0x80, 0x1F, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0xF0, 0x00, 0xFF, + 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xFC, 0x1F, 0xE0, 0x1F, 0xC1, 0xFE, 0x00, + 0x3C, 0x1F, 0xE0, 0x01, 0xC1, 0xFE, 0x00, 0x0C, 0x1F, 0xE0, 0x00, 0xC1, + 0xFE, 0x00, 0x04, 0x1F, 0xE0, 0x20, 0x41, 0xFE, 0x02, 0x00, 0x1F, 0xE0, + 0x60, 0x01, 0xFE, 0x06, 0x00, 0x1F, 0xE0, 0xE0, 0x01, 0xFE, 0x1E, 0x00, + 0x1F, 0xFF, 0xE0, 0x01, 0xFF, 0xFE, 0x00, 0x1F, 0xE3, 0xE0, 0x01, 0xFE, + 0x0E, 0x00, 0x1F, 0xE0, 0x60, 0x01, 0xFE, 0x06, 0x00, 0x1F, 0xE0, 0x20, + 0x01, 0xFE, 0x02, 0x00, 0x1F, 0xE0, 0x00, 0x11, 0xFE, 0x00, 0x03, 0x1F, + 0xE0, 0x00, 0x71, 0xFE, 0x00, 0x07, 0x1F, 0xE0, 0x00, 0xE1, 0xFE, 0x00, + 0x1E, 0x1F, 0xE0, 0x03, 0xE3, 0xFF, 0x01, 0xFE, 0xFF, 0xFF, 0xFF, 0xEF, + 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0x9F, 0xFF, 0xFF, 0xC7, 0xFC, 0x07, + 0xE3, 0xFC, 0x00, 0xF1, 0xFE, 0x00, 0x38, 0xFF, 0x00, 0x0C, 0x7F, 0x80, + 0x06, 0x3F, 0xC0, 0x01, 0x1F, 0xE0, 0x20, 0x8F, 0xF0, 0x10, 0x07, 0xF8, + 0x18, 0x03, 0xFC, 0x0C, 0x01, 0xFE, 0x0E, 0x00, 0xFF, 0x1F, 0x00, 0x7F, + 0xFF, 0x80, 0x3F, 0xFF, 0xC0, 0x1F, 0xE3, 0xE0, 0x0F, 0xF0, 0x70, 0x07, + 0xF8, 0x18, 0x03, 0xFC, 0x0C, 0x01, 0xFE, 0x02, 0x00, 0xFF, 0x01, 0x00, + 0x7F, 0x80, 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, + 0x07, 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x00, + 0x00, 0xFF, 0xC0, 0x01, 0xFF, 0xFC, 0x00, 0x00, 0x0F, 0xF0, 0x08, 0x00, + 0x3F, 0xFE, 0x0C, 0x00, 0x3F, 0x07, 0xC6, 0x00, 0x7E, 0x00, 0xFF, 0x00, + 0x7E, 0x00, 0x1F, 0x80, 0x7E, 0x00, 0x07, 0xC0, 0x7F, 0x00, 0x01, 0xE0, + 0x3F, 0x00, 0x00, 0x70, 0x3F, 0x80, 0x00, 0x38, 0x1F, 0xC0, 0x00, 0x0C, + 0x1F, 0xE0, 0x00, 0x06, 0x0F, 0xE0, 0x00, 0x01, 0x07, 0xF0, 0x00, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x01, 0xFE, 0x00, 0x00, + 0x00, 0xFF, 0x00, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x00, 0x3F, 0xC0, 0x00, + 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x0F, 0xF0, 0x03, 0xFF, 0xFF, 0xF8, 0x00, + 0x3F, 0xF1, 0xFC, 0x00, 0x0F, 0xF0, 0xFF, 0x00, 0x07, 0xF8, 0x7F, 0x80, + 0x03, 0xFC, 0x1F, 0xC0, 0x01, 0xFE, 0x0F, 0xE0, 0x00, 0xFF, 0x03, 0xF8, + 0x00, 0x7F, 0x80, 0xFC, 0x00, 0x3F, 0xC0, 0x3F, 0x00, 0x1F, 0xE0, 0x0F, + 0xC0, 0x0F, 0xF0, 0x03, 0xF8, 0x1F, 0xF0, 0x00, 0x7F, 0xFF, 0xC0, 0x00, + 0x07, 0xFE, 0x00, 0x00, 0xFF, 0xFC, 0x1F, 0xFF, 0x9F, 0xF8, 0x03, 0xFF, + 0x07, 0xF8, 0x00, 0xFF, 0x03, 0xFC, 0x00, 0x7F, 0x81, 0xFE, 0x00, 0x3F, + 0xC0, 0xFF, 0x00, 0x1F, 0xE0, 0x7F, 0x80, 0x0F, 0xF0, 0x3F, 0xC0, 0x07, + 0xF8, 0x1F, 0xE0, 0x03, 0xFC, 0x0F, 0xF0, 0x01, 0xFE, 0x07, 0xF8, 0x00, + 0xFF, 0x03, 0xFC, 0x00, 0x7F, 0x81, 0xFE, 0x00, 0x3F, 0xC0, 0xFF, 0x00, + 0x1F, 0xE0, 0x7F, 0x80, 0x0F, 0xF0, 0x3F, 0xFF, 0xFF, 0xF8, 0x1F, 0xFF, + 0xFF, 0xFC, 0x0F, 0xF0, 0x01, 0xFE, 0x07, 0xF8, 0x00, 0xFF, 0x03, 0xFC, + 0x00, 0x7F, 0x81, 0xFE, 0x00, 0x3F, 0xC0, 0xFF, 0x00, 0x1F, 0xE0, 0x7F, + 0x80, 0x0F, 0xF0, 0x3F, 0xC0, 0x07, 0xF8, 0x1F, 0xE0, 0x03, 0xFC, 0x0F, + 0xF0, 0x01, 0xFE, 0x07, 0xF8, 0x00, 0xFF, 0x03, 0xFC, 0x00, 0x7F, 0x81, + 0xFE, 0x00, 0x3F, 0xC0, 0xFF, 0x00, 0x1F, 0xE0, 0xFF, 0xC0, 0x1F, 0xF9, + 0xFF, 0xF8, 0x3F, 0xFF, 0xFF, 0xFE, 0x7F, 0xE0, 0x7F, 0x80, 0xFF, 0x01, + 0xFE, 0x03, 0xFC, 0x07, 0xF8, 0x0F, 0xF0, 0x1F, 0xE0, 0x3F, 0xC0, 0x7F, + 0x80, 0xFF, 0x01, 0xFE, 0x03, 0xFC, 0x07, 0xF8, 0x0F, 0xF0, 0x1F, 0xE0, + 0x3F, 0xC0, 0x7F, 0x80, 0xFF, 0x01, 0xFE, 0x03, 0xFC, 0x07, 0xF8, 0x0F, + 0xF0, 0x1F, 0xE0, 0x3F, 0xC0, 0x7F, 0x80, 0xFF, 0x01, 0xFE, 0x03, 0xFC, + 0x0F, 0xFC, 0x7F, 0xFF, 0x01, 0xFF, 0xFC, 0x00, 0xFF, 0xC0, 0x01, 0xFE, + 0x00, 0x07, 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, + 0x07, 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x07, + 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x07, 0xF8, + 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x07, 0xF8, 0x00, + 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x07, 0xF8, 0x00, 0x1F, + 0xE0, 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x07, 0xF8, 0x78, 0x1F, 0xE3, + 0xF0, 0x7F, 0x8F, 0xC1, 0xFC, 0x3F, 0x07, 0xF0, 0xFC, 0x1F, 0xC1, 0xE0, + 0xFE, 0x07, 0xC3, 0xF0, 0x0F, 0xFF, 0x80, 0x07, 0xF0, 0x00, 0xFF, 0xFC, + 0x1F, 0xFF, 0x0F, 0xFC, 0x00, 0xFF, 0x01, 0xFE, 0x00, 0x1E, 0x00, 0x7F, + 0x80, 0x07, 0x00, 0x1F, 0xE0, 0x03, 0x80, 0x07, 0xF8, 0x01, 0xC0, 0x01, + 0xFE, 0x00, 0xE0, 0x00, 0x7F, 0x80, 0x70, 0x00, 0x1F, 0xE0, 0x38, 0x00, + 0x07, 0xF8, 0x1C, 0x00, 0x01, 0xFE, 0x0E, 0x00, 0x00, 0x7F, 0x87, 0x00, + 0x00, 0x1F, 0xE3, 0xC0, 0x00, 0x07, 0xF9, 0xF8, 0x00, 0x01, 0xFE, 0xFE, + 0x00, 0x00, 0x7F, 0xFF, 0xC0, 0x00, 0x1F, 0xFF, 0xF8, 0x00, 0x07, 0xFD, + 0xFF, 0x00, 0x01, 0xFE, 0x7F, 0xE0, 0x00, 0x7F, 0x8F, 0xF8, 0x00, 0x1F, + 0xE1, 0xFF, 0x00, 0x07, 0xF8, 0x3F, 0xE0, 0x01, 0xFE, 0x07, 0xFC, 0x00, + 0x7F, 0x81, 0xFF, 0x80, 0x1F, 0xE0, 0x3F, 0xE0, 0x07, 0xF8, 0x07, 0xFC, + 0x01, 0xFE, 0x00, 0xFF, 0x80, 0x7F, 0x80, 0x1F, 0xF0, 0x1F, 0xE0, 0x07, + 0xFE, 0x07, 0xF8, 0x00, 0xFF, 0x83, 0xFF, 0x00, 0x3F, 0xF3, 0xFF, 0xF0, + 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x03, 0xFF, 0x00, 0x00, 0x1F, 0xE0, 0x00, + 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x1F, + 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, + 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, + 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xE0, + 0x00, 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, + 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x01, 0x1F, 0xE0, 0x00, 0x31, 0xFE, + 0x00, 0x03, 0x1F, 0xE0, 0x00, 0x71, 0xFE, 0x00, 0x07, 0x1F, 0xE0, 0x00, + 0xE1, 0xFE, 0x00, 0x1E, 0x1F, 0xE0, 0x07, 0xE3, 0xFF, 0x01, 0xFE, 0xFF, + 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xFE, 0x7F, 0xF0, 0x00, 0x01, 0xFF, 0xE1, + 0xFF, 0x00, 0x00, 0x3F, 0xF0, 0x1F, 0xE0, 0x00, 0x0F, 0xFC, 0x03, 0xFC, + 0x00, 0x01, 0xFF, 0x80, 0x7F, 0xC0, 0x00, 0x2F, 0xF0, 0x0B, 0xF8, 0x00, + 0x0D, 0xFE, 0x01, 0x7F, 0x80, 0x01, 0xBF, 0xC0, 0x27, 0xF0, 0x00, 0x67, + 0xF8, 0x04, 0xFF, 0x00, 0x0C, 0xFF, 0x00, 0x8F, 0xE0, 0x03, 0x1F, 0xE0, + 0x11, 0xFE, 0x00, 0x63, 0xFC, 0x02, 0x3F, 0xC0, 0x08, 0x7F, 0x80, 0x43, + 0xF8, 0x03, 0x0F, 0xF0, 0x08, 0x7F, 0x80, 0x61, 0xFE, 0x01, 0x07, 0xF0, + 0x18, 0x3F, 0xC0, 0x20, 0xFF, 0x03, 0x07, 0xF8, 0x04, 0x0F, 0xE0, 0xC0, + 0xFF, 0x00, 0x81, 0xFE, 0x18, 0x1F, 0xE0, 0x10, 0x3F, 0xC6, 0x03, 0xFC, + 0x02, 0x03, 0xF8, 0xC0, 0x7F, 0x80, 0x40, 0x7F, 0x98, 0x0F, 0xF0, 0x08, + 0x07, 0xF6, 0x01, 0xFE, 0x01, 0x00, 0xFF, 0xC0, 0x3F, 0xC0, 0x20, 0x0F, + 0xF0, 0x07, 0xF8, 0x04, 0x01, 0xFE, 0x00, 0xFF, 0x00, 0x80, 0x1F, 0x80, + 0x1F, 0xE0, 0x10, 0x03, 0xF0, 0x03, 0xFC, 0x02, 0x00, 0x7E, 0x00, 0x7F, + 0x80, 0x40, 0x07, 0x80, 0x0F, 0xF0, 0x0C, 0x00, 0xF0, 0x01, 0xFE, 0x07, + 0xC0, 0x0C, 0x00, 0x7F, 0xE7, 0xFF, 0x01, 0x80, 0x3F, 0xFF, 0xFF, 0xC0, + 0x03, 0xFE, 0xFF, 0xC0, 0x01, 0xF0, 0xFF, 0xC0, 0x01, 0xC0, 0xFF, 0xC0, + 0x01, 0x80, 0xFF, 0x80, 0x03, 0x01, 0xFF, 0x80, 0x06, 0x03, 0xFF, 0x80, + 0x0C, 0x07, 0xFF, 0x80, 0x18, 0x0D, 0xFF, 0x80, 0x30, 0x19, 0xFF, 0x00, + 0x60, 0x31, 0xFF, 0x00, 0xC0, 0x61, 0xFF, 0x01, 0x80, 0xC1, 0xFF, 0x03, + 0x01, 0x83, 0xFF, 0x06, 0x03, 0x03, 0xFE, 0x0C, 0x06, 0x03, 0xFE, 0x18, + 0x0C, 0x03, 0xFE, 0x30, 0x18, 0x03, 0xFE, 0x60, 0x30, 0x03, 0xFE, 0xC0, + 0x60, 0x07, 0xFD, 0x80, 0xC0, 0x07, 0xFF, 0x01, 0x80, 0x07, 0xFE, 0x03, + 0x00, 0x07, 0xFC, 0x06, 0x00, 0x07, 0xF8, 0x0C, 0x00, 0x07, 0xF0, 0x18, + 0x00, 0x0F, 0xE0, 0x30, 0x00, 0x0F, 0xC0, 0x60, 0x00, 0x0F, 0x80, 0xC0, + 0x00, 0x0F, 0x01, 0xC0, 0x00, 0x0E, 0x0F, 0xC0, 0x00, 0x1C, 0x7F, 0xE0, + 0x00, 0x18, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x3F, 0xFF, 0x80, 0x00, 0x3F, + 0x07, 0xF0, 0x00, 0x7E, 0x00, 0xFC, 0x00, 0x7E, 0x00, 0x3F, 0x00, 0x7E, + 0x00, 0x1F, 0xC0, 0x7F, 0x00, 0x07, 0xF0, 0x3F, 0x00, 0x03, 0xF8, 0x3F, + 0x80, 0x00, 0xFE, 0x3F, 0xC0, 0x00, 0x7F, 0x1F, 0xE0, 0x00, 0x3F, 0xCF, + 0xE0, 0x00, 0x0F, 0xEF, 0xF0, 0x00, 0x07, 0xF7, 0xF8, 0x00, 0x03, 0xFF, + 0xFC, 0x00, 0x01, 0xFF, 0xFE, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x7F, + 0xFF, 0x80, 0x00, 0x3F, 0xFF, 0xC0, 0x00, 0x1F, 0xFF, 0xE0, 0x00, 0x0F, + 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xF8, 0x00, 0x03, 0xFD, 0xFC, 0x00, 0x01, + 0xFC, 0xFE, 0x00, 0x01, 0xFE, 0x7F, 0x80, 0x00, 0xFF, 0x1F, 0xC0, 0x00, + 0x7F, 0x0F, 0xE0, 0x00, 0x3F, 0x83, 0xF8, 0x00, 0x3F, 0x80, 0xFC, 0x00, + 0x1F, 0x80, 0x3F, 0x00, 0x1F, 0x80, 0x0F, 0xC0, 0x1F, 0x80, 0x03, 0xF8, + 0x3F, 0x80, 0x00, 0x7F, 0xFF, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0xFF, + 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0x01, 0xFE, 0x1F, 0xE0, 0x7F, 0x81, 0xFC, + 0x1F, 0xE0, 0x7F, 0x87, 0xF8, 0x0F, 0xE1, 0xFE, 0x03, 0xFC, 0x7F, 0x80, + 0xFF, 0x1F, 0xE0, 0x3F, 0xC7, 0xF8, 0x0F, 0xF1, 0xFE, 0x03, 0xFC, 0x7F, + 0x80, 0xFF, 0x1F, 0xE0, 0x3F, 0x87, 0xF8, 0x1F, 0xE1, 0xFE, 0x07, 0xF0, + 0x7F, 0x87, 0xF8, 0x1F, 0xFF, 0xF8, 0x07, 0xFF, 0xF8, 0x01, 0xFE, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xF8, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x7F, 0x80, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xF8, 0x00, 0x01, + 0xFE, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xF8, 0x00, + 0x03, 0xFF, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, + 0x3F, 0xFF, 0x80, 0x00, 0x3F, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0xFC, 0x00, + 0x7E, 0x00, 0x3F, 0x00, 0x7E, 0x00, 0x1F, 0xC0, 0x7F, 0x00, 0x07, 0xF0, + 0x3F, 0x00, 0x03, 0xF8, 0x3F, 0x80, 0x00, 0xFE, 0x1F, 0xC0, 0x00, 0x7F, + 0x1F, 0xE0, 0x00, 0x3F, 0xCF, 0xE0, 0x00, 0x0F, 0xE7, 0xF0, 0x00, 0x07, + 0xF7, 0xF8, 0x00, 0x03, 0xFF, 0xFC, 0x00, 0x01, 0xFF, 0xFE, 0x00, 0x00, + 0xFF, 0xFF, 0x00, 0x00, 0x7F, 0xFF, 0x80, 0x00, 0x3F, 0xFF, 0xC0, 0x00, + 0x1F, 0xFF, 0xE0, 0x00, 0x0F, 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xF8, 0x00, + 0x03, 0xFD, 0xFC, 0x00, 0x01, 0xFC, 0xFE, 0x00, 0x01, 0xFE, 0x7F, 0x80, + 0x00, 0xFF, 0x1F, 0xC0, 0x00, 0x7F, 0x0F, 0xE0, 0x00, 0x3F, 0x83, 0xF8, + 0x00, 0x3F, 0x80, 0xFC, 0x00, 0x1F, 0x80, 0x3F, 0x00, 0x1F, 0x80, 0x0F, + 0xC0, 0x1F, 0x80, 0x03, 0xF0, 0x1F, 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x00, + 0x0F, 0xFC, 0x00, 0x00, 0x03, 0xFF, 0x00, 0x00, 0x01, 0xFF, 0xC0, 0x00, + 0x00, 0x7F, 0xF0, 0x00, 0x00, 0x1F, 0xFC, 0x00, 0x00, 0x07, 0xFF, 0x80, + 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0xFF, 0xFF, 0xE0, + 0x00, 0xFF, 0xFF, 0xF8, 0x00, 0x7F, 0xC3, 0xFC, 0x00, 0xFF, 0x01, 0xFC, + 0x01, 0xFE, 0x03, 0xFC, 0x03, 0xFC, 0x03, 0xF8, 0x07, 0xF8, 0x07, 0xF8, + 0x0F, 0xF0, 0x0F, 0xF0, 0x1F, 0xE0, 0x1F, 0xE0, 0x3F, 0xC0, 0x3F, 0xC0, + 0x7F, 0x80, 0x7F, 0x80, 0xFF, 0x00, 0xFF, 0x01, 0xFE, 0x01, 0xFC, 0x03, + 0xFC, 0x07, 0xF8, 0x07, 0xF8, 0x1F, 0xE0, 0x0F, 0xF0, 0xFF, 0x00, 0x1F, + 0xFF, 0xF8, 0x00, 0x3F, 0xFF, 0xE0, 0x00, 0x7F, 0x9F, 0xE0, 0x00, 0xFF, + 0x3F, 0xC0, 0x01, 0xFE, 0x3F, 0xC0, 0x03, 0xFC, 0x7F, 0xC0, 0x07, 0xF8, + 0x7F, 0xC0, 0x0F, 0xF0, 0x7F, 0x80, 0x1F, 0xE0, 0xFF, 0x80, 0x3F, 0xC0, + 0xFF, 0x80, 0x7F, 0x80, 0xFF, 0x00, 0xFF, 0x01, 0xFF, 0x01, 0xFE, 0x01, + 0xFF, 0x03, 0xFC, 0x01, 0xFF, 0x0F, 0xFC, 0x03, 0xFE, 0x7F, 0xFE, 0x03, + 0xFF, 0x03, 0xF8, 0x10, 0x7F, 0xF9, 0x87, 0xC1, 0xFC, 0x78, 0x03, 0xE7, + 0x80, 0x0F, 0x3C, 0x00, 0x3B, 0xE0, 0x01, 0xDF, 0x00, 0x06, 0xF8, 0x00, + 0x37, 0xE0, 0x00, 0xBF, 0x80, 0x01, 0xFF, 0x00, 0x0F, 0xFE, 0x00, 0x3F, + 0xFC, 0x01, 0xFF, 0xF8, 0x07, 0xFF, 0xF0, 0x1F, 0xFF, 0xC0, 0x7F, 0xFF, + 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xE0, 0x03, 0xFF, 0x80, 0x07, 0xFC, 0x00, + 0x1F, 0xF0, 0x00, 0x3F, 0x80, 0x01, 0xFE, 0x00, 0x07, 0xF0, 0x00, 0x3F, + 0xC0, 0x01, 0xEE, 0x00, 0x0F, 0x78, 0x00, 0xF3, 0xE0, 0x0F, 0x9F, 0xC0, + 0xF8, 0x8F, 0xFF, 0x04, 0x0F, 0xE0, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFC, 0x3F, 0xC3, 0xFF, 0x03, 0xFC, 0x0F, 0xE0, 0x3F, 0xC0, + 0x7C, 0x03, 0xFC, 0x03, 0xC0, 0x3F, 0xC0, 0x38, 0x03, 0xFC, 0x01, 0x80, + 0x3F, 0xC0, 0x10, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x03, 0xFC, + 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, + 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, + 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x03, 0xFC, 0x00, + 0x00, 0x3F, 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x03, + 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, + 0x00, 0x03, 0xFC, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0xFF, 0xC0, 0xFF, + 0xFE, 0x07, 0xFC, 0xFF, 0xC0, 0x07, 0xC1, 0xFE, 0x00, 0x0E, 0x07, 0xF8, + 0x00, 0x18, 0x1F, 0xE0, 0x00, 0x60, 0x7F, 0x80, 0x01, 0x81, 0xFE, 0x00, + 0x06, 0x07, 0xF8, 0x00, 0x18, 0x1F, 0xE0, 0x00, 0x60, 0x7F, 0x80, 0x01, + 0x81, 0xFE, 0x00, 0x06, 0x07, 0xF8, 0x00, 0x18, 0x1F, 0xE0, 0x00, 0x60, + 0x7F, 0x80, 0x01, 0x81, 0xFE, 0x00, 0x06, 0x07, 0xF8, 0x00, 0x18, 0x1F, + 0xE0, 0x00, 0x60, 0x7F, 0x80, 0x01, 0x81, 0xFE, 0x00, 0x06, 0x07, 0xF8, + 0x00, 0x18, 0x1F, 0xE0, 0x00, 0x60, 0x7F, 0x80, 0x01, 0x81, 0xFE, 0x00, + 0x06, 0x07, 0xF8, 0x00, 0x18, 0x1F, 0xE0, 0x00, 0x60, 0x7F, 0x80, 0x03, + 0x00, 0xFF, 0x00, 0x0C, 0x03, 0xFC, 0x00, 0x30, 0x07, 0xF0, 0x01, 0x80, + 0x0F, 0xE0, 0x0E, 0x00, 0x1F, 0xE0, 0xF0, 0x00, 0x1F, 0xFF, 0x00, 0x00, + 0x1F, 0xF0, 0x00, 0xFF, 0xFF, 0x01, 0xFF, 0x9F, 0xFC, 0x00, 0x1F, 0x07, + 0xFC, 0x00, 0x07, 0x01, 0xFE, 0x00, 0x03, 0x00, 0x7F, 0x80, 0x03, 0x80, + 0x3F, 0xC0, 0x01, 0x80, 0x1F, 0xE0, 0x00, 0xC0, 0x07, 0xF8, 0x00, 0xC0, + 0x03, 0xFC, 0x00, 0x60, 0x00, 0xFF, 0x00, 0x30, 0x00, 0x7F, 0x80, 0x30, + 0x00, 0x1F, 0xE0, 0x18, 0x00, 0x0F, 0xF0, 0x18, 0x00, 0x07, 0xF8, 0x0C, + 0x00, 0x01, 0xFE, 0x06, 0x00, 0x00, 0xFF, 0x06, 0x00, 0x00, 0x3F, 0xC3, + 0x00, 0x00, 0x1F, 0xE3, 0x80, 0x00, 0x0F, 0xF1, 0x80, 0x00, 0x03, 0xFC, + 0xC0, 0x00, 0x01, 0xFE, 0xC0, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0x00, 0x3F, + 0xF0, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x03, + 0xF8, 0x00, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, + 0x01, 0x80, 0x00, 0xFF, 0xF8, 0x7F, 0xFF, 0x0F, 0xFB, 0xFF, 0x00, 0xFF, + 0xC0, 0x1F, 0x0F, 0xF0, 0x03, 0xFC, 0x00, 0x70, 0x3F, 0x80, 0x0F, 0xE0, + 0x03, 0x81, 0xFE, 0x00, 0x7F, 0x80, 0x1C, 0x0F, 0xF0, 0x03, 0xFC, 0x00, + 0xC0, 0x3F, 0x80, 0x0F, 0xE0, 0x06, 0x01, 0xFE, 0x00, 0x7F, 0x00, 0x70, + 0x0F, 0xF0, 0x07, 0xFC, 0x03, 0x00, 0x3F, 0x80, 0x3F, 0xE0, 0x18, 0x01, + 0xFE, 0x01, 0xFF, 0x01, 0xC0, 0x0F, 0xF0, 0x1B, 0xFC, 0x0C, 0x00, 0x3F, + 0x80, 0xCF, 0xE0, 0x60, 0x01, 0xFE, 0x06, 0x7F, 0x07, 0x00, 0x0F, 0xF0, + 0x63, 0xFC, 0x30, 0x00, 0x3F, 0x83, 0x0F, 0xE1, 0x80, 0x01, 0xFE, 0x30, + 0x7F, 0x1C, 0x00, 0x07, 0xF1, 0x81, 0xFC, 0xC0, 0x00, 0x3F, 0x8C, 0x0F, + 0xE6, 0x00, 0x01, 0xFE, 0xC0, 0x7F, 0x70, 0x00, 0x07, 0xF6, 0x01, 0xFB, + 0x00, 0x00, 0x3F, 0xE0, 0x0F, 0xF8, 0x00, 0x01, 0xFF, 0x00, 0x7F, 0xC0, + 0x00, 0x07, 0xF8, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x00, + 0x01, 0xFC, 0x00, 0x7F, 0x00, 0x00, 0x07, 0xE0, 0x01, 0xF0, 0x00, 0x00, + 0x3E, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x00, 0x07, + 0x00, 0x01, 0xC0, 0x00, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x00, 0x01, 0xC0, + 0x00, 0x70, 0x00, 0x00, 0x04, 0x00, 0x01, 0x00, 0x00, 0xFF, 0xFF, 0x0F, + 0xFF, 0x3F, 0xF8, 0x01, 0xF8, 0x1F, 0xF8, 0x01, 0xE0, 0x0F, 0xF8, 0x01, + 0xC0, 0x0F, 0xF8, 0x01, 0x80, 0x07, 0xFC, 0x03, 0x80, 0x03, 0xFE, 0x07, + 0x00, 0x03, 0xFE, 0x06, 0x00, 0x01, 0xFF, 0x0C, 0x00, 0x00, 0xFF, 0x9C, + 0x00, 0x00, 0xFF, 0x98, 0x00, 0x00, 0x7F, 0xF0, 0x00, 0x00, 0x3F, 0xF0, + 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x0F, 0xFC, + 0x00, 0x00, 0x0F, 0xFE, 0x00, 0x00, 0x19, 0xFE, 0x00, 0x00, 0x31, 0xFF, + 0x00, 0x00, 0x70, 0xFF, 0x80, 0x00, 0x60, 0x7F, 0x80, 0x00, 0xC0, 0x7F, + 0xC0, 0x01, 0xC0, 0x3F, 0xE0, 0x03, 0x80, 0x1F, 0xE0, 0x07, 0x00, 0x1F, + 0xF0, 0x07, 0x00, 0x0F, 0xF8, 0x0F, 0x00, 0x0F, 0xF8, 0x3F, 0x80, 0x1F, + 0xFC, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0x7F, 0xF0, 0x00, + 0x7E, 0x1F, 0xF0, 0x00, 0x38, 0x1F, 0xF0, 0x00, 0x38, 0x0F, 0xF0, 0x00, + 0x70, 0x0F, 0xF8, 0x00, 0x60, 0x07, 0xF8, 0x00, 0x60, 0x07, 0xFC, 0x00, + 0xC0, 0x03, 0xFC, 0x01, 0xC0, 0x01, 0xFE, 0x01, 0x80, 0x01, 0xFE, 0x03, + 0x00, 0x00, 0xFF, 0x03, 0x00, 0x00, 0xFF, 0x86, 0x00, 0x00, 0x7F, 0x8E, + 0x00, 0x00, 0x7F, 0xCC, 0x00, 0x00, 0x3F, 0xD8, 0x00, 0x00, 0x3F, 0xF8, + 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x7F, 0xFE, + 0x00, 0x3F, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0xFC, 0x3F, 0x80, 0x7F, 0xC3, + 0xE0, 0x07, 0xF8, 0x38, 0x00, 0xFF, 0x83, 0x80, 0x0F, 0xF0, 0x30, 0x01, + 0xFE, 0x07, 0x00, 0x3F, 0xE0, 0x60, 0x03, 0xFC, 0x06, 0x00, 0x7F, 0xC0, + 0x00, 0x0F, 0xF8, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x01, + 0xFE, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x7F, 0x80, + 0x00, 0x0F, 0xF8, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x03, + 0xFE, 0x00, 0x00, 0x3F, 0xC0, 0x01, 0x07, 0xFC, 0x00, 0x30, 0xFF, 0x80, + 0x03, 0x0F, 0xF0, 0x00, 0x31, 0xFF, 0x00, 0x07, 0x1F, 0xE0, 0x00, 0xF3, + 0xFE, 0x00, 0x1E, 0x7F, 0xC0, 0x03, 0xE7, 0xF8, 0x01, 0xFE, 0xFF, 0xFF, + 0xFF, 0xEF, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xF0, 0x7C, 0x0F, 0x81, + 0xF0, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, + 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, + 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, + 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xFF, 0xFF, 0xF8, 0xF0, + 0x01, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0xC0, 0x07, 0x80, 0x0F, 0x00, + 0x1F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x7C, 0x00, 0x78, 0x00, 0xF0, 0x01, + 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1F, + 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, + 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, + 0x1E, 0xFF, 0xFF, 0xFC, 0x1F, 0x81, 0xF0, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, + 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, + 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, + 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, + 0x0F, 0x81, 0xF0, 0x3F, 0xFF, 0xFF, 0xF8, 0x00, 0x78, 0x00, 0x07, 0xC0, + 0x00, 0x3F, 0x00, 0x03, 0xF8, 0x00, 0x1F, 0xE0, 0x01, 0xEF, 0x00, 0x0F, + 0x3C, 0x00, 0xF1, 0xE0, 0x07, 0x87, 0x80, 0x78, 0x3C, 0x03, 0xC0, 0xF0, + 0x3C, 0x07, 0x81, 0xE0, 0x1E, 0x1E, 0x00, 0xF0, 0xF0, 0x07, 0xCF, 0x00, + 0x1E, 0x78, 0x00, 0xF8, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0x70, 0x1F, 0x03, 0xF0, 0x7E, 0x03, 0xE0, 0x3E, 0x01, 0xE0, 0x1E, + 0x00, 0xE0, 0x03, 0xFC, 0x00, 0x3F, 0xFC, 0x03, 0xE1, 0xF8, 0x0F, 0x03, + 0xF0, 0x7C, 0x07, 0xC1, 0xF8, 0x1F, 0x87, 0xE0, 0x7E, 0x1F, 0x81, 0xF8, + 0x3C, 0x07, 0xE0, 0x00, 0x1F, 0x80, 0x01, 0xFE, 0x00, 0x3F, 0xF8, 0x03, + 0xE7, 0xE0, 0x3E, 0x1F, 0x83, 0xF0, 0x7E, 0x1F, 0x81, 0xF8, 0x7E, 0x07, + 0xE3, 0xF8, 0x1F, 0x8F, 0xE0, 0x7E, 0x3F, 0x83, 0xF8, 0xFF, 0x1F, 0xE1, + 0xFF, 0xDF, 0xF7, 0xFE, 0x3F, 0x07, 0xE0, 0xF8, 0xFF, 0x80, 0x00, 0x1F, + 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03, 0xF0, 0x00, 0x01, 0xF8, 0x00, 0x00, + 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0x80, 0x00, + 0x0F, 0xC7, 0xF0, 0x07, 0xEF, 0xFE, 0x03, 0xFC, 0x3F, 0x81, 0xFC, 0x0F, + 0xE0, 0xFC, 0x03, 0xF0, 0x7E, 0x01, 0xFC, 0x3F, 0x00, 0xFE, 0x1F, 0x80, + 0x3F, 0x8F, 0xC0, 0x1F, 0xC7, 0xE0, 0x0F, 0xE3, 0xF0, 0x07, 0xF1, 0xF8, + 0x03, 0xF8, 0xFC, 0x01, 0xFC, 0x7E, 0x00, 0xFE, 0x3F, 0x00, 0x7F, 0x1F, + 0x80, 0x3F, 0x0F, 0xC0, 0x1F, 0x87, 0xE0, 0x1F, 0xC3, 0xF0, 0x0F, 0xC1, + 0xF8, 0x07, 0xE0, 0xFE, 0x07, 0xE0, 0x73, 0x87, 0xE0, 0x30, 0xFF, 0xC0, + 0x10, 0x1F, 0x80, 0x00, 0x00, 0xFC, 0x00, 0x7F, 0xE0, 0x3E, 0x3E, 0x0F, + 0x83, 0xE3, 0xE0, 0x7C, 0x7C, 0x0F, 0x9F, 0x01, 0xF3, 0xE0, 0x1C, 0x7C, + 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, + 0x00, 0x3F, 0x00, 0x07, 0xF0, 0x00, 0xFE, 0x00, 0x0F, 0xE0, 0x01, 0xFC, + 0x00, 0x1F, 0xC0, 0x21, 0xFE, 0x0C, 0x3F, 0xFF, 0x01, 0xFF, 0x80, 0x0F, + 0xC0, 0x00, 0x1F, 0xF8, 0x00, 0x03, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, + 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, + 0xF8, 0x00, 0x01, 0xF8, 0x03, 0xF1, 0xF8, 0x07, 0xFD, 0xF8, 0x1F, 0xC7, + 0xF8, 0x1F, 0x83, 0xF8, 0x3F, 0x01, 0xF8, 0x7F, 0x01, 0xF8, 0x7E, 0x01, + 0xF8, 0x7E, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, + 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, + 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0x7E, 0x01, 0xF8, 0x7F, 0x01, + 0xF8, 0x3F, 0x03, 0xF8, 0x3F, 0x03, 0xF8, 0x1F, 0x87, 0xFC, 0x0F, 0xFD, + 0xFF, 0x03, 0xF1, 0xC0, 0x03, 0xF0, 0x03, 0xFF, 0x01, 0xE1, 0xE0, 0xF8, + 0x7C, 0x3C, 0x0F, 0x1F, 0x03, 0xE7, 0xC0, 0xFB, 0xF0, 0x3E, 0xFC, 0x0F, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0xFC, 0x00, 0x3F, 0x00, 0x0F, + 0xC0, 0x03, 0xF8, 0x00, 0xFE, 0x00, 0x1F, 0x80, 0x07, 0xF0, 0x0C, 0xFC, + 0x06, 0x3F, 0xC3, 0x07, 0xFF, 0x80, 0xFF, 0xC0, 0x0F, 0xC0, 0x00, 0xFC, + 0x01, 0xFF, 0x81, 0xF1, 0xC1, 0xF0, 0xF0, 0xF8, 0xF8, 0xFC, 0x7C, 0x7E, + 0x1C, 0x3F, 0x00, 0x1F, 0x80, 0x0F, 0xC0, 0x07, 0xE0, 0x1F, 0xFF, 0x0F, + 0xFF, 0x80, 0xFC, 0x00, 0x7E, 0x00, 0x3F, 0x00, 0x1F, 0x80, 0x0F, 0xC0, + 0x07, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0x7E, 0x00, 0x3F, + 0x00, 0x1F, 0x80, 0x0F, 0xC0, 0x07, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x00, + 0xFC, 0x00, 0x7E, 0x00, 0x7F, 0x80, 0xFF, 0xF8, 0x00, 0x07, 0xF0, 0x03, + 0xFF, 0xFC, 0xF8, 0x7F, 0xBE, 0x07, 0x87, 0xC0, 0xF9, 0xF8, 0x1F, 0xBF, + 0x03, 0xF7, 0xE0, 0x7E, 0xFC, 0x0F, 0xDF, 0x81, 0xF9, 0xF0, 0x3F, 0x3E, + 0x07, 0xC3, 0xE1, 0xF8, 0x3C, 0x7E, 0x01, 0xFF, 0x00, 0x60, 0x00, 0x38, + 0x00, 0x0F, 0x00, 0x01, 0xF0, 0x00, 0x7F, 0xFF, 0x0F, 0xFF, 0xF9, 0xFF, + 0xFF, 0x9F, 0xFF, 0xF9, 0xFF, 0xFF, 0x0F, 0xFF, 0xEF, 0x00, 0x3F, 0xC0, + 0x03, 0xF8, 0x00, 0x7F, 0x00, 0x1C, 0xF8, 0x07, 0x0F, 0xFF, 0xC0, 0x7F, + 0xC0, 0xFF, 0x80, 0x00, 0x3F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, + 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, + 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x87, 0xE0, 0x1F, 0x9F, 0xF0, 0x1F, 0xBF, + 0xF8, 0x1F, 0xF1, 0xF8, 0x1F, 0xC0, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, + 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, + 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, + 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, + 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x3F, 0xC1, 0xFE, 0xFF, 0xE3, + 0xFF, 0x0F, 0x07, 0xE1, 0xFE, 0x3F, 0xC7, 0xF8, 0x7F, 0x03, 0xC0, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x7F, 0xC3, 0xF8, 0x3F, 0x07, 0xE0, 0xFC, 0x1F, + 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x07, 0xE0, 0xFC, 0x1F, 0x83, + 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x07, 0xE1, 0xFE, 0xFF, 0xE0, 0x00, + 0x70, 0x07, 0xF0, 0x3F, 0xC0, 0xFF, 0x03, 0xFC, 0x07, 0xF0, 0x0F, 0x80, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0x01, 0xFC, 0x03, 0xF0, + 0x0F, 0xC0, 0x3F, 0x00, 0xFC, 0x03, 0xF0, 0x0F, 0xC0, 0x3F, 0x00, 0xFC, + 0x03, 0xF0, 0x0F, 0xC0, 0x3F, 0x00, 0xFC, 0x03, 0xF0, 0x0F, 0xC0, 0x3F, + 0x00, 0xFC, 0x03, 0xF0, 0x0F, 0xC0, 0x3F, 0x00, 0xFC, 0x03, 0xF0, 0x0F, + 0xDC, 0x3F, 0xF8, 0xFB, 0xE3, 0xEF, 0x0F, 0xBC, 0x7C, 0x7F, 0xE0, 0x7E, + 0x00, 0xFF, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03, 0xF0, + 0x00, 0x01, 0xF8, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, + 0x00, 0x00, 0x1F, 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xE1, 0xFF, 0x83, + 0xF0, 0x3F, 0x01, 0xF8, 0x0E, 0x00, 0xFC, 0x06, 0x00, 0x7E, 0x06, 0x00, + 0x3F, 0x06, 0x00, 0x1F, 0x86, 0x00, 0x0F, 0xC7, 0x00, 0x07, 0xE7, 0x80, + 0x03, 0xF7, 0xE0, 0x01, 0xFF, 0xF8, 0x00, 0xFF, 0xFC, 0x00, 0x7E, 0x7F, + 0x00, 0x3F, 0x1F, 0xC0, 0x1F, 0x8F, 0xE0, 0x0F, 0xC3, 0xF8, 0x07, 0xE0, + 0xFE, 0x03, 0xF0, 0x7F, 0x81, 0xF8, 0x1F, 0xC0, 0xFC, 0x0F, 0xF0, 0xFF, + 0x07, 0xFD, 0xFF, 0xC7, 0xFF, 0xFF, 0x87, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, + 0x3F, 0x07, 0xE0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, + 0x07, 0xE0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x07, + 0xE0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x0F, 0xF7, + 0xFF, 0x00, 0x07, 0xE0, 0x3F, 0x07, 0xFC, 0xFF, 0x87, 0xFC, 0x0F, 0xEF, + 0xFE, 0x7F, 0xF0, 0x3F, 0xC3, 0xFF, 0x1F, 0x81, 0xFC, 0x0F, 0xE0, 0x7E, + 0x0F, 0xC0, 0x7E, 0x03, 0xF0, 0x7E, 0x03, 0xF0, 0x1F, 0x83, 0xF0, 0x1F, + 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x07, 0xE0, 0xFC, 0x07, 0xE0, 0x3F, 0x07, + 0xE0, 0x3F, 0x01, 0xF8, 0x3F, 0x01, 0xF8, 0x0F, 0xC1, 0xF8, 0x0F, 0xC0, + 0x7E, 0x0F, 0xC0, 0x7E, 0x03, 0xF0, 0x7E, 0x03, 0xF0, 0x1F, 0x83, 0xF0, + 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x07, 0xE0, 0xFC, 0x07, 0xE0, 0x3F, + 0x07, 0xE0, 0x3F, 0x01, 0xF8, 0x3F, 0x01, 0xF8, 0x0F, 0xC1, 0xF8, 0x0F, + 0xC0, 0x7E, 0x1F, 0xE0, 0xFF, 0x07, 0xFB, 0xFF, 0x8F, 0xFC, 0x7F, 0xE0, + 0x00, 0x07, 0xE0, 0xFF, 0x9F, 0xF0, 0x3F, 0xBF, 0xF8, 0x1F, 0xF1, 0xF8, + 0x1F, 0xC0, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, + 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, + 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, + 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, + 0x1F, 0x80, 0xFC, 0x3F, 0xC1, 0xFE, 0xFF, 0xE3, 0xFF, 0x01, 0xFC, 0x00, + 0x3F, 0xF8, 0x03, 0xE3, 0xE0, 0x3E, 0x0F, 0x83, 0xF0, 0x7E, 0x1F, 0x01, + 0xF1, 0xF8, 0x0F, 0xCF, 0xC0, 0x7E, 0xFE, 0x03, 0xFF, 0xF0, 0x1F, 0xFF, + 0x80, 0xFF, 0xFC, 0x07, 0xFF, 0xE0, 0x3F, 0xFF, 0x01, 0xFF, 0xF8, 0x0F, + 0xFF, 0xC0, 0x7F, 0x7E, 0x03, 0xF3, 0xF0, 0x1F, 0x8F, 0x80, 0xF8, 0x7E, + 0x0F, 0xC1, 0xF0, 0x7C, 0x07, 0xC7, 0xC0, 0x1F, 0xFC, 0x00, 0x3F, 0x80, + 0x00, 0x0F, 0xC0, 0xFF, 0xBF, 0xF0, 0x3F, 0xF1, 0xF8, 0x1F, 0xC0, 0xFC, + 0x1F, 0xC0, 0xFC, 0x1F, 0x80, 0xFE, 0x1F, 0x80, 0x7E, 0x1F, 0x80, 0x7F, + 0x1F, 0x80, 0x7F, 0x1F, 0x80, 0x7F, 0x1F, 0x80, 0x7F, 0x1F, 0x80, 0x7F, + 0x1F, 0x80, 0x7F, 0x1F, 0x80, 0x7F, 0x1F, 0x80, 0x7F, 0x1F, 0x80, 0x7F, + 0x1F, 0x80, 0x7E, 0x1F, 0x80, 0x7E, 0x1F, 0x80, 0xFE, 0x1F, 0x80, 0xFC, + 0x1F, 0xC1, 0xF8, 0x1F, 0xE3, 0xF8, 0x1F, 0xBF, 0xE0, 0x1F, 0x8F, 0xC0, + 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, + 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0xF8, 0x00, + 0x00, 0xF8, 0x08, 0x07, 0xFE, 0x18, 0x0F, 0xC7, 0x38, 0x1F, 0x83, 0xF8, + 0x3F, 0x01, 0xF8, 0x3F, 0x01, 0xF8, 0x7F, 0x01, 0xF8, 0x7E, 0x01, 0xF8, + 0x7E, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, + 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, + 0xFE, 0x01, 0xF8, 0x7E, 0x01, 0xF8, 0x7F, 0x01, 0xF8, 0x7F, 0x01, 0xF8, + 0x3F, 0x83, 0xF8, 0x1F, 0xC7, 0xF8, 0x0F, 0xFD, 0xF8, 0x03, 0xF1, 0xF8, + 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, + 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xFF, + 0x00, 0x07, 0x9F, 0xF3, 0xF8, 0xFE, 0xFF, 0x8F, 0xFF, 0xF1, 0xFE, 0x7E, + 0x3F, 0x87, 0x87, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, + 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0, 0x00, + 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, + 0xF8, 0x00, 0x7F, 0x80, 0x3F, 0xFC, 0x00, 0x0F, 0x84, 0x3F, 0xF8, 0xE1, + 0xF3, 0x80, 0xEF, 0x00, 0xDE, 0x01, 0xBE, 0x01, 0x7E, 0x00, 0xFF, 0x01, + 0xFF, 0x81, 0xFF, 0xC3, 0xFF, 0xC3, 0xFF, 0xC1, 0xFF, 0x80, 0xFF, 0x80, + 0x7F, 0x80, 0x7F, 0x80, 0x7F, 0x00, 0x7E, 0x00, 0xFE, 0x01, 0xDF, 0x0F, + 0x37, 0xFC, 0x43, 0xF0, 0x01, 0x00, 0x0C, 0x00, 0x70, 0x01, 0xC0, 0x0F, + 0x00, 0x7C, 0x03, 0xF0, 0x1F, 0xC0, 0xFF, 0xF3, 0xFF, 0xC3, 0xF0, 0x0F, + 0xC0, 0x3F, 0x00, 0xFC, 0x03, 0xF0, 0x0F, 0xC0, 0x3F, 0x00, 0xFC, 0x03, + 0xF0, 0x0F, 0xC0, 0x3F, 0x00, 0xFC, 0x03, 0xF0, 0x0F, 0xC0, 0x3F, 0x00, + 0xFC, 0x23, 0xF0, 0x8F, 0xE6, 0x1F, 0xF0, 0x7F, 0x80, 0xF8, 0x00, 0xFF, + 0x87, 0xFC, 0x1F, 0xC0, 0xFE, 0x07, 0xE0, 0x3F, 0x03, 0xF0, 0x1F, 0x81, + 0xF8, 0x0F, 0xC0, 0xFC, 0x07, 0xE0, 0x7E, 0x03, 0xF0, 0x3F, 0x01, 0xF8, + 0x1F, 0x80, 0xFC, 0x0F, 0xC0, 0x7E, 0x07, 0xE0, 0x3F, 0x03, 0xF0, 0x1F, + 0x81, 0xF8, 0x0F, 0xC0, 0xFC, 0x07, 0xE0, 0x7E, 0x03, 0xF0, 0x3F, 0x01, + 0xF8, 0x1F, 0x80, 0xFC, 0x0F, 0xC0, 0x7E, 0x07, 0xE0, 0x7F, 0x03, 0xF8, + 0x7F, 0xC0, 0xFF, 0xEF, 0xF8, 0x3F, 0xE7, 0xC0, 0x0F, 0xC2, 0x00, 0xFF, + 0xF1, 0xFC, 0xFF, 0x01, 0xE3, 0xFC, 0x03, 0x07, 0xF0, 0x0C, 0x1F, 0xC0, + 0x60, 0x3F, 0x81, 0x80, 0xFE, 0x04, 0x01, 0xF8, 0x30, 0x07, 0xF0, 0xC0, + 0x1F, 0xC6, 0x00, 0x3F, 0x98, 0x00, 0xFE, 0x40, 0x01, 0xFB, 0x00, 0x07, + 0xFC, 0x00, 0x1F, 0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFE, 0x00, 0x01, 0xF0, + 0x00, 0x07, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, + 0x01, 0x00, 0x00, 0xFF, 0xE7, 0xFF, 0x3F, 0xBF, 0xE0, 0xFE, 0x07, 0x0F, + 0xE0, 0x7F, 0x03, 0x83, 0xF0, 0x1F, 0x81, 0x81, 0xFC, 0x0F, 0xC0, 0xC0, + 0xFE, 0x07, 0xF0, 0x40, 0x3F, 0x03, 0xF8, 0x60, 0x1F, 0xC3, 0xFC, 0x30, + 0x07, 0xE1, 0xFE, 0x10, 0x03, 0xF0, 0x9F, 0x98, 0x01, 0xFC, 0xCF, 0xCC, + 0x00, 0x7E, 0x67, 0xEC, 0x00, 0x3F, 0xE1, 0xFE, 0x00, 0x1F, 0xF0, 0xFE, + 0x00, 0x07, 0xF0, 0x7F, 0x00, 0x03, 0xF8, 0x3F, 0x80, 0x00, 0xFC, 0x0F, + 0x80, 0x00, 0x7C, 0x07, 0xC0, 0x00, 0x3E, 0x03, 0xE0, 0x00, 0x0F, 0x00, + 0xE0, 0x00, 0x07, 0x00, 0x70, 0x00, 0x03, 0x80, 0x38, 0x00, 0x00, 0x80, + 0x08, 0x00, 0xFF, 0xF3, 0xFD, 0xFF, 0x03, 0xC3, 0xFC, 0x0E, 0x07, 0xF0, + 0x30, 0x1F, 0xE1, 0x80, 0x3F, 0x8C, 0x00, 0x7F, 0x70, 0x01, 0xFF, 0x80, + 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x1F, 0xE0, 0x00, 0x3F, 0x80, 0x00, + 0xFF, 0x00, 0x07, 0xFE, 0x00, 0x1B, 0xF8, 0x00, 0xCF, 0xF0, 0x06, 0x1F, + 0xC0, 0x38, 0x3F, 0x80, 0xC0, 0xFF, 0x07, 0x01, 0xFC, 0x3C, 0x07, 0xFB, + 0xFC, 0x7F, 0xF0, 0xFF, 0xE3, 0xFB, 0xFC, 0x07, 0x8F, 0xE0, 0x18, 0x7F, + 0x01, 0x81, 0xF8, 0x0C, 0x0F, 0xE0, 0x60, 0x7F, 0x06, 0x01, 0xF8, 0x30, + 0x0F, 0xE1, 0x80, 0x7F, 0x18, 0x01, 0xF8, 0xC0, 0x0F, 0xE6, 0x00, 0x3F, + 0x60, 0x01, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0x80, 0x01, 0xFC, 0x00, + 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x07, 0x00, 0x00, 0x38, + 0x00, 0x00, 0x80, 0x00, 0x0C, 0x00, 0x00, 0x60, 0x03, 0x82, 0x00, 0x3E, + 0x30, 0x01, 0xF1, 0x00, 0x0F, 0x98, 0x00, 0x3F, 0x80, 0x00, 0xF0, 0x00, + 0x00, 0x7F, 0xFF, 0xEF, 0xFF, 0xFD, 0xE0, 0x7F, 0x30, 0x1F, 0xC6, 0x07, + 0xF8, 0x80, 0xFE, 0x00, 0x3F, 0xC0, 0x07, 0xF0, 0x01, 0xFC, 0x00, 0x3F, + 0x80, 0x0F, 0xE0, 0x03, 0xFC, 0x00, 0x7F, 0x00, 0x1F, 0xE0, 0x03, 0xF8, + 0x00, 0xFE, 0x03, 0x3F, 0xC0, 0x67, 0xF0, 0x19, 0xFE, 0x07, 0x3F, 0x83, + 0xEF, 0xFF, 0xFD, 0xFF, 0xFF, 0x80, 0x00, 0x7C, 0x07, 0xE0, 0x3E, 0x00, + 0xF8, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, + 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, + 0x1F, 0x00, 0xF8, 0x03, 0xC0, 0x3C, 0x01, 0xF0, 0x00, 0xF0, 0x03, 0xE0, + 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, + 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, + 0x00, 0x3E, 0x00, 0xF8, 0x01, 0xF8, 0x01, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF0, 0xF8, 0x01, 0xF8, 0x01, 0xF0, 0x07, 0xC0, 0x0F, 0x80, 0x3E, 0x00, + 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, + 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0x7C, 0x00, 0xF0, + 0x00, 0xF0, 0x03, 0xE0, 0x3C, 0x01, 0xF0, 0x0F, 0x80, 0x3E, 0x00, 0xF8, + 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, + 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x01, 0xF0, 0x07, 0xC0, 0x7E, + 0x03, 0xE0, 0x00, 0x0F, 0x80, 0x00, 0xFF, 0xC0, 0x47, 0xFF, 0xC3, 0x9F, + 0xFF, 0xFF, 0x70, 0x7F, 0xF8, 0x80, 0x7F, 0xC0, 0x00, 0x3E, 0x00 }; + +const GFXglyph FreeSerifBold24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 12, 0, 1 }, // 0x20 ' ' + { 0, 8, 34, 16, 4, -32 }, // 0x21 '!' + { 34, 17, 13, 26, 4, -32 }, // 0x22 '"' + { 62, 23, 33, 23, 0, -32 }, // 0x23 '#' + { 157, 21, 39, 24, 1, -34 }, // 0x24 '$' + { 260, 35, 34, 47, 6, -32 }, // 0x25 '%' + { 409, 34, 34, 39, 3, -32 }, // 0x26 '&' + { 554, 5, 13, 13, 4, -32 }, // 0x27 ''' + { 563, 12, 41, 16, 2, -32 }, // 0x28 '(' + { 625, 12, 41, 16, 1, -32 }, // 0x29 ')' + { 687, 18, 21, 24, 3, -32 }, // 0x2A '*' + { 735, 26, 25, 32, 3, -24 }, // 0x2B '+' + { 817, 8, 15, 12, 2, -6 }, // 0x2C ',' + { 832, 11, 5, 16, 2, -12 }, // 0x2D '-' + { 839, 8, 8, 12, 2, -6 }, // 0x2E '.' + { 847, 15, 33, 13, -1, -32 }, // 0x2F '/' + { 909, 22, 34, 23, 1, -32 }, // 0x30 '0' + { 1003, 18, 33, 23, 3, -32 }, // 0x31 '1' + { 1078, 21, 33, 24, 1, -32 }, // 0x32 '2' + { 1165, 21, 34, 24, 1, -32 }, // 0x33 '3' + { 1255, 21, 33, 24, 1, -32 }, // 0x34 '4' + { 1342, 20, 32, 23, 2, -31 }, // 0x35 '5' + { 1422, 21, 34, 24, 1, -32 }, // 0x36 '6' + { 1512, 21, 32, 23, 1, -31 }, // 0x37 '7' + { 1596, 21, 34, 23, 1, -32 }, // 0x38 '8' + { 1686, 22, 34, 23, 1, -32 }, // 0x39 '9' + { 1780, 8, 24, 16, 4, -22 }, // 0x3A ':' + { 1804, 9, 31, 16, 3, -22 }, // 0x3B ';' + { 1839, 26, 26, 32, 3, -24 }, // 0x3C '<' + { 1924, 26, 17, 32, 3, -20 }, // 0x3D '=' + { 1980, 26, 26, 32, 3, -24 }, // 0x3E '>' + { 2065, 18, 34, 24, 3, -32 }, // 0x3F '?' + { 2142, 33, 34, 44, 5, -32 }, // 0x40 '@' + { 2283, 32, 33, 34, 1, -32 }, // 0x41 'A' + { 2415, 28, 32, 31, 1, -31 }, // 0x42 'B' + { 2527, 30, 34, 33, 2, -32 }, // 0x43 'C' + { 2655, 32, 32, 34, 1, -31 }, // 0x44 'D' + { 2783, 28, 32, 32, 2, -31 }, // 0x45 'E' + { 2895, 25, 32, 29, 2, -31 }, // 0x46 'F' + { 2995, 33, 34, 36, 2, -32 }, // 0x47 'G' + { 3136, 33, 32, 37, 2, -31 }, // 0x48 'H' + { 3268, 15, 32, 18, 2, -31 }, // 0x49 'I' + { 3328, 22, 37, 24, 0, -31 }, // 0x4A 'J' + { 3430, 34, 32, 36, 2, -31 }, // 0x4B 'K' + { 3566, 28, 32, 31, 2, -31 }, // 0x4C 'L' + { 3678, 43, 32, 45, 0, -31 }, // 0x4D 'M' + { 3850, 31, 32, 34, 1, -31 }, // 0x4E 'N' + { 3974, 33, 34, 37, 2, -32 }, // 0x4F 'O' + { 4115, 26, 32, 30, 2, -31 }, // 0x50 'P' + { 4219, 33, 41, 37, 2, -32 }, // 0x51 'Q' + { 4389, 31, 32, 34, 2, -31 }, // 0x52 'R' + { 4513, 21, 34, 27, 3, -32 }, // 0x53 'S' + { 4603, 28, 32, 30, 1, -31 }, // 0x54 'T' + { 4715, 30, 33, 34, 2, -31 }, // 0x55 'U' + { 4839, 33, 32, 33, 0, -31 }, // 0x56 'V' + { 4971, 45, 33, 46, 1, -31 }, // 0x57 'W' + { 5157, 32, 32, 34, 1, -31 }, // 0x58 'X' + { 5285, 32, 32, 33, 1, -31 }, // 0x59 'Y' + { 5413, 28, 32, 30, 1, -31 }, // 0x5A 'Z' + { 5525, 11, 39, 16, 3, -31 }, // 0x5B '[' + { 5579, 15, 33, 13, -1, -32 }, // 0x5C '\' + { 5641, 11, 39, 16, 2, -31 }, // 0x5D ']' + { 5695, 21, 17, 27, 3, -31 }, // 0x5E '^' + { 5740, 24, 3, 23, 0, 5 }, // 0x5F '_' + { 5749, 11, 9, 16, 0, -33 }, // 0x60 '`' + { 5762, 22, 24, 23, 1, -22 }, // 0x61 'a' + { 5828, 25, 33, 26, 0, -31 }, // 0x62 'b' + { 5932, 19, 24, 20, 1, -22 }, // 0x63 'c' + { 5989, 24, 33, 26, 1, -31 }, // 0x64 'd' + { 6088, 18, 24, 21, 1, -22 }, // 0x65 'e' + { 6142, 17, 33, 18, 1, -32 }, // 0x66 'f' + { 6213, 19, 32, 24, 2, -22 }, // 0x67 'g' + { 6289, 24, 32, 26, 0, -31 }, // 0x68 'h' + { 6385, 11, 33, 14, 1, -32 }, // 0x69 'i' + { 6431, 14, 42, 18, 0, -32 }, // 0x6A 'j' + { 6505, 25, 32, 26, 0, -31 }, // 0x6B 'k' + { 6605, 11, 32, 13, 0, -31 }, // 0x6C 'l' + { 6649, 37, 23, 39, 0, -22 }, // 0x6D 'm' + { 6756, 24, 23, 26, 0, -22 }, // 0x6E 'n' + { 6825, 21, 24, 24, 1, -22 }, // 0x6F 'o' + { 6888, 24, 32, 26, 0, -22 }, // 0x70 'p' + { 6984, 24, 32, 26, 1, -22 }, // 0x71 'q' + { 7080, 19, 23, 20, 0, -22 }, // 0x72 'r' + { 7135, 15, 24, 19, 2, -22 }, // 0x73 's' + { 7180, 14, 31, 16, 1, -29 }, // 0x74 't' + { 7235, 25, 23, 27, 0, -21 }, // 0x75 'u' + { 7307, 22, 23, 23, 0, -21 }, // 0x76 'v' + { 7371, 33, 23, 33, 0, -21 }, // 0x77 'w' + { 7466, 22, 22, 24, 1, -21 }, // 0x78 'x' + { 7527, 21, 31, 23, 0, -21 }, // 0x79 'y' + { 7609, 19, 22, 21, 1, -21 }, // 0x7A 'z' + { 7662, 14, 42, 19, 1, -33 }, // 0x7B '{' + { 7736, 4, 33, 10, 3, -32 }, // 0x7C '|' + { 7753, 14, 42, 19, 4, -33 }, // 0x7D '}' + { 7827, 22, 7, 24, 1, -14 } }; // 0x7E '~' + +const GFXfont FreeSerifBold24pt7b PROGMEM = { + (uint8_t *)FreeSerifBold24pt7bBitmaps, + (GFXglyph *)FreeSerifBold24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 8519 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBold9pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBold9pt7b.h new file mode 100644 index 0000000..52dbe36 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBold9pt7b.h @@ -0,0 +1,202 @@ +const uint8_t FreeSerifBold9pt7bBitmaps[] PROGMEM = { + 0xFF, 0xF4, 0x92, 0x1F, 0xF0, 0xCF, 0x3C, 0xE3, 0x88, 0x13, 0x09, 0x84, + 0xC2, 0x47, 0xF9, 0x90, 0xC8, 0x4C, 0xFF, 0x13, 0x09, 0x0C, 0x86, 0x40, + 0x10, 0x38, 0xD6, 0x92, 0xD2, 0xF0, 0x7C, 0x3E, 0x17, 0x93, 0x93, 0xD6, + 0x7C, 0x10, 0x3C, 0x21, 0xCF, 0x0E, 0x24, 0x30, 0xA0, 0xC5, 0x03, 0x34, + 0xE7, 0x26, 0x40, 0xB9, 0x04, 0xC4, 0x23, 0x30, 0x8C, 0x84, 0x1C, 0x0F, + 0x00, 0xCC, 0x06, 0x60, 0x3E, 0x00, 0xE7, 0x8F, 0x18, 0x9C, 0x8C, 0xE4, + 0xE3, 0xC7, 0x9E, 0x3C, 0x72, 0xFD, 0xE0, 0xFF, 0x80, 0x32, 0x44, 0xCC, + 0xCC, 0xCC, 0xC4, 0x62, 0x10, 0x84, 0x22, 0x33, 0x33, 0x33, 0x32, 0x64, + 0x80, 0x31, 0x6B, 0xB1, 0x8E, 0xD6, 0x8C, 0x00, 0x08, 0x04, 0x02, 0x01, + 0x0F, 0xF8, 0x40, 0x20, 0x10, 0x08, 0x00, 0xDF, 0x95, 0x00, 0xFF, 0xFF, + 0x80, 0x0C, 0x21, 0x86, 0x10, 0xC3, 0x08, 0x61, 0x84, 0x30, 0xC0, 0x1C, + 0x33, 0x98, 0xDC, 0x7E, 0x3F, 0x1F, 0x8F, 0xC7, 0xE3, 0xB1, 0x98, 0xC3, + 0x80, 0x08, 0xE3, 0x8E, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0xBF, 0x3C, 0x3F, + 0x23, 0xC0, 0xE0, 0x70, 0x30, 0x38, 0x18, 0x18, 0x18, 0x5F, 0xDF, 0xE0, + 0x7C, 0x8E, 0x0E, 0x0E, 0x0C, 0x1E, 0x07, 0x03, 0x03, 0x02, 0xE6, 0xF8, + 0x06, 0x0E, 0x0E, 0x3E, 0x2E, 0x4E, 0x8E, 0x8E, 0xFF, 0xFF, 0x0E, 0x0E, + 0x3F, 0x7E, 0x40, 0x40, 0xF8, 0xFC, 0x1E, 0x06, 0x02, 0x02, 0xE4, 0xF8, + 0x07, 0x1C, 0x30, 0x70, 0xFC, 0xE6, 0xE7, 0xE7, 0xE7, 0x67, 0x66, 0x3C, + 0x7F, 0x3F, 0xA0, 0xD0, 0x40, 0x60, 0x30, 0x10, 0x18, 0x0C, 0x04, 0x06, + 0x03, 0x00, 0x3C, 0xC6, 0xC6, 0xC6, 0xFC, 0x7C, 0x3E, 0xCF, 0xC7, 0xC7, + 0xC6, 0x7C, 0x3E, 0x33, 0xB8, 0xDC, 0x7E, 0x3F, 0x1D, 0xCE, 0x7F, 0x07, + 0x07, 0x0F, 0x1C, 0x00, 0xFF, 0x80, 0x3F, 0xE0, 0xFF, 0x80, 0x37, 0xE5, + 0x40, 0x00, 0x00, 0x70, 0x78, 0x78, 0x78, 0x38, 0x03, 0x80, 0x3C, 0x03, + 0xC0, 0x30, 0xFF, 0xC0, 0x00, 0x00, 0x00, 0xFF, 0xC0, 0xC0, 0x3C, 0x03, + 0xC0, 0x1C, 0x01, 0xC1, 0xE1, 0xE1, 0xE0, 0xE0, 0x00, 0x00, 0x3D, 0x9F, + 0x3E, 0x70, 0xE1, 0x04, 0x08, 0x00, 0x70, 0xE1, 0xC0, 0x0F, 0x81, 0x83, + 0x18, 0xC4, 0x89, 0x9C, 0x4C, 0xE4, 0x67, 0x22, 0x39, 0x22, 0x4F, 0xE3, + 0x00, 0x0C, 0x10, 0x1F, 0x00, 0x02, 0x00, 0x30, 0x01, 0xC0, 0x0E, 0x00, + 0xB8, 0x05, 0xC0, 0x4F, 0x02, 0x38, 0x3F, 0xE1, 0x07, 0x18, 0x3D, 0xE3, + 0xF0, 0xFF, 0x87, 0x1C, 0xE3, 0x9C, 0x73, 0x9C, 0x7F, 0x0E, 0x71, 0xC7, + 0x38, 0xE7, 0x1C, 0xE7, 0x7F, 0xC0, 0x1F, 0x26, 0x1D, 0xC1, 0xB0, 0x1E, + 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x0E, 0x04, 0xE1, 0x0F, 0xC0, 0xFF, + 0x0E, 0x71, 0xC7, 0x38, 0x77, 0x0E, 0xE1, 0xDC, 0x3B, 0x87, 0x70, 0xCE, + 0x39, 0xC6, 0x7F, 0x80, 0xFF, 0xCE, 0x19, 0xC1, 0x38, 0x87, 0x30, 0xFE, + 0x1C, 0xC3, 0x88, 0x70, 0x2E, 0x0D, 0xC3, 0x7F, 0xE0, 0xFF, 0xDC, 0x37, + 0x05, 0xC4, 0x73, 0x1F, 0xC7, 0x31, 0xC4, 0x70, 0x1C, 0x07, 0x03, 0xE0, + 0x1F, 0x23, 0x0E, 0x70, 0x6E, 0x02, 0xE0, 0x0E, 0x00, 0xE1, 0xFE, 0x0E, + 0x60, 0xE7, 0x0E, 0x38, 0xE0, 0xF8, 0xF9, 0xF7, 0x0E, 0x70, 0xE7, 0x0E, + 0x70, 0xE7, 0xFE, 0x70, 0xE7, 0x0E, 0x70, 0xE7, 0x0E, 0x70, 0xEF, 0x9F, + 0xFB, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9D, 0xF0, 0x1F, 0x0E, 0x0E, 0x0E, + 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0xCE, 0xCC, 0x78, 0xF9, 0xF3, + 0x82, 0x1C, 0x20, 0xE2, 0x07, 0x20, 0x3F, 0x01, 0xDC, 0x0E, 0x70, 0x73, + 0xC3, 0x8F, 0x1C, 0x3D, 0xF3, 0xF0, 0xF8, 0x0E, 0x01, 0xC0, 0x38, 0x07, + 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x2E, 0x09, 0xC3, 0x7F, 0xE0, 0xF8, + 0x0F, 0x3C, 0x1E, 0x3C, 0x1E, 0x2E, 0x2E, 0x2E, 0x2E, 0x26, 0x4E, 0x27, + 0x4E, 0x27, 0x4E, 0x23, 0x8E, 0x23, 0x8E, 0x21, 0x0E, 0x71, 0x1F, 0xF0, + 0xEE, 0x09, 0xE1, 0x3E, 0x25, 0xE4, 0x9E, 0x91, 0xD2, 0x1E, 0x43, 0xC8, + 0x39, 0x03, 0x70, 0x20, 0x1F, 0x83, 0x0C, 0x70, 0xEE, 0x07, 0xE0, 0x7E, + 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0x77, 0x0E, 0x30, 0xC1, 0xF8, 0xFF, 0x1C, + 0xE7, 0x1D, 0xC7, 0x71, 0xDC, 0xE7, 0xF1, 0xC0, 0x70, 0x1C, 0x07, 0x03, + 0xE0, 0x0F, 0x83, 0x9C, 0x70, 0xE6, 0x06, 0xE0, 0x7E, 0x07, 0xE0, 0x7E, + 0x07, 0xE0, 0x76, 0x06, 0x30, 0xC1, 0x98, 0x0F, 0x00, 0x78, 0x03, 0xE0, + 0xFF, 0x07, 0x38, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x38, 0x7E, 0x07, 0x70, + 0x77, 0x87, 0x3C, 0x71, 0xEF, 0x8F, 0x39, 0x47, 0xC1, 0xC0, 0xF0, 0x7C, + 0x3E, 0x0F, 0x83, 0xC3, 0xC6, 0xBC, 0xFF, 0xFC, 0xE3, 0x8E, 0x10, 0xE0, + 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x01, 0xF0, + 0xF8, 0xEE, 0x09, 0xC1, 0x38, 0x27, 0x04, 0xE0, 0x9C, 0x13, 0x82, 0x70, + 0x4E, 0x08, 0xE2, 0x0F, 0x80, 0xFC, 0x7B, 0xC1, 0x0E, 0x08, 0x70, 0x81, + 0xC4, 0x0E, 0x20, 0x7A, 0x01, 0xD0, 0x0E, 0x80, 0x38, 0x01, 0xC0, 0x04, + 0x00, 0x20, 0x00, 0xFD, 0xFB, 0xDC, 0x38, 0x43, 0x87, 0x10, 0xE1, 0xC4, + 0x38, 0xF2, 0x07, 0x2E, 0x81, 0xD3, 0xA0, 0x34, 0x70, 0x0E, 0x1C, 0x03, + 0x87, 0x00, 0x60, 0x80, 0x10, 0x20, 0xFE, 0xF3, 0xC3, 0x0F, 0x10, 0x39, + 0x00, 0xF0, 0x03, 0x80, 0x1E, 0x01, 0x70, 0x09, 0xC0, 0x8F, 0x08, 0x3D, + 0xF3, 0xF0, 0xFC, 0x7B, 0xC1, 0x8E, 0x08, 0x38, 0x81, 0xE8, 0x07, 0x40, + 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x1F, 0x00, 0xFF, 0xD8, + 0x72, 0x1E, 0x43, 0x80, 0xE0, 0x1C, 0x07, 0x01, 0xC0, 0x38, 0x2E, 0x0F, + 0x83, 0x7F, 0xE0, 0xFC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xF0, 0xC1, + 0x06, 0x18, 0x20, 0xC3, 0x04, 0x18, 0x60, 0x83, 0x0C, 0xF3, 0x33, 0x33, + 0x33, 0x33, 0x33, 0x33, 0xF0, 0x18, 0x1C, 0x34, 0x26, 0x62, 0x43, 0xC1, + 0xFF, 0x80, 0xC6, 0x30, 0x7C, 0x63, 0xB1, 0xC0, 0xE1, 0xF3, 0x3B, 0x9D, + 0xCE, 0xFF, 0x80, 0xF0, 0x1C, 0x07, 0x01, 0xDC, 0x7B, 0x9C, 0x77, 0x1D, + 0xC7, 0x71, 0xDC, 0x77, 0x39, 0x3C, 0x3C, 0xED, 0x9F, 0x0E, 0x1C, 0x38, + 0x39, 0x3C, 0x07, 0x80, 0xE0, 0x38, 0xEE, 0x77, 0xB8, 0xEE, 0x3B, 0x8E, + 0xE3, 0xB8, 0xE7, 0x78, 0xEF, 0x3C, 0x66, 0xE6, 0xFE, 0xE0, 0xE0, 0xE0, + 0x72, 0x3C, 0x3E, 0xED, 0xC7, 0xC7, 0x0E, 0x1C, 0x38, 0x70, 0xE1, 0xC7, + 0xC0, 0x31, 0xDF, 0xBF, 0x7E, 0xE7, 0x90, 0x60, 0xFC, 0xFE, 0x0C, 0x17, + 0xC0, 0xF0, 0x1C, 0x07, 0x01, 0xDC, 0x7B, 0x9C, 0xE7, 0x39, 0xCE, 0x73, + 0x9C, 0xE7, 0x3B, 0xFF, 0x73, 0x9D, 0xE7, 0x39, 0xCE, 0x73, 0x9D, 0xF0, + 0x1C, 0x71, 0xCF, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x7D, 0xBE, + 0xF0, 0x1C, 0x07, 0x01, 0xCE, 0x71, 0x1C, 0x87, 0x41, 0xF8, 0x77, 0x1C, + 0xE7, 0x1B, 0xEF, 0xF3, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9D, 0xF0, 0xF7, + 0x38, 0xF7, 0xB9, 0xCE, 0x73, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9C, 0xE7, + 0x39, 0xCE, 0xFF, 0xFE, 0xF7, 0x1E, 0xE7, 0x39, 0xCE, 0x73, 0x9C, 0xE7, + 0x39, 0xCE, 0xFF, 0xC0, 0x3E, 0x31, 0xB8, 0xFC, 0x7E, 0x3F, 0x1F, 0x8E, + 0xC6, 0x3E, 0x00, 0xF7, 0x1E, 0xE7, 0x1D, 0xC7, 0x71, 0xDC, 0x77, 0x1D, + 0xCE, 0x7F, 0x1C, 0x07, 0x01, 0xC0, 0xF8, 0x00, 0x3C, 0x9C, 0xEE, 0x3B, + 0x8E, 0xE3, 0xB8, 0xEE, 0x39, 0xCE, 0x3F, 0x80, 0xE0, 0x38, 0x0E, 0x07, + 0xC0, 0xF7, 0x7B, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0xF8, 0x7E, 0x73, + 0xC7, 0x8E, 0x39, 0xB0, 0x10, 0xCF, 0x9C, 0x71, 0xC7, 0x1C, 0x71, 0xD3, + 0x80, 0xF7, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9C, 0xE7, 0x39, 0xCE, 0x3F, + 0xC0, 0xFB, 0xB8, 0x8C, 0x87, 0x43, 0xC0, 0xE0, 0x70, 0x10, 0x08, 0x00, + 0xF7, 0xB6, 0x31, 0x73, 0xA3, 0x3A, 0x3D, 0xA3, 0xDC, 0x18, 0xC1, 0x88, + 0x10, 0x80, 0xFB, 0xB8, 0x8E, 0x83, 0x81, 0xC0, 0xF0, 0x98, 0xCE, 0xEF, + 0x80, 0xF7, 0x62, 0x72, 0x34, 0x34, 0x3C, 0x18, 0x18, 0x10, 0x10, 0x10, + 0xE0, 0xE0, 0xFF, 0x1C, 0x70, 0xE3, 0x87, 0x1C, 0x71, 0xFE, 0x19, 0x8C, + 0x63, 0x18, 0xCC, 0x61, 0x8C, 0x63, 0x18, 0xC3, 0xFF, 0xF8, 0xC3, 0x18, + 0xC6, 0x31, 0x86, 0x33, 0x18, 0xC6, 0x31, 0x98, 0xF0, 0x8E }; + +const GFXglyph FreeSerifBold9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 3, 12, 6, 1, -11 }, // 0x21 '!' + { 5, 6, 5, 10, 2, -11 }, // 0x22 '"' + { 9, 9, 13, 9, 0, -12 }, // 0x23 '#' + { 24, 8, 14, 9, 1, -12 }, // 0x24 '$' + { 38, 14, 12, 18, 2, -11 }, // 0x25 '%' + { 59, 13, 12, 15, 1, -11 }, // 0x26 '&' + { 79, 2, 5, 5, 1, -11 }, // 0x27 ''' + { 81, 4, 15, 6, 1, -11 }, // 0x28 '(' + { 89, 4, 15, 6, 1, -11 }, // 0x29 ')' + { 97, 7, 7, 9, 2, -11 }, // 0x2A '*' + { 104, 9, 9, 12, 1, -8 }, // 0x2B '+' + { 115, 3, 6, 4, 1, -2 }, // 0x2C ',' + { 118, 4, 2, 6, 1, -4 }, // 0x2D '-' + { 119, 3, 3, 4, 1, -2 }, // 0x2E '.' + { 121, 6, 13, 5, 0, -11 }, // 0x2F '/' + { 131, 9, 12, 9, 0, -11 }, // 0x30 '0' + { 145, 6, 12, 9, 1, -11 }, // 0x31 '1' + { 154, 9, 12, 9, 0, -11 }, // 0x32 '2' + { 168, 8, 12, 9, 0, -11 }, // 0x33 '3' + { 180, 8, 12, 9, 1, -11 }, // 0x34 '4' + { 192, 8, 12, 9, 1, -11 }, // 0x35 '5' + { 204, 8, 12, 9, 1, -11 }, // 0x36 '6' + { 216, 9, 12, 9, 0, -11 }, // 0x37 '7' + { 230, 8, 12, 9, 1, -11 }, // 0x38 '8' + { 242, 9, 12, 9, 0, -11 }, // 0x39 '9' + { 256, 3, 9, 6, 1, -8 }, // 0x3A ':' + { 260, 3, 12, 6, 2, -8 }, // 0x3B ';' + { 265, 10, 10, 12, 1, -9 }, // 0x3C '<' + { 278, 10, 5, 12, 1, -6 }, // 0x3D '=' + { 285, 10, 10, 12, 1, -8 }, // 0x3E '>' + { 298, 7, 12, 9, 1, -11 }, // 0x3F '?' + { 309, 13, 12, 17, 2, -11 }, // 0x40 '@' + { 329, 13, 12, 13, 0, -11 }, // 0x41 'A' + { 349, 11, 12, 12, 0, -11 }, // 0x42 'B' + { 366, 11, 12, 13, 1, -11 }, // 0x43 'C' + { 383, 11, 12, 13, 1, -11 }, // 0x44 'D' + { 400, 11, 12, 12, 1, -11 }, // 0x45 'E' + { 417, 10, 12, 11, 1, -11 }, // 0x46 'F' + { 432, 12, 12, 14, 1, -11 }, // 0x47 'G' + { 450, 12, 12, 14, 1, -11 }, // 0x48 'H' + { 468, 5, 12, 7, 1, -11 }, // 0x49 'I' + { 476, 8, 14, 9, 0, -11 }, // 0x4A 'J' + { 490, 13, 12, 14, 1, -11 }, // 0x4B 'K' + { 510, 11, 12, 12, 1, -11 }, // 0x4C 'L' + { 527, 16, 12, 17, 0, -11 }, // 0x4D 'M' + { 551, 11, 12, 13, 1, -11 }, // 0x4E 'N' + { 568, 12, 12, 14, 1, -11 }, // 0x4F 'O' + { 586, 10, 12, 11, 1, -11 }, // 0x50 'P' + { 601, 12, 15, 14, 1, -11 }, // 0x51 'Q' + { 624, 12, 12, 13, 1, -11 }, // 0x52 'R' + { 642, 8, 12, 10, 1, -11 }, // 0x53 'S' + { 654, 12, 12, 12, 0, -11 }, // 0x54 'T' + { 672, 11, 12, 13, 1, -11 }, // 0x55 'U' + { 689, 13, 13, 13, 0, -11 }, // 0x56 'V' + { 711, 18, 12, 18, 0, -11 }, // 0x57 'W' + { 738, 13, 12, 13, 0, -11 }, // 0x58 'X' + { 758, 13, 12, 13, 0, -11 }, // 0x59 'Y' + { 778, 11, 12, 12, 1, -11 }, // 0x5A 'Z' + { 795, 4, 15, 6, 1, -11 }, // 0x5B '[' + { 803, 6, 13, 5, 0, -11 }, // 0x5C '\' + { 813, 4, 15, 6, 1, -11 }, // 0x5D ']' + { 821, 8, 7, 10, 1, -11 }, // 0x5E '^' + { 828, 9, 1, 9, 0, 3 }, // 0x5F '_' + { 830, 4, 3, 6, 0, -12 }, // 0x60 '`' + { 832, 9, 9, 9, 0, -8 }, // 0x61 'a' + { 843, 10, 12, 10, 0, -11 }, // 0x62 'b' + { 858, 7, 9, 8, 0, -8 }, // 0x63 'c' + { 866, 10, 12, 10, 0, -11 }, // 0x64 'd' + { 881, 8, 9, 8, 0, -8 }, // 0x65 'e' + { 890, 7, 12, 7, 0, -11 }, // 0x66 'f' + { 901, 7, 13, 9, 1, -8 }, // 0x67 'g' + { 913, 10, 12, 10, 0, -11 }, // 0x68 'h' + { 928, 5, 12, 5, 0, -11 }, // 0x69 'i' + { 936, 6, 16, 7, 0, -11 }, // 0x6A 'j' + { 948, 10, 12, 10, 0, -11 }, // 0x6B 'k' + { 963, 5, 12, 5, 0, -11 }, // 0x6C 'l' + { 971, 15, 9, 15, 0, -8 }, // 0x6D 'm' + { 988, 10, 9, 10, 0, -8 }, // 0x6E 'n' + { 1000, 9, 9, 9, 0, -8 }, // 0x6F 'o' + { 1011, 10, 13, 10, 0, -8 }, // 0x70 'p' + { 1028, 10, 13, 10, 0, -8 }, // 0x71 'q' + { 1045, 8, 9, 8, 0, -8 }, // 0x72 'r' + { 1054, 5, 9, 7, 1, -8 }, // 0x73 's' + { 1060, 6, 11, 6, 0, -10 }, // 0x74 't' + { 1069, 10, 9, 10, 0, -8 }, // 0x75 'u' + { 1081, 9, 9, 9, 0, -8 }, // 0x76 'v' + { 1092, 12, 9, 13, 0, -8 }, // 0x77 'w' + { 1106, 9, 9, 9, 0, -8 }, // 0x78 'x' + { 1117, 8, 13, 9, 0, -8 }, // 0x79 'y' + { 1130, 7, 9, 8, 1, -8 }, // 0x7A 'z' + { 1138, 5, 16, 7, 0, -12 }, // 0x7B '{' + { 1148, 1, 13, 4, 1, -11 }, // 0x7C '|' + { 1150, 5, 16, 7, 2, -12 }, // 0x7D '}' + { 1160, 8, 2, 9, 1, -4 } }; // 0x7E '~' + +const GFXfont FreeSerifBold9pt7b PROGMEM = { + (uint8_t *)FreeSerifBold9pt7bBitmaps, + (GFXglyph *)FreeSerifBold9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 1834 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic12pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic12pt7b.h new file mode 100644 index 0000000..1f674e9 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic12pt7b.h @@ -0,0 +1,292 @@ +const uint8_t FreeSerifBoldItalic12pt7bBitmaps[] PROGMEM = { + 0x07, 0x07, 0x07, 0x0F, 0x0E, 0x0E, 0x0C, 0x0C, 0x08, 0x18, 0x10, 0x00, + 0x00, 0x60, 0xF0, 0xF0, 0x60, 0x61, 0xF1, 0xF8, 0xF8, 0x6C, 0x34, 0x12, + 0x08, 0x01, 0x8C, 0x06, 0x60, 0x31, 0x80, 0xCC, 0x06, 0x30, 0xFF, 0xF0, + 0xC6, 0x03, 0x18, 0x0C, 0xC0, 0x63, 0x0F, 0xFF, 0x0C, 0x60, 0x33, 0x01, + 0x8C, 0x06, 0x30, 0x19, 0x80, 0x00, 0x80, 0x08, 0x07, 0xC1, 0x96, 0x31, + 0x33, 0x13, 0x3A, 0x23, 0xE0, 0x1E, 0x01, 0xF0, 0x07, 0x80, 0x7C, 0x05, + 0xC4, 0xCC, 0x48, 0xCC, 0x8C, 0xF8, 0x83, 0x30, 0x1E, 0x01, 0x00, 0x00, + 0x02, 0x07, 0x83, 0x03, 0x9F, 0x81, 0xC4, 0x20, 0x71, 0x10, 0x3C, 0x44, + 0x0E, 0x22, 0x03, 0x88, 0x80, 0xE4, 0x40, 0x1E, 0x31, 0xE0, 0x08, 0xE4, + 0x06, 0x71, 0x01, 0x3C, 0x40, 0x8E, 0x10, 0x23, 0x88, 0x10, 0xE2, 0x04, + 0x39, 0x02, 0x07, 0x80, 0x00, 0xF0, 0x01, 0x98, 0x03, 0x98, 0x03, 0x98, + 0x03, 0xB0, 0x03, 0xE0, 0x03, 0x80, 0x0F, 0x9F, 0x19, 0xCE, 0x31, 0xCC, + 0x61, 0xC8, 0xE1, 0xC8, 0xE0, 0xF0, 0xE0, 0xE0, 0xF0, 0x70, 0x78, 0x79, + 0x3F, 0xBE, 0x7F, 0xED, 0x20, 0x02, 0x08, 0x20, 0xC3, 0x0E, 0x18, 0x30, + 0xE1, 0x83, 0x06, 0x0C, 0x18, 0x30, 0x20, 0x40, 0x80, 0x81, 0x01, 0x00, + 0x10, 0x10, 0x20, 0x20, 0x40, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x70, 0xE1, + 0x83, 0x0C, 0x18, 0x61, 0x86, 0x00, 0x00, 0x0C, 0x33, 0x6C, 0x9B, 0xAE, + 0x1C, 0x3F, 0xEC, 0x9B, 0x36, 0x0C, 0x02, 0x00, 0x06, 0x00, 0x60, 0x06, + 0x00, 0x60, 0x06, 0x0F, 0xFF, 0xFF, 0xF0, 0x60, 0x06, 0x00, 0x60, 0x06, + 0x00, 0x60, 0x31, 0xCE, 0x31, 0x08, 0x98, 0xFF, 0xFF, 0xC0, 0x6F, 0xF6, + 0x01, 0x80, 0x60, 0x30, 0x0C, 0x07, 0x01, 0x80, 0xE0, 0x30, 0x1C, 0x06, + 0x01, 0x80, 0xC0, 0x30, 0x18, 0x06, 0x03, 0x00, 0x03, 0x81, 0xC8, 0x71, + 0x1C, 0x33, 0x86, 0xE1, 0xDC, 0x3B, 0x87, 0xE0, 0xFC, 0x3B, 0x87, 0x70, + 0xEC, 0x39, 0x87, 0x31, 0xC2, 0x30, 0x3C, 0x00, 0x01, 0xC3, 0xF0, 0x38, + 0x0E, 0x03, 0x81, 0xE0, 0x70, 0x1C, 0x0F, 0x03, 0x80, 0xE0, 0x38, 0x1E, + 0x07, 0x01, 0xC0, 0xF0, 0xFF, 0x80, 0x07, 0x81, 0xF8, 0x47, 0x90, 0x70, + 0x0E, 0x01, 0xC0, 0x30, 0x0E, 0x01, 0x80, 0x60, 0x18, 0x06, 0x01, 0x80, + 0x40, 0x8F, 0xF3, 0xFC, 0xFF, 0x80, 0x07, 0xC3, 0x3C, 0x03, 0x80, 0x70, + 0x0C, 0x03, 0x81, 0xC0, 0xFC, 0x07, 0xC0, 0x78, 0x07, 0x00, 0xE0, 0x1C, + 0x03, 0x30, 0xE7, 0x10, 0x7C, 0x00, 0x00, 0x10, 0x01, 0x80, 0x3C, 0x03, + 0xE0, 0x2E, 0x02, 0x70, 0x23, 0x82, 0x38, 0x21, 0xC2, 0x0E, 0x1F, 0xF9, + 0xFF, 0xC0, 0x38, 0x01, 0xC0, 0x1C, 0x00, 0xE0, 0x07, 0xF0, 0x7E, 0x0F, + 0xE0, 0x80, 0x08, 0x01, 0xE0, 0x1F, 0x83, 0xF8, 0x03, 0xC0, 0x1C, 0x00, + 0xC0, 0x0C, 0x00, 0xC0, 0x08, 0x61, 0x8F, 0x30, 0x7C, 0x00, 0x00, 0x60, + 0x78, 0x1C, 0x0F, 0x01, 0xC0, 0x70, 0x1F, 0xC3, 0x8C, 0xE1, 0xDC, 0x3B, + 0x87, 0x61, 0xEC, 0x3D, 0x87, 0x31, 0xE2, 0x38, 0x3C, 0x00, 0x3F, 0xEF, + 0xF9, 0xFF, 0x60, 0xC8, 0x18, 0x06, 0x00, 0x80, 0x30, 0x0C, 0x01, 0x80, + 0x60, 0x1C, 0x03, 0x00, 0xC0, 0x18, 0x06, 0x00, 0x03, 0x81, 0x88, 0x61, + 0x8C, 0x31, 0x86, 0x38, 0xC7, 0xB0, 0x78, 0x0F, 0x86, 0x71, 0x87, 0x60, + 0x6C, 0x0D, 0x81, 0xB0, 0x63, 0x18, 0x3E, 0x00, 0x07, 0x81, 0xC8, 0x71, + 0x8E, 0x33, 0xC6, 0x70, 0xCE, 0x39, 0xC7, 0x38, 0xE3, 0x38, 0x3F, 0x01, + 0xC0, 0x38, 0x0E, 0x03, 0x81, 0xC0, 0xE0, 0x00, 0x0C, 0x3C, 0x78, 0x60, + 0x00, 0x00, 0x00, 0x61, 0xE3, 0xC3, 0x00, 0x0E, 0x0F, 0x0F, 0x0E, 0x00, + 0x00, 0x00, 0x00, 0x38, 0x38, 0x38, 0x18, 0x10, 0x20, 0x40, 0x00, 0x10, + 0x07, 0x01, 0xF0, 0x7C, 0x3F, 0x0F, 0x80, 0xE0, 0x0F, 0x80, 0x3E, 0x00, + 0xF8, 0x03, 0xE0, 0x07, 0x00, 0x10, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, + 0xFF, 0xFF, 0xFF, 0x80, 0x07, 0x00, 0x3F, 0x00, 0x3E, 0x00, 0x7C, 0x00, + 0xF8, 0x01, 0xE0, 0x1F, 0x07, 0xE0, 0xF8, 0x1F, 0x01, 0xE0, 0x0C, 0x00, + 0x00, 0x1E, 0x19, 0x8C, 0xE6, 0x70, 0x38, 0x38, 0x1C, 0x18, 0x18, 0x08, + 0x08, 0x00, 0x00, 0x03, 0x03, 0xC1, 0xE0, 0x60, 0x00, 0x03, 0xF0, 0x07, + 0x06, 0x06, 0x00, 0x86, 0x0E, 0x66, 0x0D, 0xDB, 0x0C, 0xE7, 0x06, 0x33, + 0x83, 0x31, 0xC3, 0x18, 0xE1, 0x8C, 0x70, 0xCC, 0x4C, 0x66, 0x46, 0x1F, + 0xC1, 0x80, 0x00, 0x30, 0x10, 0x07, 0xF0, 0x00, 0x10, 0x00, 0x30, 0x00, + 0x70, 0x00, 0x70, 0x00, 0xF0, 0x01, 0xF0, 0x01, 0x78, 0x03, 0x78, 0x02, + 0x38, 0x04, 0x38, 0x0C, 0x38, 0x0F, 0xF8, 0x18, 0x3C, 0x30, 0x3C, 0x20, + 0x3C, 0x60, 0x3C, 0xF8, 0x7F, 0x1F, 0xFC, 0x07, 0x9E, 0x07, 0x0F, 0x07, + 0x0F, 0x0F, 0x0F, 0x0F, 0x1E, 0x0E, 0x3C, 0x0F, 0xE0, 0x1E, 0x3C, 0x1E, + 0x1E, 0x1C, 0x1E, 0x3C, 0x1E, 0x3C, 0x1E, 0x3C, 0x3E, 0x38, 0x3C, 0x7C, + 0x78, 0xFF, 0xE0, 0x01, 0xF2, 0x0E, 0x1C, 0x38, 0x18, 0xE0, 0x33, 0xC0, + 0x4F, 0x00, 0x9E, 0x00, 0x7C, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, + 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x1E, 0x04, 0x1E, 0x30, 0x0F, 0x80, 0x1F, + 0xFC, 0x01, 0xE3, 0xC0, 0x70, 0x78, 0x1C, 0x0E, 0x0F, 0x03, 0xC3, 0xC0, + 0xF0, 0xE0, 0x3C, 0x38, 0x0F, 0x1E, 0x03, 0xC7, 0x81, 0xF1, 0xC0, 0x78, + 0xF0, 0x1E, 0x3C, 0x0F, 0x0F, 0x03, 0xC3, 0x81, 0xC1, 0xE1, 0xE0, 0xFF, + 0xE0, 0x00, 0x1F, 0xFF, 0x83, 0xC1, 0xC1, 0xC0, 0x40, 0xE0, 0x20, 0xF0, + 0x00, 0x78, 0xC0, 0x38, 0x40, 0x1F, 0xE0, 0x1E, 0x70, 0x0F, 0x18, 0x07, + 0x08, 0x03, 0x84, 0x03, 0xC0, 0x61, 0xE0, 0x20, 0xE0, 0x30, 0xF8, 0x78, + 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0x07, 0x87, 0x07, 0x02, 0x07, 0x02, 0x0F, + 0x00, 0x0F, 0x18, 0x0E, 0x10, 0x0F, 0xF0, 0x1E, 0x70, 0x1E, 0x30, 0x1C, + 0x20, 0x1C, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x38, 0x00, 0x7C, 0x00, 0xFE, + 0x00, 0x01, 0xF9, 0x03, 0xC3, 0x83, 0x81, 0xC3, 0x80, 0x43, 0xC0, 0x23, + 0xC0, 0x01, 0xE0, 0x01, 0xF0, 0x00, 0xF0, 0x3F, 0xF8, 0x0F, 0x3C, 0x07, + 0x9E, 0x03, 0xCF, 0x01, 0xC3, 0x80, 0xE1, 0xE0, 0xF0, 0x78, 0x70, 0x0F, + 0xE0, 0x00, 0x1F, 0xE7, 0xF0, 0x78, 0x3C, 0x07, 0x83, 0xC0, 0x70, 0x3C, + 0x0F, 0x03, 0x80, 0xF0, 0x78, 0x0E, 0x07, 0x80, 0xE0, 0x70, 0x1F, 0xFF, + 0x01, 0xE0, 0xF0, 0x1C, 0x0F, 0x03, 0xC0, 0xE0, 0x3C, 0x1E, 0x03, 0xC1, + 0xE0, 0x38, 0x1E, 0x07, 0xC3, 0xE0, 0xFE, 0x7F, 0x00, 0x1F, 0xC1, 0xE0, + 0x70, 0x1C, 0x0F, 0x03, 0xC0, 0xE0, 0x38, 0x1E, 0x07, 0x81, 0xC0, 0x70, + 0x3C, 0x0F, 0x03, 0x81, 0xF0, 0xFE, 0x00, 0x01, 0xFC, 0x03, 0xC0, 0x0F, + 0x00, 0x38, 0x00, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x70, 0x01, 0xC0, 0x0F, + 0x00, 0x3C, 0x00, 0xE0, 0x07, 0x80, 0x1E, 0x0E, 0x70, 0x3B, 0xC0, 0xCE, + 0x01, 0xF0, 0x00, 0x1F, 0xEF, 0x83, 0xC1, 0x81, 0xC1, 0x80, 0xE1, 0x80, + 0xF1, 0x80, 0x79, 0x00, 0x39, 0x00, 0x1F, 0x80, 0x1F, 0xE0, 0x0F, 0x70, + 0x07, 0x3C, 0x07, 0x8E, 0x03, 0xC7, 0x01, 0xE3, 0xC0, 0xE0, 0xE0, 0xF8, + 0x78, 0xFE, 0xFE, 0x00, 0x1F, 0xE0, 0x0F, 0x00, 0x1C, 0x00, 0x38, 0x00, + 0xF0, 0x01, 0xE0, 0x03, 0x80, 0x07, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x70, + 0x00, 0xE0, 0x03, 0xC0, 0x27, 0x00, 0xCE, 0x03, 0x3C, 0x1E, 0xFF, 0xFC, + 0x0F, 0x80, 0x7E, 0x0F, 0x00, 0xF0, 0x1E, 0x03, 0xE0, 0x3C, 0x0F, 0x80, + 0xB8, 0x17, 0x01, 0x70, 0x5E, 0x02, 0xF1, 0xBC, 0x05, 0xE2, 0x70, 0x11, + 0xC8, 0xE0, 0x23, 0xB3, 0xC0, 0x47, 0x47, 0x81, 0x0F, 0x8E, 0x02, 0x1E, + 0x1C, 0x04, 0x38, 0x78, 0x08, 0x70, 0xF0, 0x30, 0xC3, 0xE0, 0xF9, 0x8F, + 0xE0, 0x1F, 0x03, 0xE0, 0xF0, 0x38, 0x1E, 0x02, 0x03, 0xE0, 0xC0, 0xBC, + 0x10, 0x13, 0xC2, 0x02, 0x78, 0x40, 0x47, 0x90, 0x10, 0xF2, 0x02, 0x0F, + 0x40, 0x41, 0xE8, 0x18, 0x1E, 0x02, 0x03, 0xC0, 0x40, 0x38, 0x08, 0x06, + 0x03, 0x00, 0x40, 0x10, 0x08, 0x00, 0x01, 0xF8, 0x07, 0x1C, 0x0E, 0x0E, + 0x1E, 0x0F, 0x3C, 0x0F, 0x3C, 0x0F, 0x78, 0x0F, 0x78, 0x0F, 0xF8, 0x1F, + 0xF0, 0x1E, 0xF0, 0x1E, 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, 0x78, 0x70, 0x70, + 0x38, 0xE0, 0x1F, 0x80, 0x1F, 0xFC, 0x07, 0x9E, 0x07, 0x0F, 0x07, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0E, 0x1E, 0x0E, 0x3C, 0x1F, 0xF0, 0x1E, 0x00, + 0x1C, 0x00, 0x1C, 0x00, 0x3C, 0x00, 0x38, 0x00, 0x38, 0x00, 0x7C, 0x00, + 0xFE, 0x00, 0x01, 0xF8, 0x07, 0x1C, 0x0E, 0x0E, 0x1E, 0x0F, 0x3C, 0x0F, + 0x3C, 0x0F, 0x78, 0x0F, 0x78, 0x1F, 0xF8, 0x1F, 0xF0, 0x1E, 0xF0, 0x1E, + 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, 0x78, 0x70, 0x70, 0x39, 0xC0, 0x0E, 0x00, + 0x08, 0x02, 0x3F, 0x04, 0x7F, 0xF8, 0x83, 0xF0, 0x1F, 0xF8, 0x07, 0x9E, + 0x07, 0x8F, 0x07, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x1E, 0x0E, 0x3C, + 0x1F, 0xF0, 0x1E, 0xF0, 0x1C, 0xF0, 0x3C, 0xF0, 0x3C, 0x78, 0x3C, 0x78, + 0x3C, 0x78, 0x7C, 0x3C, 0xFE, 0x3E, 0x07, 0x91, 0xC7, 0x18, 0x73, 0x82, + 0x38, 0x23, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x01, 0xE0, 0x1E, + 0x40, 0xE4, 0x0E, 0x60, 0xCE, 0x1C, 0x9F, 0x00, 0x7F, 0xFE, 0xE7, 0x9D, + 0x0E, 0x16, 0x3C, 0x20, 0x78, 0x40, 0xE0, 0x01, 0xC0, 0x07, 0x80, 0x0F, + 0x00, 0x1C, 0x00, 0x38, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0x80, 0x0F, 0x00, + 0x1E, 0x00, 0xFF, 0x00, 0x7F, 0x1F, 0x3C, 0x0E, 0x38, 0x04, 0x38, 0x0C, + 0x78, 0x08, 0x78, 0x08, 0x70, 0x08, 0x70, 0x10, 0xF0, 0x10, 0xF0, 0x10, + 0xF0, 0x10, 0xF0, 0x20, 0xF0, 0x20, 0xF0, 0x20, 0xF0, 0x40, 0x78, 0xC0, + 0x3F, 0x00, 0xFF, 0x1F, 0x3C, 0x06, 0x3C, 0x04, 0x3C, 0x08, 0x3C, 0x08, + 0x3C, 0x10, 0x1C, 0x20, 0x1C, 0x20, 0x1E, 0x40, 0x1E, 0x80, 0x1E, 0x80, + 0x1F, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0C, 0x00, 0x08, 0x00, 0xFE, 0x7C, + 0x79, 0xE1, 0xC1, 0x8F, 0x0E, 0x08, 0x78, 0x70, 0x43, 0xC7, 0x84, 0x1E, + 0x3E, 0x20, 0x72, 0xF2, 0x03, 0x97, 0x90, 0x1D, 0x1D, 0x00, 0xE8, 0xE8, + 0x07, 0x87, 0x80, 0x3C, 0x3C, 0x01, 0xC1, 0xC0, 0x0E, 0x0E, 0x00, 0x20, + 0x60, 0x01, 0x02, 0x00, 0x1F, 0xCF, 0x83, 0xC1, 0x81, 0xE1, 0x80, 0x71, + 0x80, 0x39, 0x80, 0x1F, 0x80, 0x07, 0x80, 0x03, 0x80, 0x01, 0xE0, 0x01, + 0xF0, 0x00, 0xB8, 0x00, 0x9C, 0x00, 0x8F, 0x00, 0x83, 0x80, 0xC1, 0xC0, + 0xE0, 0xF0, 0xF9, 0xFE, 0x00, 0xFE, 0x7C, 0xE0, 0x63, 0x81, 0x0F, 0x08, + 0x1C, 0x40, 0x71, 0x01, 0xE8, 0x03, 0xC0, 0x0E, 0x00, 0x38, 0x01, 0xE0, + 0x07, 0x80, 0x1C, 0x00, 0x70, 0x03, 0xC0, 0x0F, 0x00, 0xFF, 0x00, 0x1F, + 0xFE, 0x38, 0x78, 0x60, 0xF1, 0x83, 0xC2, 0x0F, 0x00, 0x1E, 0x00, 0x78, + 0x01, 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xF8, 0x01, 0xE0, 0x47, + 0x81, 0x1F, 0x06, 0x3C, 0x3C, 0xFF, 0xF0, 0x07, 0xC1, 0x80, 0xE0, 0x30, + 0x0C, 0x03, 0x01, 0xC0, 0x60, 0x18, 0x06, 0x03, 0x80, 0xC0, 0x30, 0x0C, + 0x07, 0x01, 0xC0, 0x60, 0x18, 0x0E, 0x03, 0xE0, 0xC3, 0x06, 0x18, 0x61, + 0x83, 0x0C, 0x30, 0xC1, 0x86, 0x18, 0x60, 0xC3, 0x0F, 0x81, 0xC0, 0xE0, + 0x60, 0x30, 0x18, 0x1C, 0x0C, 0x06, 0x03, 0x03, 0x81, 0x80, 0xC0, 0x60, + 0x70, 0x38, 0x18, 0x0C, 0x0E, 0x1F, 0x00, 0x0C, 0x07, 0x81, 0xE0, 0xDC, + 0x33, 0x18, 0xC6, 0x1B, 0x06, 0xC0, 0xC0, 0xFF, 0xF0, 0xC7, 0x0C, 0x30, + 0x07, 0x70, 0xCE, 0x1C, 0xE3, 0x8E, 0x70, 0xC7, 0x0C, 0x71, 0xCE, 0x1C, + 0xE1, 0x8E, 0x79, 0xE9, 0xA7, 0x1C, 0x02, 0x07, 0xC0, 0x38, 0x06, 0x01, + 0xC0, 0x38, 0x06, 0x71, 0xF7, 0x38, 0xE7, 0x1C, 0xC3, 0xB8, 0x77, 0x1C, + 0xE3, 0xB8, 0xE7, 0x18, 0xE6, 0x0F, 0x80, 0x07, 0x0C, 0xCE, 0x66, 0x07, + 0x03, 0x83, 0x81, 0xC0, 0xE0, 0x70, 0xBC, 0x87, 0x80, 0x00, 0x08, 0x03, + 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x70, 0x01, 0xC0, 0x77, 0x03, 0x3C, 0x18, + 0xE0, 0xE3, 0x87, 0x0E, 0x1C, 0x70, 0x71, 0xC3, 0x87, 0x0E, 0x3C, 0x38, + 0xE8, 0xE5, 0xA1, 0xE7, 0x00, 0x07, 0x0C, 0xCE, 0x66, 0x37, 0x33, 0xBB, + 0xB1, 0xE0, 0xE0, 0x70, 0xB8, 0x87, 0x80, 0x00, 0x38, 0x01, 0xB0, 0x0C, + 0xC0, 0x30, 0x01, 0xC0, 0x07, 0x00, 0x7E, 0x00, 0xE0, 0x03, 0x80, 0x0E, + 0x00, 0x30, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, 0x70, 0x03, 0x80, 0x0E, + 0x00, 0x38, 0x00, 0xC0, 0x33, 0x00, 0xD8, 0x01, 0xC0, 0x00, 0x03, 0x80, + 0x73, 0xC7, 0x1C, 0x38, 0xE1, 0xCF, 0x06, 0x70, 0x1E, 0x01, 0x00, 0x1C, + 0x00, 0xF8, 0x07, 0xF0, 0xC7, 0x8C, 0x0C, 0x60, 0x63, 0x86, 0x07, 0xE0, + 0x01, 0x00, 0xF8, 0x01, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x31, 0xC3, + 0xBE, 0x1E, 0x70, 0xE3, 0x8F, 0x38, 0x71, 0xC3, 0x8E, 0x1C, 0xE1, 0xC7, + 0x0E, 0x3A, 0x71, 0xD3, 0x0F, 0x00, 0x1C, 0x71, 0xC0, 0x00, 0x6F, 0x8E, + 0x31, 0xC7, 0x18, 0x63, 0x8E, 0xBC, 0xE0, 0x00, 0xE0, 0x1C, 0x03, 0x80, + 0x00, 0x00, 0x0F, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x70, 0x0E, 0x01, 0xC0, + 0x38, 0x0E, 0x01, 0xC0, 0x38, 0x06, 0x01, 0xC3, 0x38, 0x6E, 0x07, 0x80, + 0x01, 0x00, 0xF8, 0x01, 0xC0, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x33, 0xE3, + 0x8C, 0x1C, 0xC0, 0xE4, 0x06, 0x40, 0x7E, 0x03, 0xF0, 0x1D, 0x81, 0xCE, + 0x0E, 0x72, 0x71, 0xA3, 0x8E, 0x00, 0x06, 0x7C, 0x70, 0xE1, 0xC3, 0x0E, + 0x1C, 0x38, 0x61, 0xC3, 0x87, 0x0C, 0x38, 0x72, 0xE9, 0xE0, 0x3C, 0x73, + 0xC7, 0x7D, 0x71, 0xE7, 0x9C, 0xF1, 0xCE, 0x3C, 0xF3, 0x8E, 0x39, 0xC3, + 0x8E, 0x71, 0xC3, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xD7, 0x1C, 0x7B, 0x8E, + 0x1C, 0x3C, 0xF1, 0xD7, 0x1E, 0x73, 0xCE, 0x3C, 0xE3, 0x8E, 0x39, 0xC7, + 0x9C, 0x71, 0xC7, 0x1D, 0x71, 0xEE, 0x1C, 0x0F, 0x06, 0x63, 0x9D, 0xC7, + 0x71, 0xF8, 0x7E, 0x3F, 0x8E, 0xE3, 0xB9, 0xC6, 0x60, 0xF0, 0x0F, 0x38, + 0x1F, 0x70, 0x71, 0xC1, 0xC7, 0x0E, 0x1C, 0x38, 0xF0, 0xE3, 0x83, 0x8E, + 0x1C, 0x70, 0x71, 0xC1, 0xCE, 0x07, 0xE0, 0x38, 0x00, 0xE0, 0x03, 0x80, + 0x3F, 0x00, 0x07, 0x70, 0xCE, 0x18, 0xE3, 0x8E, 0x70, 0xE7, 0x1C, 0xF1, + 0xCE, 0x1C, 0xE3, 0x8E, 0x38, 0xE7, 0x87, 0xB0, 0x07, 0x00, 0x70, 0x0F, + 0x03, 0xF8, 0x0D, 0xDF, 0x71, 0xAC, 0xF0, 0x38, 0x0E, 0x03, 0x81, 0xC0, + 0x70, 0x1C, 0x0E, 0x00, 0x1D, 0x99, 0x8C, 0x46, 0x23, 0x80, 0xE0, 0x70, + 0x1C, 0x06, 0x23, 0x19, 0x17, 0x00, 0x0C, 0x10, 0xE3, 0xF3, 0x86, 0x1C, + 0x38, 0x71, 0xC3, 0x87, 0x0E, 0x9E, 0x38, 0x00, 0xF8, 0xE3, 0x8E, 0x38, + 0xC3, 0x9C, 0x71, 0xC7, 0x18, 0x71, 0x87, 0x38, 0xE3, 0x8E, 0xFA, 0xF3, + 0xAE, 0x3C, 0xF0, 0xDC, 0x33, 0x0C, 0xC2, 0x31, 0x8C, 0xC3, 0x60, 0xF0, + 0x38, 0x0C, 0x02, 0x00, 0xE0, 0x86, 0xE3, 0x0C, 0xC6, 0x19, 0x9C, 0x23, + 0x78, 0xC7, 0xF9, 0x0E, 0x74, 0x1C, 0xF0, 0x31, 0xC0, 0x43, 0x00, 0x84, + 0x00, 0x0E, 0x31, 0xF3, 0x83, 0xA0, 0x0E, 0x00, 0x70, 0x03, 0x80, 0x1C, + 0x00, 0xE0, 0x0B, 0x02, 0x5D, 0x3C, 0xF1, 0xC3, 0x00, 0x04, 0x67, 0x8C, + 0x79, 0x87, 0x10, 0xE2, 0x1C, 0x81, 0x90, 0x3A, 0x07, 0x80, 0xF0, 0x1C, + 0x03, 0x00, 0x40, 0x08, 0x32, 0x07, 0x80, 0x3F, 0xCF, 0xE6, 0x30, 0x08, + 0x04, 0x02, 0x01, 0x00, 0xC0, 0x30, 0x1E, 0x0F, 0x98, 0x76, 0x07, 0x00, + 0x01, 0xE0, 0x70, 0x1C, 0x03, 0x80, 0x60, 0x1C, 0x03, 0x80, 0x60, 0x0C, + 0x03, 0x80, 0xF0, 0x3C, 0x07, 0x00, 0x40, 0x0C, 0x01, 0x80, 0x70, 0x0E, + 0x01, 0xC0, 0x30, 0x03, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0x07, 0x00, 0xE0, + 0x18, 0x06, 0x01, 0x80, 0xE0, 0x38, 0x0C, 0x03, 0x00, 0xC0, 0x10, 0x1F, + 0x07, 0x03, 0x80, 0xE0, 0x30, 0x0C, 0x07, 0x01, 0x80, 0xE0, 0xE0, 0x00, + 0x38, 0x0F, 0xCD, 0x1F, 0x80, 0xE0 }; + +const GFXglyph FreeSerifBoldItalic12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 6, 0, 1 }, // 0x20 ' ' + { 0, 8, 17, 9, 2, -15 }, // 0x21 '!' + { 17, 9, 7, 13, 4, -15 }, // 0x22 '"' + { 25, 14, 16, 12, -1, -15 }, // 0x23 '#' + { 53, 12, 20, 12, 0, -17 }, // 0x24 '$' + { 83, 18, 18, 20, 1, -16 }, // 0x25 '%' + { 124, 16, 17, 19, 0, -15 }, // 0x26 '&' + { 158, 3, 7, 7, 3, -15 }, // 0x27 ''' + { 161, 7, 21, 8, 1, -15 }, // 0x28 '(' + { 180, 7, 21, 8, -1, -15 }, // 0x29 ')' + { 199, 10, 10, 12, 1, -15 }, // 0x2A '*' + { 212, 12, 12, 14, 1, -11 }, // 0x2B '+' + { 230, 5, 8, 6, -2, -3 }, // 0x2C ',' + { 235, 6, 3, 8, 0, -6 }, // 0x2D '-' + { 238, 4, 4, 6, 0, -2 }, // 0x2E '.' + { 240, 10, 16, 8, 0, -15 }, // 0x2F '/' + { 260, 11, 17, 12, 0, -15 }, // 0x30 '0' + { 284, 10, 17, 12, 0, -15 }, // 0x31 '1' + { 306, 11, 17, 12, 0, -15 }, // 0x32 '2' + { 330, 11, 17, 12, 0, -15 }, // 0x33 '3' + { 354, 13, 16, 12, 0, -15 }, // 0x34 '4' + { 380, 12, 17, 12, 0, -15 }, // 0x35 '5' + { 406, 11, 17, 12, 1, -15 }, // 0x36 '6' + { 430, 11, 16, 12, 2, -15 }, // 0x37 '7' + { 452, 11, 17, 12, 0, -15 }, // 0x38 '8' + { 476, 11, 17, 12, 0, -15 }, // 0x39 '9' + { 500, 7, 12, 6, 0, -10 }, // 0x3A ':' + { 511, 8, 15, 6, -1, -10 }, // 0x3B ';' + { 526, 12, 13, 14, 1, -12 }, // 0x3C '<' + { 546, 12, 6, 14, 2, -8 }, // 0x3D '=' + { 555, 13, 13, 14, 1, -12 }, // 0x3E '>' + { 577, 9, 17, 12, 2, -15 }, // 0x3F '?' + { 597, 17, 16, 20, 1, -15 }, // 0x40 '@' + { 631, 16, 17, 17, 0, -15 }, // 0x41 'A' + { 665, 16, 17, 15, 0, -15 }, // 0x42 'B' + { 699, 15, 17, 15, 1, -15 }, // 0x43 'C' + { 731, 18, 17, 17, 0, -15 }, // 0x44 'D' + { 770, 17, 17, 15, 0, -15 }, // 0x45 'E' + { 807, 16, 17, 15, 0, -15 }, // 0x46 'F' + { 841, 17, 17, 17, 1, -15 }, // 0x47 'G' + { 878, 20, 17, 18, 0, -15 }, // 0x48 'H' + { 921, 10, 17, 9, 0, -15 }, // 0x49 'I' + { 943, 14, 18, 12, 0, -15 }, // 0x4A 'J' + { 975, 17, 17, 16, 0, -15 }, // 0x4B 'K' + { 1012, 15, 17, 15, 0, -15 }, // 0x4C 'L' + { 1044, 23, 17, 21, 0, -15 }, // 0x4D 'M' + { 1093, 19, 17, 17, 0, -15 }, // 0x4E 'N' + { 1134, 16, 17, 16, 1, -15 }, // 0x4F 'O' + { 1168, 16, 17, 14, 0, -15 }, // 0x50 'P' + { 1202, 16, 21, 16, 1, -15 }, // 0x51 'Q' + { 1244, 16, 17, 16, 0, -15 }, // 0x52 'R' + { 1278, 12, 17, 12, 0, -15 }, // 0x53 'S' + { 1304, 15, 17, 14, 2, -15 }, // 0x54 'T' + { 1336, 16, 17, 17, 3, -15 }, // 0x55 'U' + { 1370, 16, 16, 17, 3, -15 }, // 0x56 'V' + { 1402, 21, 16, 22, 3, -15 }, // 0x57 'W' + { 1444, 17, 17, 17, 0, -15 }, // 0x58 'X' + { 1481, 14, 17, 15, 3, -15 }, // 0x59 'Y' + { 1511, 15, 17, 13, 0, -15 }, // 0x5A 'Z' + { 1543, 10, 20, 8, -1, -15 }, // 0x5B '[' + { 1568, 6, 16, 10, 3, -15 }, // 0x5C '\' + { 1580, 9, 20, 8, -1, -15 }, // 0x5D ']' + { 1603, 10, 9, 14, 2, -15 }, // 0x5E '^' + { 1615, 12, 1, 12, 0, 4 }, // 0x5F '_' + { 1617, 5, 4, 8, 2, -15 }, // 0x60 '`' + { 1620, 12, 12, 12, 0, -10 }, // 0x61 'a' + { 1638, 11, 18, 12, 1, -16 }, // 0x62 'b' + { 1663, 9, 12, 10, 1, -10 }, // 0x63 'c' + { 1677, 14, 18, 12, 0, -16 }, // 0x64 'd' + { 1709, 9, 12, 10, 1, -10 }, // 0x65 'e' + { 1723, 14, 22, 12, -2, -16 }, // 0x66 'f' + { 1762, 13, 16, 12, -1, -10 }, // 0x67 'g' + { 1788, 13, 18, 13, 0, -16 }, // 0x68 'h' + { 1818, 6, 17, 7, 1, -15 }, // 0x69 'i' + { 1831, 11, 21, 8, -2, -15 }, // 0x6A 'j' + { 1860, 13, 18, 12, 0, -16 }, // 0x6B 'k' + { 1890, 7, 18, 7, 1, -16 }, // 0x6C 'l' + { 1906, 18, 12, 18, 0, -10 }, // 0x6D 'm' + { 1933, 12, 12, 13, 0, -10 }, // 0x6E 'n' + { 1951, 10, 12, 11, 1, -10 }, // 0x6F 'o' + { 1966, 14, 16, 12, -2, -10 }, // 0x70 'p' + { 1994, 12, 16, 12, 0, -10 }, // 0x71 'q' + { 2018, 10, 11, 10, 0, -10 }, // 0x72 'r' + { 2032, 9, 12, 9, 0, -10 }, // 0x73 's' + { 2046, 7, 15, 7, 1, -13 }, // 0x74 't' + { 2060, 12, 12, 13, 1, -10 }, // 0x75 'u' + { 2078, 10, 11, 11, 1, -10 }, // 0x76 'v' + { 2092, 15, 11, 16, 1, -10 }, // 0x77 'w' + { 2113, 13, 12, 11, -1, -10 }, // 0x78 'x' + { 2133, 11, 16, 10, -1, -10 }, // 0x79 'y' + { 2155, 10, 13, 10, 0, -10 }, // 0x7A 'z' + { 2172, 11, 21, 8, 0, -16 }, // 0x7B '{' + { 2201, 2, 16, 6, 3, -15 }, // 0x7C '|' + { 2205, 10, 21, 8, -3, -16 }, // 0x7D '}' + { 2232, 11, 4, 14, 1, -7 } }; // 0x7E '~' + +const GFXfont FreeSerifBoldItalic12pt7b PROGMEM = { + (uint8_t *)FreeSerifBoldItalic12pt7bBitmaps, + (GFXglyph *)FreeSerifBoldItalic12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 2910 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic18pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic18pt7b.h new file mode 100644 index 0000000..e24eea6 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic18pt7b.h @@ -0,0 +1,500 @@ +const uint8_t FreeSerifBoldItalic18pt7bBitmaps[] PROGMEM = { + 0x01, 0xC0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, 0x80, 0xF0, 0x3C, 0x07, + 0x80, 0xE0, 0x1C, 0x03, 0x00, 0x60, 0x0C, 0x03, 0x00, 0x60, 0x08, 0x00, + 0x00, 0x00, 0x00, 0x07, 0x81, 0xF8, 0x3F, 0x07, 0xE0, 0x78, 0x00, 0x38, + 0x1D, 0xE0, 0xF7, 0x83, 0xDC, 0x0E, 0x70, 0x39, 0xC0, 0xE6, 0x03, 0x18, + 0x0C, 0x40, 0x23, 0x01, 0x80, 0x00, 0x38, 0x60, 0x07, 0x0E, 0x00, 0x70, + 0xC0, 0x06, 0x1C, 0x00, 0xE1, 0xC0, 0x0E, 0x38, 0x01, 0xC3, 0x81, 0xFF, + 0xFF, 0x1F, 0xFF, 0xE1, 0xFF, 0xFE, 0x03, 0x86, 0x00, 0x30, 0xE0, 0x07, + 0x0E, 0x00, 0x71, 0xC0, 0x0E, 0x1C, 0x0F, 0xFF, 0xF8, 0xFF, 0xFF, 0x0F, + 0xFF, 0xF0, 0x1C, 0x30, 0x01, 0x87, 0x00, 0x38, 0x70, 0x03, 0x0E, 0x00, + 0x70, 0xE0, 0x07, 0x0C, 0x00, 0xE1, 0xC0, 0x00, 0x00, 0x08, 0x00, 0x0C, + 0x00, 0x7E, 0x00, 0xFF, 0xC0, 0xF3, 0x70, 0x71, 0x9C, 0x70, 0xC6, 0x38, + 0x43, 0x1C, 0x61, 0x0F, 0x30, 0x87, 0xD8, 0x03, 0xF8, 0x00, 0xFE, 0x00, + 0x3F, 0x80, 0x0F, 0xE0, 0x03, 0xF8, 0x01, 0xFC, 0x00, 0xDF, 0x10, 0x47, + 0x88, 0x63, 0xCC, 0x31, 0xE6, 0x10, 0xF3, 0x98, 0x71, 0xCC, 0x78, 0x7E, + 0x78, 0x07, 0xF8, 0x03, 0xF0, 0x01, 0x80, 0x00, 0xC0, 0x00, 0x03, 0xC0, + 0x18, 0x01, 0xFE, 0x0F, 0x00, 0x7C, 0xFF, 0xC0, 0x1F, 0x0F, 0x98, 0x07, + 0xC1, 0x06, 0x00, 0xF8, 0x21, 0x80, 0x3E, 0x04, 0x30, 0x07, 0xC1, 0x8C, + 0x00, 0xF0, 0x21, 0x80, 0x1E, 0x0C, 0x60, 0x03, 0xC1, 0x0C, 0x00, 0x78, + 0xC3, 0x03, 0xC7, 0xF8, 0x61, 0xFC, 0x7C, 0x18, 0x7C, 0xC0, 0x06, 0x1F, + 0x08, 0x00, 0xC7, 0xC1, 0x00, 0x30, 0xF0, 0x20, 0x06, 0x3E, 0x04, 0x01, + 0x87, 0xC1, 0x00, 0x30, 0xF0, 0x20, 0x0C, 0x1E, 0x0C, 0x03, 0x03, 0xC1, + 0x00, 0x60, 0x3C, 0xC0, 0x18, 0x07, 0xF8, 0x03, 0x00, 0x7C, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x1F, 0xF0, 0x00, 0x1E, 0x38, 0x00, 0x0E, 0x0E, 0x00, + 0x0F, 0x07, 0x00, 0x07, 0x83, 0x80, 0x03, 0xC3, 0x80, 0x01, 0xE3, 0x80, + 0x00, 0xF7, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7F, 0x0F, + 0xF0, 0xE7, 0x81, 0xE0, 0xE3, 0xE0, 0xE0, 0xE1, 0xF0, 0x60, 0xE0, 0x7C, + 0x60, 0xF0, 0x3E, 0x20, 0x78, 0x1F, 0xB0, 0x3C, 0x07, 0xF0, 0x1F, 0x03, + 0xF0, 0x0F, 0x80, 0xFC, 0x03, 0xF0, 0x7F, 0x8D, 0xFF, 0xEF, 0xFC, 0x7F, + 0xE3, 0xFC, 0x0F, 0xC0, 0x78, 0x00, 0x3B, 0xDE, 0xE7, 0x39, 0x8C, 0x46, + 0x00, 0x00, 0x60, 0x18, 0x06, 0x01, 0x80, 0x60, 0x1C, 0x07, 0x01, 0xE0, + 0x38, 0x0F, 0x01, 0xC0, 0x38, 0x0F, 0x01, 0xE0, 0x38, 0x07, 0x00, 0xE0, + 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x00, 0xC0, 0x18, 0x03, 0x00, 0x60, 0x06, + 0x00, 0xC0, 0x08, 0x00, 0x80, 0x10, 0x00, 0x06, 0x00, 0x40, 0x04, 0x00, + 0x80, 0x18, 0x01, 0x00, 0x30, 0x06, 0x00, 0xC0, 0x1C, 0x03, 0x80, 0x70, + 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x01, 0xE0, 0x3C, 0x07, 0x00, 0xE0, 0x3C, + 0x07, 0x00, 0xE0, 0x38, 0x06, 0x01, 0xC0, 0x70, 0x18, 0x06, 0x01, 0x80, + 0x00, 0x07, 0x00, 0x38, 0x01, 0xC1, 0x8E, 0x3E, 0x23, 0xF9, 0x3F, 0xEB, + 0xE0, 0xE0, 0xFF, 0xF7, 0x93, 0xF8, 0x9F, 0x8E, 0x60, 0x70, 0x03, 0x80, + 0x08, 0x00, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, + 0x00, 0x0E, 0x00, 0x07, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, + 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x03, 0x80, + 0x01, 0xC0, 0x00, 0x1C, 0x7C, 0xF9, 0xF1, 0xE1, 0xC3, 0x0C, 0x30, 0xC2, + 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xE0, 0x7B, 0xFF, 0xFF, 0x78, 0x00, 0x1C, + 0x00, 0xE0, 0x03, 0x80, 0x1E, 0x00, 0x70, 0x01, 0xC0, 0x0E, 0x00, 0x38, + 0x01, 0xC0, 0x07, 0x00, 0x38, 0x00, 0xE0, 0x07, 0x80, 0x1C, 0x00, 0x70, + 0x03, 0x80, 0x0E, 0x00, 0x70, 0x01, 0xC0, 0x0E, 0x00, 0x38, 0x01, 0xC0, + 0x07, 0x00, 0x1C, 0x00, 0xE0, 0x00, 0x00, 0xF0, 0x07, 0x30, 0x1C, 0x30, + 0x78, 0x60, 0xE0, 0xE3, 0xC1, 0xCF, 0x83, 0x9E, 0x0F, 0x3C, 0x1E, 0xF8, + 0x3D, 0xE0, 0x7B, 0xC1, 0xFF, 0x83, 0xFF, 0x07, 0xBC, 0x0F, 0x78, 0x3E, + 0xF0, 0x7D, 0xE0, 0xF3, 0x81, 0xE7, 0x07, 0x8E, 0x0F, 0x0C, 0x3C, 0x18, + 0x70, 0x19, 0xC0, 0x1E, 0x00, 0x00, 0x06, 0x01, 0xF8, 0x1F, 0xF0, 0x03, + 0xE0, 0x07, 0x80, 0x1F, 0x00, 0x3E, 0x00, 0x7C, 0x00, 0xF0, 0x03, 0xE0, + 0x07, 0xC0, 0x0F, 0x80, 0x1E, 0x00, 0x7C, 0x00, 0xF8, 0x01, 0xE0, 0x07, + 0xC0, 0x0F, 0x80, 0x1F, 0x00, 0x3C, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, + 0x0F, 0xC0, 0xFF, 0xF0, 0x00, 0xF8, 0x01, 0xFC, 0x03, 0xFE, 0x06, 0x3F, + 0x08, 0x1F, 0x18, 0x0F, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0E, + 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x30, 0x00, 0x70, 0x00, 0xC0, + 0x01, 0x80, 0x03, 0x00, 0x06, 0x02, 0x0C, 0x06, 0x08, 0x0C, 0x1F, 0xFC, + 0x3F, 0xFC, 0x7F, 0xF8, 0xFF, 0xF8, 0x00, 0xF0, 0x07, 0xF8, 0x1F, 0xF0, + 0x61, 0xF0, 0x81, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0E, 0x00, 0x3C, 0x00, + 0xE0, 0x07, 0xC0, 0x3F, 0xC0, 0x1F, 0x80, 0x0F, 0x80, 0x1F, 0x00, 0x1E, + 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xC0, 0x07, 0x9C, 0x0E, 0x3C, + 0x38, 0x7F, 0xE0, 0x7E, 0x00, 0x00, 0x00, 0xC0, 0x00, 0x70, 0x00, 0x3C, + 0x00, 0x1E, 0x00, 0x0F, 0x80, 0x07, 0xE0, 0x02, 0xF8, 0x01, 0x3C, 0x00, + 0x9F, 0x00, 0x47, 0xC0, 0x31, 0xE0, 0x18, 0x78, 0x0C, 0x3E, 0x06, 0x0F, + 0x83, 0x03, 0xC1, 0x80, 0xF0, 0x7F, 0xFF, 0x1F, 0xFF, 0xCF, 0xFF, 0xF0, + 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x07, 0xC0, 0x01, + 0xFF, 0x00, 0xFF, 0x80, 0xFF, 0xC0, 0x7F, 0xE0, 0x60, 0x00, 0x30, 0x00, + 0x10, 0x00, 0x1F, 0x00, 0x0F, 0xE0, 0x0F, 0xF8, 0x07, 0xFE, 0x00, 0x3F, + 0x00, 0x07, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x38, 0x00, 0x1C, 0x00, + 0x0E, 0x00, 0x06, 0x00, 0x03, 0x00, 0x03, 0x87, 0x83, 0x83, 0xE3, 0x81, + 0xFF, 0x80, 0x3F, 0x00, 0x00, 0x00, 0x03, 0x80, 0x0F, 0x80, 0x1F, 0x00, + 0x3E, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x1F, 0x00, + 0x1F, 0xF0, 0x1F, 0xFE, 0x0F, 0xCF, 0x07, 0xC3, 0xC7, 0xE1, 0xE3, 0xE0, + 0xF1, 0xF0, 0x78, 0xF8, 0x3C, 0x78, 0x3E, 0x3C, 0x1F, 0x1E, 0x0F, 0x0F, + 0x0F, 0x83, 0x87, 0x81, 0xE7, 0x80, 0x7F, 0x80, 0x0F, 0x80, 0x00, 0x3F, + 0xFF, 0x3F, 0xFE, 0x3F, 0xFE, 0x7F, 0xFC, 0x60, 0x1C, 0x80, 0x38, 0x80, + 0x30, 0x00, 0x70, 0x00, 0x60, 0x00, 0xE0, 0x01, 0xC0, 0x01, 0xC0, 0x03, + 0x80, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x1C, + 0x00, 0x38, 0x00, 0x38, 0x00, 0x70, 0x00, 0xF0, 0x00, 0xE0, 0x00, 0x00, + 0xF8, 0x00, 0xFF, 0x00, 0xE1, 0xC0, 0xE0, 0xF0, 0xF0, 0x38, 0x78, 0x1C, + 0x3C, 0x0E, 0x1F, 0x07, 0x0F, 0x87, 0x07, 0xE7, 0x01, 0xFF, 0x00, 0x7E, + 0x00, 0x1F, 0x80, 0x3F, 0xE0, 0x73, 0xF0, 0x70, 0xFC, 0x70, 0x3E, 0x70, + 0x0F, 0x38, 0x07, 0x9C, 0x03, 0xCE, 0x01, 0xE7, 0x00, 0xE1, 0xC0, 0xE0, + 0x70, 0xE0, 0x0F, 0xC0, 0x00, 0x00, 0xF8, 0x01, 0xFF, 0x01, 0xF3, 0xC1, + 0xF0, 0xE1, 0xF0, 0x70, 0xF0, 0x3C, 0xF8, 0x1E, 0x7C, 0x0F, 0x3C, 0x0F, + 0x9E, 0x07, 0xCF, 0x03, 0xE7, 0x83, 0xF3, 0xC1, 0xF0, 0xF1, 0xF8, 0x3F, + 0xF8, 0x0F, 0xFC, 0x00, 0x7C, 0x00, 0x7C, 0x00, 0x7E, 0x00, 0x3E, 0x00, + 0x3C, 0x00, 0x7C, 0x00, 0x7C, 0x00, 0xF0, 0x00, 0xC0, 0x00, 0x00, 0x07, + 0x83, 0xF0, 0xFC, 0x3F, 0x07, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x78, 0x3F, 0x0F, 0xC3, 0xF0, 0x78, 0x00, 0x03, 0xC0, 0xFC, + 0x1F, 0x83, 0xF0, 0x3C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0C, 0x03, 0xC0, 0x7C, 0x0F, 0x80, 0xF0, 0x0E, 0x01, 0x80, 0x30, 0x0C, + 0x03, 0x01, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0x7C, 0x00, + 0x7F, 0x00, 0x7F, 0x00, 0xFF, 0x00, 0xFF, 0x00, 0xFE, 0x00, 0xFE, 0x00, + 0x3E, 0x00, 0x0F, 0xC0, 0x01, 0xFC, 0x00, 0x1F, 0xE0, 0x01, 0xFE, 0x00, + 0x0F, 0xE0, 0x00, 0xFF, 0x00, 0x0F, 0xC0, 0x00, 0xF0, 0x00, 0x04, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, + 0x38, 0x00, 0x0F, 0x80, 0x03, 0xF8, 0x00, 0x3F, 0x80, 0x03, 0xFC, 0x00, + 0x3F, 0xC0, 0x01, 0xFC, 0x00, 0x1F, 0xC0, 0x01, 0xF0, 0x00, 0xFC, 0x00, + 0xFE, 0x01, 0xFE, 0x01, 0xFE, 0x01, 0xFC, 0x03, 0xFC, 0x00, 0xFC, 0x00, + 0x3C, 0x00, 0x08, 0x00, 0x00, 0x07, 0xC0, 0xFF, 0x0E, 0x3C, 0x70, 0xF3, + 0xC7, 0x8C, 0x3C, 0x01, 0xE0, 0x1F, 0x00, 0xF0, 0x07, 0x80, 0x78, 0x07, + 0x80, 0x30, 0x03, 0x00, 0x10, 0x01, 0x80, 0x08, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x07, 0x80, 0x7E, 0x03, 0xF0, 0x1F, 0x80, 0x78, 0x00, 0x00, 0x3F, + 0x80, 0x00, 0xFF, 0xF8, 0x01, 0xF0, 0x1E, 0x01, 0xE0, 0x03, 0x81, 0xC0, + 0x00, 0xE1, 0xC0, 0x18, 0x38, 0xE0, 0x3F, 0xCC, 0xE0, 0x3C, 0xE7, 0x70, + 0x3C, 0x71, 0xF0, 0x1C, 0x30, 0xF8, 0x1E, 0x38, 0x7C, 0x0E, 0x1C, 0x3E, + 0x0F, 0x0E, 0x1F, 0x07, 0x0E, 0x0F, 0x83, 0x87, 0x0D, 0xC1, 0xC7, 0x86, + 0x70, 0xE5, 0xC6, 0x38, 0x7C, 0xFE, 0x1C, 0x1C, 0x3E, 0x07, 0x00, 0x00, + 0x01, 0xC0, 0x00, 0x00, 0x78, 0x00, 0x40, 0x1F, 0x00, 0xE0, 0x03, 0xFF, + 0xE0, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x03, 0x00, 0x00, + 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x03, + 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x17, 0xC0, 0x00, 0x67, 0x80, 0x00, 0x8F, + 0x00, 0x03, 0x1F, 0x00, 0x0C, 0x3E, 0x00, 0x10, 0x7C, 0x00, 0x60, 0xF8, + 0x00, 0x81, 0xF0, 0x03, 0xFF, 0xE0, 0x0F, 0xFF, 0xE0, 0x18, 0x07, 0xC0, + 0x60, 0x0F, 0x81, 0xC0, 0x1F, 0x03, 0x00, 0x3E, 0x0E, 0x00, 0x7C, 0x3C, + 0x00, 0xFC, 0xFE, 0x0F, 0xFE, 0x07, 0xFF, 0xE0, 0x01, 0xFF, 0xFC, 0x01, + 0xF8, 0x7E, 0x01, 0xF8, 0x3F, 0x01, 0xF0, 0x3F, 0x01, 0xF0, 0x3F, 0x01, + 0xF0, 0x3F, 0x03, 0xE0, 0x3F, 0x03, 0xE0, 0x7E, 0x03, 0xE0, 0xFC, 0x03, + 0xE3, 0xF0, 0x07, 0xFF, 0x80, 0x07, 0xC3, 0xE0, 0x07, 0xC1, 0xF8, 0x0F, + 0xC0, 0xF8, 0x0F, 0x80, 0xFC, 0x0F, 0x80, 0xFC, 0x0F, 0x80, 0xFC, 0x1F, + 0x80, 0xFC, 0x1F, 0x01, 0xFC, 0x1F, 0x01, 0xF8, 0x1F, 0x03, 0xF0, 0x3F, + 0x0F, 0xE0, 0x7F, 0xFF, 0xC0, 0xFF, 0xFE, 0x00, 0x00, 0x1F, 0x82, 0x01, + 0xFF, 0xE8, 0x07, 0xE0, 0xF0, 0x3F, 0x80, 0xE0, 0xFE, 0x00, 0xC1, 0xF8, + 0x01, 0x87, 0xE0, 0x02, 0x1F, 0x80, 0x04, 0x3F, 0x00, 0x00, 0xFC, 0x00, + 0x01, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0x80, 0x00, + 0x3F, 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFC, 0x00, 0x01, 0xF8, 0x00, 0x03, + 0xF0, 0x00, 0x03, 0xE0, 0x01, 0x07, 0xE0, 0x06, 0x07, 0xE0, 0x18, 0x07, + 0xE0, 0xE0, 0x07, 0xFF, 0x00, 0x01, 0xF8, 0x00, 0x07, 0xFF, 0xE0, 0x01, + 0xFF, 0xFE, 0x00, 0x1F, 0x87, 0xE0, 0x07, 0xE0, 0x7C, 0x01, 0xF0, 0x1F, + 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x0F, 0x80, 0x3F, 0x03, 0xE0, + 0x0F, 0xC0, 0xF8, 0x03, 0xF0, 0x3E, 0x00, 0xFC, 0x1F, 0x00, 0x3F, 0x07, + 0xC0, 0x0F, 0xC1, 0xF0, 0x07, 0xF0, 0xFC, 0x01, 0xF8, 0x3E, 0x00, 0x7E, + 0x0F, 0x80, 0x3F, 0x83, 0xE0, 0x0F, 0xC1, 0xF8, 0x07, 0xF0, 0x7C, 0x01, + 0xF8, 0x1F, 0x00, 0xFC, 0x07, 0xC0, 0x7E, 0x03, 0xF0, 0x7E, 0x01, 0xFF, + 0xFF, 0x00, 0xFF, 0xFE, 0x00, 0x00, 0x07, 0xFF, 0xFE, 0x03, 0xFF, 0xFC, + 0x07, 0xE0, 0x78, 0x0F, 0xC0, 0x60, 0x1F, 0x00, 0x40, 0x3E, 0x00, 0x80, + 0x7C, 0x01, 0x01, 0xF8, 0x10, 0x03, 0xE0, 0x60, 0x07, 0xC3, 0x80, 0x0F, + 0xFF, 0x00, 0x3F, 0xFE, 0x00, 0x7C, 0x38, 0x00, 0xF8, 0x30, 0x03, 0xF0, + 0x60, 0x07, 0xC0, 0x80, 0x0F, 0x81, 0x00, 0x1F, 0x00, 0x10, 0x7E, 0x00, + 0x60, 0xF8, 0x01, 0xC1, 0xF0, 0x07, 0x03, 0xE0, 0x1E, 0x0F, 0xC0, 0xFC, + 0x3F, 0xFF, 0xF8, 0xFF, 0xFF, 0xE0, 0x07, 0xFF, 0xFE, 0x03, 0xFF, 0xFC, + 0x07, 0xE0, 0x78, 0x0F, 0xC0, 0x60, 0x1F, 0x00, 0x40, 0x3E, 0x00, 0x80, + 0x7C, 0x01, 0x01, 0xF8, 0x20, 0x03, 0xE0, 0xC0, 0x07, 0xC3, 0x80, 0x0F, + 0xFE, 0x00, 0x3F, 0xFC, 0x00, 0x7C, 0x38, 0x00, 0xF8, 0x30, 0x03, 0xF0, + 0x60, 0x07, 0xC0, 0x80, 0x0F, 0x81, 0x00, 0x1F, 0x00, 0x00, 0x7E, 0x00, + 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0xC0, 0x00, + 0x3F, 0x80, 0x00, 0xFF, 0xC0, 0x00, 0x00, 0x1F, 0xC2, 0x00, 0xFF, 0xF6, + 0x01, 0xF8, 0x3C, 0x03, 0xE0, 0x1C, 0x0F, 0xC0, 0x0C, 0x0F, 0xC0, 0x08, + 0x1F, 0x80, 0x08, 0x3F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x7E, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFC, 0x03, 0xFF, + 0xFC, 0x00, 0xFC, 0xFC, 0x00, 0xF8, 0xFC, 0x00, 0xF8, 0xFC, 0x00, 0xF8, + 0xFC, 0x00, 0xF0, 0x7C, 0x01, 0xF0, 0x7E, 0x01, 0xF0, 0x3E, 0x01, 0xF0, + 0x1F, 0x83, 0xE0, 0x0F, 0xFF, 0x80, 0x01, 0xFC, 0x00, 0x07, 0xFF, 0x3F, + 0xF8, 0x0F, 0xE0, 0x7F, 0x00, 0x7E, 0x01, 0xF8, 0x03, 0xF0, 0x0F, 0x80, + 0x1F, 0x00, 0x7C, 0x00, 0xF8, 0x07, 0xE0, 0x07, 0xC0, 0x3E, 0x00, 0x7E, + 0x01, 0xF0, 0x03, 0xE0, 0x0F, 0x80, 0x1F, 0x00, 0xF8, 0x00, 0xF8, 0x07, + 0xC0, 0x0F, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xF0, 0x03, 0xE0, 0x1F, 0x00, + 0x3F, 0x00, 0xF8, 0x01, 0xF0, 0x07, 0xC0, 0x0F, 0x80, 0x7E, 0x00, 0x7C, + 0x03, 0xE0, 0x07, 0xE0, 0x1F, 0x00, 0x3E, 0x00, 0xF8, 0x01, 0xF0, 0x0F, + 0xC0, 0x0F, 0x80, 0x7C, 0x00, 0xFC, 0x03, 0xE0, 0x0F, 0xE0, 0x3F, 0x80, + 0xFF, 0xC7, 0xFF, 0x00, 0x07, 0xFE, 0x03, 0xF8, 0x07, 0xE0, 0x0F, 0xC0, + 0x1F, 0x00, 0x3E, 0x00, 0x7C, 0x01, 0xF0, 0x03, 0xE0, 0x07, 0xC0, 0x0F, + 0x80, 0x3E, 0x00, 0x7C, 0x00, 0xF8, 0x03, 0xF0, 0x07, 0xC0, 0x0F, 0x80, + 0x1F, 0x00, 0x7C, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, 0x0F, 0xC0, 0x3F, + 0x80, 0xFF, 0xC0, 0x00, 0x3F, 0xF0, 0x01, 0xFE, 0x00, 0x0F, 0xC0, 0x00, + 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x1F, 0x80, 0x01, 0xF0, 0x00, + 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, + 0x07, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x0F, 0xC0, + 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x61, 0xF0, + 0x0F, 0x3F, 0x00, 0xE7, 0xE0, 0x07, 0xFC, 0x00, 0x3F, 0x00, 0x00, 0x07, + 0xFF, 0x3F, 0x80, 0xFE, 0x07, 0x80, 0x7E, 0x03, 0x00, 0x3F, 0x03, 0x00, + 0x1F, 0x03, 0x00, 0x0F, 0x83, 0x00, 0x07, 0xC3, 0x00, 0x07, 0xE3, 0x00, + 0x03, 0xE3, 0x00, 0x01, 0xF3, 0x00, 0x00, 0xFB, 0x80, 0x00, 0xFB, 0xC0, + 0x00, 0x7F, 0xE0, 0x00, 0x3E, 0xF8, 0x00, 0x3F, 0x7C, 0x00, 0x1F, 0x1F, + 0x00, 0x0F, 0x8F, 0x80, 0x07, 0xC7, 0xE0, 0x07, 0xE1, 0xF0, 0x03, 0xE0, + 0xFC, 0x01, 0xF0, 0x3E, 0x00, 0xF8, 0x1F, 0x00, 0xFC, 0x07, 0xC0, 0xFE, + 0x07, 0xF0, 0xFF, 0xCF, 0xFC, 0x00, 0x07, 0xFF, 0x00, 0x07, 0xF0, 0x00, + 0x1F, 0x80, 0x00, 0x7E, 0x00, 0x01, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x1F, + 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x3E, 0x00, + 0x01, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x1F, 0x00, 0x00, 0xFC, 0x00, 0x03, + 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x3E, 0x00, 0x11, 0xF0, 0x00, 0xC7, 0xC0, + 0x06, 0x1F, 0x00, 0x38, 0x7C, 0x01, 0xE3, 0xF0, 0x3F, 0x9F, 0xFF, 0xFC, + 0xFF, 0xFF, 0xF0, 0x07, 0xF8, 0x00, 0x7F, 0x80, 0xFC, 0x00, 0x3F, 0x80, + 0x3E, 0x00, 0x3F, 0x80, 0x1F, 0x00, 0x3F, 0x80, 0x1F, 0x80, 0x1F, 0xC0, + 0x0F, 0xE0, 0x1B, 0xE0, 0x07, 0xF0, 0x0D, 0xF0, 0x02, 0xF8, 0x0D, 0xF0, + 0x03, 0x7C, 0x0C, 0xF8, 0x01, 0xBE, 0x06, 0x7C, 0x00, 0xDF, 0x06, 0x7C, + 0x00, 0xCF, 0x83, 0x3E, 0x00, 0x67, 0xC3, 0x1F, 0x00, 0x31, 0xE3, 0x0F, + 0x80, 0x38, 0xF9, 0x8F, 0x80, 0x18, 0x7D, 0x87, 0xC0, 0x0C, 0x3F, 0x83, + 0xE0, 0x06, 0x1F, 0xC1, 0xF0, 0x06, 0x0F, 0xC1, 0xF0, 0x03, 0x07, 0xC0, + 0xF8, 0x01, 0x83, 0xE0, 0x7C, 0x01, 0xC0, 0xE0, 0x7E, 0x00, 0xE0, 0x70, + 0x3F, 0x00, 0xF8, 0x30, 0x3F, 0x80, 0xFF, 0x10, 0x7F, 0xF0, 0x00, 0x07, + 0xF0, 0x0F, 0xE0, 0x3E, 0x00, 0x78, 0x07, 0xE0, 0x06, 0x00, 0x7C, 0x00, + 0xC0, 0x1F, 0xC0, 0x10, 0x03, 0xF8, 0x06, 0x00, 0x6F, 0x80, 0xC0, 0x19, + 0xF0, 0x10, 0x03, 0x3F, 0x02, 0x00, 0x63, 0xE0, 0xC0, 0x0C, 0x7C, 0x18, + 0x03, 0x07, 0xC2, 0x00, 0x60, 0xF8, 0x40, 0x0C, 0x0F, 0x98, 0x03, 0x81, + 0xF3, 0x00, 0x60, 0x3F, 0x40, 0x0C, 0x03, 0xF8, 0x01, 0x80, 0x7F, 0x00, + 0x60, 0x07, 0xC0, 0x0C, 0x00, 0xF8, 0x01, 0x80, 0x0F, 0x00, 0x70, 0x01, + 0xE0, 0x0E, 0x00, 0x18, 0x03, 0xE0, 0x03, 0x00, 0x02, 0x00, 0x60, 0x00, + 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0xC0, 0x07, 0xC3, 0xE0, 0x1F, 0x03, 0xC0, + 0x7C, 0x03, 0xC1, 0xF0, 0x07, 0x87, 0xE0, 0x0F, 0x8F, 0x80, 0x1F, 0x3F, + 0x00, 0x3E, 0x7C, 0x00, 0x7D, 0xF8, 0x01, 0xFB, 0xE0, 0x03, 0xF7, 0xC0, + 0x07, 0xDF, 0x80, 0x1F, 0xBF, 0x00, 0x3F, 0x7C, 0x00, 0x7C, 0xF8, 0x01, + 0xF9, 0xF0, 0x03, 0xE3, 0xE0, 0x0F, 0xC7, 0xC0, 0x1F, 0x07, 0x80, 0x7C, + 0x0F, 0x81, 0xF0, 0x0F, 0x87, 0xC0, 0x0F, 0xFE, 0x00, 0x07, 0xF0, 0x00, + 0x07, 0xFF, 0xE0, 0x03, 0xFF, 0xF0, 0x07, 0xE3, 0xF0, 0x0F, 0x83, 0xE0, + 0x1F, 0x07, 0xE0, 0x3E, 0x0F, 0xC0, 0x7C, 0x1F, 0x81, 0xF0, 0x3F, 0x03, + 0xE0, 0xFE, 0x07, 0xC1, 0xF8, 0x0F, 0x87, 0xF0, 0x3E, 0x1F, 0xC0, 0x7F, + 0xFE, 0x00, 0xFF, 0xF0, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, + 0x00, 0x1F, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, + 0x03, 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x80, 0x00, 0xFF, 0xC0, 0x00, + 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0xC0, 0x07, 0xC3, 0xE0, 0x1F, 0x03, 0xC0, + 0x7C, 0x03, 0xC1, 0xF0, 0x07, 0x87, 0xE0, 0x0F, 0x8F, 0x80, 0x1F, 0x3F, + 0x00, 0x3E, 0x7C, 0x00, 0x7D, 0xF8, 0x01, 0xFB, 0xF0, 0x03, 0xF7, 0xC0, + 0x07, 0xDF, 0x80, 0x0F, 0xBF, 0x00, 0x3F, 0x7C, 0x00, 0x7C, 0xF8, 0x01, + 0xF9, 0xF0, 0x03, 0xE3, 0xE0, 0x07, 0xC7, 0xC0, 0x1F, 0x07, 0x80, 0x7C, + 0x0F, 0x01, 0xF0, 0x0F, 0x07, 0x80, 0x07, 0xFE, 0x00, 0x03, 0x80, 0x00, + 0x0C, 0x00, 0x00, 0x3C, 0x00, 0x20, 0xFF, 0xC1, 0x87, 0xFF, 0xFE, 0x1E, + 0xFF, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xFF, 0xE0, 0x01, 0xFF, 0xFC, + 0x01, 0xF8, 0x7E, 0x01, 0xF8, 0x3F, 0x01, 0xF8, 0x3F, 0x01, 0xF0, 0x3F, + 0x01, 0xF0, 0x3F, 0x03, 0xF0, 0x3F, 0x03, 0xE0, 0x7E, 0x03, 0xE0, 0xFE, + 0x03, 0xE1, 0xF8, 0x07, 0xFF, 0xF0, 0x07, 0xFF, 0x80, 0x07, 0xDF, 0xC0, + 0x0F, 0xCF, 0xC0, 0x0F, 0xCF, 0xC0, 0x0F, 0x8F, 0xE0, 0x0F, 0x87, 0xE0, + 0x1F, 0x87, 0xE0, 0x1F, 0x03, 0xF0, 0x1F, 0x03, 0xF0, 0x1F, 0x03, 0xF0, + 0x3F, 0x01, 0xF8, 0x7F, 0x01, 0xF8, 0xFF, 0xE1, 0xFE, 0x00, 0xF8, 0x40, + 0xFF, 0xB0, 0x38, 0x3C, 0x1C, 0x07, 0x0F, 0x01, 0xC3, 0xC0, 0x20, 0xF0, + 0x08, 0x3E, 0x02, 0x0F, 0xC0, 0x03, 0xF8, 0x00, 0x7F, 0x00, 0x0F, 0xE0, + 0x01, 0xFC, 0x00, 0x3F, 0x80, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x00, + 0x03, 0xC4, 0x00, 0xF1, 0x00, 0x3C, 0x60, 0x0F, 0x38, 0x07, 0x8F, 0x83, + 0xC2, 0x3F, 0xE0, 0x83, 0xF0, 0x00, 0x3F, 0xFF, 0xF9, 0xFF, 0xFF, 0xCF, + 0x1F, 0x1E, 0x70, 0xF8, 0x77, 0x0F, 0x83, 0x30, 0x7C, 0x09, 0x03, 0xE0, + 0x40, 0x3F, 0x02, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x07, + 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, + 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x00, 0x00, 0xF8, + 0x00, 0x07, 0xC0, 0x00, 0x7E, 0x00, 0x07, 0xF0, 0x00, 0xFF, 0xF0, 0x00, + 0x7F, 0xF0, 0xFF, 0x1F, 0xC0, 0x3E, 0x1F, 0x80, 0x1C, 0x1F, 0x80, 0x18, + 0x1F, 0x00, 0x18, 0x1F, 0x00, 0x18, 0x1F, 0x00, 0x30, 0x3F, 0x00, 0x30, + 0x3E, 0x00, 0x30, 0x3E, 0x00, 0x30, 0x7E, 0x00, 0x60, 0x7C, 0x00, 0x60, + 0x7C, 0x00, 0x60, 0x7C, 0x00, 0xC0, 0x7C, 0x00, 0xC0, 0xF8, 0x00, 0xC0, + 0xF8, 0x00, 0xC0, 0xF8, 0x01, 0x80, 0xF8, 0x01, 0x80, 0xF8, 0x03, 0x80, + 0xF8, 0x03, 0x00, 0x7C, 0x06, 0x00, 0x7E, 0x1E, 0x00, 0x3F, 0xF8, 0x00, + 0x0F, 0xE0, 0x00, 0xFF, 0xE0, 0x7F, 0x3F, 0x80, 0x1C, 0x1F, 0x80, 0x18, + 0x1F, 0x80, 0x18, 0x1F, 0x80, 0x30, 0x1F, 0x80, 0x30, 0x0F, 0x80, 0x60, + 0x0F, 0x80, 0x40, 0x0F, 0x80, 0xC0, 0x0F, 0x81, 0x80, 0x0F, 0x81, 0x00, + 0x0F, 0xC3, 0x00, 0x0F, 0xC6, 0x00, 0x07, 0xC6, 0x00, 0x07, 0xCC, 0x00, + 0x07, 0xC8, 0x00, 0x07, 0xD8, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF0, 0x00, + 0x07, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0x80, 0x00, + 0x03, 0x00, 0x00, 0x03, 0x00, 0x00, 0xFF, 0xCF, 0xF8, 0x7E, 0x7F, 0x07, + 0xE0, 0x38, 0x7C, 0x07, 0x80, 0x60, 0xF8, 0x0F, 0x00, 0x81, 0xF0, 0x1E, + 0x03, 0x03, 0xE0, 0x3E, 0x04, 0x07, 0xE0, 0xFC, 0x18, 0x07, 0xC1, 0xF8, + 0x20, 0x0F, 0x87, 0xF0, 0xC0, 0x1F, 0x0B, 0xE1, 0x00, 0x3E, 0x37, 0xC6, + 0x00, 0x7C, 0x47, 0x88, 0x00, 0xF9, 0x8F, 0x30, 0x01, 0xF2, 0x1F, 0x40, + 0x03, 0xEC, 0x3E, 0x80, 0x03, 0xF0, 0x7F, 0x00, 0x07, 0xE0, 0xFC, 0x00, + 0x0F, 0x81, 0xF8, 0x00, 0x1F, 0x03, 0xE0, 0x00, 0x3C, 0x07, 0xC0, 0x00, + 0x78, 0x07, 0x00, 0x00, 0xF0, 0x0E, 0x00, 0x00, 0xC0, 0x18, 0x00, 0x01, + 0x80, 0x30, 0x00, 0x02, 0x00, 0x40, 0x00, 0x0F, 0xFE, 0x3F, 0x81, 0xFC, + 0x07, 0x80, 0x7C, 0x03, 0x00, 0x3F, 0x03, 0x00, 0x0F, 0x83, 0x80, 0x07, + 0xC1, 0x80, 0x03, 0xE1, 0x80, 0x00, 0xF9, 0x80, 0x00, 0x7D, 0x80, 0x00, + 0x3F, 0x80, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, 0x00, + 0x01, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xBE, 0x00, 0x00, 0xCF, 0x00, + 0x00, 0xC7, 0xC0, 0x00, 0xC3, 0xE0, 0x00, 0xC1, 0xF0, 0x00, 0xC0, 0x7C, + 0x00, 0xE0, 0x3E, 0x00, 0xE0, 0x1F, 0x00, 0xF8, 0x1F, 0xE0, 0xFF, 0x1F, + 0xF8, 0x00, 0xFF, 0xC3, 0xF9, 0xF8, 0x07, 0x87, 0xC0, 0x38, 0x3E, 0x01, + 0x81, 0xF0, 0x18, 0x07, 0xC0, 0x80, 0x3E, 0x0C, 0x01, 0xF0, 0xC0, 0x07, + 0xC4, 0x00, 0x3E, 0x60, 0x01, 0xF6, 0x00, 0x07, 0xA0, 0x00, 0x3F, 0x00, + 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xC0, 0x00, 0x3E, + 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, + 0x7E, 0x00, 0x07, 0xF0, 0x00, 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xF8, 0x3F, + 0xFF, 0xC3, 0xE0, 0x7E, 0x1C, 0x07, 0xE0, 0xC0, 0x3E, 0x0C, 0x03, 0xF0, + 0x40, 0x3F, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x01, 0xF8, 0x00, 0x1F, + 0x80, 0x00, 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, 0x00, + 0x7E, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x83, 0xE0, 0x0C, 0x3F, 0x00, + 0xC3, 0xF0, 0x0E, 0x1F, 0x00, 0xF1, 0xF8, 0x1F, 0x9F, 0xFF, 0xF8, 0xFF, + 0xFF, 0xC0, 0x01, 0xFC, 0x0F, 0xE0, 0x3C, 0x00, 0xE0, 0x03, 0x80, 0x1E, + 0x00, 0x78, 0x01, 0xC0, 0x07, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0x80, 0x0E, + 0x00, 0x38, 0x01, 0xE0, 0x07, 0x00, 0x1C, 0x00, 0x70, 0x03, 0xC0, 0x0F, + 0x00, 0x38, 0x00, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x70, 0x01, 0xC0, 0x0F, + 0x00, 0x3C, 0x00, 0xFF, 0x03, 0xF8, 0x00, 0xE0, 0x38, 0x07, 0x01, 0xC0, + 0x70, 0x0C, 0x03, 0x80, 0xE0, 0x38, 0x07, 0x01, 0xC0, 0x70, 0x0C, 0x03, + 0x80, 0xE0, 0x38, 0x07, 0x01, 0xC0, 0x70, 0x0C, 0x03, 0x80, 0xE0, 0x38, + 0x07, 0x01, 0xC0, 0x03, 0xFC, 0x0F, 0xF0, 0x03, 0x80, 0x0E, 0x00, 0x38, + 0x01, 0xE0, 0x07, 0x80, 0x1C, 0x00, 0x70, 0x03, 0xC0, 0x0F, 0x00, 0x38, + 0x00, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x70, 0x01, 0xC0, 0x0F, 0x00, 0x3C, + 0x00, 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x78, 0x01, 0xE0, 0x07, 0x00, 0x1C, + 0x00, 0xF0, 0x03, 0xC0, 0xFE, 0x03, 0xF8, 0x00, 0x03, 0xC0, 0x03, 0xC0, + 0x07, 0xE0, 0x07, 0xE0, 0x0E, 0x70, 0x0E, 0x70, 0x1C, 0x78, 0x1C, 0x38, + 0x3C, 0x3C, 0x38, 0x1C, 0x78, 0x1E, 0x70, 0x0E, 0xF0, 0x0E, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xE1, 0xE3, 0xC1, 0xC1, 0xC0, 0xC0, 0x00, + 0xF7, 0x80, 0xFD, 0xE0, 0x7C, 0xF0, 0x3C, 0x3C, 0x1E, 0x0F, 0x0F, 0x83, + 0x83, 0xC1, 0xE1, 0xE0, 0x78, 0x78, 0x1C, 0x3E, 0x0F, 0x0F, 0x03, 0xC3, + 0xC1, 0xF0, 0xF0, 0xFC, 0xFE, 0x6F, 0x6F, 0xF3, 0xF1, 0xF8, 0xF8, 0x3C, + 0x1C, 0x00, 0x01, 0xE0, 0x1F, 0xC0, 0x07, 0xC0, 0x07, 0xC0, 0x07, 0x80, + 0x07, 0x80, 0x0F, 0x80, 0x0F, 0x00, 0x0F, 0x00, 0x0F, 0x3C, 0x1E, 0xFE, + 0x1F, 0x9F, 0x1F, 0x0F, 0x1E, 0x0F, 0x3E, 0x0F, 0x3C, 0x0F, 0x3C, 0x1F, + 0x78, 0x1E, 0x78, 0x1E, 0x78, 0x3C, 0x78, 0x3C, 0xF0, 0x78, 0xF0, 0xF0, + 0xF1, 0xE0, 0x7F, 0xC0, 0x3F, 0x00, 0x01, 0xF0, 0x3F, 0xC3, 0xCE, 0x3C, + 0xF3, 0xC7, 0x1E, 0x01, 0xE0, 0x0F, 0x00, 0xF8, 0x07, 0x80, 0x3C, 0x01, + 0xE0, 0x0F, 0x03, 0x78, 0x31, 0xE3, 0x0F, 0xF0, 0x1E, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x78, 0x00, 0x0F, + 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x01, 0xEF, 0x00, 0x7F, 0xE0, 0x3E, 0x7C, + 0x07, 0x8F, 0x01, 0xE1, 0xE0, 0x78, 0x3C, 0x0F, 0x0F, 0x83, 0xC1, 0xE0, + 0x78, 0x3C, 0x1E, 0x0F, 0x83, 0xC1, 0xF0, 0x78, 0x7C, 0x0F, 0x0F, 0x91, + 0xE3, 0xF6, 0x3F, 0xDF, 0x83, 0xF3, 0xE0, 0x3C, 0x38, 0x00, 0x01, 0xE0, + 0x3F, 0x83, 0xCE, 0x3C, 0x73, 0xC3, 0x9E, 0x1D, 0xE1, 0xCF, 0x1C, 0xFB, + 0xC7, 0xF8, 0x3C, 0x01, 0xE0, 0x0F, 0x02, 0x78, 0x31, 0xE3, 0x0F, 0xF0, + 0x1E, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x1D, 0xC0, 0x01, 0xCE, 0x00, 0x1C, + 0x70, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x07, 0x80, 0x00, + 0x3C, 0x00, 0x0F, 0xFC, 0x00, 0x7F, 0xE0, 0x00, 0xF0, 0x00, 0x07, 0x80, + 0x00, 0x3C, 0x00, 0x03, 0xE0, 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, + 0x80, 0x00, 0x7C, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, + 0x07, 0x80, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, + 0x00, 0x0F, 0x00, 0x0E, 0x70, 0x00, 0x77, 0x80, 0x03, 0xF8, 0x00, 0x0F, + 0x80, 0x00, 0x00, 0xFE, 0x00, 0x7F, 0xFC, 0x1F, 0x1F, 0x87, 0xC3, 0xC1, + 0xF0, 0x78, 0x3C, 0x1F, 0x07, 0x83, 0xE0, 0xF0, 0xF8, 0x0E, 0x3E, 0x01, + 0xFF, 0x80, 0x3F, 0xC0, 0x0C, 0x00, 0x03, 0xC0, 0x00, 0x7F, 0x80, 0x0F, + 0xFE, 0x00, 0x7F, 0xF0, 0x70, 0xFF, 0x1C, 0x03, 0xE3, 0x80, 0x3C, 0x70, + 0x07, 0x0F, 0x03, 0xE0, 0xFF, 0xF0, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x03, + 0xE0, 0x00, 0xF0, 0x00, 0xF8, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1E, 0x00, + 0x1F, 0x00, 0x0F, 0x0E, 0x07, 0x9F, 0x83, 0xDF, 0xC3, 0xE9, 0xE1, 0xE8, + 0xF0, 0xF8, 0xF8, 0x7C, 0x78, 0x7C, 0x3C, 0x3E, 0x3E, 0x1E, 0x1E, 0x1F, + 0x0F, 0x0F, 0x0F, 0x87, 0x87, 0xCB, 0xC3, 0xCB, 0xE1, 0xE9, 0xE0, 0xFC, + 0xF0, 0x38, 0x00, 0x03, 0x03, 0xC1, 0xE0, 0xF0, 0x30, 0x00, 0x00, 0x00, + 0x07, 0x3F, 0x87, 0x83, 0xC1, 0xE0, 0xF0, 0xF0, 0x78, 0x3C, 0x1E, 0x1E, + 0x0F, 0x27, 0x17, 0x93, 0xF1, 0xF8, 0x70, 0x00, 0x00, 0x06, 0x00, 0x0F, + 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x06, 0x00, 0xFE, 0x00, 0x3E, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x3C, + 0x00, 0x7C, 0x00, 0x78, 0x00, 0x78, 0x00, 0x78, 0x00, 0xF8, 0x00, 0xF0, + 0x00, 0xF0, 0x00, 0xF0, 0x01, 0xF0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, + 0x03, 0xC0, 0xE3, 0xC0, 0xE7, 0x80, 0xFF, 0x00, 0x7C, 0x00, 0x1F, 0xC0, + 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1E, + 0x00, 0x1F, 0x00, 0x0F, 0x3F, 0x87, 0x87, 0x83, 0xC3, 0x03, 0xE3, 0x01, + 0xE3, 0x00, 0xF3, 0x00, 0x7B, 0x80, 0x7B, 0xC0, 0x3F, 0xE0, 0x1E, 0xF0, + 0x1F, 0x78, 0x0F, 0x1E, 0x07, 0x8F, 0x13, 0xC7, 0x93, 0xE1, 0xF9, 0xE0, + 0xF8, 0xF0, 0x38, 0x00, 0x1F, 0xC0, 0xF8, 0x1F, 0x03, 0xC0, 0x78, 0x1F, + 0x03, 0xE0, 0x78, 0x0F, 0x01, 0xE0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x0F, + 0x01, 0xE0, 0x3C, 0x0F, 0x81, 0xE0, 0x3C, 0x8F, 0x31, 0xEC, 0x3F, 0x07, + 0xC0, 0x70, 0x00, 0x01, 0x87, 0x07, 0x0F, 0xE7, 0xE7, 0xE0, 0xF3, 0xF9, + 0xF8, 0x3D, 0x9E, 0x9E, 0x0F, 0x47, 0xC7, 0x83, 0xE1, 0xD1, 0xE1, 0xF8, + 0xF8, 0xF0, 0x7C, 0x3C, 0x3C, 0x1F, 0x0F, 0x1F, 0x0F, 0x87, 0xC7, 0x83, + 0xE1, 0xE1, 0xE0, 0xF0, 0x78, 0x78, 0x3C, 0x1E, 0x3C, 0x1F, 0x0F, 0x0F, + 0x27, 0x83, 0xC3, 0xD1, 0xE0, 0xF0, 0xFC, 0xF8, 0x78, 0x1C, 0x00, 0x01, + 0x8F, 0x0F, 0xE7, 0xE0, 0xF3, 0xF8, 0x3C, 0x9E, 0x0F, 0x47, 0x87, 0xA3, + 0xC1, 0xE8, 0xF0, 0x7C, 0x3C, 0x1E, 0x1E, 0x0F, 0x87, 0x83, 0xE1, 0xE0, + 0xF0, 0xF8, 0x3C, 0x3C, 0x1F, 0x0F, 0x27, 0x83, 0xD1, 0xE0, 0xFC, 0x78, + 0x1C, 0x00, 0x01, 0xF0, 0x0E, 0x30, 0x38, 0x70, 0xF0, 0xF3, 0xC1, 0xE7, + 0x83, 0xDE, 0x07, 0xBC, 0x1F, 0xF8, 0x3F, 0xE0, 0x7B, 0xC0, 0xF7, 0x83, + 0xCF, 0x07, 0x9E, 0x1E, 0x1C, 0x38, 0x1C, 0xE0, 0x1F, 0x00, 0x00, 0xE3, + 0x80, 0xFD, 0xF8, 0x0F, 0xFF, 0x81, 0xE8, 0xF0, 0x3E, 0x1E, 0x07, 0x83, + 0xC0, 0xF0, 0x78, 0x3E, 0x1F, 0x07, 0x83, 0xC0, 0xF0, 0x78, 0x1E, 0x1F, + 0x07, 0x83, 0xC0, 0xF0, 0xF8, 0x1E, 0x1E, 0x03, 0xC7, 0x80, 0xFF, 0xE0, + 0x1E, 0xF0, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, 0x00, + 0xF8, 0x00, 0x3F, 0xC0, 0x00, 0x01, 0xEF, 0x07, 0xFF, 0x0F, 0x1E, 0x1E, + 0x1E, 0x1E, 0x1E, 0x3C, 0x1E, 0x7C, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0xF0, + 0x7C, 0xF0, 0x78, 0xF0, 0xF8, 0xF0, 0xF8, 0xF1, 0xF0, 0xFE, 0xF0, 0x7E, + 0xF0, 0x39, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x03, 0xC0, 0x03, + 0xC0, 0x1F, 0xF8, 0x03, 0x9C, 0x7F, 0x7C, 0x3D, 0xF8, 0x7A, 0xE0, 0xF8, + 0x03, 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x3E, 0x00, 0x7C, 0x00, 0xF0, 0x01, + 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x7C, 0x00, 0x07, 0x18, 0xFF, + 0xC7, 0x1C, 0x70, 0x63, 0x81, 0x1E, 0x08, 0xF8, 0x07, 0xE0, 0x1F, 0x00, + 0x7C, 0x01, 0xF0, 0x07, 0x84, 0x3C, 0x20, 0xE1, 0x87, 0x1C, 0x70, 0x9E, + 0x00, 0x00, 0x80, 0x60, 0x30, 0x1C, 0x1F, 0x1F, 0xF7, 0xFC, 0x78, 0x1E, + 0x07, 0x83, 0xC0, 0xF0, 0x3C, 0x1F, 0x07, 0x81, 0xE0, 0x79, 0x3C, 0x4F, + 0x23, 0xF0, 0xFC, 0x1C, 0x00, 0x0F, 0x0F, 0x3F, 0x87, 0x8F, 0x83, 0xC7, + 0xC1, 0xE3, 0xE1, 0xE1, 0xE0, 0xF0, 0xF0, 0x78, 0xF8, 0x78, 0x78, 0x3C, + 0x3C, 0x3E, 0x1E, 0x1F, 0x1E, 0x1F, 0x0F, 0x17, 0x97, 0x9B, 0xCB, 0xF9, + 0xF9, 0xF8, 0xF8, 0x78, 0x38, 0x00, 0x18, 0x37, 0xC3, 0xDE, 0x1E, 0x78, + 0x73, 0xC1, 0x9E, 0x08, 0xF0, 0xC7, 0x84, 0x3C, 0x41, 0xE4, 0x0F, 0x40, + 0x7C, 0x03, 0xC0, 0x1C, 0x00, 0xC0, 0x04, 0x00, 0x38, 0x10, 0xDF, 0x06, + 0x3D, 0xE0, 0xC7, 0xBC, 0x38, 0x73, 0xC7, 0x06, 0x79, 0xF0, 0x8F, 0x3E, + 0x11, 0xEB, 0xC4, 0x3F, 0x79, 0x07, 0xCF, 0x60, 0xF9, 0xE8, 0x1E, 0x3E, + 0x03, 0x87, 0x80, 0x70, 0xF0, 0x0C, 0x0C, 0x01, 0x01, 0x00, 0x03, 0x83, + 0x87, 0xF1, 0xF0, 0x3C, 0xF8, 0x0F, 0x60, 0x03, 0xD0, 0x00, 0xF8, 0x00, + 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1F, 0x00, 0x0F, + 0xC0, 0x02, 0xF1, 0x39, 0x3C, 0xCF, 0xCF, 0xE3, 0xE1, 0xF0, 0x70, 0x38, + 0x00, 0x01, 0x83, 0x07, 0xE3, 0xC1, 0xF1, 0xE0, 0x78, 0xF0, 0x3E, 0x18, + 0x1F, 0x08, 0x07, 0x84, 0x03, 0xC6, 0x01, 0xE2, 0x00, 0xFB, 0x00, 0x3D, + 0x00, 0x1F, 0x80, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xC0, 0x01, 0xE0, 0x00, + 0xE0, 0x00, 0x60, 0x00, 0x60, 0x0E, 0x60, 0x0F, 0xE0, 0x07, 0xE0, 0x01, + 0xC0, 0x00, 0x1F, 0xFC, 0x3F, 0xF8, 0x7F, 0xE1, 0x81, 0x82, 0x06, 0x00, + 0x08, 0x00, 0x20, 0x00, 0xC0, 0x03, 0x00, 0x0C, 0x00, 0x10, 0x00, 0x40, + 0x01, 0x80, 0x07, 0xC0, 0x1F, 0x86, 0x3F, 0x8E, 0xCF, 0x9C, 0x07, 0x30, + 0x03, 0xC0, 0x00, 0x1E, 0x00, 0xF8, 0x03, 0xC0, 0x0F, 0x00, 0x1E, 0x00, + 0x38, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x1E, 0x00, 0x3C, + 0x00, 0x78, 0x01, 0xE0, 0x03, 0xC0, 0x1F, 0x00, 0x7E, 0x00, 0x30, 0x00, + 0x60, 0x00, 0xE0, 0x01, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x38, + 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x0E, 0x00, 0x0C, 0x00, + 0x0F, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, + 0x00, 0xF0, 0x00, 0x70, 0x00, 0x70, 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, + 0x07, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xE0, 0x03, 0xC0, 0x07, + 0x80, 0x0F, 0x00, 0x1C, 0x00, 0x18, 0x00, 0x10, 0x00, 0xF0, 0x03, 0xF0, + 0x0F, 0x00, 0x1E, 0x00, 0x38, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, + 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x70, 0x01, 0xE0, 0x0F, 0x80, 0x7C, 0x00, + 0x3E, 0x00, 0x7F, 0xC6, 0xFF, 0xFF, 0x61, 0xFE, 0x00, 0x7C }; + +const GFXglyph FreeSerifBoldItalic18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 9, 0, 1 }, // 0x20 ' ' + { 0, 11, 25, 14, 2, -23 }, // 0x21 '!' + { 35, 14, 10, 19, 4, -23 }, // 0x22 '"' + { 53, 20, 25, 17, -1, -24 }, // 0x23 '#' + { 116, 17, 29, 18, 0, -25 }, // 0x24 '$' + { 178, 27, 25, 29, 1, -23 }, // 0x25 '%' + { 263, 25, 25, 27, 0, -23 }, // 0x26 '&' + { 342, 5, 10, 10, 4, -23 }, // 0x27 ''' + { 349, 11, 30, 12, 1, -23 }, // 0x28 '(' + { 391, 11, 30, 12, -2, -23 }, // 0x29 ')' + { 433, 13, 15, 18, 2, -23 }, // 0x2A '*' + { 458, 17, 17, 20, 1, -16 }, // 0x2B '+' + { 495, 7, 11, 9, -2, -4 }, // 0x2C ',' + { 505, 9, 4, 12, 0, -9 }, // 0x2D '-' + { 510, 6, 5, 9, 0, -3 }, // 0x2E '.' + { 514, 14, 25, 12, 0, -23 }, // 0x2F '/' + { 558, 15, 25, 18, 1, -23 }, // 0x30 '0' + { 605, 15, 25, 17, 0, -23 }, // 0x31 '1' + { 652, 16, 25, 18, 0, -23 }, // 0x32 '2' + { 702, 15, 25, 17, 1, -23 }, // 0x33 '3' + { 749, 18, 24, 17, 0, -23 }, // 0x34 '4' + { 803, 17, 25, 18, 0, -23 }, // 0x35 '5' + { 857, 17, 25, 18, 1, -23 }, // 0x36 '6' + { 911, 16, 24, 17, 3, -23 }, // 0x37 '7' + { 959, 17, 25, 18, 0, -23 }, // 0x38 '8' + { 1013, 17, 25, 18, 0, -23 }, // 0x39 '9' + { 1067, 10, 17, 9, 0, -15 }, // 0x3A ':' + { 1089, 11, 22, 9, -1, -15 }, // 0x3B ';' + { 1120, 18, 19, 20, 1, -18 }, // 0x3C '<' + { 1163, 18, 10, 20, 2, -13 }, // 0x3D '=' + { 1186, 18, 19, 20, 2, -18 }, // 0x3E '>' + { 1229, 13, 25, 17, 3, -23 }, // 0x3F '?' + { 1270, 25, 25, 29, 2, -23 }, // 0x40 '@' + { 1349, 23, 25, 24, 0, -23 }, // 0x41 'A' + { 1421, 24, 25, 22, 0, -23 }, // 0x42 'B' + { 1496, 23, 25, 22, 1, -23 }, // 0x43 'C' + { 1568, 26, 25, 25, 0, -23 }, // 0x44 'D' + { 1650, 23, 25, 22, 0, -23 }, // 0x45 'E' + { 1722, 23, 25, 21, 0, -23 }, // 0x46 'F' + { 1794, 24, 25, 25, 2, -23 }, // 0x47 'G' + { 1869, 29, 25, 26, 0, -23 }, // 0x48 'H' + { 1960, 15, 25, 13, 0, -23 }, // 0x49 'I' + { 2007, 20, 27, 17, 0, -23 }, // 0x4A 'J' + { 2075, 25, 25, 23, 0, -23 }, // 0x4B 'K' + { 2154, 22, 25, 21, 0, -23 }, // 0x4C 'L' + { 2223, 33, 25, 31, 0, -23 }, // 0x4D 'M' + { 2327, 27, 25, 25, 0, -23 }, // 0x4E 'N' + { 2412, 23, 25, 24, 1, -23 }, // 0x4F 'O' + { 2484, 23, 25, 21, 0, -23 }, // 0x50 'P' + { 2556, 23, 31, 24, 1, -23 }, // 0x51 'Q' + { 2646, 24, 25, 23, 0, -23 }, // 0x52 'R' + { 2721, 18, 25, 18, 0, -23 }, // 0x53 'S' + { 2778, 21, 25, 21, 3, -23 }, // 0x54 'T' + { 2844, 24, 25, 25, 4, -23 }, // 0x55 'U' + { 2919, 24, 25, 25, 4, -23 }, // 0x56 'V' + { 2994, 31, 25, 32, 4, -23 }, // 0x57 'W' + { 3091, 25, 25, 24, 0, -23 }, // 0x58 'X' + { 3170, 21, 25, 22, 4, -23 }, // 0x59 'Y' + { 3236, 21, 25, 20, 0, -23 }, // 0x5A 'Z' + { 3302, 14, 30, 12, -1, -23 }, // 0x5B '[' + { 3355, 10, 25, 14, 4, -23 }, // 0x5C '\' + { 3387, 14, 30, 12, -2, -23 }, // 0x5D ']' + { 3440, 16, 13, 20, 2, -23 }, // 0x5E '^' + { 3466, 18, 3, 17, 0, 3 }, // 0x5F '_' + { 3473, 7, 6, 12, 3, -23 }, // 0x60 '`' + { 3479, 18, 17, 18, 0, -15 }, // 0x61 'a' + { 3518, 16, 26, 17, 1, -24 }, // 0x62 'b' + { 3570, 13, 17, 15, 1, -15 }, // 0x63 'c' + { 3598, 19, 25, 18, 1, -23 }, // 0x64 'd' + { 3658, 13, 17, 15, 1, -15 }, // 0x65 'e' + { 3686, 21, 32, 17, -3, -24 }, // 0x66 'f' + { 3770, 19, 23, 17, -1, -15 }, // 0x67 'g' + { 3825, 17, 25, 19, 1, -23 }, // 0x68 'h' + { 3879, 9, 25, 10, 1, -23 }, // 0x69 'i' + { 3908, 16, 31, 12, -3, -23 }, // 0x6A 'j' + { 3970, 17, 25, 18, 1, -23 }, // 0x6B 'k' + { 4024, 11, 25, 10, 1, -23 }, // 0x6C 'l' + { 4059, 26, 17, 27, 0, -15 }, // 0x6D 'm' + { 4115, 18, 17, 18, 0, -15 }, // 0x6E 'n' + { 4154, 15, 17, 17, 1, -15 }, // 0x6F 'o' + { 4186, 19, 23, 17, -2, -15 }, // 0x70 'p' + { 4241, 16, 23, 17, 1, -15 }, // 0x71 'q' + { 4287, 15, 16, 14, 0, -15 }, // 0x72 'r' + { 4317, 13, 17, 12, 0, -15 }, // 0x73 's' + { 4345, 10, 22, 10, 1, -20 }, // 0x74 't' + { 4373, 17, 17, 19, 1, -15 }, // 0x75 'u' + { 4410, 13, 16, 15, 2, -15 }, // 0x76 'v' + { 4436, 19, 16, 23, 3, -15 }, // 0x77 'w' + { 4474, 18, 17, 17, -1, -15 }, // 0x78 'x' + { 4513, 17, 23, 15, -2, -15 }, // 0x79 'y' + { 4562, 15, 19, 14, 0, -15 }, // 0x7A 'z' + { 4598, 15, 32, 12, 0, -24 }, // 0x7B '{' + { 4658, 3, 25, 9, 4, -23 }, // 0x7C '|' + { 4668, 15, 32, 12, -5, -24 }, // 0x7D '}' + { 4728, 16, 5, 20, 2, -11 } }; // 0x7E '~' + +const GFXfont FreeSerifBoldItalic18pt7b PROGMEM = { + (uint8_t *)FreeSerifBoldItalic18pt7bBitmaps, + (GFXglyph *)FreeSerifBoldItalic18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 5410 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic24pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic24pt7b.h new file mode 100644 index 0000000..fcb857e --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic24pt7b.h @@ -0,0 +1,793 @@ +const uint8_t FreeSerifBoldItalic24pt7bBitmaps[] PROGMEM = { + 0x00, 0x3C, 0x00, 0xFC, 0x01, 0xF8, 0x07, 0xF0, 0x0F, 0xE0, 0x1F, 0xC0, + 0x3F, 0x00, 0x7E, 0x00, 0xF8, 0x01, 0xF0, 0x07, 0xC0, 0x0F, 0x80, 0x1E, + 0x00, 0x3C, 0x00, 0x70, 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x00, 0x0E, 0x00, + 0x18, 0x00, 0x30, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0xF0, 0x03, 0xF0, 0x0F, 0xF0, 0x1F, 0xE0, 0x3F, 0xC0, 0x3F, 0x00, + 0x3C, 0x00, 0x1C, 0x01, 0xC7, 0xC0, 0x7D, 0xF8, 0x1F, 0xBF, 0x03, 0xF7, + 0xC0, 0x7C, 0xF8, 0x0F, 0x9E, 0x01, 0xE3, 0xC0, 0x3C, 0x70, 0x07, 0x1E, + 0x00, 0xE3, 0x80, 0x38, 0x70, 0x07, 0x0C, 0x00, 0xC0, 0x00, 0x03, 0xC1, + 0xE0, 0x00, 0x70, 0x38, 0x00, 0x1E, 0x0F, 0x00, 0x03, 0xC1, 0xE0, 0x00, + 0x70, 0x38, 0x00, 0x1E, 0x0F, 0x00, 0x03, 0x81, 0xC0, 0x00, 0xF0, 0x78, + 0x00, 0x1E, 0x0F, 0x00, 0x07, 0x83, 0xC0, 0x1F, 0xFF, 0xFF, 0x83, 0xFF, + 0xFF, 0xF0, 0x7F, 0xFF, 0xFC, 0x00, 0xE0, 0x70, 0x00, 0x3C, 0x1E, 0x00, + 0x07, 0x83, 0xC0, 0x00, 0xE0, 0x70, 0x00, 0x3C, 0x1E, 0x00, 0x07, 0x83, + 0xC0, 0x00, 0xE0, 0x70, 0x07, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFC, 0x1F, + 0xFF, 0xFF, 0x00, 0x38, 0x1C, 0x00, 0x0F, 0x07, 0x80, 0x01, 0xE0, 0xF0, + 0x00, 0x38, 0x1C, 0x00, 0x0F, 0x07, 0x80, 0x01, 0xC0, 0xE0, 0x00, 0x78, + 0x3C, 0x00, 0x0F, 0x07, 0x80, 0x01, 0xC0, 0xE0, 0x00, 0x78, 0x3C, 0x00, + 0x00, 0x00, 0x00, 0xE0, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x1F, + 0xE0, 0x00, 0x7F, 0xF8, 0x01, 0xF1, 0x9E, 0x01, 0xC1, 0x8F, 0x03, 0x83, + 0x8F, 0x03, 0x83, 0x06, 0x07, 0x83, 0x06, 0x07, 0x87, 0x06, 0x07, 0xC7, + 0x04, 0x07, 0xE6, 0x04, 0x07, 0xFE, 0x00, 0x03, 0xFE, 0x00, 0x03, 0xFF, + 0x00, 0x01, 0xFF, 0x80, 0x00, 0xFF, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x1F, + 0xE0, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xF0, 0x00, 0x3B, 0xF8, 0x20, 0x31, + 0xF8, 0x20, 0x30, 0xF8, 0x60, 0x70, 0xF8, 0x60, 0x60, 0xF8, 0x60, 0x60, + 0xF8, 0xF0, 0xE0, 0xF0, 0xF0, 0xE1, 0xE0, 0x78, 0xC3, 0xE0, 0x3C, 0xC7, + 0xC0, 0x0F, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x01, 0x80, 0x00, 0x03, 0x80, + 0x00, 0x03, 0x80, 0x00, 0x03, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, 0xF0, + 0x00, 0x70, 0x00, 0xFF, 0x80, 0x1C, 0x00, 0x3F, 0x38, 0x1F, 0x00, 0x0F, + 0xC7, 0xFF, 0xE0, 0x03, 0xF0, 0x3F, 0xB8, 0x00, 0x7E, 0x04, 0x07, 0x00, + 0x1F, 0x80, 0x81, 0xC0, 0x03, 0xF0, 0x10, 0x38, 0x00, 0xFC, 0x02, 0x0E, + 0x00, 0x1F, 0x80, 0x81, 0x80, 0x03, 0xF0, 0x10, 0x70, 0x00, 0x7C, 0x06, + 0x1C, 0x00, 0x0F, 0x80, 0x83, 0x80, 0x01, 0xF0, 0x30, 0xE0, 0x00, 0x1E, + 0x0C, 0x1C, 0x07, 0xC3, 0xE3, 0x07, 0x03, 0xFC, 0x3F, 0xC0, 0xC0, 0xFC, + 0x43, 0xE0, 0x38, 0x3E, 0x0C, 0x00, 0x0E, 0x0F, 0xC0, 0x80, 0x01, 0xC3, + 0xF0, 0x10, 0x00, 0x70, 0xFC, 0x02, 0x00, 0x0C, 0x1F, 0x80, 0x40, 0x03, + 0x83, 0xE0, 0x08, 0x00, 0x60, 0xFC, 0x02, 0x00, 0x1C, 0x1F, 0x80, 0x40, + 0x07, 0x03, 0xE0, 0x10, 0x00, 0xE0, 0x7C, 0x02, 0x00, 0x38, 0x0F, 0x80, + 0xC0, 0x06, 0x01, 0xF0, 0x30, 0x01, 0xC0, 0x1F, 0x0C, 0x00, 0x30, 0x01, + 0xFF, 0x00, 0x0E, 0x00, 0x1F, 0x80, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x00, + 0xFF, 0x80, 0x00, 0x01, 0xF1, 0xE0, 0x00, 0x00, 0xF0, 0x78, 0x00, 0x00, + 0xF0, 0x3C, 0x00, 0x00, 0x78, 0x1E, 0x00, 0x00, 0x7C, 0x0F, 0x00, 0x00, + 0x3E, 0x0F, 0x80, 0x00, 0x1F, 0x07, 0x80, 0x00, 0x0F, 0x87, 0x80, 0x00, + 0x07, 0xC7, 0x80, 0x00, 0x03, 0xFF, 0x00, 0x00, 0x01, 0xFE, 0x00, 0x00, + 0x00, 0xFC, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x01, 0xFF, 0x07, 0xFE, + 0x03, 0xCF, 0xC0, 0xFE, 0x03, 0xC7, 0xE0, 0x3C, 0x07, 0xC3, 0xF0, 0x1C, + 0x07, 0xC0, 0xFC, 0x0C, 0x03, 0xC0, 0x7E, 0x0E, 0x03, 0xE0, 0x3F, 0x0E, + 0x01, 0xF0, 0x1F, 0xC6, 0x01, 0xF8, 0x07, 0xF6, 0x00, 0xFC, 0x03, 0xFF, + 0x00, 0x7E, 0x00, 0xFF, 0x00, 0x3F, 0x80, 0x7F, 0x80, 0x1F, 0xC0, 0x1F, + 0xC0, 0x07, 0xF0, 0x0F, 0xF0, 0x13, 0xFE, 0x0F, 0xFE, 0x18, 0xFF, 0xFE, + 0xFF, 0xF8, 0x3F, 0xFE, 0x3F, 0xF8, 0x07, 0xF8, 0x03, 0xF0, 0x00, 0x1C, + 0x7D, 0xFB, 0xF7, 0xCF, 0x9E, 0x3C, 0x71, 0xE3, 0x87, 0x0C, 0x00, 0x00, + 0x04, 0x00, 0x70, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x3C, 0x01, + 0xE0, 0x0F, 0x00, 0x3C, 0x01, 0xE0, 0x0F, 0x80, 0x3C, 0x00, 0xF0, 0x07, + 0xC0, 0x1E, 0x00, 0x78, 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0xF0, 0x03, + 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x3C, 0x00, + 0x70, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, 0x30, 0x00, 0xE0, 0x01, 0x80, + 0x06, 0x00, 0x0C, 0x00, 0x30, 0x00, 0x60, 0x01, 0x80, 0x00, 0x00, 0x01, + 0x00, 0x06, 0x00, 0x08, 0x00, 0x30, 0x00, 0x40, 0x01, 0x80, 0x06, 0x00, + 0x1C, 0x00, 0x30, 0x00, 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x38, 0x00, 0xF0, + 0x03, 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x7C, + 0x01, 0xF0, 0x07, 0xC0, 0x1E, 0x00, 0x78, 0x03, 0xE0, 0x0F, 0x80, 0x3C, + 0x01, 0xF0, 0x07, 0x80, 0x1E, 0x00, 0xF0, 0x03, 0x80, 0x1E, 0x00, 0xF0, + 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x06, 0x00, 0x30, 0x00, 0x80, 0x00, 0x00, + 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x07, 0x0E, 0x1D, 0xF1, + 0xC7, 0xFF, 0x11, 0xFF, 0xE2, 0x3F, 0x7E, 0x4F, 0xC0, 0x3E, 0x00, 0x07, + 0xC0, 0x3F, 0x27, 0xEF, 0xC4, 0x7F, 0xF8, 0x8F, 0xFE, 0x38, 0xFB, 0x87, + 0x0E, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0x70, 0x00, 0x00, + 0x78, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x78, + 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x03, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x01, + 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, + 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, + 0x07, 0x80, 0x00, 0x0F, 0x07, 0xE1, 0xFC, 0x7F, 0x1F, 0xC3, 0xF0, 0x7C, + 0x0E, 0x03, 0x80, 0xC0, 0x60, 0x30, 0x18, 0x1C, 0x04, 0x00, 0x7F, 0xF7, + 0xFF, 0x7F, 0xEF, 0xFE, 0xFF, 0xE0, 0x3C, 0x7E, 0xFF, 0xFF, 0xFF, 0x7E, + 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, + 0x78, 0x00, 0x1E, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x07, + 0xC0, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x3C, + 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x01, 0xE0, + 0x00, 0x7C, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x0F, 0x00, + 0x03, 0xC0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x03, 0xC0, 0x00, 0xF8, 0x00, + 0x1E, 0x00, 0x07, 0xC0, 0x00, 0xF0, 0x00, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0xE3, 0x80, 0x0F, 0x07, 0x00, 0x7C, 0x1C, 0x03, 0xE0, 0x78, 0x0F, 0x81, + 0xE0, 0x7C, 0x07, 0x83, 0xF0, 0x1F, 0x0F, 0xC0, 0xFC, 0x7E, 0x03, 0xF1, + 0xF8, 0x0F, 0xCF, 0xE0, 0x3F, 0x3F, 0x00, 0xFD, 0xFC, 0x07, 0xF7, 0xF0, + 0x1F, 0xDF, 0xC0, 0x7F, 0x7E, 0x01, 0xFB, 0xF8, 0x0F, 0xEF, 0xE0, 0x3F, + 0xBF, 0x80, 0xFE, 0xFC, 0x03, 0xF3, 0xF0, 0x1F, 0xCF, 0xC0, 0x7F, 0x3F, + 0x01, 0xF8, 0xFC, 0x07, 0xE3, 0xE0, 0x3F, 0x0F, 0x80, 0xFC, 0x1E, 0x07, + 0xE0, 0x78, 0x1F, 0x00, 0xE0, 0x78, 0x03, 0x83, 0xC0, 0x07, 0x1E, 0x00, + 0x07, 0xE0, 0x00, 0x00, 0x00, 0x70, 0x01, 0xFE, 0x01, 0xFF, 0xE0, 0x00, + 0xFE, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, 0x01, 0xFC, 0x00, + 0x1F, 0x80, 0x01, 0xF8, 0x00, 0x3F, 0x80, 0x03, 0xF8, 0x00, 0x3F, 0x00, + 0x03, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x07, 0xE0, + 0x00, 0xFE, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x1F, 0xC0, 0x01, 0xFC, + 0x00, 0x1F, 0x80, 0x01, 0xF8, 0x00, 0x3F, 0x80, 0x03, 0xF0, 0x00, 0x3F, + 0x00, 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x1F, 0xF8, 0x0F, 0xFF, 0xF0, 0x00, + 0x0F, 0x80, 0x01, 0xFF, 0x80, 0x0F, 0xFF, 0x00, 0x7F, 0xFE, 0x03, 0x83, + 0xF8, 0x0C, 0x07, 0xF0, 0x60, 0x1F, 0xC3, 0x00, 0x3F, 0x00, 0x00, 0xFC, + 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF8, 0x00, + 0x07, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x1E, + 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, + 0x0E, 0x00, 0x00, 0x70, 0x06, 0x03, 0x80, 0x10, 0x1C, 0x00, 0xC0, 0xE0, + 0x06, 0x07, 0xFF, 0xF8, 0x3F, 0xFF, 0xE1, 0xFF, 0xFF, 0x0F, 0xFF, 0xFC, + 0x3F, 0xFF, 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0xFF, 0xC0, 0x0F, 0xFF, 0x80, + 0x60, 0xFE, 0x03, 0x01, 0xFC, 0x08, 0x03, 0xF0, 0x00, 0x0F, 0xC0, 0x00, + 0x3F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0xFC, + 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x07, 0xF8, 0x00, 0x7F, 0xF0, 0x00, + 0x7F, 0xE0, 0x00, 0x3F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x03, + 0xF0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xE0, + 0x00, 0x0F, 0x80, 0x00, 0x3C, 0x1C, 0x01, 0xF0, 0xF8, 0x07, 0x83, 0xF0, + 0x3C, 0x0F, 0xE1, 0xE0, 0x1F, 0xFE, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x00, + 0x07, 0x00, 0x00, 0x07, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x07, 0xE0, 0x00, + 0x07, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x07, 0xFC, 0x00, + 0x06, 0xFC, 0x00, 0x06, 0x7E, 0x00, 0x06, 0x3F, 0x00, 0x06, 0x3F, 0x00, + 0x06, 0x1F, 0x80, 0x06, 0x0F, 0xC0, 0x06, 0x07, 0xE0, 0x03, 0x07, 0xE0, + 0x03, 0x03, 0xF0, 0x03, 0x01, 0xF8, 0x03, 0x01, 0xFC, 0x03, 0x00, 0xFC, + 0x03, 0x00, 0x7E, 0x03, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, + 0xF0, 0xFF, 0xFF, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x07, 0xE0, 0x00, 0x03, + 0xF0, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, + 0x7F, 0xFC, 0x00, 0xFF, 0xFC, 0x00, 0xC0, 0x00, 0x01, 0x80, 0x00, 0x01, + 0x80, 0x00, 0x03, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x07, 0xFE, 0x00, 0x07, + 0xFF, 0x00, 0x07, 0xFF, 0x80, 0x0F, 0xFF, 0xC0, 0x00, 0xFF, 0xE0, 0x00, + 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF0, 0x00, + 0x03, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, + 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x78, 0x03, 0xC0, 0xFC, + 0x07, 0x80, 0xFC, 0x0F, 0x00, 0xFE, 0x1E, 0x00, 0x7F, 0xF8, 0x00, 0x1F, + 0xC0, 0x00, 0x00, 0x00, 0x0E, 0x00, 0x01, 0xF8, 0x00, 0x0F, 0x80, 0x00, + 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x01, 0xFC, + 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFE, 0x00, + 0x01, 0xFF, 0xF0, 0x07, 0xFF, 0xF0, 0x0F, 0xE1, 0xF0, 0x3F, 0x81, 0xF0, + 0x7F, 0x03, 0xF0, 0xFC, 0x07, 0xE3, 0xF8, 0x0F, 0xC7, 0xF0, 0x1F, 0x8F, + 0xC0, 0x7F, 0x1F, 0x80, 0xFE, 0x3F, 0x01, 0xFC, 0x7C, 0x03, 0xF0, 0xF8, + 0x0F, 0xE1, 0xF0, 0x1F, 0xC1, 0xE0, 0x3F, 0x03, 0xC0, 0xFC, 0x07, 0x81, + 0xF0, 0x07, 0x87, 0xC0, 0x07, 0xFF, 0x00, 0x03, 0xF8, 0x00, 0x0F, 0xFF, + 0xFC, 0x1F, 0xFF, 0xF8, 0x3F, 0xFF, 0xE0, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, + 0x07, 0x00, 0x1C, 0x08, 0x00, 0x78, 0x30, 0x01, 0xE0, 0x40, 0x03, 0xC0, + 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, + 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, + 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x78, + 0x00, 0x01, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0x78, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x80, 0x00, + 0x1E, 0x00, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x03, 0xFE, 0x00, 0x3C, 0x78, + 0x03, 0xC1, 0xE0, 0x3C, 0x07, 0x81, 0xE0, 0x3C, 0x1F, 0x01, 0xE0, 0xF8, + 0x0F, 0x07, 0xC0, 0x78, 0x3F, 0x03, 0xC1, 0xF8, 0x3C, 0x0F, 0xE1, 0xE0, + 0x3F, 0x9E, 0x01, 0xFF, 0xC0, 0x07, 0xFC, 0x00, 0x3F, 0xC0, 0x00, 0xFF, + 0x00, 0x1F, 0xFC, 0x03, 0xCF, 0xF0, 0x3C, 0x3F, 0x83, 0xC0, 0xFC, 0x3C, + 0x03, 0xF1, 0xE0, 0x1F, 0x9E, 0x00, 0x7C, 0xF0, 0x03, 0xE7, 0x80, 0x1F, + 0x3C, 0x00, 0xF9, 0xE0, 0x07, 0x87, 0x00, 0x3C, 0x3C, 0x03, 0xC0, 0xF0, + 0x3C, 0x03, 0xC3, 0xC0, 0x07, 0xF0, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0xFF, + 0xE0, 0x03, 0xF1, 0xE0, 0x0F, 0xC1, 0xC0, 0x3F, 0x03, 0xC0, 0xFE, 0x07, + 0x81, 0xF8, 0x0F, 0x87, 0xF0, 0x1F, 0x0F, 0xC0, 0x3E, 0x3F, 0x80, 0xFC, + 0x7F, 0x01, 0xF8, 0xFC, 0x03, 0xF1, 0xF8, 0x07, 0xE3, 0xF0, 0x1F, 0xC7, + 0xE0, 0x3F, 0x8F, 0xC0, 0x7E, 0x0F, 0x81, 0xFC, 0x1F, 0x03, 0xF8, 0x1F, + 0x0F, 0xE0, 0x1F, 0xFF, 0xC0, 0x1F, 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x03, + 0xF8, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x7E, 0x00, 0x01, 0xF8, + 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, + 0x1F, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x01, 0xE0, 0x1F, 0x81, 0xFE, 0x0F, + 0xF0, 0x7F, 0x81, 0xF8, 0x07, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x80, 0x7E, 0x07, 0xF8, 0x3F, + 0xC1, 0xFE, 0x07, 0xE0, 0x1E, 0x00, 0x00, 0x78, 0x01, 0xF8, 0x07, 0xF8, + 0x0F, 0xF0, 0x1F, 0xE0, 0x1F, 0x80, 0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x80, + 0x1F, 0x80, 0x3F, 0x80, 0x7F, 0x00, 0xFE, 0x00, 0xFC, 0x00, 0xF8, 0x00, + 0xE0, 0x01, 0xC0, 0x07, 0x00, 0x0C, 0x00, 0x30, 0x01, 0xC0, 0x0E, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x07, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x7F, 0x00, 0x03, 0xFF, 0x00, 0x0F, 0xFC, 0x00, 0x3F, 0xF0, + 0x01, 0xFF, 0xC0, 0x07, 0xFE, 0x00, 0x1F, 0xF8, 0x00, 0x7F, 0xE0, 0x00, + 0xFF, 0x80, 0x00, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0xFF, 0xE0, 0x00, + 0x1F, 0xF8, 0x00, 0x07, 0xFE, 0x00, 0x01, 0xFF, 0xC0, 0x00, 0x3F, 0xF0, + 0x00, 0x0F, 0xFC, 0x00, 0x03, 0xFF, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x07, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0x80, 0x00, 0x00, 0xE0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFF, 0x00, 0x00, + 0xFF, 0xC0, 0x00, 0x3F, 0xF0, 0x00, 0x0F, 0xFC, 0x00, 0x03, 0xFF, 0x80, + 0x00, 0x7F, 0xE0, 0x00, 0x1F, 0xF8, 0x00, 0x07, 0xFF, 0x00, 0x00, 0xFF, + 0x00, 0x00, 0x3F, 0x00, 0x00, 0xFF, 0x00, 0x03, 0xFF, 0x00, 0x1F, 0xFC, + 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0x80, 0x0F, 0xFE, 0x00, 0x3F, 0xF0, 0x00, + 0xFF, 0xC0, 0x00, 0xFF, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xE0, 0x00, 0x00, + 0x80, 0x00, 0x00, 0x01, 0xF8, 0x01, 0xFF, 0x80, 0xF1, 0xF0, 0x38, 0x3E, + 0x1E, 0x0F, 0xC7, 0xC3, 0xF1, 0xF0, 0xFC, 0x7C, 0x3F, 0x0E, 0x0F, 0xC0, + 0x07, 0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0x3F, 0x00, 0x1F, 0x00, 0x07, + 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x0C, 0x00, + 0x06, 0x00, 0x01, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x03, 0xC0, 0x01, 0xF8, 0x00, 0xFF, 0x00, 0x3F, 0xC0, 0x0F, 0xF0, + 0x01, 0xF8, 0x00, 0x3C, 0x00, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x1F, + 0xFF, 0xC0, 0x00, 0x3F, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x7C, + 0x00, 0x03, 0x80, 0x7C, 0x00, 0x00, 0xE0, 0x7C, 0x00, 0x00, 0x38, 0x3C, + 0x00, 0xF0, 0x4C, 0x3E, 0x00, 0xFD, 0xE7, 0x1E, 0x00, 0xF3, 0xF1, 0x9F, + 0x00, 0xF1, 0xF0, 0xEF, 0x80, 0xF0, 0x78, 0x3F, 0x80, 0xF0, 0x3C, 0x1F, + 0xC0, 0x78, 0x1E, 0x0F, 0xE0, 0x78, 0x1E, 0x07, 0xF0, 0x3C, 0x0F, 0x03, + 0xF8, 0x3E, 0x07, 0x81, 0xFC, 0x1E, 0x07, 0x81, 0xFE, 0x0F, 0x03, 0xC0, + 0xDF, 0x07, 0x83, 0xC0, 0x6F, 0x83, 0xC3, 0xE0, 0x63, 0xE1, 0xF3, 0xF0, + 0x71, 0xF0, 0x7E, 0x78, 0x70, 0xF8, 0x1E, 0x3F, 0xF0, 0x3E, 0x00, 0x07, + 0xE0, 0x0F, 0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x01, 0xF0, 0x00, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x03, 0x80, 0x03, 0xF0, + 0x07, 0xC0, 0x00, 0x7F, 0xFF, 0x80, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x00, + 0x00, 0x06, 0x00, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, + 0x1F, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x03, + 0x7E, 0x00, 0x00, 0x06, 0xFC, 0x00, 0x00, 0x19, 0xF8, 0x00, 0x00, 0x63, + 0xF8, 0x00, 0x00, 0xC7, 0xF0, 0x00, 0x03, 0x07, 0xE0, 0x00, 0x06, 0x0F, + 0xC0, 0x00, 0x18, 0x1F, 0x80, 0x00, 0x60, 0x3F, 0x00, 0x00, 0xC0, 0x7F, + 0x00, 0x03, 0x00, 0xFE, 0x00, 0x0F, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0xF8, + 0x00, 0x60, 0x03, 0xF0, 0x00, 0xC0, 0x07, 0xE0, 0x03, 0x00, 0x0F, 0xE0, + 0x0E, 0x00, 0x1F, 0xC0, 0x18, 0x00, 0x3F, 0x80, 0x70, 0x00, 0x7F, 0x01, + 0xC0, 0x00, 0xFE, 0x03, 0x80, 0x01, 0xFE, 0x1F, 0x80, 0x07, 0xFE, 0x7F, + 0xC0, 0x3F, 0xFF, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0xFF, 0xFF, 0xE0, 0x00, + 0xFE, 0x1F, 0xE0, 0x01, 0xFC, 0x1F, 0xE0, 0x03, 0xF8, 0x1F, 0xE0, 0x0F, + 0xE0, 0x3F, 0xC0, 0x1F, 0xC0, 0x7F, 0x80, 0x3F, 0x80, 0xFF, 0x00, 0x7F, + 0x01, 0xFE, 0x01, 0xFC, 0x03, 0xF8, 0x03, 0xF8, 0x0F, 0xF0, 0x07, 0xF0, + 0x1F, 0xC0, 0x0F, 0xC0, 0x7F, 0x00, 0x3F, 0x87, 0xF0, 0x00, 0x7F, 0xFF, + 0x00, 0x00, 0xFE, 0x1F, 0xC0, 0x03, 0xF8, 0x0F, 0xE0, 0x07, 0xF0, 0x0F, + 0xE0, 0x0F, 0xE0, 0x1F, 0xC0, 0x1F, 0xC0, 0x3F, 0xC0, 0x7F, 0x00, 0x7F, + 0x80, 0xFE, 0x00, 0xFF, 0x01, 0xFC, 0x01, 0xFE, 0x03, 0xF0, 0x07, 0xFC, + 0x0F, 0xE0, 0x0F, 0xF0, 0x1F, 0xC0, 0x3F, 0xE0, 0x3F, 0x80, 0x7F, 0x80, + 0xFE, 0x01, 0xFE, 0x01, 0xFE, 0x0F, 0xF8, 0x07, 0xFF, 0xFF, 0xC0, 0x3F, + 0xFF, 0xFC, 0x00, 0x00, 0x00, 0x01, 0xFE, 0x08, 0x00, 0x7F, 0xFE, 0xC0, + 0x0F, 0xF0, 0x7E, 0x00, 0xFE, 0x01, 0xF0, 0x1F, 0xE0, 0x07, 0x01, 0xFE, + 0x00, 0x38, 0x1F, 0xE0, 0x00, 0xC0, 0xFE, 0x00, 0x06, 0x0F, 0xF0, 0x00, + 0x30, 0xFF, 0x00, 0x01, 0x07, 0xF8, 0x00, 0x08, 0x7F, 0x80, 0x00, 0x03, + 0xFC, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0xFF, 0x80, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, + 0x01, 0xFE, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x03, + 0xFC, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x03, 0xF8, + 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x60, 0x7F, 0x00, 0x06, 0x03, 0xFC, 0x00, + 0x70, 0x0F, 0xE0, 0x07, 0x00, 0x1F, 0xC0, 0xE0, 0x00, 0x7F, 0xFE, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x3F, 0xFF, 0xFE, + 0x00, 0x00, 0xFE, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x3F, 0x00, 0x03, 0xF8, + 0x07, 0xF0, 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x1F, 0xC0, 0x07, 0xF0, 0x03, + 0xF8, 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x1F, 0xC0, 0x1F, 0xC0, 0x03, 0xFC, + 0x03, 0xF8, 0x00, 0x7F, 0x80, 0x7F, 0x00, 0x0F, 0xF0, 0x0F, 0xC0, 0x01, + 0xFE, 0x03, 0xF8, 0x00, 0x3F, 0xC0, 0x7F, 0x00, 0x07, 0xF8, 0x0F, 0xE0, + 0x01, 0xFF, 0x03, 0xF8, 0x00, 0x3F, 0xE0, 0x7F, 0x00, 0x07, 0xF8, 0x0F, + 0xE0, 0x00, 0xFF, 0x01, 0xFC, 0x00, 0x3F, 0xE0, 0x7F, 0x00, 0x07, 0xF8, + 0x0F, 0xE0, 0x01, 0xFF, 0x01, 0xFC, 0x00, 0x3F, 0xC0, 0x3F, 0x00, 0x0F, + 0xF0, 0x0F, 0xE0, 0x01, 0xFC, 0x01, 0xFC, 0x00, 0x7F, 0x00, 0x3F, 0x80, + 0x1F, 0xC0, 0x0F, 0xE0, 0x0F, 0xF0, 0x01, 0xFE, 0x07, 0xF8, 0x00, 0x7F, + 0xFF, 0xFC, 0x00, 0x3F, 0xFF, 0xF8, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0xFF, + 0x00, 0x7F, 0xFF, 0xFF, 0x00, 0x3F, 0xC0, 0x7E, 0x00, 0x3F, 0x80, 0x1E, + 0x00, 0x3F, 0x80, 0x0E, 0x00, 0x7F, 0x00, 0x06, 0x00, 0x7F, 0x00, 0x04, + 0x00, 0x7F, 0x00, 0x04, 0x00, 0x7F, 0x00, 0x00, 0x00, 0xFE, 0x01, 0x80, + 0x00, 0xFE, 0x01, 0x00, 0x00, 0xFE, 0x03, 0x00, 0x00, 0xFC, 0x0F, 0x00, + 0x01, 0xFF, 0xFF, 0x00, 0x01, 0xFF, 0xFE, 0x00, 0x01, 0xFC, 0x3E, 0x00, + 0x03, 0xF8, 0x1E, 0x00, 0x03, 0xF8, 0x0C, 0x00, 0x03, 0xF8, 0x0C, 0x00, + 0x03, 0xF8, 0x0C, 0x00, 0x07, 0xF0, 0x08, 0x00, 0x07, 0xF0, 0x00, 0x08, + 0x07, 0xF0, 0x00, 0x18, 0x07, 0xE0, 0x00, 0x30, 0x0F, 0xE0, 0x00, 0x30, + 0x0F, 0xE0, 0x00, 0x70, 0x0F, 0xE0, 0x01, 0xE0, 0x1F, 0xC0, 0x07, 0xE0, + 0x1F, 0xE0, 0x3F, 0xE0, 0x3F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFF, 0xC0, + 0x01, 0xFF, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0xFF, 0x03, 0xF0, + 0x01, 0xFC, 0x01, 0xE0, 0x03, 0xF8, 0x01, 0xC0, 0x0F, 0xE0, 0x01, 0x80, + 0x1F, 0xC0, 0x02, 0x00, 0x3F, 0x80, 0x04, 0x00, 0x7F, 0x00, 0x00, 0x01, + 0xFC, 0x03, 0x00, 0x03, 0xF8, 0x04, 0x00, 0x07, 0xF0, 0x18, 0x00, 0x0F, + 0xC0, 0xF0, 0x00, 0x3F, 0xFF, 0xE0, 0x00, 0x7F, 0xFF, 0x80, 0x00, 0xFE, + 0x1F, 0x00, 0x03, 0xF8, 0x1E, 0x00, 0x07, 0xF0, 0x18, 0x00, 0x0F, 0xE0, + 0x30, 0x00, 0x1F, 0xC0, 0x60, 0x00, 0x7F, 0x00, 0x80, 0x00, 0xFE, 0x01, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x0F, 0xE0, 0x00, + 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0xFF, 0x00, 0x00, + 0x01, 0xFE, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x3F, 0xFF, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xFF, 0x02, 0x00, 0x0F, 0xFF, 0xEE, 0x00, 0x3F, 0xC0, + 0xFC, 0x00, 0x7F, 0x00, 0x7C, 0x01, 0xFE, 0x00, 0x3C, 0x03, 0xFC, 0x00, + 0x38, 0x07, 0xF8, 0x00, 0x18, 0x07, 0xF0, 0x00, 0x18, 0x0F, 0xF0, 0x00, + 0x10, 0x1F, 0xE0, 0x00, 0x10, 0x1F, 0xE0, 0x00, 0x00, 0x3F, 0xC0, 0x00, + 0x00, 0x3F, 0xC0, 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x00, 0x7F, 0x80, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x00, 0xFF, 0x80, 0x1F, + 0xFF, 0xFF, 0x00, 0x07, 0xFC, 0xFF, 0x00, 0x03, 0xF8, 0xFF, 0x00, 0x03, + 0xF8, 0xFF, 0x00, 0x03, 0xF0, 0xFF, 0x00, 0x03, 0xF0, 0xFF, 0x00, 0x07, + 0xF0, 0x7F, 0x00, 0x07, 0xF0, 0x7F, 0x00, 0x07, 0xE0, 0x7F, 0x80, 0x07, + 0xE0, 0x3F, 0x80, 0x0F, 0xE0, 0x1F, 0xC0, 0x0F, 0xC0, 0x0F, 0xE0, 0x0F, + 0xC0, 0x07, 0xF0, 0x3F, 0x80, 0x01, 0xFF, 0xFE, 0x00, 0x00, 0x3F, 0xE0, + 0x00, 0x01, 0xFF, 0xFC, 0x7F, 0xFE, 0x00, 0xFF, 0xC0, 0x3F, 0xF0, 0x00, + 0xFE, 0x00, 0x3F, 0xC0, 0x01, 0xFC, 0x00, 0x7F, 0x00, 0x03, 0xF8, 0x00, + 0xFE, 0x00, 0x0F, 0xE0, 0x01, 0xFC, 0x00, 0x1F, 0xC0, 0x07, 0xF0, 0x00, + 0x3F, 0x80, 0x0F, 0xE0, 0x00, 0x7F, 0x00, 0x1F, 0xC0, 0x01, 0xFC, 0x00, + 0x7F, 0x00, 0x03, 0xF8, 0x00, 0xFE, 0x00, 0x07, 0xF0, 0x01, 0xFC, 0x00, + 0x0F, 0xC0, 0x03, 0xF8, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x00, 0x7F, 0xFF, + 0xFF, 0xC0, 0x00, 0xFF, 0xFF, 0xFF, 0x80, 0x03, 0xF8, 0x00, 0x7F, 0x00, + 0x07, 0xF0, 0x01, 0xFC, 0x00, 0x0F, 0xE0, 0x03, 0xF8, 0x00, 0x1F, 0xC0, + 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x1F, 0xC0, 0x00, 0xFE, 0x00, 0x3F, 0x80, + 0x01, 0xFC, 0x00, 0x7F, 0x00, 0x03, 0xF0, 0x00, 0xFE, 0x00, 0x0F, 0xE0, + 0x03, 0xF8, 0x00, 0x1F, 0xC0, 0x07, 0xF0, 0x00, 0x3F, 0x80, 0x0F, 0xE0, + 0x00, 0xFF, 0x00, 0x3F, 0xC0, 0x01, 0xFE, 0x00, 0x7F, 0x80, 0x07, 0xFC, + 0x01, 0xFF, 0x00, 0x3F, 0xFF, 0x1F, 0xFF, 0xC0, 0x00, 0x01, 0xFF, 0xF8, + 0x03, 0xFE, 0x00, 0x0F, 0xE0, 0x00, 0x7F, 0x00, 0x03, 0xF8, 0x00, 0x3F, + 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xE0, 0x00, 0x7E, 0x00, 0x07, 0xF0, 0x00, + 0x3F, 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0xFE, 0x00, 0x07, 0xF0, + 0x00, 0x3F, 0x80, 0x03, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0xFE, 0x00, 0x07, + 0xE0, 0x00, 0x7F, 0x00, 0x03, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0xFC, 0x00, + 0x0F, 0xE0, 0x00, 0x7F, 0x00, 0x03, 0xF8, 0x00, 0x3F, 0xC0, 0x01, 0xFC, + 0x00, 0x1F, 0xF0, 0x03, 0xFF, 0xF0, 0x00, 0x00, 0x07, 0xFF, 0xE0, 0x00, + 0x3F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x0F, 0xE0, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x0F, 0xE0, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, + 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, + 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xF0, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x07, 0x03, 0xF0, 0x01, 0xF0, 0xFE, 0x00, + 0x3E, 0x1F, 0xC0, 0x07, 0xC3, 0xF0, 0x00, 0xF8, 0xFC, 0x00, 0x0F, 0x3F, + 0x80, 0x00, 0xFF, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x01, 0xFF, 0xF8, + 0xFF, 0xC0, 0x1F, 0xF8, 0x0F, 0xC0, 0x03, 0xF8, 0x01, 0xC0, 0x00, 0xFE, + 0x00, 0xE0, 0x00, 0x3F, 0x80, 0x70, 0x00, 0x1F, 0xC0, 0x38, 0x00, 0x07, + 0xF0, 0x1C, 0x00, 0x01, 0xFC, 0x0E, 0x00, 0x00, 0x7F, 0x07, 0x00, 0x00, + 0x3F, 0x83, 0x80, 0x00, 0x0F, 0xE1, 0xC0, 0x00, 0x03, 0xF8, 0xE0, 0x00, + 0x00, 0xFC, 0x60, 0x00, 0x00, 0x7F, 0x7C, 0x00, 0x00, 0x1F, 0xFF, 0x00, + 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x03, 0xFB, 0xF8, 0x00, 0x00, 0xFE, 0x7F, + 0x00, 0x00, 0x3F, 0x9F, 0xC0, 0x00, 0x0F, 0xE3, 0xF8, 0x00, 0x07, 0xF0, + 0xFE, 0x00, 0x01, 0xFC, 0x1F, 0xC0, 0x00, 0x7F, 0x07, 0xF0, 0x00, 0x1F, + 0x80, 0xFE, 0x00, 0x0F, 0xE0, 0x3F, 0x80, 0x03, 0xF8, 0x0F, 0xE0, 0x00, + 0xFE, 0x01, 0xFC, 0x00, 0x7F, 0x00, 0x7F, 0x00, 0x1F, 0xE0, 0x0F, 0xE0, + 0x0F, 0xF8, 0x07, 0xFC, 0x0F, 0xFF, 0xC7, 0xFF, 0xC0, 0x01, 0xFF, 0xF8, + 0x00, 0x03, 0xFF, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x0F, + 0xE0, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x3F, 0x80, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0x07, 0xF0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x7F, 0x00, + 0x00, 0x03, 0xF8, 0x00, 0x04, 0x1F, 0xC0, 0x00, 0x60, 0xFC, 0x00, 0x06, + 0x0F, 0xE0, 0x00, 0x30, 0x7F, 0x00, 0x03, 0x83, 0xF8, 0x00, 0x7C, 0x3F, + 0x80, 0x0F, 0xC1, 0xFE, 0x03, 0xFE, 0x1F, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, + 0xFF, 0x00, 0x01, 0xFF, 0xC0, 0x00, 0x3F, 0xF0, 0x03, 0xFC, 0x00, 0x03, + 0xFC, 0x00, 0x3F, 0xC0, 0x00, 0x7F, 0x80, 0x03, 0xFC, 0x00, 0x0F, 0xF8, + 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x80, 0x03, 0xFC, 0x00, 0x1F, 0xF0, 0x00, + 0x6F, 0xC0, 0x03, 0xFF, 0x00, 0x06, 0xFC, 0x00, 0x37, 0xF0, 0x00, 0x6F, + 0xE0, 0x06, 0x7E, 0x00, 0x04, 0xFE, 0x00, 0xEF, 0xE0, 0x00, 0xCF, 0xE0, + 0x0C, 0xFE, 0x00, 0x0C, 0xFE, 0x01, 0x8F, 0xE0, 0x00, 0xCF, 0xE0, 0x38, + 0xFC, 0x00, 0x18, 0x7E, 0x03, 0x1F, 0xC0, 0x01, 0x87, 0xE0, 0x61, 0xFC, + 0x00, 0x18, 0x7E, 0x0E, 0x1F, 0xC0, 0x01, 0x87, 0xE0, 0xC3, 0xF8, 0x00, + 0x30, 0x7F, 0x18, 0x3F, 0x80, 0x03, 0x07, 0xF3, 0x83, 0xF8, 0x00, 0x30, + 0x7F, 0x30, 0x3F, 0x00, 0x06, 0x07, 0xF7, 0x07, 0xF0, 0x00, 0x60, 0x3F, + 0xE0, 0x7F, 0x00, 0x06, 0x03, 0xFC, 0x07, 0xF0, 0x00, 0xE0, 0x3F, 0xC0, + 0x7E, 0x00, 0x0C, 0x03, 0xF8, 0x0F, 0xE0, 0x00, 0xC0, 0x3F, 0x00, 0xFE, + 0x00, 0x0C, 0x03, 0xF0, 0x0F, 0xE0, 0x01, 0xC0, 0x3E, 0x01, 0xFC, 0x00, + 0x1C, 0x03, 0xC0, 0x1F, 0xC0, 0x07, 0xE0, 0x3C, 0x03, 0xFE, 0x00, 0xFF, + 0xC1, 0x81, 0xFF, 0xFC, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x03, 0xFF, + 0x00, 0x1F, 0xF8, 0x03, 0xF8, 0x00, 0x3F, 0x00, 0x0F, 0xE0, 0x00, 0xF0, + 0x00, 0x7F, 0x00, 0x07, 0x00, 0x03, 0xFC, 0x00, 0x38, 0x00, 0x1F, 0xE0, + 0x01, 0x80, 0x01, 0xBF, 0x80, 0x0C, 0x00, 0x0D, 0xFC, 0x00, 0x60, 0x00, + 0x67, 0xF0, 0x07, 0x00, 0x02, 0x3F, 0x80, 0x30, 0x00, 0x30, 0xFE, 0x01, + 0x80, 0x01, 0x87, 0xF0, 0x0C, 0x00, 0x0C, 0x1F, 0xC0, 0xC0, 0x00, 0xC0, + 0xFE, 0x06, 0x00, 0x06, 0x07, 0xF8, 0x30, 0x00, 0x30, 0x1F, 0xC1, 0x80, + 0x01, 0x80, 0xFF, 0x18, 0x00, 0x18, 0x03, 0xF8, 0xC0, 0x00, 0xC0, 0x1F, + 0xC6, 0x00, 0x06, 0x00, 0x7F, 0x60, 0x00, 0x60, 0x03, 0xFB, 0x00, 0x03, + 0x00, 0x0F, 0xF8, 0x00, 0x18, 0x00, 0x7F, 0xC0, 0x01, 0xC0, 0x01, 0xFC, + 0x00, 0x0C, 0x00, 0x0F, 0xE0, 0x00, 0x60, 0x00, 0x3F, 0x00, 0x03, 0x00, + 0x01, 0xF0, 0x00, 0x38, 0x00, 0x07, 0x80, 0x01, 0xC0, 0x00, 0x3C, 0x00, + 0x3F, 0x00, 0x01, 0xE0, 0x03, 0xFF, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, + 0x30, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x0F, 0xFF, 0x80, 0x00, 0x7E, + 0x1F, 0x80, 0x01, 0xF0, 0x0F, 0x80, 0x0F, 0xC0, 0x1F, 0x80, 0x3F, 0x00, + 0x1F, 0x80, 0xFE, 0x00, 0x3F, 0x03, 0xF8, 0x00, 0x7E, 0x07, 0xF0, 0x00, + 0xFE, 0x1F, 0xC0, 0x01, 0xFC, 0x7F, 0x80, 0x03, 0xF8, 0xFE, 0x00, 0x07, + 0xF3, 0xFC, 0x00, 0x1F, 0xE7, 0xF0, 0x00, 0x3F, 0xDF, 0xE0, 0x00, 0x7F, + 0xBF, 0xC0, 0x00, 0xFE, 0x7F, 0x80, 0x03, 0xFC, 0xFE, 0x00, 0x07, 0xFB, + 0xFC, 0x00, 0x0F, 0xF7, 0xF8, 0x00, 0x3F, 0xCF, 0xF0, 0x00, 0x7F, 0x9F, + 0xC0, 0x00, 0xFE, 0x3F, 0x80, 0x03, 0xFC, 0x7F, 0x00, 0x07, 0xF0, 0xFE, + 0x00, 0x1F, 0xC0, 0xFC, 0x00, 0x3F, 0x81, 0xF8, 0x00, 0xFE, 0x03, 0xF0, + 0x03, 0xF8, 0x03, 0xF0, 0x07, 0xE0, 0x03, 0xE0, 0x1F, 0x00, 0x03, 0xE0, + 0xFC, 0x00, 0x03, 0xFF, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x01, 0xFF, + 0xFF, 0x80, 0x00, 0xFF, 0xFF, 0xE0, 0x00, 0xFE, 0x1F, 0xE0, 0x01, 0xFC, + 0x1F, 0xE0, 0x03, 0xF0, 0x1F, 0xC0, 0x0F, 0xE0, 0x3F, 0xC0, 0x1F, 0xC0, + 0x7F, 0x80, 0x3F, 0x80, 0xFF, 0x00, 0x7E, 0x01, 0xFE, 0x01, 0xFC, 0x03, + 0xFC, 0x03, 0xF8, 0x0F, 0xF8, 0x07, 0xF0, 0x1F, 0xE0, 0x0F, 0xC0, 0x7F, + 0x80, 0x3F, 0x81, 0xFE, 0x00, 0x7F, 0x07, 0xF8, 0x00, 0xFF, 0xFF, 0xC0, + 0x03, 0xFF, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, + 0x1F, 0x80, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x01, 0xFC, + 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x3F, 0xFF, 0x00, 0x00, 0x00, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x0F, 0xFF, 0x00, 0x00, 0x7E, 0x1F, 0x80, 0x01, + 0xF0, 0x0F, 0x80, 0x0F, 0xC0, 0x1F, 0x80, 0x3F, 0x80, 0x1F, 0x80, 0xFE, + 0x00, 0x3F, 0x03, 0xF8, 0x00, 0x7E, 0x07, 0xF0, 0x00, 0xFE, 0x1F, 0xC0, + 0x01, 0xFC, 0x7F, 0x80, 0x03, 0xF8, 0xFE, 0x00, 0x07, 0xF3, 0xFC, 0x00, + 0x1F, 0xE7, 0xF8, 0x00, 0x3F, 0xDF, 0xE0, 0x00, 0x7F, 0xBF, 0xC0, 0x00, + 0xFF, 0x7F, 0x80, 0x01, 0xFC, 0xFE, 0x00, 0x07, 0xFB, 0xFC, 0x00, 0x0F, + 0xF7, 0xF8, 0x00, 0x1F, 0xCF, 0xF0, 0x00, 0x7F, 0x9F, 0xC0, 0x00, 0xFE, + 0x3F, 0x80, 0x01, 0xFC, 0x7F, 0x00, 0x07, 0xF0, 0xFE, 0x00, 0x0F, 0xE1, + 0xFC, 0x00, 0x3F, 0x81, 0xF8, 0x00, 0x7E, 0x03, 0xF0, 0x01, 0xF8, 0x03, + 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x1F, 0x80, 0x03, 0xE0, 0x7E, 0x00, 0x03, + 0xF3, 0xF0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x06, + 0x00, 0x00, 0x00, 0x1C, 0x00, 0x00, 0xC0, 0x7F, 0xE0, 0x03, 0x03, 0xFF, + 0xF8, 0x1C, 0x0F, 0xFF, 0xFF, 0xF0, 0x3F, 0xFF, 0xFF, 0xC0, 0xE0, 0x3F, + 0xFF, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x01, 0xFF, 0xFF, 0xC0, 0x00, 0x7F, + 0xFF, 0xF8, 0x00, 0x3F, 0xC3, 0xFC, 0x00, 0x3F, 0x81, 0xFE, 0x00, 0x3F, + 0x80, 0xFF, 0x00, 0x7F, 0x80, 0xFF, 0x00, 0x7F, 0x00, 0xFF, 0x00, 0x7F, + 0x00, 0xFF, 0x00, 0x7F, 0x00, 0xFF, 0x00, 0xFF, 0x01, 0xFE, 0x00, 0xFE, + 0x01, 0xFE, 0x00, 0xFE, 0x03, 0xFC, 0x00, 0xFE, 0x07, 0xF8, 0x01, 0xFC, + 0x1F, 0xF0, 0x01, 0xFF, 0xFF, 0xC0, 0x01, 0xFF, 0xFE, 0x00, 0x03, 0xFD, + 0xFE, 0x00, 0x03, 0xF8, 0xFF, 0x00, 0x03, 0xF8, 0xFF, 0x00, 0x03, 0xF8, + 0xFF, 0x00, 0x07, 0xF8, 0x7F, 0x80, 0x07, 0xF0, 0x7F, 0x80, 0x07, 0xF0, + 0x3F, 0x80, 0x07, 0xF0, 0x3F, 0xC0, 0x0F, 0xE0, 0x3F, 0xC0, 0x0F, 0xE0, + 0x1F, 0xC0, 0x0F, 0xE0, 0x1F, 0xE0, 0x1F, 0xE0, 0x1F, 0xE0, 0x1F, 0xE0, + 0x0F, 0xF0, 0x3F, 0xF0, 0x0F, 0xF8, 0xFF, 0xFC, 0x0F, 0xFE, 0x00, 0x1F, + 0x83, 0x00, 0x7F, 0xF7, 0x00, 0xF8, 0x7E, 0x01, 0xE0, 0x1E, 0x03, 0xC0, + 0x0E, 0x03, 0xC0, 0x0E, 0x07, 0xC0, 0x0E, 0x07, 0xC0, 0x04, 0x07, 0xC0, + 0x04, 0x07, 0xE0, 0x04, 0x07, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x03, 0xFC, + 0x00, 0x03, 0xFF, 0x00, 0x01, 0xFF, 0x80, 0x00, 0xFF, 0xC0, 0x00, 0x7F, + 0xE0, 0x00, 0x3F, 0xE0, 0x00, 0x1F, 0xF0, 0x00, 0x0F, 0xF0, 0x00, 0x07, + 0xF8, 0x00, 0x03, 0xF8, 0x00, 0x01, 0xF8, 0x20, 0x00, 0xF8, 0x20, 0x00, + 0xF8, 0x20, 0x00, 0xF8, 0x70, 0x00, 0xF8, 0x70, 0x00, 0xF0, 0x78, 0x01, + 0xF0, 0x78, 0x03, 0xE0, 0x7E, 0x07, 0xC0, 0x47, 0xFF, 0x80, 0xC0, 0xFC, + 0x00, 0x3F, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xFC, 0xFE, 0x3F, 0x8F, 0x9E, + 0x07, 0xF0, 0xF3, 0x81, 0xFC, 0x0E, 0x60, 0x3F, 0x81, 0x98, 0x07, 0xF0, + 0x13, 0x00, 0xFC, 0x02, 0x00, 0x3F, 0x80, 0x40, 0x07, 0xF0, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0x1F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xF8, + 0x00, 0x00, 0x7E, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x3F, 0xFF, 0xC0, 0x00, 0x7F, 0xFF, + 0x03, 0xFF, 0x0F, 0xFC, 0x00, 0xFC, 0x07, 0xF0, 0x00, 0x38, 0x07, 0xF0, + 0x00, 0x38, 0x07, 0xF0, 0x00, 0x30, 0x0F, 0xE0, 0x00, 0x30, 0x0F, 0xE0, + 0x00, 0x70, 0x0F, 0xE0, 0x00, 0x60, 0x0F, 0xE0, 0x00, 0x60, 0x1F, 0xC0, + 0x00, 0xE0, 0x1F, 0xC0, 0x00, 0xC0, 0x1F, 0xC0, 0x00, 0xC0, 0x3F, 0x80, + 0x00, 0xC0, 0x3F, 0x80, 0x01, 0x80, 0x3F, 0x80, 0x01, 0x80, 0x3F, 0x80, + 0x01, 0x80, 0x7F, 0x00, 0x01, 0x80, 0x7F, 0x00, 0x03, 0x00, 0x7F, 0x00, + 0x03, 0x00, 0x7E, 0x00, 0x03, 0x00, 0xFE, 0x00, 0x06, 0x00, 0xFE, 0x00, + 0x06, 0x00, 0xFC, 0x00, 0x06, 0x00, 0xFC, 0x00, 0x0E, 0x00, 0xFC, 0x00, + 0x0C, 0x00, 0xFC, 0x00, 0x1C, 0x00, 0xFC, 0x00, 0x18, 0x00, 0x7E, 0x00, + 0x38, 0x00, 0x7E, 0x00, 0x70, 0x00, 0x3F, 0x81, 0xE0, 0x00, 0x0F, 0xFF, + 0x80, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFF, 0xFC, 0x03, 0xFE, 0x7F, 0xE0, + 0x01, 0xF8, 0x7F, 0x80, 0x01, 0xC0, 0xFF, 0x00, 0x03, 0x80, 0xFE, 0x00, + 0x0E, 0x01, 0xFC, 0x00, 0x18, 0x03, 0xF8, 0x00, 0x70, 0x07, 0xF0, 0x00, + 0xC0, 0x0F, 0xF0, 0x03, 0x80, 0x1F, 0xE0, 0x0E, 0x00, 0x1F, 0xC0, 0x18, + 0x00, 0x3F, 0x80, 0x70, 0x00, 0x7F, 0x00, 0xC0, 0x00, 0xFE, 0x03, 0x00, + 0x01, 0xFC, 0x0E, 0x00, 0x03, 0xF8, 0x18, 0x00, 0x07, 0xF8, 0x60, 0x00, + 0x07, 0xF1, 0xC0, 0x00, 0x0F, 0xE3, 0x00, 0x00, 0x1F, 0xCC, 0x00, 0x00, + 0x3F, 0xB8, 0x00, 0x00, 0x7F, 0x60, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x07, + 0xE0, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0xFF, 0xF8, + 0xFF, 0xF0, 0xFF, 0x9F, 0xF8, 0x1F, 0xE0, 0x0F, 0x87, 0xF8, 0x07, 0xE0, + 0x07, 0x03, 0xF8, 0x03, 0xF0, 0x03, 0x80, 0xFE, 0x01, 0xF8, 0x01, 0x80, + 0x7F, 0x00, 0xFC, 0x00, 0xC0, 0x3F, 0x80, 0x7F, 0x00, 0xC0, 0x1F, 0xC0, + 0x7F, 0x80, 0x60, 0x0F, 0xE0, 0x3F, 0xC0, 0x60, 0x07, 0xF0, 0x37, 0xE0, + 0x30, 0x03, 0xF8, 0x1B, 0xF0, 0x30, 0x00, 0xFC, 0x19, 0xF8, 0x18, 0x00, + 0x7E, 0x0C, 0xFE, 0x18, 0x00, 0x3F, 0x84, 0x7F, 0x0C, 0x00, 0x1F, 0xC6, + 0x3F, 0x8C, 0x00, 0x0F, 0xE2, 0x1F, 0xC6, 0x00, 0x07, 0xF3, 0x07, 0xE6, + 0x00, 0x03, 0xF9, 0x83, 0xF3, 0x00, 0x01, 0xFD, 0x81, 0xFB, 0x00, 0x00, + 0x7E, 0xC0, 0xFD, 0x80, 0x00, 0x3F, 0xC0, 0x7F, 0x80, 0x00, 0x1F, 0xE0, + 0x3F, 0xC0, 0x00, 0x0F, 0xE0, 0x1F, 0xC0, 0x00, 0x07, 0xF0, 0x0F, 0xE0, + 0x00, 0x03, 0xF0, 0x07, 0xE0, 0x00, 0x01, 0xF8, 0x01, 0xF0, 0x00, 0x00, + 0x78, 0x00, 0xF0, 0x00, 0x00, 0x3C, 0x00, 0x78, 0x00, 0x00, 0x1C, 0x00, + 0x38, 0x00, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x00, 0x06, 0x00, 0x0C, 0x00, + 0x00, 0x03, 0x00, 0x06, 0x00, 0x00, 0x03, 0xFF, 0xF0, 0xFF, 0xC0, 0x3F, + 0xE0, 0x0F, 0xC0, 0x03, 0xF8, 0x01, 0xE0, 0x00, 0xFE, 0x00, 0xE0, 0x00, + 0x3F, 0x80, 0x70, 0x00, 0x07, 0xE0, 0x18, 0x00, 0x01, 0xFC, 0x0C, 0x00, + 0x00, 0x7F, 0x06, 0x00, 0x00, 0x0F, 0xC3, 0x00, 0x00, 0x03, 0xF9, 0x80, + 0x00, 0x00, 0xFE, 0xC0, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x07, 0xF8, + 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x0F, + 0xC0, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x00, + 0xFF, 0x80, 0x00, 0x00, 0x77, 0xF0, 0x00, 0x00, 0x39, 0xFC, 0x00, 0x00, + 0x1C, 0x3F, 0x00, 0x00, 0x06, 0x0F, 0xE0, 0x00, 0x03, 0x03, 0xF8, 0x00, + 0x01, 0x80, 0x7E, 0x00, 0x00, 0xE0, 0x1F, 0xC0, 0x00, 0x70, 0x07, 0xF0, + 0x00, 0x38, 0x01, 0xFC, 0x00, 0x1E, 0x00, 0x7F, 0x80, 0x1F, 0xC0, 0x1F, + 0xF0, 0x0F, 0xFC, 0x3F, 0xFF, 0x80, 0xFF, 0xF8, 0x3F, 0xF3, 0xFC, 0x00, + 0xFC, 0x1F, 0xC0, 0x07, 0x81, 0xFC, 0x00, 0x70, 0x0F, 0xC0, 0x0E, 0x00, + 0xFE, 0x00, 0xC0, 0x0F, 0xE0, 0x1C, 0x00, 0x7E, 0x03, 0x80, 0x07, 0xF0, + 0x30, 0x00, 0x7F, 0x06, 0x00, 0x03, 0xF0, 0xE0, 0x00, 0x3F, 0x8C, 0x00, + 0x03, 0xF9, 0x80, 0x00, 0x1F, 0xB0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x1F, + 0xE0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x1F, 0x80, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x03, + 0xF8, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x7F, 0x00, + 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x01, + 0xFF, 0x00, 0x00, 0xFF, 0xFE, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xF0, 0x3F, + 0xFF, 0xFF, 0x03, 0xF8, 0x0F, 0xF0, 0x7C, 0x01, 0xFE, 0x07, 0x80, 0x3F, + 0xC0, 0x70, 0x03, 0xF8, 0x06, 0x00, 0x7F, 0x80, 0xC0, 0x0F, 0xF0, 0x08, + 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x7F, + 0x80, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, + 0x03, 0xFC, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, 0xFF, + 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, + 0x07, 0xF8, 0x00, 0xC0, 0xFF, 0x00, 0x0C, 0x1F, 0xE0, 0x01, 0x81, 0xFE, + 0x00, 0x38, 0x3F, 0xC0, 0x07, 0x87, 0xF8, 0x01, 0xF0, 0xFF, 0x00, 0xFF, + 0x0F, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x7F, 0xE0, 0x0F, + 0xFC, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, + 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF0, + 0x00, 0x1E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1E, 0x00, 0x03, 0xC0, + 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x1F, 0x00, + 0x03, 0xE0, 0x00, 0x78, 0x00, 0x0F, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, + 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xE0, 0x00, + 0x3C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xFE, 0x01, + 0xFF, 0xC0, 0x00, 0xF0, 0x07, 0x80, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x1C, + 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xE0, + 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x07, 0x00, 0x3C, 0x01, 0xE0, 0x0F, 0x00, + 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x01, + 0xC0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x0F, 0x00, 0x78, 0x00, 0x7F, 0xE0, + 0x0F, 0xFC, 0x00, 0x0F, 0x80, 0x01, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, + 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, + 0x07, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF0, 0x00, + 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1E, 0x00, 0x07, 0xC0, 0x00, + 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, + 0xE0, 0x00, 0x78, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x0F, + 0x00, 0x01, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xE0, 0x07, 0xFC, + 0x01, 0xFF, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x7F, 0x00, + 0x03, 0xF8, 0x00, 0x3F, 0xC0, 0x01, 0xEF, 0x00, 0x1E, 0x78, 0x00, 0xF1, + 0xE0, 0x0F, 0x0F, 0x00, 0x78, 0x3C, 0x07, 0xC1, 0xE0, 0x3C, 0x07, 0x83, + 0xE0, 0x3C, 0x1E, 0x00, 0xF1, 0xF0, 0x07, 0x8F, 0x00, 0x1E, 0xF8, 0x00, + 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x70, 0x3E, + 0x0F, 0x83, 0xF0, 0x3E, 0x07, 0x80, 0xF0, 0x0E, 0x01, 0xC0, 0x00, 0x3C, + 0x0C, 0x03, 0xF9, 0xF0, 0x1F, 0x3F, 0x80, 0xF8, 0x7E, 0x07, 0xC1, 0xF8, + 0x3F, 0x07, 0xC0, 0xF8, 0x1F, 0x07, 0xE0, 0x7C, 0x3F, 0x01, 0xF0, 0xFC, + 0x0F, 0x87, 0xE0, 0x3E, 0x1F, 0x80, 0xF8, 0x7E, 0x03, 0xC3, 0xF8, 0x1F, + 0x0F, 0xC0, 0x7C, 0x3F, 0x03, 0xF0, 0xFC, 0x0F, 0x83, 0xF0, 0x7E, 0x3F, + 0xC2, 0xF8, 0xBF, 0x9B, 0xE4, 0x7F, 0xCF, 0xE0, 0xFE, 0x3F, 0x01, 0xE0, + 0x78, 0x00, 0x00, 0x7C, 0x00, 0x3F, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0x7E, + 0x00, 0x01, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0x7C, 0x00, + 0x03, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x3E, 0x3E, 0x01, 0xF9, 0xFC, 0x07, + 0xEF, 0xF8, 0x1F, 0x47, 0xF0, 0x7E, 0x0F, 0xC3, 0xF8, 0x3F, 0x0F, 0xC0, + 0xFC, 0x3F, 0x03, 0xF1, 0xF8, 0x0F, 0xC7, 0xE0, 0x3F, 0x1F, 0x01, 0xF8, + 0x7C, 0x07, 0xE3, 0xF0, 0x1F, 0x8F, 0xC0, 0xFC, 0x3E, 0x03, 0xF1, 0xF8, + 0x0F, 0x87, 0xE0, 0x7C, 0x1F, 0x03, 0xE0, 0xFC, 0x0F, 0x03, 0xF0, 0x78, + 0x0F, 0xC7, 0xC0, 0x1F, 0xFE, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x3F, 0x00, + 0x3F, 0xE0, 0x1E, 0x3C, 0x0F, 0x0F, 0x07, 0x87, 0xC3, 0xE1, 0xF1, 0xF0, + 0x38, 0xFC, 0x00, 0x3E, 0x00, 0x1F, 0x80, 0x07, 0xE0, 0x01, 0xF8, 0x00, + 0xFC, 0x00, 0x3F, 0x00, 0x0F, 0xC0, 0x03, 0xF0, 0x00, 0xFC, 0x03, 0x3F, + 0x00, 0xCF, 0xE0, 0x61, 0xFC, 0x70, 0x3F, 0xF8, 0x07, 0xFC, 0x00, 0xFC, + 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x7F, 0xE0, 0x00, + 0x07, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x01, 0xF8, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0x80, + 0x07, 0x9F, 0x80, 0x0F, 0xFF, 0xC0, 0x0F, 0x9F, 0xE0, 0x0F, 0x87, 0xF0, + 0x0F, 0x83, 0xF0, 0x0F, 0xC1, 0xF8, 0x07, 0xC0, 0xFC, 0x07, 0xE0, 0x7C, + 0x07, 0xE0, 0x7E, 0x03, 0xF0, 0x3F, 0x03, 0xF0, 0x1F, 0x81, 0xF8, 0x0F, + 0x80, 0xFC, 0x0F, 0xC0, 0xFE, 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0x3F, 0x03, + 0xF0, 0x1F, 0x83, 0xF8, 0x0F, 0xC1, 0xF8, 0xC7, 0xE1, 0xFC, 0xC3, 0xF9, + 0xBE, 0xC0, 0xFF, 0x9F, 0xC0, 0x7F, 0x8F, 0xC0, 0x0F, 0x83, 0xC0, 0x00, + 0x00, 0x3F, 0x00, 0x3F, 0xE0, 0x1E, 0x3C, 0x0F, 0x0F, 0x07, 0x83, 0xC3, + 0xE0, 0xF1, 0xF0, 0x3C, 0xFC, 0x1E, 0x3F, 0x0F, 0x9F, 0x83, 0xC7, 0xE3, + 0xE1, 0xFB, 0xE0, 0xFF, 0xE0, 0x3F, 0xC0, 0x0F, 0xC0, 0x03, 0xF0, 0x00, + 0xFC, 0x03, 0x3F, 0x01, 0x8F, 0xC0, 0xC1, 0xF8, 0x70, 0x7F, 0xF8, 0x07, + 0xFC, 0x00, 0xFC, 0x00, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x03, 0xCE, 0x00, + 0x00, 0x78, 0xF0, 0x00, 0x0F, 0x8F, 0x00, 0x00, 0xF0, 0xF0, 0x00, 0x1F, + 0x06, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x03, 0xFF, 0xC0, 0x00, 0x3F, + 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x01, + 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x3F, 0x00, + 0x00, 0x03, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, + 0x00, 0x00, 0xFC, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x06, 0x1F, 0x00, 0x00, 0xF1, 0xE0, + 0x00, 0x0F, 0x3E, 0x00, 0x00, 0xF3, 0xC0, 0x00, 0x07, 0xF8, 0x00, 0x00, + 0x3E, 0x00, 0x00, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x7F, 0xF0, 0x00, 0x7E, + 0x3F, 0xE0, 0x7C, 0x0F, 0xF0, 0x7E, 0x07, 0xC0, 0x7E, 0x03, 0xE0, 0x3F, + 0x01, 0xF0, 0x1F, 0x01, 0xF8, 0x0F, 0x80, 0xFC, 0x07, 0xC0, 0xFC, 0x01, + 0xE0, 0xFC, 0x00, 0x78, 0xFC, 0x00, 0x1F, 0xFC, 0x00, 0x0F, 0xF0, 0x00, + 0x1C, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x0F, 0xF8, 0x00, + 0x07, 0xFF, 0x80, 0x01, 0xFF, 0xF8, 0x00, 0x7F, 0xFE, 0x00, 0x77, 0xFF, + 0x80, 0xF0, 0x7F, 0xC0, 0xF0, 0x07, 0xE0, 0xF0, 0x01, 0xF0, 0x78, 0x00, + 0xF8, 0x3C, 0x00, 0x78, 0x1F, 0x00, 0x7C, 0x07, 0xC0, 0x78, 0x01, 0xFF, + 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x04, 0x00, 0x01, 0xF8, 0x00, 0x1F, + 0xF0, 0x00, 0x07, 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x7E, + 0x00, 0x00, 0xFC, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0xC0, + 0x00, 0x1F, 0x87, 0xC0, 0x3E, 0x1F, 0xC0, 0xFC, 0x7F, 0x81, 0xF9, 0x9F, + 0x03, 0xE6, 0x3E, 0x07, 0xD8, 0x7C, 0x1F, 0xA0, 0xF8, 0x3F, 0x83, 0xF0, + 0x7F, 0x07, 0xE0, 0xFC, 0x0F, 0xC3, 0xF8, 0x3F, 0x07, 0xE0, 0x7E, 0x0F, + 0xC0, 0xFC, 0x3F, 0x03, 0xF0, 0x7E, 0x07, 0xE0, 0xFC, 0x0F, 0xC1, 0xF0, + 0x3F, 0x17, 0xE0, 0x7E, 0x6F, 0xC0, 0xF9, 0x9F, 0x01, 0xF6, 0x3E, 0x03, + 0xF8, 0xFC, 0x07, 0xF1, 0xC0, 0x07, 0x80, 0x01, 0xE0, 0x3F, 0x03, 0xF0, + 0x3F, 0x03, 0xF0, 0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xC7, + 0xFC, 0x1F, 0xC0, 0xF8, 0x0F, 0x81, 0xF8, 0x1F, 0x81, 0xF0, 0x1F, 0x03, + 0xF0, 0x3E, 0x03, 0xE0, 0x3E, 0x07, 0xE0, 0x7C, 0x07, 0xC0, 0xFC, 0x2F, + 0x84, 0xF8, 0xCF, 0x98, 0xFF, 0x0F, 0xE0, 0x78, 0x00, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xFC, 0x00, + 0x01, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x01, 0x00, 0x00, 0xFC, 0x00, 0x1F, 0xF0, 0x00, 0x1F, 0xC0, + 0x00, 0x3E, 0x00, 0x01, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x80, 0x00, + 0x7C, 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xF8, + 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x7E, 0x00, 0x01, 0xF0, 0x00, + 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xE0, 0x00, 0x1F, + 0x80, 0x00, 0x7E, 0x00, 0x01, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x3F, 0x00, + 0x60, 0xF8, 0x03, 0xC3, 0xC0, 0x0F, 0x1F, 0x00, 0x3C, 0xF8, 0x00, 0x7F, + 0xC0, 0x00, 0xFC, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0xFC, 0x00, 0x07, + 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x01, + 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x03, + 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xE3, 0xFF, 0x03, 0xE0, 0xFC, 0x07, + 0xE0, 0xF0, 0x07, 0xE0, 0xE0, 0x07, 0xC1, 0xC0, 0x0F, 0xC3, 0x80, 0x0F, + 0xC7, 0x00, 0x0F, 0x8E, 0x00, 0x0F, 0xBE, 0x00, 0x1F, 0xFE, 0x00, 0x1F, + 0xFE, 0x00, 0x1F, 0xFE, 0x00, 0x1F, 0x3E, 0x00, 0x3F, 0x3F, 0x00, 0x3F, + 0x1F, 0x00, 0x3E, 0x1F, 0x00, 0x7E, 0x1F, 0x04, 0x7E, 0x1F, 0x8C, 0x7E, + 0x0F, 0x98, 0x7C, 0x0F, 0xF0, 0xFC, 0x07, 0xE0, 0xE0, 0x03, 0xC0, 0x00, + 0x08, 0x0F, 0xC7, 0xFE, 0x07, 0xF0, 0x3F, 0x01, 0xF8, 0x0F, 0xC0, 0x7C, + 0x07, 0xE0, 0x3F, 0x01, 0xF8, 0x0F, 0x80, 0x7C, 0x07, 0xE0, 0x3E, 0x01, + 0xF0, 0x1F, 0x80, 0xFC, 0x07, 0xC0, 0x3E, 0x03, 0xF0, 0x1F, 0x80, 0xF8, + 0x0F, 0xC0, 0x7E, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x8F, 0x8C, 0x7C, 0x43, + 0xE4, 0x1F, 0xE0, 0xFE, 0x03, 0xC0, 0x00, 0x00, 0x70, 0x78, 0x0F, 0x83, + 0xFE, 0x3F, 0x87, 0xF8, 0x1F, 0xCF, 0xF1, 0xFF, 0x03, 0xF1, 0x3E, 0x73, + 0xE0, 0x7E, 0x47, 0xD8, 0x7C, 0x0F, 0xD0, 0xFB, 0x1F, 0x81, 0xF4, 0x3E, + 0xC3, 0xF0, 0x3E, 0x87, 0xF0, 0x7C, 0x0F, 0xE0, 0xFE, 0x1F, 0x81, 0xF4, + 0x1F, 0x83, 0xF0, 0x3F, 0x07, 0xE0, 0x7C, 0x07, 0xE0, 0xFC, 0x1F, 0x81, + 0xF8, 0x1F, 0x83, 0xF0, 0x3F, 0x07, 0xE0, 0x7C, 0x07, 0xE0, 0xFC, 0x0F, + 0x80, 0xF8, 0x1F, 0x03, 0xF0, 0x3F, 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0xFC, + 0x0F, 0x88, 0xF8, 0x1F, 0x81, 0xF3, 0x3F, 0x03, 0xE0, 0x3E, 0x47, 0xE0, + 0xFC, 0x07, 0xF0, 0xFC, 0x1F, 0x80, 0xFE, 0x18, 0x00, 0x00, 0x0F, 0x00, + 0x00, 0x70, 0xF8, 0x7F, 0xC3, 0xF8, 0x1F, 0x8F, 0xF0, 0x3F, 0x33, 0xE0, + 0x7C, 0x87, 0xC1, 0xF9, 0x0F, 0x83, 0xF4, 0x1F, 0x07, 0xD0, 0x3E, 0x0F, + 0xE0, 0xFC, 0x3F, 0x81, 0xF8, 0x7F, 0x03, 0xE0, 0xFC, 0x0F, 0xC1, 0xF8, + 0x1F, 0x87, 0xE0, 0x3E, 0x0F, 0xC0, 0xFC, 0x1F, 0x81, 0xF0, 0x3E, 0x03, + 0xE0, 0xFC, 0x0F, 0xC9, 0xF8, 0x1F, 0x33, 0xE0, 0x3E, 0x47, 0xC0, 0x7F, + 0x1F, 0x80, 0xFE, 0x38, 0x00, 0xF0, 0x00, 0x00, 0x3F, 0x00, 0x0E, 0x38, + 0x03, 0xC1, 0xC0, 0x78, 0x1E, 0x0F, 0x81, 0xF0, 0xF0, 0x1F, 0x1F, 0x01, + 0xF3, 0xE0, 0x1F, 0x3E, 0x03, 0xF7, 0xC0, 0x3F, 0x7C, 0x03, 0xF7, 0xC0, + 0x3E, 0xFC, 0x03, 0xEF, 0xC0, 0x7E, 0xF8, 0x07, 0xCF, 0x80, 0x7C, 0xF8, + 0x0F, 0x8F, 0x80, 0xF8, 0xF8, 0x1F, 0x07, 0x81, 0xE0, 0x78, 0x3C, 0x03, + 0xC7, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x0F, 0x1F, 0x00, 0x3F, 0xE7, 0xF8, + 0x01, 0xF9, 0xFF, 0x00, 0x1F, 0x47, 0xF0, 0x07, 0xF0, 0x7E, 0x00, 0xFE, + 0x0F, 0xC0, 0x1F, 0x81, 0xF8, 0x03, 0xF0, 0x3F, 0x00, 0xFC, 0x07, 0xE0, + 0x1F, 0x81, 0xFC, 0x03, 0xE0, 0x3F, 0x00, 0x7C, 0x07, 0xE0, 0x1F, 0x81, + 0xFC, 0x03, 0xF0, 0x3F, 0x00, 0x7C, 0x07, 0xE0, 0x0F, 0x81, 0xF8, 0x03, + 0xF0, 0x3E, 0x00, 0x7E, 0x0F, 0xC0, 0x0F, 0x81, 0xF0, 0x01, 0xF0, 0x7C, + 0x00, 0x7F, 0x1F, 0x00, 0x0F, 0xFF, 0xC0, 0x01, 0xF3, 0xE0, 0x00, 0x3E, + 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0x0F, 0xC0, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0xFC, + 0x00, 0x00, 0x00, 0x3E, 0x00, 0x03, 0xF9, 0xF0, 0x1F, 0x1F, 0xC0, 0xF8, + 0x7E, 0x07, 0xC1, 0xF8, 0x3F, 0x07, 0xE0, 0xF8, 0x1F, 0x87, 0xE0, 0x7C, + 0x3F, 0x01, 0xF0, 0xFC, 0x0F, 0xC7, 0xE0, 0x3E, 0x1F, 0x80, 0xF8, 0x7E, + 0x07, 0xE3, 0xF0, 0x1F, 0x8F, 0xC0, 0x7C, 0x3F, 0x03, 0xF0, 0xFC, 0x0F, + 0xC3, 0xF0, 0x7E, 0x0F, 0xC3, 0xF8, 0x3F, 0x9B, 0xE0, 0x7F, 0xDF, 0x01, + 0xFE, 0x7C, 0x01, 0xF1, 0xF0, 0x00, 0x0F, 0xC0, 0x00, 0x3E, 0x00, 0x00, + 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xF8, + 0x00, 0x7F, 0xF8, 0x00, 0x00, 0x71, 0xE1, 0xFF, 0x3E, 0x07, 0xE7, 0xF0, + 0x7E, 0xFF, 0x07, 0xE9, 0xE0, 0x7D, 0x0E, 0x07, 0xD0, 0x00, 0xFE, 0x00, + 0x0F, 0xE0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, 0x01, 0xFC, 0x00, 0x1F, 0x80, + 0x01, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xF0, + 0x00, 0x7E, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x07, 0xC0, 0x00, 0x01, + 0xF1, 0x07, 0xFF, 0x0F, 0x0F, 0x0E, 0x07, 0x1E, 0x06, 0x1E, 0x06, 0x1F, + 0x02, 0x1F, 0x02, 0x1F, 0x80, 0x0F, 0xC0, 0x0F, 0xE0, 0x0F, 0xF0, 0x07, + 0xF8, 0x03, 0xF8, 0x01, 0xFC, 0x00, 0xFC, 0x40, 0x7C, 0x40, 0x7C, 0x60, + 0x3C, 0xE0, 0x38, 0xF0, 0x38, 0xF8, 0xF0, 0xDF, 0xC0, 0x00, 0x20, 0x03, + 0x00, 0x38, 0x03, 0x80, 0x3C, 0x03, 0xE0, 0x7F, 0x07, 0xFF, 0x3F, 0xF8, + 0x7C, 0x07, 0xE0, 0x3F, 0x01, 0xF0, 0x0F, 0x80, 0xFC, 0x07, 0xC0, 0x3E, + 0x03, 0xF0, 0x1F, 0x80, 0xF8, 0x07, 0xC0, 0x7E, 0x03, 0xF1, 0x1F, 0x08, + 0xF8, 0x87, 0xC8, 0x3F, 0xC1, 0xFC, 0x07, 0x80, 0x00, 0x00, 0x40, 0x00, + 0x1F, 0x03, 0xF7, 0xF8, 0x0F, 0x87, 0xE0, 0x3E, 0x1F, 0x81, 0xF8, 0x7E, + 0x07, 0xC1, 0xF0, 0x1F, 0x07, 0xC0, 0xFC, 0x3F, 0x03, 0xE0, 0xF8, 0x0F, + 0x83, 0xE0, 0x7E, 0x0F, 0x81, 0xF8, 0x7E, 0x0F, 0xC1, 0xF0, 0x3F, 0x07, + 0xC1, 0xFC, 0x1F, 0x07, 0xE0, 0xF8, 0x2F, 0x83, 0xE1, 0x3C, 0x6F, 0x8D, + 0xF1, 0x3E, 0x67, 0xC8, 0xFF, 0x1F, 0xE3, 0xF8, 0x7F, 0x07, 0xC0, 0xF0, + 0x00, 0x06, 0x07, 0x1F, 0x07, 0xBF, 0x83, 0xE7, 0xC1, 0xF3, 0xE0, 0xF9, + 0xF8, 0x3C, 0x7C, 0x0C, 0x3E, 0x06, 0x1F, 0x03, 0x0F, 0x83, 0x07, 0xC1, + 0x83, 0xE1, 0x81, 0xF1, 0x80, 0xF9, 0x80, 0x7C, 0xC0, 0x3E, 0xC0, 0x1F, + 0xC0, 0x0F, 0xC0, 0x07, 0xC0, 0x03, 0xC0, 0x01, 0xC0, 0x00, 0xC0, 0x00, + 0x40, 0x00, 0x06, 0x01, 0x81, 0xC7, 0xC0, 0x30, 0x7F, 0xF8, 0x0E, 0x0F, + 0x9F, 0x01, 0xC1, 0xF3, 0xE0, 0x78, 0x3E, 0x7C, 0x1F, 0x03, 0xCF, 0xC3, + 0xE0, 0x30, 0xF8, 0xFC, 0x06, 0x1F, 0x1F, 0xC0, 0x83, 0xE7, 0xF8, 0x30, + 0x7C, 0xFF, 0x04, 0x0F, 0xB7, 0xE1, 0x81, 0xF6, 0xFC, 0x60, 0x3F, 0x8F, + 0x98, 0x07, 0xE1, 0xF3, 0x00, 0xFC, 0x3E, 0xC0, 0x1F, 0x07, 0xF0, 0x03, + 0xE0, 0xFC, 0x00, 0x78, 0x1F, 0x80, 0x0F, 0x03, 0xE0, 0x01, 0xC0, 0x78, + 0x00, 0x30, 0x0E, 0x00, 0x06, 0x01, 0x80, 0x00, 0x00, 0xF0, 0x1E, 0x0F, + 0xF0, 0x3E, 0x01, 0xF8, 0x7F, 0x01, 0xF8, 0xFF, 0x00, 0xF9, 0x8E, 0x00, + 0xFB, 0x00, 0x00, 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7C, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xBF, 0x00, 0x01, + 0xBF, 0x08, 0x73, 0x1F, 0x18, 0xFF, 0x1F, 0x30, 0xFE, 0x1F, 0xE0, 0xFC, + 0x0F, 0xC0, 0x78, 0x07, 0x80, 0x00, 0x30, 0x1C, 0x0F, 0xF0, 0x7C, 0x07, + 0xE0, 0xF8, 0x0F, 0xC1, 0xF0, 0x0F, 0xC1, 0xE0, 0x1F, 0x81, 0xC0, 0x3F, + 0x03, 0x00, 0x3E, 0x06, 0x00, 0x7E, 0x08, 0x00, 0xFC, 0x30, 0x01, 0xF8, + 0x60, 0x01, 0xF1, 0x80, 0x03, 0xE3, 0x00, 0x07, 0xCC, 0x00, 0x0F, 0xD8, + 0x00, 0x1F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0x7E, 0x00, + 0x00, 0xF8, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x00, 0x00, + 0x0C, 0x00, 0x00, 0x18, 0x00, 0x00, 0x60, 0x01, 0xC1, 0x80, 0x07, 0xE6, + 0x00, 0x0F, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x07, + 0xFF, 0xE1, 0xFF, 0xF8, 0x3F, 0xFF, 0x07, 0xFF, 0xC0, 0x80, 0x70, 0x30, + 0x1C, 0x04, 0x07, 0x00, 0x00, 0xC0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, + 0x80, 0x00, 0x60, 0x00, 0x18, 0x00, 0x06, 0x00, 0x01, 0xC0, 0x00, 0x30, + 0x00, 0x0C, 0x00, 0x03, 0xE0, 0x00, 0xFE, 0x00, 0x1F, 0xE0, 0xC7, 0xFC, + 0x3D, 0xCF, 0xC7, 0x90, 0xF8, 0xF0, 0x07, 0x9C, 0x00, 0x3E, 0x00, 0x00, + 0x01, 0xF0, 0x00, 0xFC, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, + 0x07, 0xC0, 0x00, 0x78, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, + 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x03, 0xE0, + 0x00, 0x3E, 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x0F, 0xC0, + 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, + 0x80, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x03, + 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, + 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7E, 0x00, + 0x03, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, + 0x3E, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xE0, + 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, + 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, + 0x80, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x00, + 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x03, 0xE0, 0x00, + 0x7C, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, + 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, + 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x0F, 0x80, + 0x03, 0xF0, 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x03, 0xFF, 0x01, 0x3F, + 0xFE, 0x1D, 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0x00, 0x1F, 0xF0, 0x00, 0x1F, + 0x00 }; + +const GFXglyph FreeSerifBoldItalic24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 12, 0, 1 }, // 0x20 ' ' + { 0, 15, 33, 18, 3, -31 }, // 0x21 '!' + { 62, 19, 13, 26, 6, -31 }, // 0x22 '"' + { 93, 27, 33, 23, -2, -32 }, // 0x23 '#' + { 205, 24, 39, 24, -1, -33 }, // 0x24 '$' + { 322, 35, 32, 39, 2, -30 }, // 0x25 '%' + { 462, 33, 33, 37, 0, -31 }, // 0x26 '&' + { 599, 7, 13, 13, 6, -31 }, // 0x27 ''' + { 611, 14, 41, 16, 1, -31 }, // 0x28 '(' + { 683, 14, 41, 16, -2, -31 }, // 0x29 ')' + { 755, 19, 20, 23, 3, -31 }, // 0x2A '*' + { 803, 22, 23, 27, 2, -22 }, // 0x2B '+' + { 867, 10, 15, 12, -3, -5 }, // 0x2C ',' + { 886, 12, 5, 16, 0, -12 }, // 0x2D '-' + { 894, 8, 7, 12, 0, -5 }, // 0x2E '.' + { 901, 19, 33, 16, 0, -31 }, // 0x2F '/' + { 980, 22, 33, 23, 1, -31 }, // 0x30 '0' + { 1071, 20, 32, 23, 0, -31 }, // 0x31 '1' + { 1151, 22, 32, 23, 1, -31 }, // 0x32 '2' + { 1239, 22, 33, 24, 0, -31 }, // 0x33 '3' + { 1330, 25, 32, 23, 0, -31 }, // 0x34 '4' + { 1430, 24, 32, 24, 0, -30 }, // 0x35 '5' + { 1526, 23, 32, 24, 1, -30 }, // 0x36 '6' + { 1618, 23, 31, 23, 3, -30 }, // 0x37 '7' + { 1708, 21, 33, 23, 1, -31 }, // 0x38 '8' + { 1795, 23, 33, 23, 0, -31 }, // 0x39 '9' + { 1890, 13, 22, 12, 0, -20 }, // 0x3A ':' + { 1926, 15, 30, 12, -2, -20 }, // 0x3B ';' + { 1983, 24, 25, 27, 1, -23 }, // 0x3C '<' + { 2058, 24, 14, 27, 3, -18 }, // 0x3D '=' + { 2100, 24, 25, 27, 3, -23 }, // 0x3E '>' + { 2175, 18, 33, 24, 4, -31 }, // 0x3F '?' + { 2250, 33, 33, 39, 3, -31 }, // 0x40 '@' + { 2387, 31, 32, 33, 0, -31 }, // 0x41 'A' + { 2511, 31, 31, 30, 0, -30 }, // 0x42 'B' + { 2632, 29, 33, 29, 2, -31 }, // 0x43 'C' + { 2752, 35, 31, 34, 0, -30 }, // 0x44 'D' + { 2888, 32, 31, 30, 0, -30 }, // 0x45 'E' + { 3012, 31, 31, 29, 0, -30 }, // 0x46 'F' + { 3133, 32, 33, 33, 2, -31 }, // 0x47 'G' + { 3265, 39, 31, 35, 0, -30 }, // 0x48 'H' + { 3417, 21, 31, 18, 0, -30 }, // 0x49 'I' + { 3499, 27, 36, 23, 0, -30 }, // 0x4A 'J' + { 3621, 34, 31, 31, 0, -30 }, // 0x4B 'K' + { 3753, 29, 31, 29, 0, -30 }, // 0x4C 'L' + { 3866, 44, 32, 41, 0, -30 }, // 0x4D 'M' + { 4042, 37, 32, 33, 0, -30 }, // 0x4E 'N' + { 4190, 31, 33, 32, 2, -31 }, // 0x4F 'O' + { 4318, 31, 31, 28, 0, -30 }, // 0x50 'P' + { 4439, 31, 42, 32, 2, -31 }, // 0x51 'Q' + { 4602, 32, 31, 31, 0, -30 }, // 0x52 'R' + { 4726, 24, 33, 24, 0, -31 }, // 0x53 'S' + { 4825, 27, 31, 28, 4, -30 }, // 0x54 'T' + { 4930, 32, 32, 34, 5, -30 }, // 0x55 'U' + { 5058, 31, 32, 33, 6, -30 }, // 0x56 'V' + { 5182, 41, 32, 44, 6, -30 }, // 0x57 'W' + { 5346, 34, 31, 33, 0, -30 }, // 0x58 'X' + { 5478, 28, 31, 30, 6, -30 }, // 0x59 'Y' + { 5587, 28, 31, 26, 0, -30 }, // 0x5A 'Z' + { 5696, 19, 38, 16, -2, -30 }, // 0x5B '[' + { 5787, 13, 33, 19, 6, -31 }, // 0x5C '\' + { 5841, 19, 38, 16, -3, -30 }, // 0x5D ']' + { 5932, 21, 17, 27, 3, -30 }, // 0x5E '^' + { 5977, 24, 3, 23, 0, 5 }, // 0x5F '_' + { 5986, 10, 9, 16, 4, -32 }, // 0x60 '`' + { 5998, 22, 23, 24, 1, -21 }, // 0x61 'a' + { 6062, 22, 33, 23, 1, -31 }, // 0x62 'b' + { 6153, 18, 23, 20, 1, -21 }, // 0x63 'c' + { 6205, 25, 34, 24, 1, -32 }, // 0x64 'd' + { 6312, 18, 23, 20, 1, -21 }, // 0x65 'e' + { 6364, 28, 41, 23, -4, -31 }, // 0x66 'f' + { 6508, 25, 31, 23, -1, -21 }, // 0x67 'g' + { 6605, 23, 34, 26, 1, -32 }, // 0x68 'h' + { 6703, 12, 33, 14, 2, -31 }, // 0x69 'i' + { 6753, 22, 42, 16, -4, -31 }, // 0x6A 'j' + { 6869, 24, 34, 24, 1, -32 }, // 0x6B 'k' + { 6971, 13, 34, 14, 2, -32 }, // 0x6C 'l' + { 7027, 35, 23, 36, 0, -21 }, // 0x6D 'm' + { 7128, 23, 23, 25, 0, -21 }, // 0x6E 'n' + { 7195, 20, 23, 22, 1, -21 }, // 0x6F 'o' + { 7253, 27, 31, 23, -4, -21 }, // 0x70 'p' + { 7358, 22, 31, 23, 1, -21 }, // 0x71 'q' + { 7444, 20, 22, 19, 0, -21 }, // 0x72 'r' + { 7499, 16, 23, 17, 0, -21 }, // 0x73 's' + { 7545, 13, 29, 13, 2, -27 }, // 0x74 't' + { 7593, 22, 23, 25, 2, -21 }, // 0x75 'u' + { 7657, 17, 23, 21, 3, -21 }, // 0x76 'v' + { 7706, 27, 23, 31, 3, -21 }, // 0x77 'w' + { 7784, 24, 23, 22, -1, -21 }, // 0x78 'x' + { 7853, 23, 31, 20, -3, -21 }, // 0x79 'y' + { 7943, 19, 25, 19, 0, -20 }, // 0x7A 'z' + { 8003, 20, 41, 16, 0, -31 }, // 0x7B '{' + { 8106, 4, 33, 13, 5, -31 }, // 0x7C '|' + { 8123, 20, 41, 16, -6, -31 }, // 0x7D '}' + { 8226, 21, 7, 27, 3, -14 } }; // 0x7E '~' + +const GFXfont FreeSerifBoldItalic24pt7b PROGMEM = { + (uint8_t *)FreeSerifBoldItalic24pt7bBitmaps, + (GFXglyph *)FreeSerifBoldItalic24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 8917 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic9pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic9pt7b.h new file mode 100644 index 0000000..47711ee --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic9pt7b.h @@ -0,0 +1,215 @@ +const uint8_t FreeSerifBoldItalic9pt7bBitmaps[] PROGMEM = { + 0x0C, 0x31, 0xC6, 0x18, 0x41, 0x08, 0x20, 0x0E, 0x38, 0xE0, 0xCF, 0x38, + 0xA2, 0x88, 0x02, 0x40, 0xC8, 0x13, 0x06, 0x43, 0xFC, 0x32, 0x06, 0x40, + 0x98, 0x7F, 0x84, 0xC0, 0x90, 0x32, 0x04, 0xC0, 0x01, 0x01, 0xF0, 0x4B, + 0x99, 0x33, 0x24, 0x78, 0x07, 0x80, 0x38, 0x0B, 0x89, 0x31, 0x26, 0x64, + 0xC7, 0x30, 0x3C, 0x04, 0x00, 0x38, 0x41, 0x9F, 0x06, 0x48, 0x31, 0x60, + 0xCD, 0x03, 0x2C, 0x07, 0x27, 0x81, 0x39, 0x05, 0xC4, 0x26, 0x10, 0x98, + 0x84, 0x66, 0x10, 0xE0, 0x03, 0x80, 0x22, 0x03, 0x10, 0x19, 0x00, 0xF0, + 0x0F, 0x3C, 0xF8, 0xCC, 0xC4, 0xE7, 0x47, 0x3E, 0x38, 0xE1, 0xE7, 0x97, + 0xCF, 0x00, 0xFA, 0x80, 0x08, 0x88, 0x84, 0x62, 0x10, 0x84, 0x21, 0x08, + 0x41, 0x00, 0x20, 0x84, 0x10, 0x84, 0x21, 0x08, 0xC6, 0x23, 0x11, 0x00, + 0x18, 0x18, 0xD6, 0x38, 0x18, 0xF7, 0x18, 0x18, 0x08, 0x04, 0x02, 0x01, + 0x0F, 0xF8, 0x40, 0x20, 0x10, 0x08, 0x00, 0x6D, 0x95, 0x00, 0xFF, 0xC0, + 0xFF, 0x80, 0x06, 0x0C, 0x30, 0x60, 0x83, 0x04, 0x18, 0x20, 0xC1, 0x06, + 0x00, 0x0F, 0x0C, 0x8C, 0x6E, 0x37, 0x1B, 0x1F, 0x8F, 0xC7, 0xC7, 0x63, + 0xB1, 0x89, 0x83, 0x80, 0x06, 0x1E, 0x0E, 0x0E, 0x0C, 0x0C, 0x1C, 0x18, + 0x18, 0x18, 0x38, 0x38, 0xFC, 0x1F, 0x13, 0xD0, 0xE0, 0x70, 0x38, 0x38, + 0x18, 0x18, 0x18, 0x08, 0x08, 0x4F, 0xCF, 0xE0, 0x1F, 0x11, 0xC0, 0xE0, + 0x60, 0xC1, 0xF0, 0x38, 0x0C, 0x06, 0x03, 0x01, 0x19, 0x8F, 0x00, 0x00, + 0x80, 0xC0, 0xE1, 0xE0, 0xB0, 0x98, 0x9C, 0x8C, 0xFF, 0x07, 0x03, 0x01, + 0x80, 0x0F, 0x88, 0x08, 0x07, 0x83, 0xE0, 0x78, 0x1C, 0x06, 0x03, 0x01, + 0x80, 0x9C, 0x87, 0x80, 0x03, 0x87, 0x07, 0x07, 0x07, 0x03, 0xE3, 0x99, + 0xCC, 0xC6, 0x63, 0x33, 0x89, 0x87, 0x80, 0x3F, 0xBF, 0x90, 0x80, 0xC0, + 0x40, 0x60, 0x20, 0x30, 0x30, 0x10, 0x18, 0x08, 0x00, 0x1E, 0x13, 0x31, + 0x31, 0x3A, 0x1C, 0x1C, 0x6E, 0xC6, 0xC6, 0xC6, 0x44, 0x38, 0x0E, 0x1C, + 0x8C, 0x6C, 0x36, 0x3B, 0x1D, 0x8E, 0x7E, 0x0E, 0x07, 0x07, 0x0E, 0x0C, + 0x00, 0x39, 0xCE, 0x00, 0x03, 0x9C, 0xE0, 0x39, 0xCE, 0x00, 0x01, 0x8C, + 0x22, 0x20, 0x00, 0x01, 0xC3, 0xC7, 0x8E, 0x06, 0x01, 0xE0, 0x3C, 0x07, + 0x80, 0x40, 0xFF, 0x80, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x60, 0x1E, 0x03, + 0xC0, 0x78, 0x1C, 0x3C, 0x78, 0xF0, 0x40, 0x00, 0x1C, 0x27, 0x37, 0x07, + 0x0E, 0x1C, 0x30, 0x60, 0x40, 0x00, 0xE0, 0xE0, 0xE0, 0x0F, 0x80, 0xC3, + 0x08, 0x04, 0xC3, 0x3C, 0x24, 0xE2, 0x27, 0x33, 0x39, 0x11, 0xC9, 0x93, + 0x77, 0x18, 0x00, 0x70, 0x40, 0xFC, 0x00, 0x00, 0x80, 0x18, 0x01, 0x80, + 0x38, 0x05, 0x80, 0x5C, 0x09, 0xC1, 0x1C, 0x1F, 0xC2, 0x0C, 0x20, 0xC4, + 0x0E, 0xF3, 0xF0, 0x3F, 0xE0, 0xC7, 0x0C, 0x71, 0xC7, 0x1C, 0xE1, 0xF0, + 0x39, 0xC3, 0x8E, 0x38, 0xE3, 0x0E, 0x71, 0xE7, 0x1C, 0xFF, 0x00, 0x07, + 0xD1, 0xC7, 0x38, 0x27, 0x02, 0x70, 0x0F, 0x00, 0xE0, 0x0E, 0x00, 0xE0, + 0x0E, 0x00, 0x60, 0x87, 0x18, 0x1E, 0x00, 0x3F, 0xE0, 0x30, 0xE0, 0xC1, + 0x87, 0x07, 0x1C, 0x1C, 0x60, 0x73, 0x81, 0xCE, 0x07, 0x38, 0x38, 0xC0, + 0xE7, 0x07, 0x1C, 0x78, 0xFF, 0x80, 0x1F, 0xF8, 0x61, 0xC3, 0x04, 0x38, + 0x81, 0xCC, 0x0F, 0xE0, 0xE2, 0x07, 0x10, 0x38, 0x81, 0x81, 0x1C, 0x18, + 0xE3, 0x8F, 0xFC, 0x00, 0x3F, 0xF8, 0x61, 0xC3, 0x04, 0x38, 0x81, 0xCC, + 0x0F, 0xE0, 0xE2, 0x07, 0x10, 0x38, 0x81, 0x80, 0x1C, 0x00, 0xE0, 0x0F, + 0x80, 0x00, 0x07, 0x91, 0xC7, 0x38, 0x27, 0x00, 0x70, 0x0F, 0x00, 0xE1, + 0xFE, 0x0E, 0xE0, 0xCE, 0x0C, 0x60, 0xC7, 0x1C, 0x1F, 0x00, 0x1F, 0x7E, + 0x1C, 0x38, 0x30, 0x60, 0xE1, 0xC1, 0xC3, 0x83, 0x06, 0x0F, 0xFC, 0x1C, + 0x38, 0x38, 0x70, 0x60, 0xC1, 0xC3, 0x83, 0x87, 0x0F, 0x9F, 0x00, 0x3F, + 0x0C, 0x0C, 0x1C, 0x1C, 0x18, 0x38, 0x38, 0x38, 0x30, 0x70, 0x70, 0xF8, + 0x07, 0xC0, 0xE0, 0x38, 0x0C, 0x07, 0x01, 0xC0, 0x70, 0x18, 0x0E, 0x03, + 0x80, 0xC3, 0x30, 0xDC, 0x1E, 0x00, 0x1F, 0x78, 0x71, 0x83, 0x18, 0x39, + 0x81, 0xD0, 0x0D, 0x00, 0xFC, 0x07, 0x60, 0x3B, 0x81, 0x8C, 0x1C, 0x70, + 0xE1, 0x8F, 0xBE, 0x00, 0x1F, 0x00, 0xC0, 0x0C, 0x01, 0xC0, 0x1C, 0x01, + 0x80, 0x38, 0x03, 0x80, 0x38, 0x03, 0x01, 0x70, 0x37, 0x0E, 0xFF, 0xE0, + 0x1E, 0x07, 0x87, 0x07, 0x83, 0x83, 0x82, 0xC3, 0xC1, 0x62, 0xE0, 0xB1, + 0x70, 0x99, 0x30, 0x4D, 0xB8, 0x27, 0x9C, 0x13, 0x8C, 0x11, 0xC6, 0x0C, + 0xC7, 0x0F, 0x47, 0xC0, 0x3C, 0x3C, 0x38, 0x20, 0xE0, 0x85, 0xC4, 0x13, + 0x10, 0x4E, 0x42, 0x3A, 0x08, 0x78, 0x21, 0xE0, 0x83, 0x84, 0x0C, 0x18, + 0x10, 0x00, 0x40, 0x07, 0xC1, 0xCE, 0x38, 0x73, 0x87, 0x70, 0x77, 0x07, + 0xF0, 0xFE, 0x0E, 0xE0, 0xEE, 0x1C, 0xE1, 0xC6, 0x38, 0x3E, 0x00, 0x3F, + 0xC0, 0xC7, 0x0C, 0x71, 0xC7, 0x1C, 0x71, 0x8E, 0x3F, 0xC3, 0x80, 0x30, + 0x03, 0x00, 0x70, 0x07, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0xCE, 0x38, 0x73, + 0x87, 0x70, 0x77, 0x07, 0xF0, 0x7E, 0x0E, 0xE0, 0xEE, 0x0C, 0xE1, 0xC6, + 0x38, 0x36, 0x01, 0x80, 0x3C, 0x2D, 0xFC, 0x3F, 0xC0, 0xE7, 0x0C, 0x71, + 0xC7, 0x1C, 0x71, 0x8E, 0x3F, 0x83, 0xB8, 0x3B, 0x83, 0x3C, 0x71, 0xC7, + 0x1C, 0xF9, 0xF0, 0x0C, 0x89, 0x8C, 0x46, 0x23, 0x80, 0xE0, 0x78, 0x0E, + 0x03, 0x21, 0x90, 0xCC, 0xC9, 0xC0, 0x7F, 0xE9, 0xDF, 0x31, 0x4E, 0x21, + 0xC0, 0x38, 0x06, 0x01, 0xC0, 0x38, 0x06, 0x00, 0xC0, 0x38, 0x0F, 0xC0, + 0x7C, 0xF3, 0x82, 0x30, 0x27, 0x04, 0x70, 0x46, 0x04, 0xE0, 0x4E, 0x08, + 0xE0, 0x8E, 0x08, 0xE1, 0x0F, 0x30, 0x3C, 0x00, 0xFC, 0x73, 0x82, 0x38, + 0x23, 0x84, 0x38, 0x83, 0x90, 0x39, 0x01, 0xA0, 0x1C, 0x01, 0xC0, 0x18, + 0x01, 0x00, 0xF9, 0xF7, 0x30, 0xE2, 0x30, 0xC2, 0x38, 0xC4, 0x3B, 0xC4, + 0x3A, 0xE8, 0x3C, 0xE8, 0x3C, 0xF0, 0x18, 0xF0, 0x18, 0x60, 0x10, 0x60, + 0x10, 0x40, 0x3F, 0x78, 0x61, 0x83, 0x98, 0x1D, 0x00, 0x70, 0x03, 0x80, + 0x1C, 0x01, 0x60, 0x0B, 0x80, 0x9C, 0x08, 0x60, 0xC3, 0x8F, 0x7E, 0x00, + 0xF9, 0xE6, 0x18, 0xC2, 0x1C, 0x81, 0xA0, 0x34, 0x07, 0x00, 0xC0, 0x18, + 0x07, 0x00, 0xE0, 0x1C, 0x0F, 0xC0, 0x3F, 0xE6, 0x19, 0x87, 0x21, 0xC0, + 0x30, 0x0E, 0x03, 0x80, 0x60, 0x1C, 0x07, 0x05, 0xC1, 0x38, 0xEF, 0xFC, + 0x0E, 0x08, 0x18, 0x18, 0x18, 0x10, 0x30, 0x30, 0x30, 0x20, 0x60, 0x60, + 0x60, 0x40, 0xF0, 0xC6, 0x10, 0xC6, 0x10, 0x86, 0x30, 0x86, 0x30, 0x1E, + 0x0C, 0x18, 0x20, 0xC1, 0x83, 0x04, 0x18, 0x30, 0x60, 0x83, 0x06, 0x3C, + 0x00, 0x18, 0x1C, 0x34, 0x26, 0x66, 0x43, 0xC3, 0xFF, 0x80, 0xC6, 0x30, + 0x0D, 0x9D, 0x8C, 0xCC, 0x6E, 0x26, 0x33, 0x19, 0xBE, 0x66, 0x00, 0x00, + 0x78, 0x18, 0x30, 0x30, 0x3E, 0x73, 0x63, 0x63, 0x63, 0xC6, 0xC6, 0xCC, + 0x70, 0x0F, 0x3B, 0x70, 0x70, 0xE0, 0xE0, 0xE2, 0xE4, 0x78, 0x00, 0x00, + 0xF0, 0x1C, 0x06, 0x01, 0x83, 0xE3, 0x30, 0xCC, 0x63, 0x19, 0xCC, 0x63, + 0x38, 0xCF, 0x1D, 0x80, 0x0E, 0x75, 0xCB, 0xBE, 0xDE, 0x38, 0x72, 0x78, + 0x00, 0xE0, 0x34, 0x0C, 0x01, 0x80, 0x30, 0x1F, 0x01, 0x80, 0x30, 0x06, + 0x01, 0xC0, 0x30, 0x06, 0x00, 0xC0, 0x30, 0x06, 0x04, 0x80, 0xE0, 0x00, + 0x1C, 0x19, 0xD8, 0xCC, 0x66, 0x60, 0xE1, 0x80, 0xF0, 0x7E, 0x43, 0x21, + 0x8F, 0x00, 0x00, 0x1E, 0x07, 0x03, 0x01, 0x80, 0xD8, 0xFC, 0x76, 0x33, + 0x19, 0x99, 0xCC, 0xD6, 0x77, 0x30, 0x39, 0xC0, 0x0F, 0x31, 0x8C, 0xC6, + 0x31, 0xAE, 0x00, 0x03, 0x81, 0xC0, 0x00, 0x00, 0xE0, 0x30, 0x18, 0x18, + 0x0C, 0x06, 0x03, 0x03, 0x01, 0x80, 0xC2, 0xC1, 0xC0, 0x00, 0x0F, 0x00, + 0xC0, 0x60, 0x18, 0x06, 0xF3, 0x90, 0xC8, 0x34, 0x0F, 0x06, 0xC1, 0x98, + 0x66, 0xB9, 0xC0, 0x03, 0xCC, 0x63, 0x39, 0x8C, 0x66, 0x31, 0x8E, 0x70, + 0x7B, 0x99, 0xAF, 0xCE, 0x66, 0x63, 0x67, 0x33, 0x31, 0x99, 0x8C, 0xCC, + 0xE7, 0xC6, 0x30, 0x73, 0x7F, 0x73, 0x73, 0x63, 0x67, 0xE6, 0xC7, 0xC6, + 0x1E, 0x33, 0x63, 0x63, 0xC3, 0xC6, 0xC6, 0xCC, 0x78, 0x1D, 0xC3, 0xB1, + 0xCC, 0x63, 0x19, 0xCE, 0x63, 0x18, 0xCC, 0x3E, 0x1C, 0x06, 0x03, 0xE0, + 0x0D, 0x99, 0x8C, 0xCC, 0x6E, 0x76, 0x33, 0x19, 0x9C, 0x7C, 0x06, 0x07, + 0x07, 0xC0, 0x76, 0x3A, 0x30, 0x70, 0x60, 0x60, 0x60, 0xE0, 0x3D, 0x14, + 0x58, 0x38, 0x60, 0xA2, 0xF0, 0x08, 0xCC, 0xF6, 0x31, 0x98, 0xC6, 0x35, + 0xC0, 0xE3, 0x63, 0x66, 0x66, 0x66, 0xCC, 0xCC, 0xFE, 0xEC, 0xE6, 0xCD, + 0x8B, 0x26, 0x8E, 0x18, 0x20, 0xE4, 0xD9, 0x36, 0xE5, 0xDA, 0x77, 0x19, + 0xC6, 0x61, 0x10, 0x39, 0xC7, 0xB0, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xE1, + 0x5A, 0x67, 0x00, 0x39, 0x8C, 0xC3, 0x21, 0xA0, 0xD0, 0x68, 0x38, 0x0C, + 0x04, 0x04, 0x14, 0x0C, 0x00, 0x3E, 0x46, 0x0C, 0x08, 0x10, 0x20, 0x70, + 0x1A, 0x0E, 0x03, 0x0E, 0x0C, 0x0C, 0x08, 0x18, 0x18, 0x10, 0x60, 0x30, + 0x30, 0x30, 0x60, 0x60, 0x60, 0x30, 0xFF, 0xF0, 0x0C, 0x06, 0x06, 0x06, + 0x04, 0x0C, 0x0C, 0x0C, 0x06, 0x18, 0x18, 0x18, 0x30, 0x30, 0x30, 0xE0, + 0x71, 0x8F }; + +const GFXglyph FreeSerifBoldItalic9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 6, 13, 7, 1, -11 }, // 0x21 '!' + { 10, 6, 5, 10, 3, -11 }, // 0x22 '"' + { 14, 11, 13, 9, -1, -12 }, // 0x23 '#' + { 32, 11, 15, 9, -1, -12 }, // 0x24 '$' + { 53, 14, 13, 15, 1, -11 }, // 0x25 '%' + { 76, 13, 13, 14, 0, -11 }, // 0x26 '&' + { 98, 2, 5, 5, 3, -11 }, // 0x27 ''' + { 100, 5, 16, 6, 1, -11 }, // 0x28 '(' + { 110, 5, 16, 6, -1, -11 }, // 0x29 ')' + { 120, 8, 8, 9, 1, -11 }, // 0x2A '*' + { 128, 9, 9, 10, 0, -8 }, // 0x2B '+' + { 139, 3, 6, 5, -1, -2 }, // 0x2C ',' + { 142, 5, 2, 6, 0, -4 }, // 0x2D '-' + { 144, 3, 3, 4, 0, -1 }, // 0x2E '.' + { 146, 7, 12, 6, 0, -11 }, // 0x2F '/' + { 157, 9, 13, 9, 0, -11 }, // 0x30 '0' + { 172, 8, 13, 9, 0, -11 }, // 0x31 '1' + { 185, 9, 13, 9, 0, -11 }, // 0x32 '2' + { 200, 9, 13, 9, 0, -11 }, // 0x33 '3' + { 215, 9, 12, 9, 0, -11 }, // 0x34 '4' + { 229, 9, 13, 9, 0, -11 }, // 0x35 '5' + { 244, 9, 13, 9, 1, -11 }, // 0x36 '6' + { 259, 9, 12, 9, 1, -11 }, // 0x37 '7' + { 273, 8, 13, 9, 0, -11 }, // 0x38 '8' + { 286, 9, 13, 9, 0, -11 }, // 0x39 '9' + { 301, 5, 9, 5, 0, -7 }, // 0x3A ':' + { 307, 5, 11, 5, 0, -7 }, // 0x3B ';' + { 314, 9, 10, 10, 1, -9 }, // 0x3C '<' + { 326, 9, 5, 10, 1, -6 }, // 0x3D '=' + { 332, 9, 10, 10, 1, -9 }, // 0x3E '>' + { 344, 8, 13, 9, 1, -11 }, // 0x3F '?' + { 357, 13, 13, 15, 1, -12 }, // 0x40 '@' + { 379, 12, 13, 13, 0, -11 }, // 0x41 'A' + { 399, 12, 13, 12, 0, -11 }, // 0x42 'B' + { 419, 12, 13, 11, 1, -11 }, // 0x43 'C' + { 439, 14, 13, 13, 0, -11 }, // 0x44 'D' + { 462, 13, 13, 11, 0, -11 }, // 0x45 'E' + { 484, 13, 13, 11, 0, -11 }, // 0x46 'F' + { 506, 12, 13, 13, 1, -11 }, // 0x47 'G' + { 526, 15, 13, 14, 0, -11 }, // 0x48 'H' + { 551, 8, 13, 7, 0, -11 }, // 0x49 'I' + { 564, 10, 14, 9, 0, -11 }, // 0x4A 'J' + { 582, 13, 13, 12, 0, -11 }, // 0x4B 'K' + { 604, 12, 13, 11, 0, -11 }, // 0x4C 'L' + { 624, 17, 13, 16, 0, -11 }, // 0x4D 'M' + { 652, 14, 13, 13, 0, -11 }, // 0x4E 'N' + { 675, 12, 13, 12, 1, -11 }, // 0x4F 'O' + { 695, 12, 13, 11, 0, -11 }, // 0x50 'P' + { 715, 12, 16, 12, 1, -11 }, // 0x51 'Q' + { 739, 12, 13, 12, 0, -11 }, // 0x52 'R' + { 759, 9, 13, 9, 0, -11 }, // 0x53 'S' + { 774, 11, 13, 11, 2, -11 }, // 0x54 'T' + { 792, 12, 13, 13, 2, -11 }, // 0x55 'U' + { 812, 12, 12, 13, 2, -11 }, // 0x56 'V' + { 830, 16, 12, 17, 2, -11 }, // 0x57 'W' + { 854, 13, 13, 13, 0, -11 }, // 0x58 'X' + { 876, 11, 13, 11, 2, -11 }, // 0x59 'Y' + { 894, 11, 13, 10, 0, -11 }, // 0x5A 'Z' + { 912, 8, 15, 6, -1, -11 }, // 0x5B '[' + { 927, 5, 12, 7, 2, -11 }, // 0x5C '\' + { 935, 7, 15, 6, -1, -11 }, // 0x5D ']' + { 949, 8, 7, 10, 1, -11 }, // 0x5E '^' + { 956, 9, 1, 9, 0, 3 }, // 0x5F '_' + { 958, 4, 3, 6, 2, -11 }, // 0x60 '`' + { 960, 9, 9, 9, 0, -7 }, // 0x61 'a' + { 971, 8, 14, 9, 0, -12 }, // 0x62 'b' + { 985, 8, 9, 8, 0, -7 }, // 0x63 'c' + { 994, 10, 14, 9, 0, -12 }, // 0x64 'd' + { 1012, 7, 9, 7, 0, -7 }, // 0x65 'e' + { 1020, 11, 17, 9, -2, -12 }, // 0x66 'f' + { 1044, 9, 12, 9, 0, -7 }, // 0x67 'g' + { 1058, 9, 14, 10, 0, -12 }, // 0x68 'h' + { 1074, 5, 13, 5, 1, -11 }, // 0x69 'i' + { 1083, 9, 16, 6, -1, -11 }, // 0x6A 'j' + { 1101, 10, 14, 9, 0, -12 }, // 0x6B 'k' + { 1119, 5, 14, 5, 1, -12 }, // 0x6C 'l' + { 1128, 13, 9, 14, 0, -7 }, // 0x6D 'm' + { 1143, 8, 9, 9, 0, -7 }, // 0x6E 'n' + { 1152, 8, 9, 9, 0, -7 }, // 0x6F 'o' + { 1161, 10, 12, 9, -2, -7 }, // 0x70 'p' + { 1176, 9, 12, 9, 0, -7 }, // 0x71 'q' + { 1190, 8, 8, 7, 0, -7 }, // 0x72 'r' + { 1198, 6, 9, 6, 0, -7 }, // 0x73 's' + { 1205, 5, 12, 5, 1, -10 }, // 0x74 't' + { 1213, 8, 9, 10, 1, -7 }, // 0x75 'u' + { 1222, 7, 8, 8, 1, -7 }, // 0x76 'v' + { 1229, 10, 8, 12, 1, -7 }, // 0x77 'w' + { 1239, 10, 9, 9, -1, -7 }, // 0x78 'x' + { 1251, 9, 12, 8, -1, -7 }, // 0x79 'y' + { 1265, 8, 9, 7, 0, -7 }, // 0x7A 'z' + { 1274, 8, 16, 6, 0, -12 }, // 0x7B '{' + { 1290, 1, 12, 5, 2, -11 }, // 0x7C '|' + { 1292, 8, 16, 6, -2, -12 }, // 0x7D '}' + { 1308, 8, 2, 10, 1, -4 } }; // 0x7E '~' + +const GFXfont FreeSerifBoldItalic9pt7b PROGMEM = { + (uint8_t *)FreeSerifBoldItalic9pt7bBitmaps, + (GFXglyph *)FreeSerifBoldItalic9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 1982 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic12pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic12pt7b.h new file mode 100644 index 0000000..52332a7 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic12pt7b.h @@ -0,0 +1,271 @@ +const uint8_t FreeSerifItalic12pt7bBitmaps[] PROGMEM = { + 0x0C, 0x31, 0xC6, 0x18, 0x43, 0x0C, 0x20, 0x84, 0x10, 0x03, 0x0C, 0x30, + 0x66, 0xCD, 0x12, 0x24, 0x51, 0x00, 0x03, 0x10, 0x11, 0x80, 0x8C, 0x0C, + 0x40, 0x46, 0x1F, 0xFC, 0x21, 0x01, 0x18, 0x18, 0x80, 0x84, 0x3F, 0xF8, + 0x62, 0x02, 0x30, 0x31, 0x01, 0x08, 0x08, 0xC0, 0x00, 0x40, 0x08, 0x07, + 0xC0, 0xCA, 0x18, 0xA1, 0x92, 0x19, 0x01, 0xD0, 0x0F, 0x00, 0x78, 0x03, + 0xC0, 0x2E, 0x02, 0x64, 0x46, 0x44, 0x64, 0x46, 0x64, 0xC1, 0xF0, 0x08, + 0x00, 0x80, 0x00, 0x08, 0x0F, 0x0C, 0x0C, 0x7C, 0x0C, 0x22, 0x06, 0x12, + 0x06, 0x09, 0x03, 0x09, 0x01, 0x84, 0x80, 0xC4, 0x8F, 0x3C, 0x4C, 0x40, + 0x4C, 0x20, 0x4E, 0x10, 0x26, 0x08, 0x23, 0x08, 0x11, 0x84, 0x10, 0xC4, + 0x08, 0x3C, 0x00, 0x00, 0xE0, 0x02, 0x60, 0x0C, 0xC0, 0x19, 0x80, 0x36, + 0x00, 0x70, 0x00, 0xC0, 0x07, 0x9F, 0x33, 0x08, 0xC3, 0x13, 0x06, 0x46, + 0x0D, 0x0C, 0x0C, 0x18, 0x1C, 0x1C, 0x5C, 0x9F, 0x1E, 0xFA, 0xA0, 0x02, + 0x08, 0x20, 0xC3, 0x06, 0x18, 0x30, 0xE1, 0x83, 0x06, 0x0C, 0x18, 0x30, + 0x60, 0x40, 0x80, 0x81, 0x00, 0x08, 0x10, 0x10, 0x20, 0x40, 0xC1, 0x83, + 0x06, 0x0C, 0x18, 0x70, 0xC1, 0x83, 0x0C, 0x10, 0x41, 0x04, 0x00, 0x18, + 0x18, 0x18, 0x93, 0x74, 0x38, 0xD7, 0x93, 0x18, 0x18, 0x04, 0x00, 0x80, + 0x10, 0x02, 0x00, 0x41, 0xFF, 0xC1, 0x00, 0x20, 0x04, 0x00, 0x80, 0x10, + 0x00, 0x6C, 0x95, 0x00, 0xF8, 0xFC, 0x00, 0x40, 0x18, 0x02, 0x00, 0xC0, + 0x30, 0x06, 0x01, 0x80, 0x20, 0x0C, 0x01, 0x00, 0x60, 0x18, 0x03, 0x00, + 0xC0, 0x10, 0x06, 0x00, 0x07, 0x81, 0x98, 0x61, 0x18, 0x33, 0x06, 0xC0, + 0xD8, 0x1B, 0x03, 0xE0, 0xF8, 0x1F, 0x03, 0x60, 0x6C, 0x19, 0x83, 0x10, + 0xC3, 0x30, 0x3C, 0x00, 0x01, 0x87, 0xC0, 0xC0, 0x60, 0x30, 0x18, 0x18, + 0x0C, 0x06, 0x07, 0x03, 0x01, 0x80, 0xC0, 0xC0, 0x60, 0x30, 0xFE, 0x00, + 0x0F, 0x0C, 0x64, 0x0C, 0x03, 0x00, 0xC0, 0x20, 0x18, 0x0C, 0x02, 0x01, + 0x00, 0x80, 0x40, 0x20, 0x10, 0x2F, 0xF0, 0x07, 0x86, 0x30, 0x0C, 0x03, + 0x01, 0x81, 0x81, 0xF0, 0x1E, 0x03, 0x80, 0x60, 0x18, 0x06, 0x01, 0x00, + 0xCC, 0x63, 0xE0, 0x00, 0x20, 0x0C, 0x03, 0x80, 0xA0, 0x2C, 0x09, 0x82, + 0x30, 0x84, 0x31, 0x8C, 0x33, 0x06, 0x7F, 0xE0, 0x30, 0x06, 0x00, 0x80, + 0x30, 0x03, 0xE1, 0x80, 0x20, 0x06, 0x00, 0xF0, 0x0F, 0x00, 0x60, 0x06, + 0x00, 0xC0, 0x18, 0x03, 0x00, 0x40, 0x18, 0x02, 0x30, 0x87, 0xE0, 0x00, + 0x70, 0x3C, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x7F, 0x07, 0x18, 0x60, + 0xCE, 0x0C, 0xC0, 0xCC, 0x0C, 0xC0, 0xCC, 0x18, 0x41, 0x86, 0x30, 0x3E, + 0x00, 0x7F, 0xF0, 0x18, 0x03, 0x00, 0xC0, 0x10, 0x06, 0x01, 0x80, 0x30, + 0x0C, 0x01, 0x00, 0x60, 0x08, 0x03, 0x00, 0xC0, 0x10, 0x06, 0x00, 0x0F, + 0x83, 0x18, 0xC1, 0x98, 0x33, 0x06, 0x71, 0x87, 0x60, 0x70, 0x17, 0x0C, + 0x71, 0x07, 0x60, 0x6C, 0x0D, 0x81, 0xB0, 0x63, 0x1C, 0x3E, 0x00, 0x07, + 0x83, 0x18, 0xC1, 0x18, 0x36, 0x06, 0xC0, 0xD8, 0x1B, 0x07, 0x60, 0xE6, + 0x38, 0x7F, 0x00, 0xC0, 0x30, 0x0C, 0x07, 0x03, 0xC0, 0xC0, 0x00, 0x33, + 0x30, 0x00, 0x00, 0xCC, 0xC0, 0x18, 0xC6, 0x00, 0x00, 0x00, 0x03, 0x18, + 0x44, 0x40, 0x00, 0x00, 0x03, 0x00, 0xF0, 0x38, 0x1E, 0x07, 0x80, 0xE0, + 0x0F, 0x00, 0x1C, 0x00, 0x78, 0x01, 0xE0, 0x07, 0x00, 0x10, 0xFF, 0xF0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0x00, 0x0C, 0x00, 0xF0, 0x01, + 0xC0, 0x07, 0x80, 0x1E, 0x00, 0x70, 0x0F, 0x03, 0xC1, 0xE0, 0x78, 0x0E, + 0x00, 0x80, 0x00, 0x3E, 0x21, 0x90, 0x60, 0x30, 0x38, 0x38, 0x30, 0x30, + 0x20, 0x20, 0x10, 0x00, 0x00, 0x06, 0x03, 0x01, 0x80, 0x07, 0xE0, 0x1C, + 0x18, 0x30, 0x04, 0x60, 0x02, 0x61, 0xDA, 0xC3, 0x31, 0xC6, 0x31, 0xC4, + 0x31, 0xCC, 0x31, 0xCC, 0x21, 0xCC, 0x62, 0x6C, 0xE4, 0x67, 0x38, 0x30, + 0x00, 0x1C, 0x08, 0x07, 0xF0, 0x00, 0x20, 0x00, 0xC0, 0x03, 0x80, 0x0B, + 0x00, 0x16, 0x00, 0x4E, 0x00, 0x9C, 0x02, 0x18, 0x08, 0x30, 0x1F, 0xE0, + 0x40, 0xC1, 0x81, 0xC2, 0x03, 0x8C, 0x07, 0x3C, 0x1F, 0x80, 0x1F, 0xF0, + 0x1C, 0x60, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x38, 0x60, 0xC3, 0x03, 0xF0, + 0x1C, 0x30, 0x60, 0x61, 0x81, 0x86, 0x06, 0x38, 0x18, 0xC0, 0xC3, 0x06, + 0x3F, 0xF0, 0x01, 0xF9, 0x06, 0x0F, 0x1C, 0x06, 0x38, 0x02, 0x30, 0x02, + 0x60, 0x00, 0x60, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, + 0xC0, 0x00, 0xC0, 0x08, 0x60, 0x10, 0x30, 0x60, 0x1F, 0x80, 0x1F, 0xF0, + 0x07, 0x0C, 0x06, 0x06, 0x06, 0x06, 0x06, 0x03, 0x0E, 0x03, 0x0C, 0x03, + 0x0C, 0x03, 0x1C, 0x03, 0x1C, 0x07, 0x18, 0x06, 0x18, 0x06, 0x38, 0x0C, + 0x30, 0x18, 0x30, 0x70, 0xFF, 0x80, 0x1F, 0xFF, 0x07, 0x07, 0x06, 0x02, + 0x06, 0x02, 0x06, 0x00, 0x0E, 0x10, 0x0C, 0x30, 0x0F, 0xF0, 0x1C, 0x20, + 0x18, 0x20, 0x18, 0x00, 0x18, 0x00, 0x38, 0x04, 0x30, 0x08, 0x30, 0x38, + 0xFF, 0xF8, 0x1F, 0xFF, 0x07, 0x07, 0x07, 0x02, 0x06, 0x02, 0x06, 0x00, + 0x0E, 0x10, 0x0C, 0x30, 0x0F, 0xF0, 0x1C, 0x20, 0x1C, 0x20, 0x18, 0x00, + 0x18, 0x00, 0x38, 0x00, 0x30, 0x00, 0x30, 0x00, 0xFC, 0x00, 0x01, 0xF1, + 0x06, 0x0F, 0x18, 0x07, 0x38, 0x02, 0x30, 0x02, 0x60, 0x00, 0x60, 0x00, + 0xE0, 0x00, 0xC0, 0x7F, 0xC0, 0x1C, 0xC0, 0x1C, 0xC0, 0x18, 0xC0, 0x18, + 0x60, 0x18, 0x30, 0x38, 0x0F, 0xC0, 0x1F, 0xC7, 0xE0, 0xE0, 0x70, 0x18, + 0x0E, 0x03, 0x01, 0x80, 0x60, 0x30, 0x1C, 0x0E, 0x03, 0x01, 0x80, 0x7F, + 0xF0, 0x1C, 0x06, 0x03, 0x01, 0xC0, 0x60, 0x30, 0x0C, 0x06, 0x03, 0x81, + 0xC0, 0x60, 0x38, 0x0C, 0x06, 0x07, 0xE3, 0xF0, 0x1F, 0x83, 0x81, 0x80, + 0xC0, 0x60, 0x70, 0x30, 0x18, 0x1C, 0x0C, 0x06, 0x03, 0x03, 0x81, 0x80, + 0xC1, 0xF8, 0x03, 0xF0, 0x0C, 0x00, 0xC0, 0x1C, 0x01, 0x80, 0x18, 0x03, + 0x80, 0x30, 0x03, 0x00, 0x30, 0x07, 0x00, 0x60, 0x06, 0x0C, 0xE0, 0xCC, + 0x07, 0x80, 0x1F, 0xCF, 0x83, 0x83, 0x81, 0x81, 0x00, 0xC3, 0x00, 0x62, + 0x00, 0x72, 0x00, 0x36, 0x00, 0x1E, 0x00, 0x1D, 0x80, 0x0C, 0xE0, 0x06, + 0x30, 0x03, 0x1C, 0x03, 0x87, 0x01, 0x81, 0x80, 0xC0, 0xE1, 0xF9, 0xFC, + 0x1F, 0xC0, 0x1C, 0x00, 0x60, 0x01, 0x80, 0x06, 0x00, 0x38, 0x00, 0xC0, + 0x03, 0x00, 0x1C, 0x00, 0x60, 0x01, 0x80, 0x06, 0x00, 0x38, 0x0C, 0xC0, + 0x23, 0x03, 0xBF, 0xFE, 0x0F, 0x00, 0x78, 0x38, 0x07, 0x81, 0xC0, 0x38, + 0x0E, 0x02, 0xC0, 0x70, 0x3E, 0x05, 0xC1, 0x70, 0x2E, 0x13, 0x01, 0x31, + 0x98, 0x11, 0x89, 0xC0, 0x8C, 0x8C, 0x04, 0x6C, 0x60, 0x23, 0x43, 0x02, + 0x1C, 0x38, 0x10, 0xE1, 0x81, 0x86, 0x1C, 0x1F, 0x23, 0xF8, 0x1E, 0x07, + 0xC1, 0xC0, 0x60, 0x70, 0x10, 0x1C, 0x0C, 0x05, 0x82, 0x02, 0x60, 0x80, + 0x9C, 0x60, 0x23, 0x10, 0x10, 0xC4, 0x04, 0x19, 0x01, 0x06, 0xC0, 0x40, + 0xE0, 0x20, 0x38, 0x08, 0x0E, 0x06, 0x01, 0x03, 0xE0, 0x40, 0x01, 0xF0, + 0x0C, 0x10, 0x30, 0x10, 0xC0, 0x33, 0x00, 0x6E, 0x00, 0xD8, 0x01, 0xF0, + 0x03, 0xC0, 0x0D, 0x80, 0x1B, 0x00, 0x76, 0x00, 0xCC, 0x03, 0x08, 0x0C, + 0x18, 0x70, 0x0F, 0x80, 0x1F, 0xF0, 0x1C, 0x60, 0x60, 0xC1, 0x83, 0x06, + 0x0C, 0x38, 0x30, 0xC1, 0x83, 0x0E, 0x1F, 0xE0, 0x60, 0x01, 0x80, 0x06, + 0x00, 0x38, 0x00, 0xC0, 0x03, 0x00, 0x3F, 0x00, 0x01, 0xF0, 0x06, 0x10, + 0x30, 0x30, 0xC0, 0x33, 0x00, 0x66, 0x00, 0xD8, 0x01, 0xB0, 0x03, 0xE0, + 0x0F, 0x80, 0x1B, 0x00, 0x36, 0x00, 0xCC, 0x03, 0x98, 0x06, 0x18, 0x18, + 0x18, 0xC0, 0x0E, 0x00, 0x20, 0x01, 0xF8, 0x36, 0x7F, 0x80, 0x1F, 0xF0, + 0x1C, 0x60, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x38, 0x70, 0xC3, 0x83, 0xF8, + 0x1D, 0xC0, 0x63, 0x01, 0x8C, 0x06, 0x18, 0x38, 0x60, 0xC1, 0xC3, 0x03, + 0x3F, 0x0F, 0x07, 0x90, 0xC7, 0x18, 0x21, 0x82, 0x18, 0x01, 0xC0, 0x0E, + 0x00, 0x70, 0x03, 0x80, 0x1C, 0x00, 0xC4, 0x0C, 0x40, 0xC6, 0x08, 0xE1, + 0x89, 0xE0, 0x7F, 0xFE, 0xC7, 0x1D, 0x0C, 0x14, 0x18, 0x20, 0x70, 0x00, + 0xE0, 0x01, 0x80, 0x03, 0x00, 0x0E, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, + 0x01, 0xC0, 0x03, 0x00, 0x0E, 0x00, 0x7F, 0x80, 0x7E, 0x1F, 0x38, 0x0C, + 0x38, 0x0C, 0x30, 0x08, 0x30, 0x08, 0x70, 0x08, 0x70, 0x10, 0x60, 0x10, + 0x60, 0x10, 0xE0, 0x10, 0xC0, 0x20, 0xC0, 0x20, 0xC0, 0x60, 0xC0, 0x40, + 0x61, 0x80, 0x3F, 0x00, 0xFC, 0x3E, 0xE0, 0x18, 0xC0, 0x21, 0x80, 0xC3, + 0x81, 0x07, 0x04, 0x0E, 0x08, 0x0C, 0x20, 0x18, 0x80, 0x31, 0x00, 0x64, + 0x00, 0xF0, 0x01, 0xE0, 0x01, 0x80, 0x02, 0x00, 0x04, 0x00, 0xFD, 0xF8, + 0xF7, 0x07, 0x06, 0x30, 0x60, 0x63, 0x07, 0x04, 0x30, 0x70, 0x83, 0x8F, + 0x08, 0x38, 0xB1, 0x03, 0x93, 0x10, 0x19, 0x32, 0x01, 0xA3, 0x20, 0x1A, + 0x34, 0x01, 0xC3, 0x40, 0x1C, 0x38, 0x01, 0x83, 0x00, 0x18, 0x30, 0x01, + 0x02, 0x00, 0x1F, 0x9F, 0x0E, 0x06, 0x06, 0x04, 0x07, 0x08, 0x03, 0x10, + 0x03, 0x20, 0x03, 0xC0, 0x01, 0x80, 0x01, 0xC0, 0x03, 0xC0, 0x06, 0xE0, + 0x0C, 0x60, 0x18, 0x60, 0x30, 0x70, 0x70, 0x78, 0xF8, 0xFC, 0xFC, 0xFB, + 0x81, 0x8C, 0x08, 0x60, 0x83, 0x8C, 0x0C, 0xC0, 0x64, 0x03, 0xC0, 0x0C, + 0x00, 0xE0, 0x07, 0x00, 0x30, 0x01, 0x80, 0x1C, 0x00, 0xC0, 0x1F, 0xC0, + 0x1F, 0xFE, 0x30, 0x38, 0xC0, 0xF1, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, + 0x70, 0x01, 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x38, 0x00, 0xE0, 0x01, 0xC0, + 0x47, 0x01, 0x1C, 0x06, 0x7F, 0xF8, 0x07, 0x04, 0x08, 0x08, 0x08, 0x18, + 0x10, 0x10, 0x10, 0x20, 0x20, 0x20, 0x20, 0x40, 0x40, 0x40, 0x80, 0x80, + 0x80, 0xE0, 0xC0, 0xC0, 0x40, 0x60, 0x20, 0x30, 0x30, 0x18, 0x18, 0x08, + 0x0C, 0x04, 0x06, 0x06, 0x03, 0x03, 0x0E, 0x04, 0x08, 0x10, 0x60, 0x81, + 0x02, 0x04, 0x18, 0x20, 0x40, 0x81, 0x02, 0x08, 0x10, 0x20, 0x47, 0x80, + 0x0C, 0x03, 0x81, 0xE0, 0x4C, 0x33, 0x08, 0x66, 0x19, 0x03, 0xC0, 0xC0, + 0xFF, 0xF0, 0xCE, 0x63, 0x07, 0xA0, 0xCE, 0x18, 0x63, 0x04, 0x60, 0xC6, + 0x0C, 0xC0, 0xCC, 0x18, 0xC3, 0x8C, 0x5A, 0x79, 0xC0, 0x38, 0x06, 0x01, + 0x80, 0x40, 0x30, 0x0C, 0xE3, 0xCC, 0xC3, 0x70, 0xD8, 0x36, 0x19, 0x06, + 0xC3, 0x30, 0x8C, 0xC3, 0xE0, 0x0F, 0x0C, 0xCC, 0x6C, 0x06, 0x06, 0x03, + 0x01, 0x80, 0xC0, 0x73, 0x1E, 0x00, 0x00, 0x70, 0x01, 0x80, 0x0C, 0x00, + 0x60, 0x02, 0x03, 0xF0, 0x31, 0x83, 0x08, 0x30, 0xC3, 0x06, 0x18, 0x31, + 0x81, 0x8C, 0x18, 0x61, 0xCB, 0x16, 0x8F, 0x38, 0x07, 0x19, 0x31, 0x63, + 0x62, 0xEC, 0xD0, 0xC0, 0xC0, 0xE6, 0x78, 0x00, 0x38, 0x01, 0x30, 0x0C, + 0x00, 0x20, 0x01, 0x80, 0x06, 0x00, 0xFE, 0x00, 0x40, 0x03, 0x00, 0x0C, + 0x00, 0x30, 0x00, 0x80, 0x06, 0x00, 0x18, 0x00, 0x60, 0x01, 0x80, 0x04, + 0x00, 0x30, 0x00, 0xC0, 0x02, 0x00, 0x90, 0x03, 0x80, 0x00, 0x07, 0xC0, + 0xC7, 0x18, 0x61, 0x86, 0x18, 0xE1, 0x8C, 0x07, 0x80, 0x80, 0x1C, 0x00, + 0xF0, 0x33, 0x84, 0x18, 0x80, 0x88, 0x08, 0x61, 0x03, 0xE0, 0x1C, 0x00, + 0xC0, 0x0C, 0x00, 0xC0, 0x18, 0x01, 0x8E, 0x1B, 0x61, 0xC6, 0x38, 0x63, + 0x8C, 0x30, 0xC3, 0x0C, 0x60, 0xC6, 0x1A, 0x61, 0xA4, 0x1C, 0x18, 0xC6, + 0x00, 0x0B, 0xC6, 0x23, 0x18, 0x8C, 0x63, 0x5C, 0x01, 0x80, 0xC0, 0x60, + 0x00, 0x00, 0x0C, 0x1E, 0x02, 0x03, 0x01, 0x80, 0xC0, 0x40, 0x60, 0x30, + 0x18, 0x08, 0x0C, 0x06, 0x02, 0x1B, 0x0F, 0x00, 0x1C, 0x01, 0x80, 0x30, + 0x06, 0x01, 0x80, 0x33, 0xC6, 0x30, 0x88, 0x32, 0x06, 0x80, 0xF0, 0x1B, + 0x06, 0x60, 0xC4, 0x18, 0xD2, 0x0C, 0x3C, 0x61, 0x86, 0x18, 0xC3, 0x0C, + 0x21, 0x86, 0x18, 0x43, 0x2D, 0x38, 0x78, 0xE7, 0x0D, 0xB5, 0x8D, 0x1C, + 0xC7, 0x0C, 0x63, 0x8E, 0x31, 0x86, 0x30, 0xC3, 0x18, 0xC1, 0x0C, 0x61, + 0x84, 0xB0, 0xC6, 0xB0, 0x63, 0x80, 0x78, 0xE1, 0xB6, 0x14, 0x63, 0x84, + 0x38, 0xC3, 0x0C, 0x70, 0x86, 0x18, 0x61, 0x96, 0x1A, 0xC1, 0xC0, 0x0F, + 0x06, 0x63, 0x0D, 0x83, 0x60, 0xF0, 0x3C, 0x1B, 0x06, 0xC3, 0x39, 0x87, + 0x80, 0x1E, 0xF0, 0x39, 0xC1, 0x86, 0x0C, 0x30, 0xC1, 0x86, 0x0C, 0x30, + 0xC3, 0x06, 0x18, 0x60, 0xC6, 0x07, 0xC0, 0x60, 0x03, 0x00, 0x18, 0x00, + 0xC0, 0x1F, 0x00, 0x07, 0x81, 0x9C, 0x63, 0x98, 0x76, 0x0C, 0xC1, 0xB0, + 0x76, 0x0E, 0xC3, 0x98, 0xB1, 0xE6, 0x00, 0x80, 0x30, 0x06, 0x00, 0xC0, + 0xFC, 0x79, 0x8F, 0xC5, 0x07, 0x03, 0x01, 0x80, 0xC0, 0xC0, 0x60, 0x30, + 0x10, 0x00, 0x1E, 0x98, 0xCC, 0x27, 0x11, 0x80, 0xE0, 0x39, 0x0C, 0x86, + 0x62, 0x2E, 0x00, 0x08, 0x67, 0xCC, 0x30, 0xC6, 0x18, 0x61, 0x8C, 0x34, + 0xE0, 0xF0, 0xCC, 0x19, 0x83, 0x30, 0xC6, 0x18, 0x87, 0x31, 0x66, 0x3C, + 0xCB, 0x1A, 0x6B, 0x8E, 0x00, 0x70, 0xCC, 0x33, 0x04, 0xC2, 0x18, 0x86, + 0x41, 0x90, 0x68, 0x1C, 0x06, 0x01, 0x00, 0x61, 0x0F, 0x84, 0x36, 0x30, + 0xDC, 0xC1, 0x35, 0x08, 0xD4, 0x23, 0x91, 0x0E, 0x48, 0x30, 0xE0, 0xC3, + 0x02, 0x08, 0x00, 0x0C, 0x63, 0x4A, 0x07, 0x00, 0x70, 0x06, 0x00, 0x20, + 0x07, 0x00, 0xB0, 0x0B, 0x21, 0x14, 0xE1, 0x80, 0x38, 0x63, 0x0C, 0x30, + 0x86, 0x10, 0xC4, 0x0C, 0x81, 0xA0, 0x34, 0x07, 0x00, 0x60, 0x08, 0x02, + 0x00, 0x40, 0x10, 0x04, 0x07, 0x00, 0x1F, 0x90, 0x80, 0x80, 0xC0, 0xC0, + 0x40, 0x60, 0x60, 0x60, 0x38, 0x3E, 0x03, 0xA0, 0x60, 0x00, 0x83, 0x81, + 0x01, 0x80, 0xC0, 0x40, 0x60, 0x30, 0x10, 0x10, 0x1C, 0x06, 0x03, 0x03, + 0x01, 0x80, 0xC0, 0x40, 0x60, 0x30, 0x18, 0x07, 0x00, 0xFF, 0xFF, 0x07, + 0x00, 0xC0, 0x60, 0x30, 0x10, 0x18, 0x0C, 0x06, 0x06, 0x03, 0x01, 0x80, + 0x60, 0x40, 0x60, 0x30, 0x10, 0x18, 0x0C, 0x06, 0x06, 0x06, 0x00, 0x78, + 0x18, 0x8C, 0x0F, 0x00 }; + +const GFXglyph FreeSerifItalic12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 6, 0, 1 }, // 0x20 ' ' + { 0, 6, 16, 8, 1, -15 }, // 0x21 '!' + { 12, 7, 6, 8, 3, -15 }, // 0x22 '"' + { 18, 13, 16, 12, 0, -15 }, // 0x23 '#' + { 44, 12, 20, 12, 0, -17 }, // 0x24 '$' + { 74, 17, 17, 20, 2, -16 }, // 0x25 '%' + { 111, 15, 16, 19, 2, -15 }, // 0x26 '&' + { 141, 2, 6, 5, 4, -15 }, // 0x27 ''' + { 143, 7, 20, 8, 1, -15 }, // 0x28 '(' + { 161, 7, 20, 8, 0, -15 }, // 0x29 ')' + { 179, 8, 10, 12, 4, -15 }, // 0x2A '*' + { 189, 11, 11, 16, 2, -10 }, // 0x2B '+' + { 205, 3, 6, 6, 0, -2 }, // 0x2C ',' + { 208, 5, 1, 8, 1, -5 }, // 0x2D '-' + { 209, 2, 3, 6, 1, -2 }, // 0x2E '.' + { 210, 11, 16, 7, 0, -15 }, // 0x2F '/' + { 232, 11, 17, 12, 1, -16 }, // 0x30 '0' + { 256, 9, 17, 12, 1, -16 }, // 0x31 '1' + { 276, 10, 15, 12, 1, -14 }, // 0x32 '2' + { 295, 10, 16, 12, 1, -15 }, // 0x33 '3' + { 315, 11, 16, 12, 0, -15 }, // 0x34 '4' + { 337, 11, 16, 12, 0, -15 }, // 0x35 '5' + { 359, 12, 17, 12, 1, -16 }, // 0x36 '6' + { 385, 11, 16, 12, 2, -15 }, // 0x37 '7' + { 407, 11, 17, 12, 1, -16 }, // 0x38 '8' + { 431, 11, 17, 12, 1, -16 }, // 0x39 '9' + { 455, 4, 11, 6, 1, -10 }, // 0x3A ':' + { 461, 5, 14, 6, 0, -10 }, // 0x3B ';' + { 470, 12, 13, 14, 1, -12 }, // 0x3C '<' + { 490, 12, 6, 16, 2, -8 }, // 0x3D '=' + { 499, 12, 13, 14, 2, -12 }, // 0x3E '>' + { 519, 9, 16, 11, 3, -15 }, // 0x3F '?' + { 537, 16, 16, 19, 2, -15 }, // 0x40 '@' + { 569, 15, 15, 16, 0, -14 }, // 0x41 'A' + { 598, 14, 16, 14, 0, -15 }, // 0x42 'B' + { 626, 16, 16, 15, 1, -15 }, // 0x43 'C' + { 658, 16, 16, 17, 0, -15 }, // 0x44 'D' + { 690, 16, 16, 14, 0, -15 }, // 0x45 'E' + { 722, 16, 16, 14, 0, -15 }, // 0x46 'F' + { 754, 16, 16, 17, 1, -15 }, // 0x47 'G' + { 786, 19, 16, 17, 0, -15 }, // 0x48 'H' + { 824, 9, 16, 8, 0, -15 }, // 0x49 'I' + { 842, 12, 16, 10, 0, -15 }, // 0x4A 'J' + { 866, 17, 16, 15, 0, -15 }, // 0x4B 'K' + { 900, 14, 16, 14, 0, -15 }, // 0x4C 'L' + { 928, 21, 16, 20, 0, -15 }, // 0x4D 'M' + { 970, 18, 16, 16, 0, -15 }, // 0x4E 'N' + { 1006, 15, 16, 16, 1, -15 }, // 0x4F 'O' + { 1036, 14, 16, 14, 0, -15 }, // 0x50 'P' + { 1064, 15, 20, 16, 1, -15 }, // 0x51 'Q' + { 1102, 14, 16, 15, 0, -15 }, // 0x52 'R' + { 1130, 12, 16, 11, 0, -15 }, // 0x53 'S' + { 1154, 15, 16, 14, 2, -15 }, // 0x54 'T' + { 1184, 16, 16, 17, 3, -15 }, // 0x55 'U' + { 1216, 15, 16, 16, 3, -15 }, // 0x56 'V' + { 1246, 20, 16, 21, 3, -15 }, // 0x57 'W' + { 1286, 16, 16, 16, 0, -15 }, // 0x58 'X' + { 1318, 13, 16, 14, 3, -15 }, // 0x59 'Y' + { 1344, 15, 16, 14, 0, -15 }, // 0x5A 'Z' + { 1374, 8, 20, 9, 1, -15 }, // 0x5B '[' + { 1394, 8, 16, 12, 3, -15 }, // 0x5C '\' + { 1410, 7, 20, 9, 1, -15 }, // 0x5D ']' + { 1428, 10, 9, 10, 0, -15 }, // 0x5E '^' + { 1440, 12, 1, 12, 0, 3 }, // 0x5F '_' + { 1442, 4, 4, 6, 3, -15 }, // 0x60 '`' + { 1444, 12, 11, 12, 0, -10 }, // 0x61 'a' + { 1461, 10, 16, 11, 1, -15 }, // 0x62 'b' + { 1481, 9, 11, 10, 1, -10 }, // 0x63 'c' + { 1494, 13, 16, 12, 0, -15 }, // 0x64 'd' + { 1520, 8, 11, 10, 1, -10 }, // 0x65 'e' + { 1531, 14, 22, 10, -2, -16 }, // 0x66 'f' + { 1570, 12, 16, 11, -1, -10 }, // 0x67 'g' + { 1594, 12, 16, 12, 0, -15 }, // 0x68 'h' + { 1618, 5, 16, 6, 1, -15 }, // 0x69 'i' + { 1628, 9, 21, 7, -2, -15 }, // 0x6A 'j' + { 1652, 11, 16, 11, 0, -15 }, // 0x6B 'k' + { 1674, 6, 16, 6, 1, -15 }, // 0x6C 'l' + { 1686, 17, 11, 17, 0, -10 }, // 0x6D 'm' + { 1710, 12, 11, 12, 0, -10 }, // 0x6E 'n' + { 1727, 10, 11, 11, 1, -10 }, // 0x6F 'o' + { 1741, 13, 16, 11, -2, -10 }, // 0x70 'p' + { 1767, 11, 16, 12, 0, -10 }, // 0x71 'q' + { 1789, 9, 11, 9, 0, -10 }, // 0x72 'r' + { 1802, 9, 11, 8, 0, -10 }, // 0x73 's' + { 1815, 6, 13, 6, 1, -12 }, // 0x74 't' + { 1825, 11, 11, 12, 1, -10 }, // 0x75 'u' + { 1841, 10, 11, 11, 1, -10 }, // 0x76 'v' + { 1855, 14, 11, 16, 2, -10 }, // 0x77 'w' + { 1875, 12, 11, 10, -1, -10 }, // 0x78 'x' + { 1892, 11, 16, 11, 0, -10 }, // 0x79 'y' + { 1914, 9, 13, 9, 0, -10 }, // 0x7A 'z' + { 1929, 9, 21, 10, 1, -16 }, // 0x7B '{' + { 1953, 1, 16, 7, 3, -15 }, // 0x7C '|' + { 1955, 9, 21, 10, 0, -16 }, // 0x7D '}' + { 1979, 11, 3, 13, 1, -6 } }; // 0x7E '~' + +const GFXfont FreeSerifItalic12pt7b PROGMEM = { + (uint8_t *)FreeSerifItalic12pt7bBitmaps, + (GFXglyph *)FreeSerifItalic12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 2656 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic18pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic18pt7b.h new file mode 100644 index 0000000..666ae7e --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic18pt7b.h @@ -0,0 +1,450 @@ +const uint8_t FreeSerifItalic18pt7bBitmaps[] PROGMEM = { + 0x01, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0x81, 0xE0, 0x70, 0x1C, 0x06, 0x01, + 0x80, 0xC0, 0x30, 0x0C, 0x02, 0x01, 0x80, 0x40, 0x10, 0x00, 0x00, 0x01, + 0x80, 0xF0, 0x3C, 0x06, 0x00, 0x38, 0x77, 0x8F, 0x78, 0xF7, 0x0E, 0x60, + 0xE6, 0x0C, 0xC1, 0x8C, 0x18, 0x81, 0x00, 0x00, 0x60, 0xC0, 0x0C, 0x38, + 0x03, 0x86, 0x00, 0x60, 0xC0, 0x0C, 0x38, 0x03, 0x06, 0x00, 0x60, 0xC0, + 0xFF, 0xFF, 0x1F, 0xFF, 0xE0, 0x61, 0xC0, 0x1C, 0x30, 0x03, 0x06, 0x00, + 0x61, 0xC0, 0x18, 0x30, 0x3F, 0xFF, 0xC7, 0xFF, 0xF8, 0x18, 0x30, 0x03, + 0x0E, 0x00, 0xE1, 0x80, 0x18, 0x30, 0x03, 0x0C, 0x00, 0xC1, 0x80, 0x18, + 0x70, 0x00, 0x00, 0x08, 0x00, 0x30, 0x00, 0x40, 0x0F, 0xC0, 0x61, 0xE1, + 0x86, 0xC6, 0x0D, 0x8C, 0x1A, 0x18, 0x24, 0x38, 0xC0, 0x39, 0x80, 0x7F, + 0x00, 0x7E, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x7C, 0x00, 0xDC, 0x03, 0x38, + 0x06, 0x32, 0x0C, 0x64, 0x18, 0xDC, 0x71, 0xB8, 0xC6, 0x39, 0x8C, 0x3F, + 0x30, 0x1F, 0x80, 0x18, 0x00, 0x30, 0x00, 0x60, 0x00, 0x07, 0x80, 0x60, + 0x0F, 0xE0, 0xE0, 0x0F, 0x0F, 0xB0, 0x0E, 0x04, 0x30, 0x07, 0x02, 0x18, + 0x07, 0x01, 0x18, 0x03, 0x00, 0x8C, 0x01, 0x80, 0x8C, 0x00, 0xC0, 0x4C, + 0x00, 0x60, 0x66, 0x1F, 0x30, 0x66, 0x1F, 0xCC, 0x63, 0x1C, 0x67, 0xE3, + 0x1C, 0x19, 0xE1, 0x1C, 0x04, 0x01, 0x8C, 0x02, 0x00, 0x8E, 0x01, 0x00, + 0xC7, 0x00, 0x80, 0xC3, 0x00, 0x80, 0x61, 0x80, 0xC0, 0x60, 0xC0, 0xC0, + 0x20, 0x70, 0xE0, 0x30, 0x1F, 0xC0, 0x10, 0x07, 0xC0, 0x00, 0x1E, 0x00, + 0x00, 0xFC, 0x00, 0x07, 0x18, 0x00, 0x18, 0x60, 0x00, 0xE1, 0x80, 0x03, + 0x8C, 0x00, 0x0E, 0x60, 0x00, 0x3B, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, + 0x00, 0x7F, 0x1F, 0xC3, 0x3C, 0x1C, 0x38, 0x70, 0x61, 0xE1, 0xE3, 0x87, + 0x07, 0x8C, 0x3C, 0x0F, 0x60, 0xF0, 0x3D, 0x03, 0xC0, 0x78, 0x0F, 0x01, + 0xE0, 0x3E, 0x07, 0xC0, 0x7C, 0x77, 0x84, 0xFF, 0x8F, 0xE1, 0xF8, 0x0F, + 0x00, 0x3B, 0xDE, 0xE7, 0x33, 0x18, 0x80, 0x00, 0x80, 0x80, 0x80, 0x80, + 0xC0, 0xC0, 0xE0, 0x60, 0x70, 0x38, 0x18, 0x0C, 0x0E, 0x07, 0x03, 0x01, + 0x80, 0xC0, 0x60, 0x30, 0x18, 0x0C, 0x06, 0x01, 0x00, 0x80, 0x40, 0x30, + 0x08, 0x04, 0x02, 0x00, 0x04, 0x01, 0x00, 0x80, 0x60, 0x10, 0x08, 0x04, + 0x03, 0x01, 0x80, 0xC0, 0x60, 0x30, 0x18, 0x0C, 0x0E, 0x07, 0x03, 0x81, + 0x80, 0xC0, 0xE0, 0x60, 0x30, 0x30, 0x18, 0x18, 0x08, 0x08, 0x08, 0x08, + 0x00, 0x06, 0x00, 0x60, 0x06, 0x0C, 0x43, 0xE4, 0xF1, 0x58, 0x0E, 0x00, + 0xF0, 0x74, 0xEE, 0x47, 0xC4, 0x30, 0x60, 0x06, 0x00, 0x60, 0x01, 0x80, + 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, + 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, + 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x31, 0xCE, + 0x31, 0x08, 0x98, 0xFF, 0xFF, 0x6F, 0xF6, 0x00, 0x06, 0x00, 0x0E, 0x00, + 0x0C, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x30, 0x00, 0x70, 0x00, 0x60, 0x00, + 0xE0, 0x00, 0xC0, 0x01, 0xC0, 0x03, 0x80, 0x03, 0x00, 0x07, 0x00, 0x06, + 0x00, 0x0E, 0x00, 0x0C, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x30, 0x00, 0x70, + 0x00, 0x60, 0x00, 0xE0, 0x00, 0x00, 0x78, 0x00, 0xC3, 0x00, 0xC1, 0xC0, + 0xC0, 0x60, 0xE0, 0x30, 0xE0, 0x1C, 0x70, 0x0E, 0x70, 0x07, 0x38, 0x03, + 0xBC, 0x01, 0xDC, 0x01, 0xEE, 0x00, 0xFF, 0x00, 0x7F, 0x80, 0x3B, 0x80, + 0x1D, 0xC0, 0x1E, 0xE0, 0x0E, 0x70, 0x0F, 0x38, 0x07, 0x1C, 0x07, 0x06, + 0x03, 0x83, 0x83, 0x80, 0xC3, 0x00, 0x1F, 0x00, 0x00, 0xF0, 0x7F, 0x00, + 0x70, 0x07, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x01, 0xC0, 0x1C, 0x01, + 0xC0, 0x38, 0x03, 0x80, 0x38, 0x03, 0x80, 0x70, 0x07, 0x00, 0x70, 0x0E, + 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x1E, 0x0F, 0xF8, 0x01, 0xF0, 0x07, 0xFC, + 0x0C, 0x3E, 0x10, 0x1F, 0x20, 0x0F, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0F, + 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x30, 0x00, 0x70, 0x00, 0xE0, + 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x04, + 0x30, 0x0C, 0x7F, 0xF8, 0xFF, 0xF0, 0x00, 0x7C, 0x00, 0xFF, 0x00, 0xC3, + 0xC0, 0x80, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1C, 0x00, 0x1C, 0x00, + 0x38, 0x00, 0xF0, 0x03, 0xFC, 0x00, 0x1F, 0x00, 0x03, 0xC0, 0x01, 0xE0, + 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x06, 0x00, 0x07, + 0x00, 0x03, 0x07, 0x87, 0x03, 0xFF, 0x00, 0xFC, 0x00, 0x00, 0x01, 0x80, + 0x01, 0x80, 0x01, 0xC0, 0x01, 0xE0, 0x01, 0xF0, 0x01, 0xB0, 0x01, 0xB8, + 0x01, 0x9C, 0x01, 0x8C, 0x00, 0x86, 0x00, 0x87, 0x00, 0x83, 0x80, 0x81, + 0x80, 0x81, 0xC0, 0xC0, 0xE0, 0xC0, 0x70, 0xFF, 0xFF, 0x7F, 0xFF, 0x00, + 0x1C, 0x00, 0x0C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x03, 0x80, 0x01, 0x80, + 0x01, 0xFF, 0x01, 0xFF, 0x02, 0x00, 0x02, 0x00, 0x06, 0x00, 0x07, 0x00, + 0x0F, 0xC0, 0x0F, 0xF0, 0x00, 0xF8, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x1C, + 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x08, 0x00, 0x18, + 0x00, 0x30, 0x00, 0x30, 0x70, 0xE0, 0xFF, 0x80, 0x7E, 0x00, 0x00, 0x03, + 0x80, 0x1F, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, + 0x00, 0x3C, 0x00, 0x3D, 0xF0, 0x1F, 0xFE, 0x1F, 0x0F, 0x8E, 0x03, 0xC7, + 0x00, 0xF7, 0x00, 0x7B, 0x80, 0x3D, 0x80, 0x1E, 0xC0, 0x0F, 0x60, 0x0F, + 0xB0, 0x07, 0x98, 0x03, 0xC4, 0x03, 0xC3, 0x03, 0xC0, 0xC3, 0x80, 0x1F, + 0x00, 0x3F, 0xFF, 0x7F, 0xFE, 0x40, 0x0E, 0x80, 0x0C, 0x00, 0x18, 0x00, + 0x18, 0x00, 0x30, 0x00, 0x70, 0x00, 0x60, 0x00, 0xC0, 0x01, 0xC0, 0x01, + 0x80, 0x03, 0x80, 0x03, 0x00, 0x06, 0x00, 0x0E, 0x00, 0x0C, 0x00, 0x1C, + 0x00, 0x18, 0x00, 0x30, 0x00, 0x70, 0x00, 0x60, 0x00, 0xE0, 0x00, 0x00, + 0xF8, 0x03, 0x0E, 0x06, 0x06, 0x0C, 0x03, 0x0C, 0x03, 0x0C, 0x03, 0x0C, + 0x03, 0x0E, 0x06, 0x07, 0x8E, 0x07, 0xD8, 0x03, 0xE0, 0x07, 0xF0, 0x1C, + 0xF8, 0x30, 0x3C, 0x60, 0x1C, 0x60, 0x0E, 0xC0, 0x06, 0xC0, 0x06, 0xC0, + 0x06, 0xC0, 0x06, 0xE0, 0x0C, 0x60, 0x18, 0x38, 0x30, 0x0F, 0xC0, 0x01, + 0xF8, 0x07, 0x8C, 0x0E, 0x06, 0x1E, 0x02, 0x3C, 0x03, 0x3C, 0x03, 0x78, + 0x03, 0x78, 0x03, 0x78, 0x03, 0x78, 0x07, 0x78, 0x07, 0x78, 0x07, 0x3C, + 0x0E, 0x3E, 0x1E, 0x1F, 0xEE, 0x07, 0x9C, 0x00, 0x38, 0x00, 0x78, 0x00, + 0x70, 0x01, 0xE0, 0x03, 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xE0, 0x00, 0x0C, + 0x3C, 0x78, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x0F, 0x1E, 0x18, + 0x00, 0x07, 0x03, 0xC1, 0xE0, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x02, 0x03, 0x81, 0xC0, 0xE0, 0x30, 0x10, 0x10, 0x10, 0x00, 0x00, + 0x00, 0x00, 0xC0, 0x01, 0xF0, 0x01, 0xF8, 0x01, 0xF8, 0x01, 0xF0, 0x01, + 0xF0, 0x03, 0xF0, 0x03, 0xF0, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xE0, + 0x00, 0x7E, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xF0, 0x00, 0x3F, + 0x00, 0x03, 0xC0, 0x00, 0x10, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFF, + 0xFF, 0xC0, 0xC0, 0x00, 0x3C, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x07, + 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x3F, 0x00, 0x03, 0xC0, 0x01, + 0xF0, 0x01, 0xF8, 0x01, 0xF8, 0x01, 0xF0, 0x01, 0xF0, 0x03, 0xF0, 0x03, + 0xF0, 0x00, 0xF0, 0x00, 0x20, 0x00, 0x00, 0x0F, 0x81, 0x86, 0x30, 0x33, + 0x03, 0x30, 0x30, 0x03, 0x00, 0x60, 0x0E, 0x01, 0xC0, 0x38, 0x06, 0x00, + 0xC0, 0x08, 0x01, 0x00, 0x10, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, + 0x00, 0xF0, 0x0F, 0x00, 0x60, 0x00, 0x00, 0x7F, 0x00, 0x03, 0xFF, 0xE0, + 0x07, 0x80, 0xF0, 0x0E, 0x00, 0x38, 0x1C, 0x00, 0x0C, 0x38, 0x0E, 0x06, + 0x70, 0x3F, 0xE2, 0x70, 0x71, 0xE3, 0xF0, 0x60, 0xE1, 0xE0, 0xC0, 0xC1, + 0xE0, 0xC0, 0xC1, 0xE1, 0x81, 0xC1, 0xE1, 0x81, 0xC1, 0xE1, 0x81, 0x82, + 0xE1, 0x83, 0x82, 0x71, 0x83, 0x86, 0x71, 0xC7, 0x8C, 0x38, 0xF9, 0xF8, + 0x3C, 0xF0, 0xF0, 0x1E, 0x00, 0x00, 0x0F, 0x80, 0x30, 0x03, 0xFF, 0xE0, + 0x00, 0x7F, 0x00, 0x00, 0x03, 0x00, 0x00, 0x18, 0x00, 0x01, 0xC0, 0x00, + 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x5E, 0x00, 0x04, 0xF0, + 0x00, 0x63, 0x80, 0x02, 0x1C, 0x00, 0x20, 0xE0, 0x01, 0x07, 0x00, 0x10, + 0x3C, 0x01, 0xFF, 0xE0, 0x0F, 0xFF, 0x00, 0xC0, 0x38, 0x04, 0x01, 0xC0, + 0x60, 0x0E, 0x06, 0x00, 0x78, 0x30, 0x03, 0xC3, 0x00, 0x1E, 0x38, 0x00, + 0xFB, 0xF0, 0x1F, 0xE0, 0x07, 0xFF, 0x80, 0x0F, 0xFF, 0x00, 0x78, 0x3C, + 0x03, 0xC0, 0xF0, 0x1E, 0x07, 0x80, 0xE0, 0x3C, 0x07, 0x01, 0xE0, 0x78, + 0x1E, 0x03, 0x83, 0xE0, 0x1F, 0xF8, 0x01, 0xFF, 0xC0, 0x0F, 0x0F, 0x00, + 0x70, 0x3C, 0x03, 0x80, 0xF0, 0x3C, 0x07, 0x81, 0xC0, 0x3C, 0x0E, 0x01, + 0xE0, 0xF0, 0x0F, 0x07, 0x80, 0xF0, 0x38, 0x0F, 0x81, 0xC1, 0xF8, 0x1F, + 0xFF, 0x83, 0xFF, 0xE0, 0x00, 0x00, 0x3F, 0x08, 0x07, 0xFF, 0xC0, 0xF8, + 0x3E, 0x0F, 0x00, 0x70, 0xF0, 0x03, 0x8F, 0x00, 0x08, 0xF0, 0x00, 0x47, + 0x80, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x01, 0xE0, 0x00, + 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, + 0x00, 0x03, 0x80, 0x02, 0x1E, 0x00, 0x20, 0x78, 0x02, 0x03, 0xE0, 0x60, + 0x07, 0xFE, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xFF, 0xC0, 0x00, 0xFF, 0xFC, + 0x00, 0x78, 0x1F, 0x00, 0x3C, 0x03, 0xC0, 0x1E, 0x00, 0xF0, 0x0E, 0x00, + 0x78, 0x07, 0x00, 0x1E, 0x07, 0x80, 0x0F, 0x03, 0x80, 0x07, 0x81, 0xC0, + 0x03, 0xC1, 0xE0, 0x01, 0xE0, 0xF0, 0x00, 0xF0, 0x70, 0x00, 0x78, 0x38, + 0x00, 0x78, 0x3C, 0x00, 0x3C, 0x1E, 0x00, 0x3E, 0x0E, 0x00, 0x1E, 0x0F, + 0x00, 0x1E, 0x07, 0x80, 0x1E, 0x03, 0x80, 0x3E, 0x01, 0xC0, 0x7E, 0x01, + 0xFF, 0xFC, 0x03, 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xFC, 0x07, 0xFF, 0xF0, + 0x1E, 0x01, 0xC0, 0x78, 0x02, 0x01, 0xE0, 0x08, 0x07, 0x00, 0x00, 0x1C, + 0x08, 0x00, 0xF0, 0x60, 0x03, 0x83, 0x80, 0x0F, 0xFC, 0x00, 0x7F, 0xF0, + 0x01, 0xE0, 0xC0, 0x07, 0x03, 0x00, 0x1C, 0x08, 0x00, 0xF0, 0x20, 0x03, + 0x80, 0x00, 0x0E, 0x00, 0x00, 0x78, 0x00, 0x81, 0xE0, 0x06, 0x07, 0x00, + 0x38, 0x1C, 0x03, 0xC0, 0xFF, 0xFF, 0x0F, 0xFF, 0xFC, 0x00, 0x07, 0xFF, + 0xFC, 0x07, 0xFF, 0xF0, 0x1E, 0x01, 0xC0, 0x78, 0x02, 0x01, 0xE0, 0x08, + 0x07, 0x00, 0x20, 0x1C, 0x00, 0x00, 0xF0, 0x20, 0x03, 0x81, 0x80, 0x0E, + 0x0C, 0x00, 0x7F, 0xF0, 0x01, 0xFF, 0xC0, 0x07, 0x03, 0x00, 0x1C, 0x0C, + 0x00, 0xF0, 0x20, 0x03, 0xC0, 0x00, 0x0E, 0x00, 0x00, 0x78, 0x00, 0x01, + 0xE0, 0x00, 0x07, 0x00, 0x00, 0x1C, 0x00, 0x00, 0xF8, 0x00, 0x0F, 0xF8, + 0x00, 0x00, 0x00, 0x3F, 0x02, 0x01, 0xFF, 0x88, 0x0F, 0x81, 0xF0, 0x3C, + 0x01, 0xE0, 0xF0, 0x01, 0xC3, 0xC0, 0x01, 0x0F, 0x80, 0x02, 0x1E, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x07, 0xC0, 0x00, + 0x0F, 0x00, 0x3F, 0xFE, 0x00, 0x1E, 0x3C, 0x00, 0x38, 0x78, 0x00, 0x70, + 0xF0, 0x00, 0xE0, 0xE0, 0x01, 0xC1, 0xE0, 0x07, 0x01, 0xE0, 0x0E, 0x01, + 0xF0, 0x3C, 0x01, 0xFF, 0xF0, 0x00, 0xFF, 0x00, 0x00, 0x07, 0xFC, 0x3F, + 0xE0, 0x3E, 0x00, 0xF0, 0x07, 0x80, 0x1C, 0x00, 0xF0, 0x03, 0x80, 0x1C, + 0x00, 0xF0, 0x03, 0x80, 0x1E, 0x00, 0x70, 0x03, 0x80, 0x1E, 0x00, 0x70, + 0x03, 0x80, 0x1E, 0x00, 0x70, 0x03, 0x80, 0x1F, 0xFF, 0xF0, 0x03, 0xFF, + 0xFE, 0x00, 0x70, 0x03, 0xC0, 0x0E, 0x00, 0x70, 0x03, 0xC0, 0x0E, 0x00, + 0x70, 0x03, 0xC0, 0x0E, 0x00, 0x78, 0x03, 0xC0, 0x0E, 0x00, 0x78, 0x01, + 0xC0, 0x0E, 0x00, 0x78, 0x01, 0xC0, 0x0E, 0x00, 0x78, 0x03, 0xE0, 0x3F, + 0xE1, 0xFF, 0x00, 0x07, 0xFC, 0x07, 0xC0, 0x1E, 0x00, 0x78, 0x01, 0xC0, + 0x07, 0x00, 0x1C, 0x00, 0xF0, 0x03, 0x80, 0x0E, 0x00, 0x78, 0x01, 0xE0, + 0x07, 0x00, 0x1C, 0x00, 0xF0, 0x03, 0x80, 0x0E, 0x00, 0x78, 0x01, 0xE0, + 0x07, 0x00, 0x1C, 0x00, 0xF0, 0x0F, 0xF8, 0x00, 0x00, 0xFF, 0x80, 0x0F, + 0x00, 0x07, 0x80, 0x03, 0x80, 0x01, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, + 0x70, 0x00, 0x38, 0x00, 0x3C, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x0F, 0x00, + 0x07, 0x80, 0x03, 0x80, 0x01, 0xC0, 0x01, 0xE0, 0x00, 0xE0, 0x00, 0x70, + 0x1E, 0x78, 0x0F, 0x38, 0x07, 0xF8, 0x01, 0xF0, 0x00, 0x07, 0xFC, 0x7F, + 0x80, 0xF8, 0x0F, 0x00, 0x38, 0x07, 0x00, 0x3C, 0x07, 0x00, 0x1C, 0x06, + 0x00, 0x0E, 0x06, 0x00, 0x07, 0x0C, 0x00, 0x07, 0x8C, 0x00, 0x03, 0x9C, + 0x00, 0x01, 0xD8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x73, + 0x80, 0x00, 0x39, 0xE0, 0x00, 0x3C, 0x78, 0x00, 0x1C, 0x1C, 0x00, 0x0E, + 0x0F, 0x00, 0x07, 0x03, 0x80, 0x07, 0x81, 0xE0, 0x03, 0x80, 0x70, 0x01, + 0xC0, 0x3C, 0x01, 0xE0, 0x1F, 0x03, 0xFE, 0x3F, 0xE0, 0x07, 0xFC, 0x00, + 0x1F, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, + 0x01, 0xC0, 0x00, 0x3C, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x07, 0x80, + 0x00, 0x78, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x0F, 0x00, 0x00, 0xE0, + 0x00, 0x0E, 0x00, 0x11, 0xE0, 0x03, 0x1E, 0x00, 0x61, 0xC0, 0x06, 0x1C, + 0x01, 0xE3, 0xFF, 0xFC, 0xFF, 0xFF, 0xC0, 0x07, 0xF0, 0x00, 0x7E, 0x03, + 0xE0, 0x01, 0xF0, 0x03, 0xC0, 0x03, 0xE0, 0x07, 0x80, 0x0F, 0x80, 0x1F, + 0x00, 0x37, 0x00, 0x2E, 0x00, 0x5E, 0x00, 0x5C, 0x01, 0xB8, 0x01, 0xB8, + 0x06, 0x70, 0x02, 0x78, 0x09, 0xE0, 0x04, 0x70, 0x33, 0xC0, 0x08, 0xE0, + 0xC7, 0x00, 0x31, 0xC1, 0x0E, 0x00, 0x43, 0x86, 0x3C, 0x00, 0x87, 0x18, + 0x70, 0x03, 0x0E, 0x20, 0xE0, 0x06, 0x1C, 0xC3, 0xC0, 0x08, 0x3B, 0x07, + 0x80, 0x10, 0x7C, 0x0E, 0x00, 0x60, 0x78, 0x1C, 0x00, 0x80, 0xE0, 0x78, + 0x03, 0x01, 0x80, 0xF0, 0x07, 0x03, 0x03, 0xE0, 0x3F, 0x84, 0x1F, 0xF0, + 0x00, 0x07, 0xC0, 0x3F, 0xC0, 0x78, 0x03, 0xE0, 0x0E, 0x00, 0x70, 0x03, + 0xC0, 0x18, 0x01, 0xF0, 0x0E, 0x00, 0x6C, 0x03, 0x00, 0x1B, 0x80, 0xC0, + 0x0C, 0xE0, 0x30, 0x03, 0x18, 0x1C, 0x00, 0xC7, 0x06, 0x00, 0x30, 0xC1, + 0x80, 0x18, 0x38, 0xE0, 0x06, 0x06, 0x30, 0x01, 0x81, 0x8C, 0x00, 0xC0, + 0x73, 0x00, 0x30, 0x0D, 0xC0, 0x0C, 0x03, 0xE0, 0x03, 0x00, 0x78, 0x01, + 0x80, 0x1E, 0x00, 0x60, 0x07, 0x00, 0x38, 0x00, 0xC0, 0x0E, 0x00, 0x30, + 0x0F, 0xE0, 0x04, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0xFF, 0xE0, 0x07, 0xC1, + 0xE0, 0x1E, 0x01, 0xE0, 0x78, 0x01, 0xC1, 0xE0, 0x03, 0xC7, 0x80, 0x07, + 0x9F, 0x00, 0x0F, 0x3C, 0x00, 0x1E, 0xF8, 0x00, 0x3D, 0xE0, 0x00, 0xFF, + 0xC0, 0x01, 0xEF, 0x80, 0x03, 0xDE, 0x00, 0x0F, 0xBC, 0x00, 0x1E, 0x78, + 0x00, 0x7C, 0xF0, 0x00, 0xF1, 0xE0, 0x03, 0xC1, 0xC0, 0x0F, 0x03, 0xC0, + 0x3C, 0x03, 0xC1, 0xF0, 0x03, 0xFF, 0x80, 0x01, 0xFC, 0x00, 0x00, 0x07, + 0xFF, 0xC0, 0x07, 0xFF, 0xC0, 0x0E, 0x0F, 0x80, 0x78, 0x1F, 0x01, 0xC0, + 0x3C, 0x07, 0x00, 0xF0, 0x1C, 0x03, 0xC0, 0xF0, 0x0F, 0x03, 0x80, 0x78, + 0x0E, 0x01, 0xE0, 0x78, 0x1F, 0x01, 0xFF, 0xF8, 0x07, 0x7F, 0x00, 0x1C, + 0x00, 0x00, 0xF0, 0x00, 0x03, 0x80, 0x00, 0x0E, 0x00, 0x00, 0x78, 0x00, + 0x01, 0xE0, 0x00, 0x07, 0x00, 0x00, 0x1C, 0x00, 0x00, 0xF0, 0x00, 0x0F, + 0xF0, 0x00, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0xFF, 0xE0, 0x03, 0xC1, 0xE0, + 0x1E, 0x01, 0xC0, 0x78, 0x03, 0xC1, 0xE0, 0x03, 0x87, 0x80, 0x07, 0x8F, + 0x00, 0x0F, 0x3C, 0x00, 0x1E, 0x78, 0x00, 0x3D, 0xE0, 0x00, 0x7B, 0xC0, + 0x01, 0xFF, 0x80, 0x03, 0xDE, 0x00, 0x07, 0xBC, 0x00, 0x1F, 0x78, 0x00, + 0x3C, 0xF0, 0x00, 0xF1, 0xE0, 0x01, 0xE3, 0xC0, 0x07, 0x83, 0x80, 0x1E, + 0x07, 0x80, 0x78, 0x07, 0x01, 0xC0, 0x03, 0xDE, 0x00, 0x01, 0xC0, 0x00, + 0x06, 0x00, 0x00, 0x18, 0x00, 0x10, 0x7F, 0xC0, 0xC3, 0xFF, 0xFF, 0x08, + 0x07, 0xF0, 0x00, 0x07, 0xFF, 0x80, 0x0F, 0xFF, 0x00, 0x78, 0x3C, 0x03, + 0xC0, 0xF0, 0x1E, 0x07, 0x80, 0xE0, 0x3C, 0x07, 0x01, 0xE0, 0x78, 0x1E, + 0x03, 0x83, 0xF0, 0x1F, 0xFE, 0x01, 0xFF, 0xC0, 0x0F, 0x38, 0x00, 0x71, + 0xE0, 0x03, 0x87, 0x00, 0x3C, 0x38, 0x01, 0xC1, 0xE0, 0x0E, 0x07, 0x00, + 0xF0, 0x3C, 0x07, 0x81, 0xE0, 0x38, 0x07, 0x01, 0xC0, 0x3C, 0x1E, 0x00, + 0xF3, 0xFC, 0x07, 0xC0, 0x00, 0xF8, 0x81, 0xFF, 0xC1, 0xE1, 0xE1, 0xE0, + 0x70, 0xF0, 0x10, 0x78, 0x08, 0x3C, 0x00, 0x1F, 0x00, 0x07, 0x80, 0x01, + 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0xF8, + 0x80, 0x3C, 0x40, 0x1E, 0x20, 0x0F, 0x38, 0x07, 0x9E, 0x07, 0x8F, 0x87, + 0x84, 0x7F, 0xC2, 0x0F, 0x80, 0x3F, 0xFF, 0xF7, 0xFF, 0xFF, 0x70, 0x78, + 0x76, 0x07, 0x02, 0xC0, 0x70, 0x28, 0x0F, 0x02, 0x00, 0xF0, 0x00, 0x0E, + 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x03, + 0xC0, 0x00, 0x3C, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x07, 0x80, 0x00, + 0x70, 0x00, 0x07, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x01, 0xF0, 0x00, + 0xFF, 0xE0, 0x00, 0x7F, 0xE0, 0xFE, 0x3F, 0x00, 0x78, 0x3C, 0x00, 0x60, + 0xF0, 0x01, 0x81, 0xE0, 0x03, 0x03, 0xC0, 0x06, 0x07, 0x00, 0x08, 0x1E, + 0x00, 0x30, 0x3C, 0x00, 0x60, 0x70, 0x00, 0x81, 0xE0, 0x01, 0x03, 0xC0, + 0x06, 0x07, 0x80, 0x0C, 0x0E, 0x00, 0x10, 0x3C, 0x00, 0x60, 0x78, 0x00, + 0xC0, 0xF0, 0x01, 0x01, 0xE0, 0x06, 0x03, 0xC0, 0x08, 0x03, 0xC0, 0x30, + 0x07, 0xC1, 0xC0, 0x07, 0xFF, 0x00, 0x03, 0xF8, 0x00, 0x00, 0xFF, 0x01, + 0xFB, 0xE0, 0x07, 0x8E, 0x00, 0x18, 0x78, 0x01, 0x83, 0xC0, 0x0C, 0x1E, + 0x00, 0xC0, 0xF0, 0x06, 0x03, 0x80, 0x60, 0x1C, 0x02, 0x00, 0xE0, 0x30, + 0x07, 0x83, 0x00, 0x3C, 0x10, 0x01, 0xE1, 0x80, 0x07, 0x08, 0x00, 0x38, + 0x80, 0x01, 0xC4, 0x00, 0x0E, 0x40, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, + 0x0E, 0x00, 0x00, 0x70, 0x00, 0x03, 0x00, 0x00, 0x10, 0x00, 0x00, 0xFF, + 0x3F, 0xC3, 0xFB, 0xE0, 0x78, 0x07, 0x8E, 0x03, 0xC0, 0x18, 0x78, 0x0E, + 0x01, 0x83, 0xC0, 0x70, 0x0C, 0x1E, 0x03, 0x80, 0x40, 0xF0, 0x3C, 0x06, + 0x03, 0x81, 0xE0, 0x60, 0x1C, 0x17, 0x83, 0x00, 0xE0, 0xBC, 0x30, 0x07, + 0x09, 0xE1, 0x00, 0x38, 0x47, 0x18, 0x01, 0xE4, 0x38, 0x80, 0x0F, 0x21, + 0xCC, 0x00, 0x7A, 0x0E, 0x40, 0x01, 0xD0, 0x76, 0x00, 0x0F, 0x03, 0xA0, + 0x00, 0x78, 0x1F, 0x00, 0x03, 0x80, 0xF0, 0x00, 0x1C, 0x07, 0x00, 0x00, + 0xC0, 0x38, 0x00, 0x06, 0x00, 0x80, 0x00, 0x20, 0x04, 0x00, 0x00, 0x0F, + 0xF8, 0x7F, 0x03, 0xE0, 0x3E, 0x01, 0xC0, 0x18, 0x01, 0xE0, 0x30, 0x01, + 0xE0, 0x60, 0x00, 0xE0, 0xC0, 0x00, 0xF1, 0xC0, 0x00, 0x71, 0x80, 0x00, + 0x7B, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0x7E, 0x00, 0x00, 0xCE, 0x00, 0x01, 0x8F, 0x00, 0x01, + 0x07, 0x00, 0x03, 0x07, 0x00, 0x06, 0x07, 0x80, 0x0C, 0x03, 0x80, 0x18, + 0x03, 0xC0, 0x78, 0x03, 0xE0, 0xFE, 0x1F, 0xF8, 0xFF, 0x87, 0xE7, 0xC0, + 0x38, 0x70, 0x06, 0x0E, 0x01, 0x81, 0xE0, 0x30, 0x1C, 0x0C, 0x03, 0x83, + 0x00, 0x78, 0xC0, 0x07, 0x30, 0x00, 0xE4, 0x00, 0x1D, 0x80, 0x03, 0xE0, + 0x00, 0x38, 0x00, 0x0F, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x07, 0x00, + 0x01, 0xE0, 0x00, 0x38, 0x00, 0x07, 0x00, 0x01, 0xE0, 0x00, 0x7C, 0x00, + 0x3F, 0xF0, 0x00, 0x07, 0xFF, 0xFC, 0x3F, 0xFF, 0xE0, 0xE0, 0x0F, 0x82, + 0x00, 0x3C, 0x18, 0x01, 0xE0, 0x40, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, + 0xC0, 0x00, 0x0E, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, + 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x1C, 0x00, 0x00, 0xF0, 0x00, 0x07, + 0x80, 0x00, 0x3C, 0x00, 0xC1, 0xE0, 0x02, 0x0F, 0x00, 0x18, 0x38, 0x01, + 0xE1, 0xFF, 0xFF, 0x0F, 0xFF, 0xFC, 0x00, 0x01, 0xF8, 0x0C, 0x00, 0xC0, + 0x06, 0x00, 0x30, 0x01, 0x80, 0x18, 0x00, 0xC0, 0x06, 0x00, 0x30, 0x03, + 0x00, 0x18, 0x00, 0xC0, 0x06, 0x00, 0x60, 0x03, 0x00, 0x18, 0x01, 0xC0, + 0x0C, 0x00, 0x60, 0x03, 0x00, 0x30, 0x01, 0x80, 0x0C, 0x00, 0x60, 0x06, + 0x00, 0x30, 0x01, 0xF8, 0x00, 0xE0, 0x0E, 0x00, 0x60, 0x07, 0x00, 0x30, + 0x03, 0x80, 0x18, 0x01, 0xC0, 0x0C, 0x00, 0xC0, 0x0E, 0x00, 0x60, 0x07, + 0x00, 0x30, 0x03, 0x80, 0x18, 0x01, 0xC0, 0x0C, 0x00, 0xC0, 0x0E, 0x00, + 0x60, 0x07, 0x00, 0x30, 0x03, 0xF0, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x0E, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x01, 0x80, 0x18, 0x01, 0x80, + 0x18, 0x03, 0x00, 0x30, 0x03, 0x00, 0x30, 0x03, 0x00, 0x60, 0x06, 0x00, + 0x60, 0x06, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x0F, 0xC0, 0x03, 0x80, + 0x07, 0x00, 0x1F, 0x00, 0x36, 0x00, 0xCE, 0x01, 0x8C, 0x06, 0x1C, 0x0C, + 0x18, 0x38, 0x38, 0x60, 0x31, 0xC0, 0x73, 0x00, 0x6E, 0x00, 0xE0, 0xFF, + 0xFF, 0xFF, 0xFF, 0xF0, 0xE3, 0x8F, 0x0E, 0x18, 0x30, 0x01, 0xEC, 0x0E, + 0x58, 0x30, 0x70, 0xE0, 0xC3, 0x81, 0x86, 0x07, 0x1C, 0x0C, 0x38, 0x18, + 0xE0, 0x71, 0xC0, 0xE3, 0x83, 0x87, 0x0B, 0x2F, 0x36, 0xCF, 0xCF, 0x1F, + 0x1C, 0x00, 0x03, 0x00, 0x1F, 0x00, 0x07, 0x00, 0x07, 0x00, 0x06, 0x00, + 0x0E, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0C, 0x00, 0x1C, 0x7C, 0x1C, 0xFE, + 0x19, 0x8F, 0x1A, 0x07, 0x3C, 0x07, 0x38, 0x07, 0x38, 0x07, 0x70, 0x0E, + 0x70, 0x0E, 0x70, 0x1C, 0x60, 0x18, 0xE0, 0x30, 0xE0, 0x60, 0xE1, 0xC0, + 0x3F, 0x00, 0x01, 0xF0, 0x38, 0xC3, 0x8E, 0x78, 0x73, 0x80, 0x3C, 0x01, + 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x47, 0x84, 0x3F, + 0xC0, 0x7C, 0x00, 0x00, 0x01, 0x80, 0x07, 0xC0, 0x00, 0xE0, 0x00, 0x60, + 0x00, 0x30, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0C, 0x00, 0x06, 0x00, 0xF7, + 0x01, 0xC7, 0x81, 0xC3, 0x81, 0xC1, 0xC1, 0xE0, 0xE0, 0xE0, 0x60, 0xF0, + 0x30, 0x78, 0x38, 0x78, 0x18, 0x3C, 0x0C, 0x1E, 0x0C, 0x0F, 0x0E, 0x27, + 0xCB, 0x21, 0xF9, 0xE0, 0x78, 0xE0, 0x00, 0xF0, 0x1C, 0xC3, 0x86, 0x38, + 0x33, 0xC3, 0x1C, 0x31, 0xE3, 0x1F, 0xE0, 0xF0, 0x07, 0x80, 0x3C, 0x01, + 0xE0, 0x47, 0x84, 0x3F, 0xC0, 0x7C, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x33, + 0x00, 0x06, 0x30, 0x00, 0xC0, 0x00, 0x0C, 0x00, 0x01, 0xC0, 0x00, 0x18, + 0x00, 0x01, 0x80, 0x00, 0x38, 0x00, 0x3F, 0xF8, 0x03, 0xFF, 0x80, 0x03, + 0x00, 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x06, 0x00, 0x00, + 0x60, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x0C, 0x00, 0x00, 0xC0, 0x00, + 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x18, 0x00, 0x01, 0x80, 0x00, 0x18, 0x00, + 0x03, 0x00, 0x00, 0x30, 0x00, 0xC6, 0x00, 0x0C, 0xC0, 0x00, 0x78, 0x00, + 0x00, 0x01, 0xF8, 0x07, 0x1F, 0x0E, 0x0F, 0x0C, 0x0E, 0x18, 0x0E, 0x18, + 0x0E, 0x18, 0x1E, 0x18, 0x3C, 0x0C, 0x78, 0x07, 0xE0, 0x08, 0x00, 0x18, + 0x00, 0x1E, 0x00, 0x0F, 0xE0, 0x13, 0xF0, 0x60, 0x78, 0xC0, 0x38, 0xC0, + 0x18, 0xC0, 0x18, 0xC0, 0x30, 0x60, 0x60, 0x3F, 0x80, 0x03, 0x00, 0x1F, + 0x00, 0x07, 0x00, 0x07, 0x00, 0x06, 0x00, 0x06, 0x00, 0x0E, 0x00, 0x0E, + 0x00, 0x0C, 0x00, 0x1C, 0x38, 0x1C, 0x7C, 0x1C, 0xCC, 0x19, 0x0C, 0x3A, + 0x0C, 0x3C, 0x1C, 0x3C, 0x18, 0x38, 0x18, 0x70, 0x38, 0x70, 0x38, 0x70, + 0x30, 0x60, 0x72, 0xE0, 0x76, 0xE0, 0x7C, 0xC0, 0x70, 0x03, 0x03, 0xC1, + 0xE0, 0x60, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x7E, 0x0F, 0x03, 0x81, 0x81, + 0xC0, 0xE0, 0x70, 0x30, 0x38, 0x1C, 0x1C, 0x4C, 0x47, 0xC3, 0xC0, 0x00, + 0x0C, 0x00, 0x3C, 0x00, 0x78, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x18, 0x03, 0xF0, 0x00, 0xE0, 0x01, 0x80, 0x03, 0x00, + 0x0E, 0x00, 0x1C, 0x00, 0x30, 0x00, 0x60, 0x01, 0xC0, 0x03, 0x80, 0x06, + 0x00, 0x0C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xC0, 0x03, 0x80, 0x06, 0x00, + 0x0C, 0x06, 0x30, 0x0C, 0xC0, 0x0F, 0x00, 0x00, 0x03, 0x00, 0x3E, 0x00, + 0x1C, 0x00, 0x38, 0x00, 0x60, 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0C, + 0x00, 0x38, 0xFC, 0x70, 0x60, 0xE1, 0x81, 0x86, 0x07, 0x10, 0x0E, 0x40, + 0x1B, 0x80, 0x3F, 0x00, 0xE7, 0x01, 0xCE, 0x03, 0x0C, 0x06, 0x1C, 0x5C, + 0x1D, 0x38, 0x3E, 0x60, 0x38, 0x03, 0x1F, 0x07, 0x07, 0x06, 0x0E, 0x0E, + 0x0E, 0x0C, 0x1C, 0x1C, 0x18, 0x38, 0x38, 0x38, 0x30, 0x70, 0x70, 0x70, + 0x64, 0xE4, 0xE8, 0xF0, 0xE0, 0x00, 0x06, 0x18, 0x1E, 0x3E, 0x3C, 0x3F, + 0x0E, 0x4C, 0x47, 0x0C, 0x8C, 0x8E, 0x1D, 0x0D, 0x0E, 0x1E, 0x1A, 0x0E, + 0x1C, 0x1E, 0x0C, 0x3C, 0x1C, 0x1C, 0x38, 0x38, 0x1C, 0x38, 0x38, 0x1C, + 0x30, 0x38, 0x18, 0x70, 0x30, 0x39, 0x70, 0x70, 0x32, 0x60, 0x70, 0x3C, + 0x60, 0x60, 0x38, 0x06, 0x0E, 0x1F, 0x1F, 0x83, 0x99, 0xC1, 0x98, 0xC1, + 0xD8, 0xE0, 0xE8, 0x70, 0x78, 0x30, 0x38, 0x38, 0x3C, 0x1C, 0x1C, 0x0E, + 0x0E, 0x06, 0x0E, 0x03, 0x17, 0x01, 0xB3, 0x80, 0xF1, 0x80, 0x70, 0x01, + 0xF0, 0x0E, 0x38, 0x38, 0x30, 0xE0, 0x73, 0x80, 0xEE, 0x01, 0xDC, 0x03, + 0xF8, 0x0F, 0xE0, 0x1D, 0xC0, 0x3B, 0x80, 0xE7, 0x03, 0x8E, 0x06, 0x0E, + 0x38, 0x07, 0xC0, 0x00, 0x00, 0xE7, 0xC0, 0x7C, 0xFE, 0x01, 0xD1, 0xF0, + 0x1E, 0x0F, 0x01, 0xC0, 0xF0, 0x38, 0x0F, 0x03, 0x80, 0xF0, 0x38, 0x0E, + 0x03, 0x01, 0xE0, 0x70, 0x1C, 0x07, 0x03, 0xC0, 0x60, 0x78, 0x06, 0x0F, + 0x00, 0xE1, 0xC0, 0x0F, 0xF0, 0x00, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xC0, + 0x00, 0x1C, 0x00, 0x01, 0x80, 0x00, 0x38, 0x00, 0x0F, 0xF0, 0x00, 0x00, + 0xF7, 0x03, 0xCE, 0x0F, 0x06, 0x1E, 0x06, 0x1C, 0x04, 0x3C, 0x04, 0x78, + 0x04, 0x78, 0x0C, 0xF0, 0x08, 0xF0, 0x18, 0xF0, 0x38, 0xF0, 0xF0, 0xF9, + 0x70, 0x7E, 0x70, 0x3C, 0x70, 0x00, 0x60, 0x00, 0xE0, 0x00, 0xE0, 0x00, + 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x0F, 0xF0, 0x7C, 0x70, 0xE7, 0xC7, 0x4C, + 0x34, 0x01, 0xA0, 0x1E, 0x00, 0xF0, 0x07, 0x00, 0x78, 0x03, 0x80, 0x1C, + 0x00, 0xC0, 0x0E, 0x00, 0x70, 0x03, 0x80, 0x00, 0x07, 0x88, 0x63, 0x86, + 0x0C, 0x30, 0x21, 0xC1, 0x0E, 0x00, 0x38, 0x00, 0xE0, 0x03, 0x80, 0x1C, + 0x10, 0x60, 0x83, 0x06, 0x18, 0x71, 0x82, 0x78, 0x00, 0x02, 0x03, 0x03, + 0x07, 0xF7, 0xF8, 0xE0, 0x60, 0x70, 0x38, 0x1C, 0x0C, 0x0E, 0x07, 0x03, + 0x01, 0x91, 0xC8, 0xF8, 0x78, 0x00, 0x1C, 0x0D, 0xF8, 0x38, 0x60, 0x70, + 0xC1, 0xC3, 0x83, 0x87, 0x07, 0x0C, 0x1E, 0x38, 0x78, 0x70, 0xB0, 0xE2, + 0x61, 0x8D, 0xC7, 0x33, 0x2C, 0xC6, 0x5F, 0x0F, 0x38, 0x1C, 0x00, 0x18, + 0x1B, 0xE0, 0x73, 0x81, 0xC6, 0x03, 0x18, 0x0C, 0x70, 0x21, 0xC1, 0x83, + 0x0C, 0x0C, 0x20, 0x31, 0x00, 0xC8, 0x03, 0x40, 0x0E, 0x00, 0x30, 0x00, + 0x80, 0x00, 0x18, 0x04, 0x1B, 0xE0, 0x30, 0x71, 0x80, 0xC1, 0xC6, 0x07, + 0x01, 0x1C, 0x2C, 0x08, 0x70, 0xB0, 0x20, 0xC4, 0xC1, 0x03, 0x21, 0x84, + 0x0D, 0x86, 0x20, 0x34, 0x19, 0x00, 0xE0, 0x68, 0x03, 0x81, 0xA0, 0x0C, + 0x07, 0x00, 0x30, 0x18, 0x00, 0x80, 0x40, 0x00, 0x03, 0x07, 0x0F, 0x8F, + 0x13, 0x93, 0x01, 0xB0, 0x01, 0xE0, 0x01, 0xC0, 0x00, 0xC0, 0x00, 0xC0, + 0x01, 0xC0, 0x03, 0xE0, 0x02, 0x60, 0x04, 0x62, 0x08, 0x64, 0xF0, 0x7C, + 0xE0, 0x30, 0x06, 0x06, 0x3F, 0x07, 0x07, 0x07, 0x07, 0x03, 0x03, 0x81, + 0x03, 0x82, 0x01, 0x82, 0x01, 0xC4, 0x01, 0xC4, 0x01, 0xC8, 0x00, 0xC8, + 0x00, 0xD0, 0x00, 0xF0, 0x00, 0xE0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0x80, + 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x78, 0x00, 0x70, 0x00, 0x1F, 0xFC, + 0x7F, 0xE1, 0x01, 0x08, 0x08, 0x00, 0x40, 0x02, 0x00, 0x10, 0x00, 0x80, + 0x06, 0x00, 0x10, 0x00, 0x80, 0x04, 0x00, 0x38, 0x01, 0xF0, 0x0B, 0xE0, + 0x01, 0xC6, 0x03, 0x98, 0x03, 0x80, 0x00, 0x70, 0x0C, 0x01, 0x80, 0x38, + 0x03, 0x80, 0x30, 0x07, 0x00, 0x70, 0x07, 0x00, 0x60, 0x0E, 0x00, 0xE0, + 0x0C, 0x01, 0xC0, 0x1C, 0x07, 0x80, 0x30, 0x04, 0x00, 0x20, 0x03, 0x00, + 0x30, 0x07, 0x00, 0x70, 0x06, 0x00, 0x60, 0x0E, 0x00, 0xE0, 0x0C, 0x00, + 0xC0, 0x07, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0xC0, 0x06, + 0x00, 0x30, 0x03, 0x00, 0x30, 0x03, 0x00, 0x70, 0x07, 0x00, 0x70, 0x06, + 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0C, 0x00, 0x40, 0x04, 0x00, 0xC0, 0x1E, + 0x03, 0x80, 0x38, 0x03, 0x00, 0x70, 0x07, 0x00, 0x70, 0x06, 0x00, 0xE0, + 0x0E, 0x00, 0xC0, 0x1C, 0x01, 0x80, 0x70, 0x00, 0x1E, 0x00, 0x3F, 0xE1, + 0xF8, 0x7F, 0xC0, 0x07, 0x80 }; + +const GFXglyph FreeSerifItalic18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 9, 0, 1 }, // 0x20 ' ' + { 0, 10, 23, 12, 1, -22 }, // 0x21 '!' + { 29, 12, 9, 12, 4, -22 }, // 0x22 '"' + { 43, 19, 23, 17, 0, -22 }, // 0x23 '#' + { 98, 15, 29, 17, 1, -25 }, // 0x24 '$' + { 153, 25, 23, 29, 3, -22 }, // 0x25 '%' + { 225, 22, 23, 27, 3, -22 }, // 0x26 '&' + { 289, 5, 9, 7, 4, -22 }, // 0x27 ''' + { 295, 9, 29, 12, 1, -22 }, // 0x28 '(' + { 328, 9, 29, 12, 1, -22 }, // 0x29 ')' + { 361, 12, 14, 18, 5, -22 }, // 0x2A '*' + { 382, 16, 18, 24, 4, -17 }, // 0x2B '+' + { 418, 5, 8, 9, -1, -2 }, // 0x2C ',' + { 423, 8, 2, 12, 2, -8 }, // 0x2D '-' + { 425, 4, 4, 9, 1, -3 }, // 0x2E '.' + { 427, 16, 23, 10, 0, -22 }, // 0x2F '/' + { 473, 17, 24, 17, 1, -23 }, // 0x30 '0' + { 524, 12, 24, 17, 2, -23 }, // 0x31 '1' + { 560, 16, 23, 17, 1, -22 }, // 0x32 '2' + { 606, 17, 24, 18, 0, -23 }, // 0x33 '3' + { 657, 17, 24, 17, 0, -23 }, // 0x34 '4' + { 708, 16, 23, 18, 0, -22 }, // 0x35 '5' + { 754, 17, 24, 18, 1, -23 }, // 0x36 '6' + { 805, 16, 23, 17, 3, -22 }, // 0x37 '7' + { 851, 16, 24, 18, 1, -23 }, // 0x38 '8' + { 899, 16, 24, 17, 1, -23 }, // 0x39 '9' + { 947, 7, 15, 9, 2, -14 }, // 0x3A ':' + { 961, 9, 20, 9, 1, -14 }, // 0x3B ';' + { 984, 18, 18, 20, 2, -17 }, // 0x3C '<' + { 1025, 18, 9, 23, 3, -12 }, // 0x3D '=' + { 1046, 18, 18, 20, 2, -17 }, // 0x3E '>' + { 1087, 12, 23, 16, 4, -22 }, // 0x3F '?' + { 1122, 24, 23, 27, 2, -22 }, // 0x40 '@' + { 1191, 21, 23, 23, 0, -22 }, // 0x41 'A' + { 1252, 21, 23, 21, 0, -22 }, // 0x42 'B' + { 1313, 21, 23, 21, 2, -22 }, // 0x43 'C' + { 1374, 25, 23, 25, 0, -22 }, // 0x44 'D' + { 1446, 22, 23, 20, 0, -22 }, // 0x45 'E' + { 1510, 22, 23, 20, 0, -22 }, // 0x46 'F' + { 1574, 23, 23, 24, 2, -22 }, // 0x47 'G' + { 1641, 27, 23, 25, 0, -22 }, // 0x48 'H' + { 1719, 14, 23, 11, 0, -22 }, // 0x49 'I' + { 1760, 17, 23, 15, 0, -22 }, // 0x4A 'J' + { 1809, 25, 23, 22, 0, -22 }, // 0x4B 'K' + { 1881, 20, 23, 20, 0, -22 }, // 0x4C 'L' + { 1939, 31, 23, 29, 0, -22 }, // 0x4D 'M' + { 2029, 26, 23, 24, 0, -22 }, // 0x4E 'N' + { 2104, 23, 23, 23, 1, -22 }, // 0x4F 'O' + { 2171, 22, 23, 20, 0, -22 }, // 0x50 'P' + { 2235, 23, 29, 23, 1, -22 }, // 0x51 'Q' + { 2319, 21, 23, 22, 0, -22 }, // 0x52 'R' + { 2380, 17, 23, 16, 0, -22 }, // 0x53 'S' + { 2429, 20, 23, 21, 3, -22 }, // 0x54 'T' + { 2487, 23, 23, 25, 4, -22 }, // 0x55 'U' + { 2554, 21, 23, 23, 5, -22 }, // 0x56 'V' + { 2615, 29, 23, 31, 5, -22 }, // 0x57 'W' + { 2699, 24, 23, 23, 0, -22 }, // 0x58 'X' + { 2768, 19, 23, 21, 4, -22 }, // 0x59 'Y' + { 2823, 22, 23, 20, 0, -22 }, // 0x5A 'Z' + { 2887, 13, 28, 14, 1, -22 }, // 0x5B '[' + { 2933, 12, 23, 17, 4, -22 }, // 0x5C '\' + { 2968, 12, 28, 14, 1, -22 }, // 0x5D ']' + { 3010, 15, 13, 15, 0, -22 }, // 0x5E '^' + { 3035, 18, 2, 17, 0, 3 }, // 0x5F '_' + { 3040, 6, 6, 9, 5, -22 }, // 0x60 '`' + { 3045, 15, 15, 17, 1, -14 }, // 0x61 'a' + { 3074, 16, 24, 17, 1, -23 }, // 0x62 'b' + { 3122, 13, 15, 14, 1, -14 }, // 0x63 'c' + { 3147, 17, 24, 18, 1, -23 }, // 0x64 'd' + { 3198, 13, 15, 14, 1, -14 }, // 0x65 'e' + { 3223, 20, 31, 15, -3, -23 }, // 0x66 'f' + { 3301, 16, 22, 15, -1, -14 }, // 0x67 'g' + { 3345, 16, 24, 17, 1, -23 }, // 0x68 'h' + { 3393, 9, 23, 9, 1, -22 }, // 0x69 'i' + { 3419, 15, 30, 10, -3, -22 }, // 0x6A 'j' + { 3476, 15, 24, 16, 1, -23 }, // 0x6B 'k' + { 3521, 8, 25, 9, 1, -23 }, // 0x6C 'l' + { 3546, 24, 15, 25, 0, -14 }, // 0x6D 'm' + { 3591, 17, 15, 17, 0, -14 }, // 0x6E 'n' + { 3623, 15, 15, 17, 1, -14 }, // 0x6F 'o' + { 3652, 20, 22, 16, -3, -14 }, // 0x70 'p' + { 3707, 16, 22, 17, 1, -14 }, // 0x71 'q' + { 3751, 13, 15, 13, 1, -14 }, // 0x72 'r' + { 3776, 13, 15, 12, 0, -14 }, // 0x73 's' + { 3801, 9, 18, 8, 1, -17 }, // 0x74 't' + { 3822, 15, 15, 17, 1, -14 }, // 0x75 'u' + { 3851, 14, 15, 16, 2, -14 }, // 0x76 'v' + { 3878, 22, 15, 24, 1, -14 }, // 0x77 'w' + { 3920, 16, 15, 15, -1, -14 }, // 0x78 'x' + { 3950, 16, 22, 16, 0, -14 }, // 0x79 'y' + { 3994, 14, 18, 14, 0, -14 }, // 0x7A 'z' + { 4026, 12, 30, 14, 2, -23 }, // 0x7B '{' + { 4071, 2, 23, 10, 4, -22 }, // 0x7C '|' + { 4077, 12, 31, 14, 0, -24 }, // 0x7D '}' + { 4124, 17, 4, 19, 1, -10 } }; // 0x7E '~' + +const GFXfont FreeSerifItalic18pt7b PROGMEM = { + (uint8_t *)FreeSerifItalic18pt7bBitmaps, + (GFXglyph *)FreeSerifItalic18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 4805 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic24pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic24pt7b.h new file mode 100644 index 0000000..75da1e0 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic24pt7b.h @@ -0,0 +1,737 @@ +const uint8_t FreeSerifItalic24pt7bBitmaps[] PROGMEM = { + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x01, 0xF0, 0x1E, 0x01, 0xE0, 0x1C, + 0x01, 0xC0, 0x3C, 0x03, 0x80, 0x38, 0x03, 0x80, 0x30, 0x07, 0x00, 0x60, + 0x06, 0x00, 0x60, 0x04, 0x00, 0x40, 0x0C, 0x00, 0x80, 0x08, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0xF8, 0x0F, 0x80, 0xF8, 0x07, 0x00, + 0x38, 0x1D, 0xE0, 0x77, 0x83, 0xDC, 0x0E, 0x70, 0x39, 0xC1, 0xEE, 0x07, + 0x38, 0x1C, 0xC0, 0x63, 0x01, 0x8C, 0x06, 0x20, 0x10, 0x00, 0x06, 0x03, + 0x00, 0x07, 0x03, 0x80, 0x03, 0x81, 0xC0, 0x03, 0x81, 0xC0, 0x01, 0xC0, + 0xE0, 0x00, 0xE0, 0x70, 0x00, 0xE0, 0x70, 0x00, 0x70, 0x38, 0x00, 0x30, + 0x18, 0x00, 0x38, 0x1C, 0x03, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xF0, 0x0E, + 0x07, 0x00, 0x06, 0x03, 0x00, 0x07, 0x03, 0x80, 0x03, 0x81, 0xC0, 0x03, + 0x81, 0xC0, 0x01, 0xC0, 0xE0, 0x00, 0xE0, 0x70, 0x1F, 0xFF, 0xFF, 0x8F, + 0xFF, 0xFF, 0x80, 0x70, 0x38, 0x00, 0x38, 0x1C, 0x00, 0x1C, 0x0C, 0x00, + 0x1C, 0x0E, 0x00, 0x0E, 0x07, 0x00, 0x0E, 0x07, 0x00, 0x07, 0x03, 0x80, + 0x03, 0x81, 0xC0, 0x03, 0x81, 0xC0, 0x01, 0xC0, 0xE0, 0x00, 0x00, 0x01, + 0x00, 0x00, 0x18, 0x00, 0x00, 0xC0, 0x00, 0xFF, 0x80, 0x1C, 0x2F, 0x01, + 0x83, 0x3C, 0x1C, 0x18, 0xE1, 0xC0, 0xC3, 0x0E, 0x06, 0x18, 0x70, 0x60, + 0x83, 0x83, 0x04, 0x1E, 0x18, 0x00, 0xF8, 0xC0, 0x03, 0xEC, 0x00, 0x0F, + 0xE0, 0x00, 0x3F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xC0, + 0x00, 0x7F, 0x00, 0x03, 0x7C, 0x00, 0x19, 0xE0, 0x01, 0x87, 0x80, 0x0C, + 0x3C, 0x00, 0x60, 0xE2, 0x03, 0x07, 0x10, 0x30, 0x39, 0x81, 0x81, 0xCE, + 0x0C, 0x0C, 0x70, 0x60, 0xE3, 0xC6, 0x06, 0x0F, 0x30, 0x60, 0x1F, 0x9E, + 0x00, 0x3F, 0x80, 0x00, 0xC0, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, + 0x80, 0x00, 0x01, 0xF0, 0x00, 0xC0, 0x03, 0xFE, 0x01, 0xE0, 0x03, 0xC7, + 0x83, 0xE0, 0x03, 0xC0, 0x7F, 0x60, 0x03, 0xC0, 0x20, 0x70, 0x01, 0xC0, + 0x10, 0x30, 0x01, 0xE0, 0x08, 0x38, 0x00, 0xE0, 0x04, 0x18, 0x00, 0xF0, + 0x02, 0x1C, 0x00, 0x70, 0x02, 0x0C, 0x00, 0x38, 0x01, 0x0E, 0x00, 0x1C, + 0x01, 0x8E, 0x00, 0x0E, 0x00, 0x86, 0x00, 0x07, 0x00, 0x87, 0x03, 0xE1, + 0x80, 0xC3, 0x07, 0xFC, 0xE1, 0xC3, 0x87, 0xC6, 0x3F, 0x81, 0x87, 0x81, + 0x8F, 0x81, 0xC7, 0x80, 0x40, 0x00, 0xC3, 0xC0, 0x20, 0x00, 0xE3, 0xC0, + 0x10, 0x00, 0x61, 0xC0, 0x08, 0x00, 0x61, 0xE0, 0x04, 0x00, 0x70, 0xF0, + 0x06, 0x00, 0x30, 0x70, 0x02, 0x00, 0x38, 0x38, 0x03, 0x00, 0x18, 0x1C, + 0x01, 0x00, 0x1C, 0x0E, 0x01, 0x80, 0x0C, 0x07, 0x01, 0x80, 0x0E, 0x01, + 0xC3, 0x80, 0x06, 0x00, 0x7F, 0x80, 0x06, 0x00, 0x1F, 0x00, 0x07, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x71, + 0xC0, 0x00, 0x01, 0xC3, 0x80, 0x00, 0x0E, 0x0E, 0x00, 0x00, 0x38, 0x38, + 0x00, 0x01, 0xE0, 0xE0, 0x00, 0x07, 0x87, 0x00, 0x00, 0x1E, 0x18, 0x00, + 0x00, 0x78, 0xC0, 0x00, 0x01, 0xE6, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x7F, + 0xC1, 0xFE, 0x03, 0x9F, 0x03, 0xE0, 0x3C, 0x3C, 0x07, 0x01, 0xE0, 0xF8, + 0x1C, 0x0F, 0x03, 0xE0, 0xE0, 0x7C, 0x07, 0x83, 0x01, 0xE0, 0x1F, 0x1C, + 0x07, 0x80, 0x7C, 0x60, 0x3E, 0x00, 0xFB, 0x00, 0xF8, 0x03, 0xFC, 0x03, + 0xE0, 0x07, 0xE0, 0x0F, 0x80, 0x1F, 0x00, 0x3F, 0x00, 0x3E, 0x00, 0x7C, + 0x00, 0xFC, 0x01, 0xF8, 0x0F, 0xF0, 0x03, 0xF0, 0xF3, 0xF0, 0x87, 0xFF, + 0x07, 0xFC, 0x07, 0xF0, 0x07, 0xC0, 0x39, 0xDE, 0xE7, 0x3B, 0x9C, 0xC6, + 0x31, 0x00, 0x00, 0x10, 0x01, 0x00, 0x18, 0x01, 0x80, 0x18, 0x01, 0x80, + 0x1C, 0x00, 0xC0, 0x0E, 0x00, 0xE0, 0x07, 0x00, 0x78, 0x03, 0x80, 0x3C, + 0x01, 0xE0, 0x0E, 0x00, 0x70, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x0E, 0x00, + 0x70, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x0E, + 0x00, 0x30, 0x01, 0x80, 0x0C, 0x00, 0x60, 0x01, 0x80, 0x0C, 0x00, 0x60, + 0x01, 0x00, 0x0C, 0x00, 0x20, 0x00, 0x00, 0x80, 0x06, 0x00, 0x10, 0x00, + 0x80, 0x06, 0x00, 0x30, 0x00, 0xC0, 0x06, 0x00, 0x30, 0x01, 0x80, 0x0C, + 0x00, 0x70, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xC0, + 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xC0, 0x1E, 0x00, 0xF0, 0x07, + 0x80, 0x38, 0x03, 0xC0, 0x1C, 0x00, 0xE0, 0x0E, 0x00, 0x60, 0x07, 0x00, + 0x30, 0x03, 0x00, 0x30, 0x03, 0x00, 0x10, 0x01, 0x00, 0x00, 0x01, 0x00, + 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0xE1, 0x07, 0xE1, 0x0F, + 0xF1, 0x1F, 0x19, 0x30, 0x07, 0xC0, 0x03, 0x80, 0x0D, 0x60, 0x79, 0x3C, + 0xF1, 0x1F, 0xE1, 0x0F, 0xE1, 0x07, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, + 0x03, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, 0x00, 0xE0, 0x00, 0x01, + 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, + 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xE0, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, + 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, + 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x7C, 0xF9, + 0xF1, 0xE1, 0xC3, 0x0C, 0x10, 0xC1, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0x00, + 0x77, 0xFF, 0xF7, 0x00, 0x00, 0x00, 0x78, 0x00, 0x03, 0x80, 0x00, 0x3C, + 0x00, 0x01, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x00, + 0xF0, 0x00, 0x07, 0x00, 0x00, 0x78, 0x00, 0x03, 0x80, 0x00, 0x3C, 0x00, + 0x01, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x70, + 0x00, 0x07, 0x80, 0x00, 0x38, 0x00, 0x03, 0x80, 0x00, 0x3C, 0x00, 0x01, + 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x70, 0x00, + 0x07, 0x80, 0x00, 0x38, 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xE0, + 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x00, 0x1F, 0x80, 0x03, 0x86, + 0x00, 0x30, 0x18, 0x03, 0x00, 0xC0, 0x38, 0x03, 0x03, 0x80, 0x18, 0x38, + 0x00, 0xC1, 0xC0, 0x07, 0x1C, 0x00, 0x38, 0xE0, 0x01, 0xCF, 0x00, 0x0E, + 0x70, 0x00, 0x77, 0x80, 0x07, 0xBC, 0x00, 0x3D, 0xE0, 0x01, 0xEE, 0x00, + 0x0F, 0xF0, 0x00, 0x77, 0x80, 0x07, 0xBC, 0x00, 0x3D, 0xC0, 0x01, 0xCE, + 0x00, 0x1E, 0x70, 0x00, 0xF3, 0x80, 0x07, 0x1C, 0x00, 0x78, 0xE0, 0x03, + 0x83, 0x00, 0x38, 0x18, 0x03, 0x80, 0xE0, 0x18, 0x03, 0x01, 0x80, 0x0C, + 0x38, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x00, 0x80, 0x1F, 0xC0, 0x3F, 0xE0, + 0x01, 0xF0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1C, 0x00, 0x1E, + 0x00, 0x0F, 0x00, 0x07, 0x80, 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x00, + 0xF0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x1E, 0x00, + 0x0F, 0x00, 0x07, 0x80, 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x01, 0xE0, + 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x3F, 0x01, 0xFF, + 0xF0, 0x00, 0x3F, 0x00, 0x07, 0xFE, 0x00, 0x7F, 0xF8, 0x07, 0x07, 0xE0, + 0x60, 0x1F, 0x06, 0x00, 0x7C, 0x20, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, + 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xE0, 0x00, 0x0E, 0x00, + 0x00, 0xF0, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0x70, + 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, 0x03, + 0x00, 0x00, 0x30, 0x00, 0x03, 0x00, 0x00, 0x30, 0x01, 0x03, 0x00, 0x08, + 0x30, 0x00, 0xC3, 0xFF, 0xFC, 0x3F, 0xFF, 0xE3, 0xFF, 0xFE, 0x00, 0x00, + 0x0F, 0xC0, 0x00, 0xFF, 0xC0, 0x06, 0x0F, 0x80, 0x30, 0x1E, 0x01, 0x80, + 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x78, + 0x00, 0x01, 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xF0, 0x00, 0x0E, 0x00, 0x01, + 0xF8, 0x00, 0x3F, 0xF8, 0x00, 0x0F, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x0F, + 0x80, 0x00, 0x3E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, + 0x00, 0x1E, 0x00, 0x00, 0x70, 0x00, 0x01, 0xC0, 0x00, 0x07, 0x00, 0x00, + 0x38, 0x00, 0x00, 0xC0, 0x70, 0x06, 0x03, 0xF8, 0x70, 0x07, 0xFF, 0x00, + 0x0F, 0xF0, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x70, 0x00, 0x03, 0xC0, + 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x37, 0x80, 0x00, + 0xDC, 0x00, 0x06, 0x70, 0x00, 0x33, 0xC0, 0x01, 0x8F, 0x00, 0x0C, 0x38, + 0x00, 0x60, 0xE0, 0x03, 0x07, 0x80, 0x18, 0x1E, 0x00, 0xC0, 0x70, 0x06, + 0x03, 0xC0, 0x30, 0x0F, 0x01, 0x80, 0x38, 0x0C, 0x00, 0xE0, 0x70, 0x07, + 0x81, 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xBF, 0xFF, 0xFE, 0x00, 0x0F, 0x00, + 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, + 0x70, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3F, 0xFC, 0x00, 0xFF, + 0xF0, 0x07, 0xFF, 0x80, 0x10, 0x00, 0x00, 0x40, 0x00, 0x02, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x70, 0x00, 0x01, 0xF8, 0x00, 0x0F, 0xF0, 0x00, 0x3F, + 0xF0, 0x00, 0x1F, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x03, 0x80, 0x00, 0x0E, 0x00, + 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x03, 0x80, 0x00, 0x0C, 0x00, 0x00, + 0x70, 0x00, 0x01, 0xC0, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0x80, + 0x70, 0x0E, 0x03, 0xF0, 0xE0, 0x07, 0xFF, 0x00, 0x0F, 0xE0, 0x00, 0x00, + 0x00, 0x0E, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x03, + 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xC0, + 0x00, 0x0F, 0x80, 0x00, 0x3E, 0x00, 0x00, 0xF9, 0xF8, 0x01, 0xFF, 0xFC, + 0x07, 0xE0, 0x7C, 0x0F, 0x80, 0x7C, 0x3E, 0x00, 0x78, 0x78, 0x00, 0x78, + 0xF0, 0x00, 0xF3, 0xC0, 0x01, 0xE7, 0x80, 0x03, 0xCF, 0x00, 0x07, 0x9C, + 0x00, 0x0F, 0x38, 0x00, 0x3E, 0x70, 0x00, 0x78, 0xE0, 0x00, 0xF1, 0xC0, + 0x03, 0xC1, 0x80, 0x07, 0x83, 0x00, 0x1E, 0x03, 0x00, 0x38, 0x06, 0x01, + 0xE0, 0x03, 0x07, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0xFF, 0xF9, 0xFF, 0xFF, + 0xCF, 0xFF, 0xFC, 0xE0, 0x00, 0xCC, 0x00, 0x0E, 0x40, 0x00, 0x60, 0x00, + 0x07, 0x00, 0x00, 0x70, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x01, 0x80, + 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x07, + 0x00, 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0x38, 0x00, 0x03, 0x80, 0x00, + 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, + 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0x78, 0x00, 0x03, 0x80, 0x00, 0x38, + 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x00, 0x00, 0x3F, 0x80, 0x03, 0x83, + 0x80, 0x1C, 0x03, 0x00, 0xE0, 0x0E, 0x07, 0x00, 0x1C, 0x1C, 0x00, 0x70, + 0x70, 0x01, 0xC1, 0xC0, 0x07, 0x07, 0x80, 0x1C, 0x1E, 0x00, 0xE0, 0x3C, + 0x07, 0x80, 0xFC, 0x38, 0x01, 0xFB, 0xC0, 0x03, 0xF8, 0x00, 0x0F, 0xE0, + 0x00, 0x7F, 0xC0, 0x07, 0x1F, 0x80, 0x78, 0x3F, 0x03, 0x80, 0x7C, 0x1E, + 0x00, 0xF8, 0x70, 0x01, 0xE3, 0x80, 0x03, 0xCE, 0x00, 0x07, 0x38, 0x00, + 0x1C, 0xE0, 0x00, 0x73, 0x80, 0x01, 0xCE, 0x00, 0x06, 0x1C, 0x00, 0x38, + 0x70, 0x01, 0xC0, 0xE0, 0x0E, 0x01, 0xE0, 0xE0, 0x01, 0xFE, 0x00, 0x00, + 0x1F, 0x80, 0x03, 0xC3, 0x00, 0x1C, 0x02, 0x00, 0xE0, 0x0C, 0x07, 0x00, + 0x18, 0x3C, 0x00, 0x60, 0xE0, 0x01, 0xC7, 0x80, 0x07, 0x1E, 0x00, 0x1C, + 0xF0, 0x00, 0x73, 0xC0, 0x01, 0xCF, 0x00, 0x07, 0x3C, 0x00, 0x3C, 0xF0, + 0x00, 0xF3, 0xC0, 0x03, 0xCF, 0x00, 0x1E, 0x1E, 0x00, 0x78, 0x7C, 0x03, + 0xE0, 0xF8, 0x3F, 0x01, 0xFF, 0xBC, 0x03, 0xF1, 0xE0, 0x00, 0x0F, 0x80, + 0x00, 0x3C, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x03, + 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x78, 0x00, + 0x0F, 0x80, 0x00, 0xE0, 0x00, 0x00, 0x07, 0x07, 0xC3, 0xE1, 0xF0, 0x70, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x38, 0x3E, 0x1F, 0x0F, 0x83, 0x80, 0x01, 0xC0, 0x7C, 0x0F, 0x81, + 0xF0, 0x1C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x18, 0x07, 0x80, 0xF8, 0x1F, 0x01, 0xE0, + 0x1C, 0x03, 0x00, 0xC0, 0x18, 0x04, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x0C, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x3F, 0xC0, + 0x01, 0xFC, 0x00, 0x0F, 0xE0, 0x00, 0xFF, 0x00, 0x07, 0xF8, 0x00, 0x3F, + 0xC0, 0x01, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x1F, 0x80, + 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, + 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x1F, + 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x07, 0x00, 0x00, 0x02, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, + 0xE0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x07, 0xF0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x3F, 0x00, 0x00, 0xFE, 0x00, 0x07, 0xF8, 0x00, 0x1F, 0xE0, + 0x00, 0x7F, 0x80, 0x01, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x3F, 0xC0, 0x00, + 0xFF, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x80, 0x00, 0x00, + 0x03, 0xF0, 0x06, 0x1C, 0x0C, 0x0E, 0x1C, 0x06, 0x1C, 0x07, 0x1C, 0x07, + 0x1C, 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x0E, 0x00, 0x1E, 0x00, 0x3C, + 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, 0x03, 0x00, + 0x06, 0x00, 0x04, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x10, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xF8, 0x00, + 0xF8, 0x00, 0xF8, 0x00, 0x70, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x1F, + 0xFF, 0x80, 0x00, 0x3F, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x7C, + 0x00, 0x07, 0x80, 0x7C, 0x00, 0x00, 0xE0, 0x3C, 0x00, 0x00, 0x38, 0x3C, + 0x00, 0x00, 0x0C, 0x3C, 0x00, 0x78, 0x07, 0x1E, 0x00, 0xFE, 0xE1, 0x9E, + 0x00, 0xF1, 0xF0, 0xEF, 0x00, 0xE0, 0xF0, 0x37, 0x80, 0xE0, 0x38, 0x1F, + 0x80, 0x70, 0x1C, 0x0F, 0xC0, 0x70, 0x1E, 0x07, 0xE0, 0x38, 0x0F, 0x03, + 0xF0, 0x18, 0x07, 0x01, 0xF8, 0x1C, 0x03, 0x80, 0xFC, 0x0E, 0x01, 0xC0, + 0xDE, 0x07, 0x01, 0xE0, 0x6F, 0x03, 0x80, 0xE0, 0x73, 0xC1, 0xC0, 0xF0, + 0x31, 0xE0, 0xF0, 0xF8, 0x30, 0xF0, 0x38, 0xDC, 0x30, 0x3C, 0x1F, 0xC7, + 0xF0, 0x0E, 0x07, 0x81, 0xF0, 0x07, 0x80, 0x00, 0x00, 0x01, 0xE0, 0x00, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x01, 0x00, 0x03, 0xF0, + 0x0F, 0x80, 0x00, 0x7F, 0xFF, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x00, + 0x00, 0x18, 0x00, 0x00, 0x01, 0xC0, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x00, + 0xF0, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x03, 0xF0, + 0x00, 0x00, 0x37, 0x80, 0x00, 0x03, 0x3C, 0x00, 0x00, 0x19, 0xE0, 0x00, + 0x01, 0x8F, 0x80, 0x00, 0x08, 0x7C, 0x00, 0x00, 0xC3, 0xE0, 0x00, 0x0C, + 0x0F, 0x00, 0x00, 0x60, 0x78, 0x00, 0x06, 0x03, 0xC0, 0x00, 0x20, 0x1F, + 0x00, 0x03, 0x00, 0xF8, 0x00, 0x3F, 0xFF, 0xC0, 0x01, 0xFF, 0xFE, 0x00, + 0x18, 0x00, 0xF0, 0x00, 0xC0, 0x07, 0x80, 0x0C, 0x00, 0x3E, 0x00, 0xE0, + 0x01, 0xF0, 0x06, 0x00, 0x0F, 0x80, 0x70, 0x00, 0x3C, 0x03, 0x00, 0x01, + 0xE0, 0x38, 0x00, 0x0F, 0x83, 0xC0, 0x00, 0x7C, 0x3E, 0x00, 0x07, 0xF3, + 0xFC, 0x01, 0xFF, 0xE0, 0x03, 0xFF, 0xFE, 0x00, 0x07, 0xFF, 0xF8, 0x00, + 0x3E, 0x07, 0xC0, 0x03, 0xE0, 0x3E, 0x00, 0x3E, 0x01, 0xF0, 0x03, 0xC0, + 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x78, 0x01, 0xF0, + 0x07, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x7C, 0x00, 0xF0, + 0x3F, 0x00, 0x1F, 0xFF, 0x80, 0x01, 0xFF, 0xFC, 0x00, 0x1F, 0x07, 0xE0, + 0x01, 0xE0, 0x1F, 0x00, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x07, 0xC0, 0x3C, + 0x00, 0x7C, 0x03, 0xC0, 0x07, 0xC0, 0x7C, 0x00, 0x7C, 0x07, 0xC0, 0x07, + 0xC0, 0x78, 0x00, 0x7C, 0x0F, 0x80, 0x0F, 0x80, 0xF8, 0x00, 0xF8, 0x0F, + 0x00, 0x1F, 0x00, 0xF0, 0x03, 0xE0, 0x1F, 0x81, 0xFC, 0x03, 0xFF, 0xFF, + 0x80, 0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x01, 0xFE, 0x04, 0x00, 0x3F, 0xFF, + 0xE0, 0x03, 0xF0, 0x1F, 0x80, 0x1F, 0x00, 0x3E, 0x00, 0xF0, 0x00, 0x78, + 0x0F, 0x80, 0x00, 0xE0, 0x3C, 0x00, 0x03, 0x81, 0xF0, 0x00, 0x04, 0x0F, + 0x80, 0x00, 0x10, 0x7C, 0x00, 0x00, 0x41, 0xF0, 0x00, 0x00, 0x0F, 0x80, + 0x00, 0x00, 0x3E, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x07, 0xC0, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x03, + 0xE0, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0xF8, + 0x00, 0x00, 0x01, 0xF0, 0x00, 0x02, 0x07, 0xC0, 0x00, 0x18, 0x0F, 0x80, + 0x00, 0xC0, 0x3E, 0x00, 0x06, 0x00, 0x7C, 0x00, 0x70, 0x00, 0xFC, 0x07, + 0x00, 0x00, 0xFF, 0xF8, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x03, 0xFF, 0xFF, + 0x00, 0x00, 0x3F, 0xFF, 0xE0, 0x00, 0x0F, 0xC0, 0xFC, 0x00, 0x07, 0xC0, + 0x1F, 0x00, 0x03, 0xE0, 0x07, 0xC0, 0x01, 0xE0, 0x01, 0xF0, 0x01, 0xF0, + 0x00, 0x7C, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x7C, 0x00, 0x0F, 0x00, 0x3C, + 0x00, 0x07, 0xC0, 0x3E, 0x00, 0x03, 0xE0, 0x1F, 0x00, 0x01, 0xF0, 0x0F, + 0x00, 0x00, 0xF8, 0x0F, 0x80, 0x00, 0x7C, 0x07, 0xC0, 0x00, 0x3E, 0x03, + 0xE0, 0x00, 0x1F, 0x01, 0xE0, 0x00, 0x1F, 0x81, 0xF0, 0x00, 0x0F, 0x80, + 0xF8, 0x00, 0x07, 0xC0, 0x78, 0x00, 0x03, 0xE0, 0x3C, 0x00, 0x03, 0xE0, + 0x3E, 0x00, 0x01, 0xF0, 0x1F, 0x00, 0x01, 0xF0, 0x0F, 0x00, 0x01, 0xF0, + 0x0F, 0x80, 0x01, 0xF8, 0x07, 0xC0, 0x01, 0xF0, 0x03, 0xE0, 0x01, 0xF0, + 0x01, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x0F, 0xE0, 0x01, 0xFF, 0xFF, 0xC0, + 0x03, 0xFF, 0xFE, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xF8, 0x03, 0xFF, 0xFF, + 0xC0, 0x0F, 0x80, 0x1E, 0x00, 0x7C, 0x00, 0x30, 0x03, 0xE0, 0x01, 0x00, + 0x1E, 0x00, 0x08, 0x01, 0xF0, 0x00, 0x40, 0x0F, 0x80, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x03, 0xC0, 0x10, 0x00, 0x3E, 0x01, 0x80, 0x01, 0xF0, 0x08, + 0x00, 0x0F, 0x01, 0xC0, 0x00, 0xFF, 0xFE, 0x00, 0x07, 0xFF, 0xF0, 0x00, + 0x3E, 0x07, 0x00, 0x01, 0xE0, 0x18, 0x00, 0x1F, 0x00, 0xC0, 0x00, 0xF8, + 0x04, 0x00, 0x07, 0x80, 0x20, 0x00, 0x3C, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x08, 0x0F, 0x80, 0x00, 0xC0, + 0x7C, 0x00, 0x0E, 0x03, 0xC0, 0x00, 0xE0, 0x1E, 0x00, 0x0F, 0x01, 0xF8, + 0x03, 0xF8, 0x1F, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0xFC, 0x00, 0x03, 0xFF, + 0xFF, 0xF8, 0x03, 0xFF, 0xFF, 0xC0, 0x0F, 0x80, 0x1E, 0x00, 0x7C, 0x00, + 0x30, 0x03, 0xE0, 0x01, 0x00, 0x1E, 0x00, 0x08, 0x01, 0xF0, 0x00, 0x40, + 0x0F, 0x80, 0x02, 0x00, 0x7C, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x3E, + 0x00, 0x80, 0x01, 0xF0, 0x0C, 0x00, 0x0F, 0x00, 0xC0, 0x00, 0xF8, 0x0E, + 0x00, 0x07, 0xFF, 0xF0, 0x00, 0x3F, 0xFF, 0x00, 0x01, 0xE0, 0x18, 0x00, + 0x1F, 0x00, 0xC0, 0x00, 0xF8, 0x06, 0x00, 0x07, 0xC0, 0x20, 0x00, 0x3C, + 0x01, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xFF, + 0xC0, 0x00, 0x00, 0x00, 0x01, 0xFE, 0x02, 0x00, 0x1F, 0xFF, 0x8C, 0x00, + 0xFC, 0x07, 0xF8, 0x03, 0xE0, 0x03, 0xF0, 0x0F, 0x00, 0x03, 0xC0, 0x3C, + 0x00, 0x03, 0x80, 0xF0, 0x00, 0x07, 0x03, 0xC0, 0x00, 0x0E, 0x0F, 0x80, + 0x00, 0x08, 0x3E, 0x00, 0x00, 0x10, 0x7C, 0x00, 0x00, 0x01, 0xF0, 0x00, + 0x00, 0x03, 0xE0, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x3F, + 0xFF, 0xE0, 0x00, 0x0F, 0xE7, 0xC0, 0x00, 0x0F, 0x0F, 0x80, 0x00, 0x1E, + 0x1F, 0x00, 0x00, 0x7C, 0x3E, 0x00, 0x00, 0xF0, 0x7C, 0x00, 0x01, 0xE0, + 0x78, 0x00, 0x03, 0xC0, 0xF8, 0x00, 0x0F, 0x01, 0xF0, 0x00, 0x1E, 0x01, + 0xF0, 0x00, 0x3C, 0x01, 0xE0, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, 0x01, + 0xF8, 0x0F, 0x80, 0x00, 0xFF, 0xFC, 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x03, + 0xFF, 0xE0, 0x7F, 0xF0, 0x07, 0xF8, 0x01, 0xFC, 0x00, 0x3E, 0x00, 0x0F, + 0x80, 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, + 0x00, 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, + 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0xF8, 0x00, 0x3E, + 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, 0x00, + 0x03, 0xC0, 0x01, 0xFF, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0xFF, 0x80, 0x01, + 0xE0, 0x00, 0x78, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF8, + 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x7C, 0x00, + 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x0F, + 0x80, 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x03, 0xC0, + 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x03, 0xF8, 0x00, + 0xFE, 0x00, 0xFF, 0xE0, 0x7F, 0xFC, 0x00, 0x01, 0xFF, 0xC0, 0x1F, 0xE0, + 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x07, 0xC0, 0x01, + 0xF0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF0, + 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xE0, 0x00, 0xF8, 0x00, + 0x3E, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1E, + 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, 0x00, + 0x0F, 0xE0, 0x0F, 0xFE, 0x00, 0x00, 0x1F, 0xFE, 0x00, 0x07, 0xF0, 0x00, + 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0xF8, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x78, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, + 0x00, 0x07, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x78, 0x00, + 0x00, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF0, 0x01, 0xC1, 0xE0, 0x07, 0xC7, + 0x80, 0x0F, 0x8F, 0x00, 0x1F, 0x3C, 0x00, 0x1F, 0xF0, 0x00, 0x0F, 0x80, + 0x00, 0x01, 0xFF, 0xE1, 0xFF, 0x80, 0x3F, 0xC0, 0x1F, 0x80, 0x0F, 0x80, + 0x0F, 0x00, 0x07, 0xC0, 0x0F, 0x00, 0x03, 0xC0, 0x0F, 0x00, 0x01, 0xE0, + 0x0E, 0x00, 0x01, 0xF0, 0x0E, 0x00, 0x00, 0xF8, 0x0E, 0x00, 0x00, 0x78, + 0x1C, 0x00, 0x00, 0x3C, 0x1C, 0x00, 0x00, 0x3E, 0x3C, 0x00, 0x00, 0x1F, + 0x38, 0x00, 0x00, 0x0F, 0x38, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x07, + 0xFE, 0x00, 0x00, 0x03, 0xDF, 0x00, 0x00, 0x01, 0xE7, 0xC0, 0x00, 0x01, + 0xF3, 0xE0, 0x00, 0x00, 0xF8, 0xF8, 0x00, 0x00, 0x78, 0x3C, 0x00, 0x00, + 0x3C, 0x1F, 0x00, 0x00, 0x3E, 0x07, 0xC0, 0x00, 0x1F, 0x03, 0xE0, 0x00, + 0x0F, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x3C, 0x00, 0x07, 0xC0, 0x1F, 0x00, + 0x03, 0xC0, 0x07, 0x80, 0x01, 0xE0, 0x03, 0xE0, 0x01, 0xF0, 0x01, 0xF8, + 0x01, 0xFC, 0x01, 0xFE, 0x03, 0xFF, 0xC3, 0xFF, 0xE0, 0x03, 0xFF, 0xE0, + 0x00, 0x0F, 0xF0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, + 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x78, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x0F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, + 0x00, 0x01, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x01, + 0xF0, 0x00, 0x08, 0x3C, 0x00, 0x03, 0x0F, 0x80, 0x00, 0x41, 0xF0, 0x00, + 0x18, 0x3C, 0x00, 0x07, 0x07, 0x80, 0x01, 0xC1, 0xF8, 0x01, 0xF8, 0x7F, + 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xC0, 0x01, 0xFF, 0x00, 0x00, 0x3F, 0xC0, + 0x0F, 0xC0, 0x00, 0x1F, 0xC0, 0x01, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0xFC, + 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x01, 0xFC, 0x00, 0x0F, 0xC0, 0x00, + 0xFF, 0x00, 0x02, 0xF0, 0x00, 0x37, 0x80, 0x01, 0xBC, 0x00, 0x19, 0xE0, + 0x00, 0x6F, 0x80, 0x0E, 0xF8, 0x00, 0x1B, 0xE0, 0x03, 0x3E, 0x00, 0x04, + 0x78, 0x01, 0x8F, 0x00, 0x03, 0x1E, 0x00, 0xE7, 0xC0, 0x00, 0xC7, 0x80, + 0x31, 0xF0, 0x00, 0x21, 0xE0, 0x18, 0x78, 0x00, 0x18, 0x78, 0x0E, 0x1E, + 0x00, 0x06, 0x1E, 0x03, 0x0F, 0x80, 0x01, 0x87, 0x81, 0x83, 0xE0, 0x00, + 0x41, 0xF0, 0xE0, 0xF0, 0x00, 0x30, 0x7C, 0x30, 0x3C, 0x00, 0x0C, 0x0F, + 0x18, 0x1F, 0x00, 0x03, 0x03, 0xCE, 0x07, 0xC0, 0x01, 0x80, 0xF3, 0x01, + 0xE0, 0x00, 0x60, 0x3D, 0x80, 0xF8, 0x00, 0x18, 0x0F, 0xE0, 0x3E, 0x00, + 0x0C, 0x03, 0xF0, 0x0F, 0x00, 0x03, 0x00, 0xF8, 0x03, 0xC0, 0x00, 0xC0, + 0x3E, 0x01, 0xF0, 0x00, 0x70, 0x0F, 0x00, 0x7C, 0x00, 0x1C, 0x01, 0x80, + 0x3F, 0x00, 0x0F, 0x80, 0x60, 0x1F, 0xC0, 0x0F, 0xF8, 0x10, 0x1F, 0xFE, + 0x00, 0x03, 0xFC, 0x00, 0x3F, 0xE0, 0x1F, 0xC0, 0x01, 0xF8, 0x00, 0xF8, + 0x00, 0x1C, 0x00, 0x1F, 0x00, 0x03, 0x80, 0x03, 0xF0, 0x00, 0x60, 0x00, + 0x7E, 0x00, 0x0C, 0x00, 0x0B, 0xE0, 0x03, 0x80, 0x03, 0x7C, 0x00, 0x60, + 0x00, 0x67, 0x80, 0x0C, 0x00, 0x0C, 0xF8, 0x03, 0x80, 0x03, 0x0F, 0x00, + 0x70, 0x00, 0x61, 0xF0, 0x0C, 0x00, 0x0C, 0x3E, 0x01, 0x80, 0x01, 0x83, + 0xC0, 0x70, 0x00, 0x60, 0x7C, 0x0C, 0x00, 0x0C, 0x07, 0x81, 0x80, 0x01, + 0x80, 0xF8, 0x30, 0x00, 0x60, 0x0F, 0x0E, 0x00, 0x0C, 0x01, 0xE1, 0x80, + 0x01, 0x80, 0x3E, 0x30, 0x00, 0x30, 0x03, 0xCE, 0x00, 0x0C, 0x00, 0x7D, + 0x80, 0x01, 0x80, 0x07, 0xB0, 0x00, 0x30, 0x00, 0xF6, 0x00, 0x0E, 0x00, + 0x1F, 0xC0, 0x01, 0x80, 0x01, 0xF0, 0x00, 0x30, 0x00, 0x3E, 0x00, 0x0E, + 0x00, 0x03, 0xC0, 0x01, 0xC0, 0x00, 0x70, 0x00, 0x7C, 0x00, 0x06, 0x00, + 0x3F, 0xE0, 0x00, 0xC0, 0x00, 0x00, 0x00, 0x18, 0x00, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0x1F, 0xFE, 0x00, 0x01, 0xF0, 0x7C, 0x00, 0x0F, 0x00, 0x78, + 0x00, 0x78, 0x00, 0xF0, 0x07, 0xC0, 0x03, 0xE0, 0x3E, 0x00, 0x07, 0x81, + 0xF0, 0x00, 0x1E, 0x07, 0xC0, 0x00, 0x7C, 0x3E, 0x00, 0x01, 0xF1, 0xF0, + 0x00, 0x07, 0xC7, 0xC0, 0x00, 0x1F, 0x3F, 0x00, 0x00, 0x7C, 0xF8, 0x00, + 0x01, 0xF7, 0xE0, 0x00, 0x0F, 0xDF, 0x00, 0x00, 0x3F, 0x7C, 0x00, 0x00, + 0xFB, 0xF0, 0x00, 0x07, 0xEF, 0xC0, 0x00, 0x1F, 0xBE, 0x00, 0x00, 0x7C, + 0xF8, 0x00, 0x03, 0xF3, 0xE0, 0x00, 0x0F, 0x8F, 0x80, 0x00, 0x3E, 0x3E, + 0x00, 0x01, 0xF0, 0xF8, 0x00, 0x0F, 0x81, 0xE0, 0x00, 0x3E, 0x07, 0x80, + 0x01, 0xF0, 0x1F, 0x00, 0x0F, 0x80, 0x3C, 0x00, 0x7C, 0x00, 0x78, 0x03, + 0xC0, 0x00, 0xF8, 0x3E, 0x00, 0x01, 0xFF, 0xE0, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x0F, 0x81, 0xF8, + 0x00, 0x7C, 0x03, 0xE0, 0x03, 0xE0, 0x1F, 0x00, 0x1E, 0x00, 0x7C, 0x01, + 0xF0, 0x03, 0xE0, 0x0F, 0x80, 0x1F, 0x00, 0x78, 0x00, 0xF8, 0x03, 0xC0, + 0x07, 0xC0, 0x3E, 0x00, 0x3C, 0x01, 0xF0, 0x03, 0xE0, 0x0F, 0x00, 0x3E, + 0x00, 0xF8, 0x03, 0xF0, 0x07, 0xC0, 0x7E, 0x00, 0x3F, 0xFF, 0xE0, 0x01, + 0xEF, 0xF8, 0x00, 0x1F, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x07, 0x80, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x03, + 0xC0, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x03, 0xFF, 0x80, 0x00, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, + 0xFE, 0x00, 0x00, 0xF0, 0x7C, 0x00, 0x0F, 0x00, 0x78, 0x00, 0x78, 0x00, + 0xF0, 0x03, 0xC0, 0x03, 0xE0, 0x1E, 0x00, 0x07, 0x80, 0xF0, 0x00, 0x1E, + 0x07, 0xC0, 0x00, 0x7C, 0x3E, 0x00, 0x01, 0xF1, 0xF8, 0x00, 0x07, 0xC7, + 0xC0, 0x00, 0x1F, 0x3F, 0x00, 0x00, 0x7C, 0xF8, 0x00, 0x01, 0xF7, 0xE0, + 0x00, 0x0F, 0xDF, 0x80, 0x00, 0x3F, 0x7C, 0x00, 0x00, 0xFB, 0xF0, 0x00, + 0x03, 0xEF, 0xC0, 0x00, 0x1F, 0xBE, 0x00, 0x00, 0x7C, 0xF8, 0x00, 0x01, + 0xF3, 0xE0, 0x00, 0x0F, 0x8F, 0x80, 0x00, 0x3E, 0x3E, 0x00, 0x01, 0xF0, + 0xF8, 0x00, 0x07, 0xC3, 0xE0, 0x00, 0x3E, 0x07, 0x80, 0x01, 0xF0, 0x1F, + 0x00, 0x07, 0x80, 0x3C, 0x00, 0x3C, 0x00, 0xF8, 0x01, 0xE0, 0x01, 0xE0, + 0x1E, 0x00, 0x01, 0xF3, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x03, 0x00, + 0x00, 0x00, 0x18, 0x00, 0x00, 0x01, 0xC0, 0x00, 0x04, 0x0F, 0xF0, 0x00, + 0x60, 0x7F, 0xFC, 0x07, 0x03, 0xFF, 0xFF, 0xF8, 0x38, 0x1F, 0xFF, 0x80, + 0x00, 0x07, 0xF8, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x07, 0xFF, 0xF8, 0x00, + 0x3E, 0x0F, 0xC0, 0x03, 0xE0, 0x3E, 0x00, 0x3E, 0x01, 0xF0, 0x03, 0xC0, + 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x78, 0x01, 0xF0, + 0x07, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x7C, 0x00, 0xF0, + 0x1F, 0x80, 0x1F, 0xFF, 0xE0, 0x01, 0xFF, 0xF0, 0x00, 0x1E, 0x1E, 0x00, + 0x01, 0xE1, 0xE0, 0x00, 0x3E, 0x1F, 0x00, 0x03, 0xE0, 0xF0, 0x00, 0x3C, + 0x0F, 0x00, 0x03, 0xC0, 0xF8, 0x00, 0x7C, 0x07, 0x80, 0x07, 0xC0, 0x7C, + 0x00, 0x78, 0x03, 0xC0, 0x0F, 0x80, 0x3C, 0x00, 0xF8, 0x03, 0xE0, 0x0F, + 0x00, 0x1E, 0x00, 0xF0, 0x01, 0xE0, 0x1F, 0x00, 0x1F, 0x03, 0xF8, 0x00, + 0xF8, 0xFF, 0xE0, 0x0F, 0xE0, 0x00, 0x3F, 0x06, 0x01, 0xFF, 0xDC, 0x07, + 0xC1, 0xF0, 0x1E, 0x01, 0xE0, 0x3C, 0x01, 0xC0, 0xF0, 0x03, 0x81, 0xE0, + 0x03, 0x03, 0xC0, 0x04, 0x07, 0x80, 0x08, 0x0F, 0x80, 0x00, 0x1F, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, + 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7C, 0x08, 0x00, 0x78, 0x10, + 0x00, 0xF0, 0x20, 0x01, 0xE0, 0xC0, 0x03, 0xC1, 0x80, 0x07, 0x83, 0x80, + 0x1E, 0x07, 0x00, 0x3C, 0x0F, 0x00, 0xF0, 0x1F, 0x87, 0xC0, 0x23, 0xFF, + 0x00, 0x81, 0xF8, 0x00, 0x3F, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xFD, 0xF0, + 0x3E, 0x07, 0xB8, 0x07, 0xC0, 0x76, 0x00, 0xF8, 0x04, 0x80, 0x3E, 0x00, + 0xB0, 0x07, 0xC0, 0x14, 0x00, 0xF8, 0x02, 0x00, 0x1E, 0x00, 0x00, 0x07, + 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xC0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0xF8, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x0F, 0x00, + 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x03, + 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x3F, 0xFF, 0x00, + 0x00, 0x7F, 0xFE, 0x03, 0xFE, 0x1F, 0xE0, 0x01, 0xF8, 0x1F, 0x80, 0x01, + 0xC0, 0x3E, 0x00, 0x03, 0x80, 0x7C, 0x00, 0x07, 0x00, 0xF8, 0x00, 0x0C, + 0x03, 0xE0, 0x00, 0x18, 0x07, 0xC0, 0x00, 0x70, 0x0F, 0x80, 0x00, 0xC0, + 0x1F, 0x00, 0x01, 0x80, 0x7C, 0x00, 0x03, 0x00, 0xF8, 0x00, 0x0E, 0x01, + 0xF0, 0x00, 0x18, 0x07, 0xC0, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x60, 0x1F, + 0x00, 0x01, 0x80, 0x3E, 0x00, 0x03, 0x00, 0xF8, 0x00, 0x06, 0x01, 0xF0, + 0x00, 0x18, 0x03, 0xE0, 0x00, 0x30, 0x07, 0xC0, 0x00, 0x60, 0x1F, 0x00, + 0x00, 0xC0, 0x3E, 0x00, 0x03, 0x00, 0x7C, 0x00, 0x06, 0x00, 0xF8, 0x00, + 0x18, 0x01, 0xF0, 0x00, 0x30, 0x03, 0xE0, 0x00, 0xC0, 0x03, 0xE0, 0x03, + 0x80, 0x03, 0xE0, 0x0E, 0x00, 0x03, 0xF0, 0x78, 0x00, 0x03, 0xFF, 0xC0, + 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0xE0, 0x0F, 0xF9, 0xFC, 0x00, 0x1F, + 0x07, 0xC0, 0x00, 0x78, 0x3E, 0x00, 0x03, 0x81, 0xF0, 0x00, 0x18, 0x0F, + 0x80, 0x01, 0xC0, 0x7C, 0x00, 0x0C, 0x01, 0xE0, 0x00, 0xC0, 0x0F, 0x80, + 0x06, 0x00, 0x7C, 0x00, 0x60, 0x03, 0xE0, 0x07, 0x00, 0x1F, 0x00, 0x30, + 0x00, 0xF8, 0x03, 0x00, 0x03, 0xC0, 0x18, 0x00, 0x1E, 0x01, 0x80, 0x00, + 0xF8, 0x1C, 0x00, 0x07, 0xC0, 0xC0, 0x00, 0x3E, 0x0C, 0x00, 0x01, 0xF0, + 0x60, 0x00, 0x07, 0x86, 0x00, 0x00, 0x3C, 0x30, 0x00, 0x01, 0xE3, 0x00, + 0x00, 0x0F, 0xB0, 0x00, 0x00, 0x7D, 0x80, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0x0F, 0xC0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x1E, + 0x00, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x10, 0x00, + 0x00, 0xFF, 0xE3, 0xFF, 0x81, 0xFE, 0x7F, 0x01, 0xFC, 0x00, 0xF8, 0x7C, + 0x01, 0xF0, 0x00, 0xE0, 0xF8, 0x03, 0xE0, 0x01, 0x81, 0xF0, 0x03, 0xC0, + 0x07, 0x03, 0xE0, 0x07, 0x80, 0x0C, 0x03, 0xC0, 0x0F, 0x00, 0x18, 0x07, + 0x80, 0x1E, 0x00, 0x60, 0x0F, 0x00, 0x7E, 0x00, 0xC0, 0x1F, 0x00, 0xFC, + 0x03, 0x00, 0x3E, 0x03, 0xF8, 0x06, 0x00, 0x7C, 0x05, 0xF0, 0x18, 0x00, + 0xF8, 0x1B, 0xE0, 0x30, 0x01, 0xF0, 0x33, 0xC0, 0xC0, 0x01, 0xE0, 0xC7, + 0x83, 0x80, 0x03, 0xC1, 0x8F, 0x06, 0x00, 0x07, 0x86, 0x1E, 0x1C, 0x00, + 0x0F, 0x0C, 0x3C, 0x30, 0x00, 0x1F, 0x30, 0x7C, 0xE0, 0x00, 0x3E, 0x60, + 0xF9, 0x80, 0x00, 0x7D, 0x81, 0xF7, 0x00, 0x00, 0xFB, 0x03, 0xEC, 0x00, + 0x01, 0xFC, 0x03, 0xF8, 0x00, 0x01, 0xF8, 0x07, 0xE0, 0x00, 0x03, 0xE0, + 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x1F, 0x00, 0x00, 0x0F, 0x00, 0x3C, 0x00, + 0x00, 0x1E, 0x00, 0x78, 0x00, 0x00, 0x38, 0x00, 0xE0, 0x00, 0x00, 0x70, + 0x01, 0xC0, 0x00, 0x00, 0xC0, 0x03, 0x00, 0x00, 0x00, 0x80, 0x06, 0x00, + 0x00, 0x07, 0xFF, 0x83, 0xFF, 0x01, 0xFE, 0x00, 0xFE, 0x00, 0x7C, 0x00, + 0x78, 0x00, 0x7C, 0x00, 0x70, 0x00, 0x3C, 0x00, 0xE0, 0x00, 0x3E, 0x01, + 0xC0, 0x00, 0x3E, 0x01, 0x80, 0x00, 0x1F, 0x03, 0x00, 0x00, 0x1F, 0x07, + 0x00, 0x00, 0x0F, 0x0E, 0x00, 0x00, 0x0F, 0x9C, 0x00, 0x00, 0x0F, 0xB8, + 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x03, 0xC0, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x07, 0xF0, + 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x1C, 0xF0, 0x00, 0x00, 0x38, 0xF8, + 0x00, 0x00, 0x30, 0xF8, 0x00, 0x00, 0x60, 0x7C, 0x00, 0x00, 0xC0, 0x7C, + 0x00, 0x01, 0xC0, 0x3C, 0x00, 0x03, 0x80, 0x3E, 0x00, 0x07, 0x00, 0x3E, + 0x00, 0x0E, 0x00, 0x1F, 0x00, 0x1E, 0x00, 0x1F, 0x00, 0x7F, 0x00, 0x3F, + 0xC0, 0xFF, 0xC1, 0xFF, 0xF0, 0x7F, 0xF0, 0x7F, 0xC7, 0xF0, 0x03, 0xE0, + 0xF8, 0x00, 0x70, 0x3E, 0x00, 0x38, 0x07, 0x80, 0x0C, 0x01, 0xE0, 0x07, + 0x00, 0x7C, 0x03, 0x80, 0x1F, 0x00, 0xC0, 0x03, 0xC0, 0x60, 0x00, 0xF0, + 0x30, 0x00, 0x3E, 0x1C, 0x00, 0x07, 0x8E, 0x00, 0x01, 0xE3, 0x00, 0x00, + 0x7D, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, + 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x0F, 0xC0, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x03, 0xFF, + 0xFF, 0xF8, 0x1F, 0xFF, 0xFF, 0x81, 0xF0, 0x00, 0xFC, 0x0E, 0x00, 0x0F, + 0xC0, 0x60, 0x00, 0xFC, 0x06, 0x00, 0x0F, 0xC0, 0x20, 0x00, 0x7C, 0x00, + 0x00, 0x07, 0xE0, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x03, 0xF0, + 0x00, 0x00, 0x3F, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x01, 0xF8, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x1F, + 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0xFC, 0x00, + 0x08, 0x0F, 0xC0, 0x00, 0x80, 0xFC, 0x00, 0x0C, 0x07, 0xC0, 0x00, 0x60, + 0x7E, 0x00, 0x07, 0x07, 0xE0, 0x01, 0xF0, 0x7F, 0xFF, 0xFF, 0x83, 0xFF, + 0xFF, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x3C, 0x00, 0x1C, 0x00, 0x0E, 0x00, + 0x07, 0x00, 0x07, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0xE0, + 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, + 0x00, 0x03, 0x80, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, + 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x07, 0x00, + 0x03, 0x80, 0x01, 0xC0, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x38, + 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x07, 0x80, 0x03, + 0xFC, 0x00, 0xF0, 0x00, 0x38, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x03, 0x80, + 0x01, 0xE0, 0x00, 0x70, 0x00, 0x3C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x03, + 0xC0, 0x00, 0xE0, 0x00, 0x78, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x03, 0x80, + 0x01, 0xC0, 0x00, 0xF0, 0x00, 0x38, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x03, + 0x80, 0x01, 0xE0, 0x00, 0x70, 0x00, 0x3C, 0x00, 0x0E, 0x00, 0x07, 0x00, + 0x03, 0xC0, 0x00, 0xE0, 0x00, 0x78, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, + 0x80, 0x00, 0xFF, 0x80, 0x07, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0xF0, + 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x07, + 0x00, 0x03, 0x80, 0x01, 0xC0, 0x01, 0xE0, 0x00, 0xE0, 0x00, 0x70, 0x00, + 0x38, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x03, 0x80, + 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x78, 0x00, 0x38, + 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x07, 0x00, 0x03, 0x80, 0x01, + 0xC0, 0x00, 0xE0, 0x00, 0xF0, 0x00, 0x70, 0x00, 0x38, 0x03, 0xFC, 0x00, + 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0x80, 0x03, 0xBC, + 0x00, 0x39, 0xC0, 0x07, 0x1E, 0x00, 0x70, 0xE0, 0x0E, 0x0F, 0x00, 0xE0, + 0x70, 0x1E, 0x07, 0x81, 0xC0, 0x38, 0x3C, 0x03, 0xC3, 0x80, 0x1C, 0x78, + 0x01, 0xE7, 0x00, 0x0E, 0xF0, 0x00, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0x60, 0xF0, 0xF8, 0x78, 0x3C, 0x1E, 0x0E, 0x07, 0x00, 0x1E, 0x70, + 0x03, 0x0B, 0x80, 0x70, 0x3C, 0x07, 0x01, 0xE0, 0x70, 0x0E, 0x07, 0x00, + 0x70, 0x78, 0x03, 0x83, 0x80, 0x38, 0x3C, 0x01, 0xC1, 0xC0, 0x0E, 0x1E, + 0x00, 0xF0, 0xF0, 0x07, 0x0F, 0x00, 0x78, 0x78, 0x03, 0xC3, 0xC0, 0x3E, + 0x1E, 0x01, 0x70, 0xF0, 0x17, 0x0F, 0x81, 0x38, 0xBE, 0x11, 0xC8, 0xFF, + 0x0F, 0x83, 0xF0, 0x70, 0x00, 0x00, 0xF0, 0x00, 0x7F, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00, + 0x78, 0x00, 0x03, 0x80, 0x00, 0x1C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x0F, + 0x80, 0x71, 0xFE, 0x03, 0x98, 0xF8, 0x3D, 0x03, 0xE1, 0xE8, 0x0F, 0x0E, + 0x80, 0x78, 0x78, 0x03, 0xC7, 0xC0, 0x1E, 0x3C, 0x00, 0xF1, 0xE0, 0x0F, + 0x1E, 0x00, 0x78, 0xF0, 0x03, 0xC7, 0x80, 0x3C, 0x38, 0x01, 0xE3, 0xC0, + 0x1E, 0x1E, 0x00, 0xE0, 0xE0, 0x0E, 0x07, 0x00, 0xF0, 0x78, 0x07, 0x03, + 0xC0, 0xE0, 0x0F, 0x0E, 0x00, 0x1F, 0x80, 0x00, 0x00, 0x3F, 0x00, 0x38, + 0x60, 0x38, 0x1C, 0x1C, 0x0F, 0x0E, 0x03, 0x87, 0x80, 0x03, 0xC0, 0x00, + 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x03, 0xC0, 0x00, 0xF0, + 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x02, 0x3E, 0x01, + 0x87, 0x80, 0xC1, 0xF0, 0x60, 0x3F, 0xF0, 0x03, 0xF0, 0x00, 0x00, 0x00, + 0x0E, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x1C, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x38, 0x00, 0x00, 0x38, 0x00, 0x00, 0x78, 0x00, 0x1E, 0x78, 0x00, 0x71, + 0x70, 0x00, 0xC1, 0x70, 0x03, 0x80, 0xF0, 0x07, 0x80, 0xE0, 0x07, 0x01, + 0xE0, 0x0E, 0x01, 0xE0, 0x1E, 0x01, 0xE0, 0x3C, 0x01, 0xC0, 0x3C, 0x01, + 0xC0, 0x78, 0x03, 0xC0, 0x78, 0x03, 0xC0, 0x78, 0x03, 0x80, 0xF0, 0x07, + 0x80, 0xF0, 0x07, 0x80, 0xF0, 0x0F, 0x80, 0xF0, 0x0F, 0x00, 0xF0, 0x17, + 0x08, 0xF0, 0x27, 0x10, 0x78, 0x47, 0x20, 0x7F, 0x87, 0xC0, 0x1E, 0x07, + 0x00, 0x00, 0x1F, 0x00, 0x1C, 0xF0, 0x1C, 0x1C, 0x0E, 0x07, 0x07, 0x01, + 0xC3, 0xC0, 0xF1, 0xE0, 0x38, 0x70, 0x1C, 0x3C, 0x0E, 0x1F, 0x0F, 0x07, + 0x8F, 0x01, 0xFE, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, + 0x00, 0xF0, 0x01, 0x3C, 0x00, 0xC7, 0x80, 0x61, 0xF0, 0x60, 0x3F, 0xF0, + 0x03, 0xE0, 0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x03, 0x1C, 0x00, 0x00, + 0xC3, 0x80, 0x00, 0x38, 0x70, 0x00, 0x06, 0x00, 0x00, 0x01, 0xC0, 0x00, + 0x00, 0x30, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x01, 0xC0, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x0E, 0x00, 0x00, 0x01, 0xC0, 0x00, 0x07, 0xFF, 0xC0, 0x00, + 0xFF, 0xF8, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x38, 0x00, 0x00, 0x07, 0x00, + 0x00, 0x01, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, + 0xE0, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0x1C, 0x00, 0x00, 0x03, 0x80, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x1E, + 0x00, 0x00, 0x03, 0x80, 0x00, 0x00, 0x70, 0x00, 0x00, 0x0E, 0x00, 0x00, + 0x03, 0xC0, 0x00, 0x00, 0x70, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x01, 0xC0, + 0x00, 0x00, 0x70, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x01, 0x80, 0x00, 0x38, + 0x60, 0x00, 0x07, 0x0C, 0x00, 0x00, 0xE3, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x00, 0x00, 0x3F, 0x00, 0x07, 0x0E, 0x00, 0x70, 0x3E, 0x07, 0x01, 0xF0, + 0x70, 0x0E, 0x07, 0x80, 0x70, 0x3C, 0x03, 0x81, 0xC0, 0x1C, 0x0E, 0x01, + 0xE0, 0x70, 0x0E, 0x03, 0x80, 0xF0, 0x0E, 0x0F, 0x00, 0x30, 0xE0, 0x00, + 0xFE, 0x00, 0x0C, 0x00, 0x00, 0xC0, 0x00, 0x0E, 0x00, 0x00, 0x7E, 0x00, + 0x03, 0xFE, 0x00, 0x0F, 0xFC, 0x00, 0x8F, 0xF0, 0x18, 0x0F, 0xC1, 0x80, + 0x1F, 0x18, 0x00, 0x78, 0xC0, 0x01, 0xC6, 0x00, 0x0E, 0x30, 0x00, 0x61, + 0xC0, 0x07, 0x06, 0x00, 0x70, 0x1C, 0x0E, 0x00, 0x3F, 0xC0, 0x00, 0x00, + 0xF0, 0x00, 0x7F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, + 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1C, + 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x03, 0x80, 0x78, 0x7E, 0x03, 0x86, 0x70, + 0x3C, 0x43, 0x81, 0xE4, 0x1C, 0x0E, 0x40, 0xE0, 0x74, 0x0E, 0x07, 0xA0, + 0x70, 0x3E, 0x03, 0x81, 0xE0, 0x1C, 0x0F, 0x00, 0xE0, 0xF0, 0x0E, 0x07, + 0x80, 0x70, 0x38, 0x03, 0x81, 0xC0, 0x1C, 0x1E, 0x00, 0xC2, 0xF0, 0x0E, + 0x27, 0x00, 0x73, 0x38, 0x03, 0x93, 0xC0, 0x1F, 0x1E, 0x00, 0xE0, 0x03, + 0x81, 0xF0, 0x7C, 0x1F, 0x03, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x71, 0xFC, 0x1F, 0x07, 0x81, 0xE0, 0x78, 0x1C, 0x07, 0x03, 0xC0, 0xF0, + 0x38, 0x0E, 0x07, 0x81, 0xE0, 0x70, 0x1C, 0x0F, 0x03, 0x84, 0xE2, 0x39, + 0x0F, 0x81, 0xC0, 0x00, 0x01, 0xC0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, + 0xF0, 0x00, 0x1C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0E, 0x00, 0x3F, 0xC0, 0x00, 0xF0, 0x00, 0x1E, + 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x0E, 0x00, 0x03, 0xC0, 0x00, 0x78, + 0x00, 0x0F, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x0F, 0x00, 0x01, 0xE0, + 0x00, 0x38, 0x00, 0x07, 0x00, 0x01, 0xE0, 0x00, 0x38, 0x00, 0x07, 0x00, + 0x00, 0xE0, 0x00, 0x3C, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, + 0x07, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x01, 0xC7, 0x00, 0x38, 0xC0, 0x07, + 0x30, 0x00, 0x7C, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x7F, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00, + 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, + 0x00, 0x70, 0xFF, 0x83, 0x80, 0xF0, 0x3C, 0x06, 0x01, 0xE0, 0x60, 0x0E, + 0x06, 0x00, 0x70, 0xE0, 0x07, 0x8C, 0x00, 0x3C, 0xC0, 0x01, 0xCC, 0x00, + 0x0F, 0xF0, 0x00, 0xFF, 0x80, 0x07, 0x9E, 0x00, 0x38, 0xF0, 0x01, 0xC3, + 0x80, 0x1E, 0x1E, 0x00, 0xF0, 0x70, 0x07, 0x03, 0xC2, 0x78, 0x0E, 0x13, + 0xC0, 0x79, 0x1E, 0x01, 0xF0, 0x00, 0x07, 0x00, 0x00, 0xE1, 0xFC, 0x0F, + 0x80, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1C, 0x07, 0x80, 0xF0, 0x1E, 0x03, + 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x70, 0x1E, 0x03, 0xC0, 0x78, 0x0E, 0x03, + 0xC0, 0x78, 0x0E, 0x01, 0xC0, 0x78, 0x0F, 0x01, 0xC0, 0x38, 0x4F, 0x11, + 0xE4, 0x39, 0x07, 0xC0, 0x70, 0x00, 0x07, 0x81, 0xC0, 0x78, 0xFE, 0x0F, + 0xC1, 0xF8, 0x3C, 0x33, 0x84, 0x70, 0x78, 0x87, 0x10, 0xE0, 0xF2, 0x0E, + 0x41, 0xC1, 0xC8, 0x39, 0x07, 0x87, 0xA0, 0x74, 0x0F, 0x0F, 0x40, 0xE8, + 0x1E, 0x1F, 0x01, 0xE0, 0x38, 0x3C, 0x07, 0xC0, 0xF0, 0xF8, 0x0F, 0x01, + 0xE1, 0xE0, 0x1E, 0x03, 0xC3, 0xC0, 0x38, 0x07, 0x07, 0x00, 0xF0, 0x1E, + 0x1E, 0x01, 0xE0, 0x3C, 0x3C, 0x03, 0x80, 0x79, 0x70, 0x07, 0x00, 0xE2, + 0xE0, 0x1E, 0x03, 0x8B, 0xC0, 0x3C, 0x07, 0x27, 0x80, 0x70, 0x0F, 0x8E, + 0x00, 0xE0, 0x1E, 0x00, 0x07, 0x81, 0xE3, 0xFC, 0x3F, 0x83, 0xC2, 0x3C, + 0x1E, 0x21, 0xE0, 0xF2, 0x0F, 0x07, 0x20, 0x70, 0x39, 0x07, 0x83, 0xD0, + 0x3C, 0x1F, 0x01, 0xE0, 0xE8, 0x0E, 0x0F, 0x80, 0xF0, 0x78, 0x07, 0x83, + 0xC0, 0x38, 0x1C, 0x01, 0xC1, 0xE0, 0x1E, 0x0F, 0x00, 0xF1, 0x70, 0x07, + 0x0B, 0x80, 0x38, 0xBC, 0x01, 0xC9, 0xE0, 0x0F, 0x8E, 0x00, 0x38, 0x00, + 0x00, 0x1F, 0x80, 0x07, 0x8F, 0x00, 0x70, 0x3C, 0x07, 0x00, 0xE0, 0x70, + 0x07, 0x87, 0x80, 0x3C, 0x78, 0x01, 0xE7, 0x80, 0x0F, 0x3C, 0x00, 0x7B, + 0xC0, 0x03, 0xDE, 0x00, 0x3D, 0xF0, 0x01, 0xEF, 0x80, 0x0F, 0x78, 0x00, + 0xF3, 0xC0, 0x07, 0x9E, 0x00, 0x78, 0xF0, 0x03, 0x87, 0x80, 0x38, 0x1C, + 0x03, 0x80, 0xF0, 0x38, 0x03, 0xC3, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x3C, + 0x3F, 0x00, 0x7F, 0x8F, 0xF0, 0x01, 0xF7, 0x3F, 0x00, 0x1D, 0x83, 0xF0, + 0x07, 0xA0, 0x3E, 0x00, 0xF8, 0x07, 0xC0, 0x1E, 0x00, 0xF8, 0x03, 0xC0, + 0x1F, 0x00, 0xF0, 0x03, 0xE0, 0x1E, 0x00, 0x7C, 0x03, 0xC0, 0x1F, 0x00, + 0x70, 0x03, 0xE0, 0x1E, 0x00, 0x78, 0x03, 0xC0, 0x1F, 0x00, 0x70, 0x03, + 0xC0, 0x0E, 0x00, 0xF8, 0x03, 0xC0, 0x1E, 0x00, 0x78, 0x07, 0x80, 0x0F, + 0x01, 0xE0, 0x01, 0xE0, 0x70, 0x00, 0x7C, 0x3C, 0x00, 0x0F, 0x7C, 0x00, + 0x01, 0xC0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x01, 0xE0, + 0x00, 0x00, 0x38, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x03, 0x8D, + 0xC0, 0x38, 0x2E, 0x07, 0x80, 0xF0, 0x78, 0x07, 0x03, 0x80, 0x38, 0x38, + 0x03, 0xC3, 0xC0, 0x1E, 0x3C, 0x00, 0xE1, 0xE0, 0x07, 0x1E, 0x00, 0x78, + 0xF0, 0x03, 0x87, 0x80, 0x3C, 0x78, 0x01, 0xE3, 0xC0, 0x1F, 0x1E, 0x01, + 0x70, 0xF0, 0x17, 0x87, 0x80, 0xBC, 0x3C, 0x09, 0xC0, 0xF1, 0x8E, 0x07, + 0xF8, 0xF0, 0x1F, 0x07, 0x80, 0x00, 0x38, 0x00, 0x03, 0xC0, 0x00, 0x1E, + 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, + 0x3E, 0x00, 0x0F, 0xFE, 0x00, 0x07, 0x87, 0x3F, 0x87, 0xC3, 0xC7, 0xE1, + 0xE6, 0xF0, 0xF6, 0x00, 0x72, 0x00, 0x3A, 0x00, 0x1D, 0x00, 0x1F, 0x00, + 0x0E, 0x80, 0x07, 0x80, 0x03, 0xC0, 0x03, 0xC0, 0x01, 0xE0, 0x00, 0xF0, + 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1C, 0x00, 0x1E, 0x00, 0x0F, + 0x00, 0x00, 0x01, 0xF8, 0x81, 0x87, 0xC1, 0x80, 0xE1, 0xC0, 0x60, 0xE0, + 0x10, 0x70, 0x08, 0x3C, 0x04, 0x1F, 0x00, 0x07, 0xC0, 0x03, 0xE0, 0x00, + 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x03, 0xC1, 0x01, 0xE0, 0x80, 0x70, + 0x40, 0x38, 0x30, 0x1C, 0x38, 0x0C, 0x1C, 0x0E, 0x0F, 0x0E, 0x04, 0x7C, + 0x00, 0x00, 0xC0, 0x18, 0x03, 0x80, 0x78, 0x1F, 0x03, 0xFF, 0x7F, 0xF0, + 0xF0, 0x0E, 0x00, 0xE0, 0x1E, 0x01, 0xE0, 0x1C, 0x01, 0xC0, 0x3C, 0x03, + 0xC0, 0x38, 0x03, 0x80, 0x78, 0x07, 0x80, 0x70, 0x8F, 0x10, 0xF1, 0x0F, + 0x20, 0xFC, 0x07, 0x80, 0x00, 0x00, 0x00, 0xF0, 0x0E, 0x7F, 0x00, 0xE0, + 0xF0, 0x1E, 0x0E, 0x01, 0xE1, 0xE0, 0x3C, 0x1E, 0x03, 0xC1, 0xE0, 0x3C, + 0x1C, 0x07, 0xC3, 0xC0, 0x78, 0x3C, 0x0F, 0x83, 0xC0, 0xB8, 0x38, 0x1F, + 0x87, 0x83, 0x70, 0x78, 0x27, 0x07, 0x86, 0x70, 0x70, 0xC7, 0x1F, 0x08, + 0xE1, 0xE1, 0x0E, 0x2E, 0x60, 0xE4, 0xFC, 0x0F, 0x87, 0x00, 0x70, 0x1C, + 0x03, 0xBF, 0x00, 0xF1, 0xE0, 0x3C, 0x78, 0x07, 0x1E, 0x00, 0xC3, 0x80, + 0x30, 0xE0, 0x08, 0x38, 0x06, 0x0E, 0x01, 0x03, 0x80, 0xC0, 0xF0, 0x20, + 0x3C, 0x10, 0x07, 0x04, 0x01, 0xC2, 0x00, 0x71, 0x00, 0x1C, 0xC0, 0x07, + 0x60, 0x01, 0xF0, 0x00, 0x78, 0x00, 0x1C, 0x00, 0x06, 0x00, 0x01, 0x00, + 0x00, 0x0C, 0x00, 0x40, 0x3B, 0xF8, 0x01, 0x00, 0xF1, 0xE0, 0x0C, 0x03, + 0xC3, 0x80, 0x78, 0x07, 0x0E, 0x01, 0xE0, 0x0C, 0x38, 0x0F, 0x80, 0x20, + 0xE0, 0x6E, 0x00, 0x83, 0x81, 0x38, 0x04, 0x0F, 0x0C, 0xE0, 0x10, 0x1C, + 0x23, 0x80, 0x80, 0x71, 0x8E, 0x06, 0x01, 0xCC, 0x38, 0x10, 0x07, 0x20, + 0xE0, 0x80, 0x1D, 0x83, 0x86, 0x00, 0x7C, 0x07, 0x30, 0x01, 0xF0, 0x1C, + 0x80, 0x07, 0x80, 0x74, 0x00, 0x1E, 0x01, 0xF0, 0x00, 0x70, 0x07, 0x80, + 0x01, 0xC0, 0x1C, 0x00, 0x06, 0x00, 0x60, 0x00, 0x10, 0x01, 0x00, 0x00, + 0x00, 0xE0, 0x38, 0x1F, 0x81, 0xF0, 0x8F, 0x09, 0x80, 0x3C, 0x40, 0x00, + 0x72, 0x00, 0x01, 0xD0, 0x00, 0x07, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0x38, + 0x00, 0x00, 0xE0, 0x00, 0x03, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x7C, 0x00, + 0x01, 0x70, 0x00, 0x09, 0xC0, 0x00, 0x67, 0x00, 0x01, 0x1E, 0x10, 0x08, + 0x38, 0x40, 0x40, 0xE2, 0x39, 0x03, 0xD0, 0xF8, 0x0F, 0x83, 0xC0, 0x1C, + 0x00, 0x07, 0x80, 0x33, 0xFC, 0x03, 0xC1, 0xE0, 0x1E, 0x07, 0x80, 0x70, + 0x3C, 0x01, 0x80, 0xE0, 0x0C, 0x07, 0x80, 0x40, 0x3C, 0x02, 0x00, 0xE0, + 0x20, 0x07, 0x81, 0x00, 0x3C, 0x18, 0x01, 0xE0, 0x80, 0x07, 0x0C, 0x00, + 0x38, 0x40, 0x01, 0xE4, 0x00, 0x0F, 0x60, 0x00, 0x3A, 0x00, 0x01, 0xF0, + 0x00, 0x0F, 0x00, 0x00, 0x70, 0x00, 0x03, 0x80, 0x00, 0x18, 0x00, 0x00, + 0x80, 0x00, 0x0C, 0x00, 0x00, 0x40, 0x00, 0x04, 0x00, 0x00, 0x40, 0x00, + 0x04, 0x00, 0x0E, 0x40, 0x00, 0x7C, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x0F, + 0xFF, 0x87, 0xFF, 0x82, 0x00, 0x83, 0x00, 0xC1, 0x00, 0xC0, 0x00, 0xC0, + 0x00, 0xC0, 0x00, 0x60, 0x00, 0x60, 0x00, 0x60, 0x00, 0x60, 0x00, 0x20, + 0x00, 0x30, 0x00, 0x30, 0x00, 0x30, 0x00, 0x30, 0x00, 0x18, 0x00, 0x1E, + 0x00, 0x1F, 0xC0, 0x1F, 0xF0, 0xE8, 0xFC, 0x70, 0x1E, 0x38, 0x03, 0x88, + 0x00, 0x78, 0x00, 0x0F, 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x0E, 0x00, 0x0F, + 0x00, 0x07, 0x80, 0x03, 0x80, 0x01, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, + 0x70, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x0F, 0x00, + 0x07, 0x80, 0x07, 0x80, 0x03, 0xC0, 0x07, 0xC0, 0x07, 0xC0, 0x00, 0x80, + 0x00, 0x60, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x0F, 0x00, 0x07, + 0x80, 0x03, 0x80, 0x01, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x70, 0x00, + 0x38, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x01, 0x80, + 0x00, 0x70, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xE0, 0x00, 0x18, 0x00, 0x0E, 0x00, 0x06, 0x00, 0x07, + 0x00, 0x07, 0x00, 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0E, + 0x00, 0x0E, 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x3C, + 0x00, 0x3C, 0x00, 0x38, 0x00, 0x38, 0x00, 0x18, 0x00, 0x08, 0x00, 0x1C, + 0x00, 0x7E, 0x00, 0x78, 0x00, 0xF0, 0x00, 0xE0, 0x01, 0xE0, 0x01, 0xE0, + 0x01, 0xC0, 0x01, 0xC0, 0x03, 0xC0, 0x03, 0x80, 0x03, 0x80, 0x07, 0x80, + 0x07, 0x80, 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x0E, 0x00, 0x1C, 0x00, + 0xF8, 0x00, 0x1F, 0x80, 0x00, 0xFF, 0x80, 0xC7, 0xFF, 0x87, 0xBC, 0x3F, + 0xFE, 0x60, 0x3F, 0xF0, 0x00, 0x1F, 0x00 }; + +const GFXglyph FreeSerifItalic24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 12, 0, 1 }, // 0x20 ' ' + { 0, 12, 32, 16, 2, -30 }, // 0x21 '!' + { 48, 14, 12, 16, 6, -31 }, // 0x22 '"' + { 69, 25, 31, 23, 0, -30 }, // 0x23 '#' + { 166, 21, 38, 24, 2, -33 }, // 0x24 '$' + { 266, 33, 32, 39, 4, -30 }, // 0x25 '%' + { 398, 30, 33, 37, 4, -31 }, // 0x26 '&' + { 522, 5, 12, 9, 6, -31 }, // 0x27 ''' + { 530, 13, 39, 16, 2, -30 }, // 0x28 '(' + { 594, 13, 39, 16, 0, -30 }, // 0x29 ')' + { 658, 16, 20, 23, 7, -31 }, // 0x2A '*' + { 698, 23, 23, 32, 4, -22 }, // 0x2B '+' + { 765, 7, 11, 12, -1, -4 }, // 0x2C ',' + { 775, 11, 3, 16, 2, -11 }, // 0x2D '-' + { 780, 5, 5, 12, 1, -3 }, // 0x2E '.' + { 784, 21, 33, 14, 0, -31 }, // 0x2F '/' + { 871, 21, 31, 23, 2, -30 }, // 0x30 '0' + { 953, 17, 32, 23, 2, -31 }, // 0x31 '1' + { 1021, 21, 31, 24, 0, -30 }, // 0x32 '2' + { 1103, 22, 32, 23, 0, -31 }, // 0x33 '3' + { 1191, 22, 32, 23, 0, -31 }, // 0x34 '4' + { 1279, 22, 32, 24, 0, -31 }, // 0x35 '5' + { 1367, 23, 32, 23, 1, -31 }, // 0x36 '6' + { 1459, 21, 32, 23, 4, -31 }, // 0x37 '7' + { 1543, 22, 32, 23, 1, -31 }, // 0x38 '8' + { 1631, 22, 33, 23, 1, -31 }, // 0x39 '9' + { 1722, 9, 22, 12, 2, -20 }, // 0x3A ':' + { 1747, 11, 27, 12, 1, -20 }, // 0x3B ';' + { 1785, 23, 25, 27, 3, -24 }, // 0x3C '<' + { 1857, 24, 12, 31, 4, -17 }, // 0x3D '=' + { 1893, 24, 25, 27, 3, -24 }, // 0x3E '>' + { 1968, 16, 33, 21, 6, -31 }, // 0x3F '?' + { 2034, 33, 33, 37, 3, -31 }, // 0x40 '@' + { 2171, 29, 31, 31, 0, -30 }, // 0x41 'A' + { 2284, 28, 31, 28, 0, -30 }, // 0x42 'B' + { 2393, 30, 33, 29, 2, -31 }, // 0x43 'C' + { 2517, 33, 31, 33, 0, -30 }, // 0x44 'D' + { 2645, 29, 31, 27, 0, -30 }, // 0x45 'E' + { 2758, 29, 31, 27, 0, -30 }, // 0x46 'F' + { 2871, 31, 33, 32, 2, -31 }, // 0x47 'G' + { 2999, 36, 31, 33, 0, -30 }, // 0x48 'H' + { 3139, 18, 31, 15, 0, -30 }, // 0x49 'I' + { 3209, 23, 32, 20, 0, -30 }, // 0x4A 'J' + { 3301, 33, 31, 30, 0, -30 }, // 0x4B 'K' + { 3429, 27, 31, 27, 0, -30 }, // 0x4C 'L' + { 3534, 42, 31, 39, 0, -30 }, // 0x4D 'M' + { 3697, 35, 32, 32, 0, -30 }, // 0x4E 'N' + { 3837, 30, 33, 31, 2, -31 }, // 0x4F 'O' + { 3961, 29, 31, 27, 0, -30 }, // 0x50 'P' + { 4074, 30, 41, 31, 2, -31 }, // 0x51 'Q' + { 4228, 28, 31, 29, 0, -30 }, // 0x52 'R' + { 4337, 23, 33, 21, 0, -31 }, // 0x53 'S' + { 4432, 27, 31, 28, 4, -30 }, // 0x54 'T' + { 4537, 31, 32, 33, 5, -30 }, // 0x55 'U' + { 4661, 29, 32, 31, 6, -30 }, // 0x56 'V' + { 4777, 39, 32, 42, 6, -30 }, // 0x57 'W' + { 4933, 32, 31, 31, 0, -30 }, // 0x58 'X' + { 5057, 26, 31, 28, 5, -30 }, // 0x59 'Y' + { 5158, 29, 31, 26, 0, -30 }, // 0x5A 'Z' + { 5271, 17, 39, 18, 1, -31 }, // 0x5B '[' + { 5354, 17, 33, 23, 5, -31 }, // 0x5C '\' + { 5425, 17, 39, 18, 1, -31 }, // 0x5D ']' + { 5508, 20, 17, 20, 0, -31 }, // 0x5E '^' + { 5551, 24, 2, 23, 0, 5 }, // 0x5F '_' + { 5557, 8, 8, 12, 6, -31 }, // 0x60 '`' + { 5565, 21, 21, 23, 1, -20 }, // 0x61 'a' + { 5621, 21, 33, 22, 1, -31 }, // 0x62 'b' + { 5708, 18, 22, 19, 1, -20 }, // 0x63 'c' + { 5758, 24, 33, 23, 1, -31 }, // 0x64 'd' + { 5857, 18, 22, 19, 1, -20 }, // 0x65 'e' + { 5907, 27, 42, 20, -4, -31 }, // 0x66 'f' + { 6049, 21, 31, 21, -1, -20 }, // 0x67 'g' + { 6131, 21, 32, 23, 1, -31 }, // 0x68 'h' + { 6215, 10, 32, 12, 2, -30 }, // 0x69 'i' + { 6255, 19, 41, 13, -3, -30 }, // 0x6A 'j' + { 6353, 21, 33, 21, 1, -31 }, // 0x6B 'k' + { 6440, 11, 33, 12, 2, -31 }, // 0x6C 'l' + { 6486, 31, 21, 34, 1, -20 }, // 0x6D 'm' + { 6568, 21, 21, 23, 1, -20 }, // 0x6E 'n' + { 6624, 21, 22, 22, 1, -20 }, // 0x6F 'o' + { 6682, 27, 31, 22, -4, -20 }, // 0x70 'p' + { 6787, 21, 31, 23, 1, -20 }, // 0x71 'q' + { 6869, 17, 21, 17, 1, -20 }, // 0x72 'r' + { 6914, 17, 22, 16, 0, -20 }, // 0x73 's' + { 6961, 12, 26, 11, 1, -24 }, // 0x74 't' + { 7000, 20, 22, 23, 1, -20 }, // 0x75 'u' + { 7055, 18, 22, 21, 3, -20 }, // 0x76 'v' + { 7105, 30, 22, 32, 2, -20 }, // 0x77 'w' + { 7188, 22, 22, 20, -1, -20 }, // 0x78 'x' + { 7249, 21, 31, 22, 1, -20 }, // 0x79 'y' + { 7331, 17, 24, 18, 0, -19 }, // 0x7A 'z' + { 7382, 17, 40, 19, 2, -31 }, // 0x7B '{' + { 7467, 3, 33, 13, 5, -31 }, // 0x7C '|' + { 7480, 16, 41, 19, 0, -32 }, // 0x7D '}' + { 7562, 22, 6, 25, 2, -14 } }; // 0x7E '~' + +const GFXfont FreeSerifItalic24pt7b PROGMEM = { + (uint8_t *)FreeSerifItalic24pt7bBitmaps, + (GFXglyph *)FreeSerifItalic24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 8251 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic9pt7b.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic9pt7b.h new file mode 100644 index 0000000..34e6b8d --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic9pt7b.h @@ -0,0 +1,202 @@ +const uint8_t FreeSerifItalic9pt7bBitmaps[] PROGMEM = { + 0x11, 0x12, 0x22, 0x24, 0x40, 0x0C, 0xDE, 0xE5, 0x40, 0x04, 0x82, 0x20, + 0x98, 0x24, 0x7F, 0xC4, 0x82, 0x23, 0xFC, 0x24, 0x11, 0x04, 0x83, 0x20, + 0x1C, 0x1B, 0x99, 0x4D, 0x26, 0x81, 0xC0, 0x70, 0x1C, 0x13, 0x49, 0xA4, + 0xDA, 0xC7, 0xC1, 0x00, 0x80, 0x1C, 0x61, 0xCF, 0x0E, 0x28, 0x30, 0xA0, + 0xC5, 0x03, 0x34, 0xE7, 0xAE, 0x40, 0xB1, 0x05, 0x84, 0x26, 0x20, 0x99, + 0x84, 0x3C, 0x03, 0x80, 0x6C, 0x06, 0xC0, 0x78, 0x06, 0x01, 0xEF, 0x66, + 0x24, 0x24, 0xC3, 0x8C, 0x10, 0xE3, 0x87, 0xCE, 0xFA, 0x08, 0x21, 0x08, + 0x61, 0x8C, 0x30, 0xC3, 0x0C, 0x30, 0x41, 0x02, 0x00, 0x10, 0x40, 0x82, + 0x0C, 0x30, 0xC3, 0x0C, 0x61, 0x84, 0x21, 0x08, 0x00, 0x30, 0xCA, 0x5E, + 0x6A, 0x93, 0x08, 0x08, 0x04, 0x02, 0x01, 0x0F, 0xF8, 0x40, 0x20, 0x10, + 0x08, 0x00, 0x56, 0xF0, 0xF0, 0x03, 0x02, 0x06, 0x04, 0x08, 0x08, 0x10, + 0x30, 0x20, 0x60, 0x40, 0xC0, 0x0E, 0x0C, 0x8C, 0x6C, 0x36, 0x1F, 0x0F, + 0x07, 0x87, 0xC3, 0x61, 0xB1, 0x88, 0x83, 0x80, 0x04, 0x70, 0xC3, 0x08, + 0x21, 0x86, 0x10, 0x43, 0x08, 0xF8, 0x1C, 0x67, 0x83, 0x03, 0x02, 0x06, + 0x0C, 0x08, 0x10, 0x20, 0x42, 0xFC, 0x0F, 0x08, 0xC0, 0x60, 0xC1, 0xE0, + 0x38, 0x0C, 0x06, 0x03, 0x01, 0x01, 0x1F, 0x00, 0x01, 0x01, 0x81, 0x41, + 0x61, 0x21, 0x11, 0x18, 0x88, 0xFF, 0x02, 0x03, 0x01, 0x00, 0x0F, 0x84, + 0x04, 0x03, 0x80, 0x60, 0x18, 0x0C, 0x06, 0x03, 0x03, 0x03, 0x1E, 0x00, + 0x01, 0x83, 0x87, 0x07, 0x03, 0x03, 0x73, 0xCD, 0x86, 0xC3, 0x61, 0xB1, + 0x88, 0xC3, 0xC0, 0x7F, 0x40, 0x80, 0x80, 0x40, 0x40, 0x60, 0x20, 0x20, + 0x10, 0x10, 0x18, 0x08, 0x00, 0x1E, 0x19, 0xCC, 0x66, 0x33, 0xB0, 0xE0, + 0x50, 0xCC, 0xC3, 0x61, 0xB0, 0xCC, 0xC3, 0xC0, 0x0E, 0x19, 0x8C, 0x6C, + 0x36, 0x1B, 0x0D, 0x86, 0xE6, 0x3F, 0x03, 0x03, 0x06, 0x0C, 0x00, 0x33, + 0x00, 0x00, 0xCC, 0x33, 0x00, 0x00, 0x44, 0x48, 0x01, 0x83, 0x86, 0x1C, + 0x0C, 0x03, 0x80, 0x30, 0x07, 0x00, 0x80, 0xFF, 0x80, 0x00, 0x00, 0x0F, + 0xF8, 0xC0, 0x1C, 0x03, 0x80, 0x70, 0x18, 0x38, 0x70, 0xC0, 0x80, 0x00, + 0x3C, 0x8C, 0x18, 0x30, 0xC3, 0x0C, 0x20, 0x40, 0x80, 0x06, 0x00, 0x0F, + 0xC0, 0xC3, 0x0C, 0x04, 0xC7, 0xBC, 0x64, 0xE2, 0x27, 0x31, 0x39, 0x91, + 0xCC, 0x93, 0x3B, 0x0E, 0x00, 0x1F, 0x80, 0x01, 0x00, 0x60, 0x14, 0x04, + 0xC0, 0x98, 0x23, 0x07, 0xE1, 0x04, 0x20, 0x88, 0x1B, 0x8F, 0x80, 0x3F, + 0xC1, 0x8C, 0x21, 0x8C, 0x31, 0x8C, 0x3E, 0x04, 0x61, 0x86, 0x30, 0xC4, + 0x19, 0x86, 0x7F, 0x80, 0x07, 0x91, 0x86, 0x30, 0x26, 0x02, 0x60, 0x0C, + 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0x61, 0x83, 0xE0, 0x3F, 0xC0, + 0x63, 0x82, 0x0C, 0x30, 0x31, 0x81, 0x8C, 0x0C, 0x40, 0x66, 0x07, 0x30, + 0x31, 0x03, 0x18, 0x71, 0xFE, 0x00, 0x3F, 0xF0, 0xC2, 0x08, 0x21, 0x80, + 0x19, 0x81, 0xF8, 0x11, 0x03, 0x10, 0x30, 0x02, 0x04, 0x60, 0x8F, 0xF8, + 0x3F, 0xF0, 0xC2, 0x08, 0x21, 0x80, 0x19, 0x81, 0xF8, 0x11, 0x03, 0x10, + 0x30, 0x02, 0x00, 0x60, 0x0F, 0x80, 0x07, 0x91, 0x87, 0x30, 0x26, 0x02, + 0x60, 0x0C, 0x00, 0xC1, 0xFC, 0x0C, 0xC0, 0xCC, 0x0C, 0x60, 0x83, 0xF0, + 0x3E, 0x3C, 0x30, 0x60, 0x81, 0x06, 0x0C, 0x18, 0x30, 0x7F, 0x81, 0x06, + 0x0C, 0x18, 0x30, 0x60, 0x81, 0x06, 0x0C, 0x3C, 0x78, 0x1E, 0x18, 0x20, + 0xC1, 0x83, 0x04, 0x18, 0x30, 0x41, 0x87, 0x80, 0x0F, 0x81, 0x80, 0x80, + 0xC0, 0x60, 0x20, 0x30, 0x18, 0x0C, 0x04, 0x36, 0x1E, 0x00, 0x3E, 0x78, + 0x61, 0x82, 0x10, 0x31, 0x01, 0xB0, 0x0E, 0x00, 0x58, 0x06, 0x60, 0x33, + 0x01, 0x0C, 0x18, 0x61, 0xE7, 0xC0, 0x3E, 0x01, 0x80, 0x20, 0x0C, 0x01, + 0x80, 0x30, 0x04, 0x01, 0x80, 0x30, 0x04, 0x0D, 0x83, 0x7F, 0xE0, 0x1C, + 0x07, 0x0C, 0x0E, 0x0C, 0x14, 0x14, 0x1C, 0x14, 0x2C, 0x16, 0x4C, 0x26, + 0x48, 0x26, 0x98, 0x27, 0x18, 0x27, 0x10, 0x42, 0x30, 0xF4, 0x7C, 0x38, + 0x78, 0x60, 0x83, 0x04, 0x2C, 0x41, 0x22, 0x09, 0x10, 0x4D, 0x84, 0x28, + 0x21, 0x41, 0x06, 0x10, 0x21, 0xE1, 0x00, 0x07, 0x83, 0x18, 0xC1, 0xB0, + 0x36, 0x07, 0xC0, 0xF0, 0x3E, 0x06, 0xC0, 0xD8, 0x31, 0x8C, 0x1E, 0x00, + 0x3F, 0xC1, 0x9C, 0x21, 0x8C, 0x31, 0x86, 0x31, 0x87, 0xE1, 0x80, 0x30, + 0x04, 0x01, 0x80, 0x78, 0x00, 0x07, 0x83, 0x18, 0xC1, 0x98, 0x36, 0x07, + 0xC0, 0xF0, 0x1E, 0x06, 0xC0, 0xD8, 0x31, 0x04, 0x13, 0x01, 0x80, 0x70, + 0xB7, 0xE0, 0x3F, 0xC1, 0x8C, 0x21, 0x8C, 0x31, 0x8C, 0x3F, 0x04, 0xC1, + 0x98, 0x31, 0x84, 0x31, 0x86, 0x78, 0x70, 0x1E, 0x4C, 0x63, 0x08, 0xC0, + 0x38, 0x07, 0x00, 0x60, 0x0C, 0x43, 0x10, 0xC6, 0x62, 0x70, 0x7F, 0xE9, + 0x8E, 0x31, 0x04, 0x01, 0x80, 0x30, 0x06, 0x00, 0x80, 0x30, 0x06, 0x00, + 0x80, 0x7E, 0x00, 0x7C, 0xF3, 0x02, 0x30, 0x46, 0x04, 0x60, 0x46, 0x04, + 0x40, 0x8C, 0x08, 0xC0, 0x8C, 0x10, 0xE3, 0x03, 0xC0, 0xF8, 0xEC, 0x0C, + 0x81, 0x18, 0x43, 0x08, 0x62, 0x0C, 0x81, 0x90, 0x14, 0x03, 0x00, 0x60, + 0x08, 0x00, 0xFB, 0xCE, 0x43, 0x0C, 0x86, 0x11, 0x8C, 0x43, 0x38, 0x86, + 0xB2, 0x0D, 0x24, 0x1C, 0x50, 0x38, 0xA0, 0x21, 0x80, 0x42, 0x01, 0x04, + 0x00, 0x3E, 0x71, 0x82, 0x0C, 0x40, 0xC8, 0x07, 0x00, 0x60, 0x06, 0x00, + 0xB0, 0x13, 0x02, 0x18, 0x61, 0x8F, 0x3E, 0xF9, 0xC8, 0x23, 0x10, 0xC8, + 0x34, 0x05, 0x01, 0x80, 0x40, 0x30, 0x0C, 0x03, 0x03, 0xE0, 0x3F, 0xE4, + 0x19, 0x03, 0x00, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0x40, 0x18, 0x06, 0x05, + 0x81, 0x7F, 0xE0, 0x0E, 0x10, 0x20, 0x81, 0x02, 0x04, 0x10, 0x20, 0x40, + 0x82, 0x04, 0x08, 0x1C, 0x00, 0x81, 0x04, 0x18, 0x20, 0xC1, 0x04, 0x08, + 0x20, 0x41, 0x38, 0x20, 0x82, 0x08, 0x41, 0x04, 0x10, 0xC2, 0x08, 0x20, + 0x8C, 0x00, 0x18, 0x18, 0x2C, 0x24, 0x46, 0x42, 0x83, 0xFF, 0x80, 0xD8, + 0x80, 0x1F, 0x98, 0x98, 0x4C, 0x2C, 0x36, 0x33, 0x3A, 0xEE, 0x38, 0x08, + 0x04, 0x02, 0x03, 0x71, 0xCC, 0xC6, 0xC3, 0x63, 0x21, 0x93, 0x8F, 0x00, + 0x1F, 0x33, 0x60, 0xC0, 0xC0, 0xC0, 0xC4, 0x78, 0x01, 0x80, 0x40, 0x60, + 0x20, 0xF1, 0x89, 0x8C, 0xC4, 0xC2, 0x63, 0x33, 0xAE, 0xE0, 0x0E, 0x65, + 0x8B, 0x2F, 0x98, 0x31, 0x3C, 0x01, 0xE0, 0x40, 0x08, 0x02, 0x00, 0x40, + 0x3E, 0x03, 0x00, 0x40, 0x08, 0x01, 0x00, 0x60, 0x0C, 0x01, 0x00, 0x20, + 0x04, 0x01, 0x00, 0xC0, 0x00, 0x1E, 0x19, 0xD8, 0xCC, 0xE1, 0xC3, 0x01, + 0xE0, 0xBC, 0x82, 0x41, 0x31, 0x0F, 0x00, 0x38, 0x08, 0x04, 0x02, 0x03, + 0x39, 0x6C, 0xC6, 0x46, 0x63, 0x21, 0x11, 0xB8, 0xE0, 0x30, 0x00, 0xE2, + 0x44, 0xC8, 0xCE, 0x06, 0x00, 0x00, 0x00, 0xC0, 0x83, 0x04, 0x08, 0x10, + 0x60, 0x81, 0x02, 0x04, 0x70, 0x38, 0x10, 0x10, 0x10, 0x37, 0x22, 0x24, + 0x38, 0x78, 0x48, 0x4D, 0xC6, 0x73, 0x32, 0x26, 0x64, 0x4C, 0xDE, 0x77, + 0x39, 0x5E, 0xCC, 0xCC, 0xCE, 0x66, 0x62, 0x22, 0x11, 0x11, 0xB9, 0x8E, + 0x77, 0x3B, 0x33, 0x62, 0x62, 0x42, 0x4D, 0xCE, 0x0F, 0x18, 0xD8, 0x7C, + 0x3C, 0x3E, 0x1B, 0x18, 0xF0, 0x3B, 0x87, 0x31, 0x8C, 0x43, 0x31, 0x88, + 0x62, 0x30, 0xF0, 0x60, 0x10, 0x04, 0x03, 0x80, 0x0F, 0x18, 0x98, 0x4C, + 0x2C, 0x26, 0x33, 0x38, 0xEC, 0x04, 0x02, 0x03, 0x03, 0xC0, 0x76, 0x50, + 0xC1, 0x06, 0x08, 0x10, 0x60, 0x1A, 0x6C, 0xC8, 0xC0, 0xD1, 0xB3, 0x5C, + 0x23, 0xC8, 0xC4, 0x21, 0x18, 0xE0, 0xC3, 0x42, 0x42, 0xC6, 0x86, 0x8C, + 0x9D, 0xEE, 0x62, 0xC4, 0x89, 0xA3, 0x47, 0x0C, 0x10, 0xE2, 0x2C, 0x44, + 0xD8, 0x9D, 0x23, 0xA4, 0x65, 0x0C, 0xC1, 0x10, 0x19, 0x95, 0x43, 0x01, + 0x80, 0xC0, 0xA0, 0x91, 0x8E, 0x70, 0x88, 0x46, 0x23, 0x20, 0x90, 0x50, + 0x28, 0x18, 0x08, 0x08, 0x08, 0x18, 0x00, 0x3F, 0x42, 0x04, 0x08, 0x10, + 0x20, 0x40, 0x72, 0x0E, 0x08, 0x61, 0x04, 0x30, 0x86, 0x08, 0x61, 0x04, + 0x30, 0xC3, 0x8F, 0x00, 0xFF, 0xF0, 0x1E, 0x0C, 0x10, 0x20, 0xC1, 0x82, + 0x04, 0x1C, 0x30, 0x40, 0x83, 0x04, 0x08, 0x20, 0x60, 0x99, 0x8E }; + +const GFXglyph FreeSerifItalic9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 4, 12, 6, 1, -11 }, // 0x21 '!' + { 6, 5, 4, 6, 3, -11 }, // 0x22 '"' + { 9, 10, 12, 9, 0, -11 }, // 0x23 '#' + { 24, 9, 15, 9, 1, -12 }, // 0x24 '$' + { 41, 14, 12, 15, 1, -11 }, // 0x25 '%' + { 62, 12, 12, 14, 1, -11 }, // 0x26 '&' + { 80, 2, 4, 4, 3, -11 }, // 0x27 ''' + { 81, 6, 15, 6, 1, -11 }, // 0x28 '(' + { 93, 6, 15, 6, 0, -11 }, // 0x29 ')' + { 105, 6, 8, 9, 3, -11 }, // 0x2A '*' + { 111, 9, 9, 12, 1, -8 }, // 0x2B '+' + { 122, 2, 4, 5, 0, -1 }, // 0x2C ',' + { 123, 4, 1, 6, 1, -3 }, // 0x2D '-' + { 124, 2, 2, 5, 0, -1 }, // 0x2E '.' + { 125, 8, 12, 5, 0, -11 }, // 0x2F '/' + { 137, 9, 13, 9, 1, -12 }, // 0x30 '0' + { 152, 6, 13, 9, 1, -12 }, // 0x31 '1' + { 162, 8, 12, 9, 1, -11 }, // 0x32 '2' + { 174, 9, 12, 9, 0, -11 }, // 0x33 '3' + { 188, 9, 12, 9, 0, -11 }, // 0x34 '4' + { 202, 9, 12, 9, 0, -11 }, // 0x35 '5' + { 216, 9, 13, 9, 1, -12 }, // 0x36 '6' + { 231, 9, 12, 9, 1, -11 }, // 0x37 '7' + { 245, 9, 13, 9, 1, -12 }, // 0x38 '8' + { 260, 9, 13, 9, 0, -12 }, // 0x39 '9' + { 275, 4, 8, 4, 1, -7 }, // 0x3A ':' + { 279, 4, 10, 4, 1, -7 }, // 0x3B ';' + { 284, 9, 9, 10, 1, -8 }, // 0x3C '<' + { 295, 9, 5, 12, 2, -6 }, // 0x3D '=' + { 301, 9, 9, 10, 1, -8 }, // 0x3E '>' + { 312, 7, 12, 8, 2, -11 }, // 0x3F '?' + { 323, 13, 12, 14, 1, -11 }, // 0x40 '@' + { 343, 11, 11, 12, 0, -10 }, // 0x41 'A' + { 359, 11, 12, 11, 0, -11 }, // 0x42 'B' + { 376, 12, 12, 11, 1, -11 }, // 0x43 'C' + { 394, 13, 12, 13, 0, -11 }, // 0x44 'D' + { 414, 12, 12, 10, 0, -11 }, // 0x45 'E' + { 432, 12, 12, 10, 0, -11 }, // 0x46 'F' + { 450, 12, 12, 12, 1, -11 }, // 0x47 'G' + { 468, 14, 12, 13, 0, -11 }, // 0x48 'H' + { 489, 7, 12, 6, 0, -11 }, // 0x49 'I' + { 500, 9, 12, 8, 0, -11 }, // 0x4A 'J' + { 514, 13, 12, 12, 0, -11 }, // 0x4B 'K' + { 534, 11, 12, 10, 0, -11 }, // 0x4C 'L' + { 551, 16, 12, 15, 0, -11 }, // 0x4D 'M' + { 575, 13, 12, 12, 0, -11 }, // 0x4E 'N' + { 595, 11, 12, 12, 1, -11 }, // 0x4F 'O' + { 612, 11, 12, 10, 0, -11 }, // 0x50 'P' + { 629, 11, 15, 12, 1, -11 }, // 0x51 'Q' + { 650, 11, 12, 11, 0, -11 }, // 0x52 'R' + { 667, 10, 12, 8, 0, -11 }, // 0x53 'S' + { 682, 11, 12, 11, 2, -11 }, // 0x54 'T' + { 699, 12, 12, 13, 2, -11 }, // 0x55 'U' + { 717, 11, 12, 12, 2, -11 }, // 0x56 'V' + { 734, 15, 12, 16, 2, -11 }, // 0x57 'W' + { 757, 12, 12, 12, 0, -11 }, // 0x58 'X' + { 775, 10, 12, 11, 2, -11 }, // 0x59 'Y' + { 790, 11, 12, 10, 0, -11 }, // 0x5A 'Z' + { 807, 7, 15, 7, 0, -11 }, // 0x5B '[' + { 821, 6, 12, 9, 2, -11 }, // 0x5C '\' + { 830, 6, 15, 7, 1, -11 }, // 0x5D ']' + { 842, 8, 7, 8, 0, -11 }, // 0x5E '^' + { 849, 9, 1, 9, 0, 2 }, // 0x5F '_' + { 851, 3, 3, 5, 2, -11 }, // 0x60 '`' + { 853, 9, 8, 9, 0, -7 }, // 0x61 'a' + { 862, 9, 12, 9, 0, -11 }, // 0x62 'b' + { 876, 8, 8, 7, 0, -7 }, // 0x63 'c' + { 884, 9, 12, 9, 0, -11 }, // 0x64 'd' + { 898, 7, 8, 7, 0, -7 }, // 0x65 'e' + { 905, 11, 17, 8, -1, -12 }, // 0x66 'f' + { 929, 9, 12, 8, 0, -7 }, // 0x67 'g' + { 943, 9, 12, 9, 0, -11 }, // 0x68 'h' + { 957, 4, 12, 4, 1, -11 }, // 0x69 'i' + { 963, 7, 16, 5, -1, -11 }, // 0x6A 'j' + { 977, 8, 12, 8, 0, -11 }, // 0x6B 'k' + { 989, 4, 12, 5, 1, -11 }, // 0x6C 'l' + { 995, 13, 8, 13, 0, -7 }, // 0x6D 'm' + { 1008, 8, 8, 9, 0, -7 }, // 0x6E 'n' + { 1016, 9, 8, 9, 0, -7 }, // 0x6F 'o' + { 1025, 10, 12, 8, -1, -7 }, // 0x70 'p' + { 1040, 9, 12, 9, 0, -7 }, // 0x71 'q' + { 1054, 7, 8, 7, 0, -7 }, // 0x72 'r' + { 1061, 7, 8, 6, 0, -7 }, // 0x73 's' + { 1068, 5, 9, 4, 0, -8 }, // 0x74 't' + { 1074, 8, 8, 9, 1, -7 }, // 0x75 'u' + { 1082, 7, 8, 8, 1, -7 }, // 0x76 'v' + { 1089, 11, 8, 12, 1, -7 }, // 0x77 'w' + { 1100, 9, 8, 8, -1, -7 }, // 0x78 'x' + { 1109, 9, 12, 9, 0, -7 }, // 0x79 'y' + { 1123, 8, 9, 7, 0, -7 }, // 0x7A 'z' + { 1132, 6, 15, 7, 1, -11 }, // 0x7B '{' + { 1144, 1, 12, 5, 2, -11 }, // 0x7C '|' + { 1146, 7, 16, 7, 0, -12 }, // 0x7D '}' + { 1160, 8, 3, 10, 1, -5 } }; // 0x7E '~' + +const GFXfont FreeSerifItalic9pt7b PROGMEM = { + (uint8_t *)FreeSerifItalic9pt7bBitmaps, + (GFXglyph *)FreeSerifItalic9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 1835 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/TomThumb.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/TomThumb.h new file mode 100644 index 0000000..dad420d --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/Fonts/TomThumb.h @@ -0,0 +1,474 @@ +/** +** The original 3x5 font is licensed under the 3-clause BSD license: +** +** Copyright 1999 Brian J. Swetland +** Copyright 1999 Vassilii Khachaturov +** Portions (of vt100.c/vt100.h) copyright Dan Marks +** +** All rights reserved. +** +** Redistribution and use in source and binary forms, with or without +** modification, are permitted provided that the following conditions +** are met: +** 1. Redistributions of source code must retain the above copyright +** notice, this list of conditions, and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright +** notice, this list of conditions, and the following disclaimer in the +** documentation and/or other materials provided with the distribution. +** 3. The name of the authors may not be used to endorse or promote products +** derived from this software without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR +** IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES +** OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. +** IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, +** INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT +** NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +** DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +** THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +** THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +** Modifications to Tom Thumb for improved readability are from Robey Pointer, +** see: +** http://robey.lag.net/2010/01/23/tiny-monospace-font.html +** +** The original author does not have any objection to relicensing of Robey +** Pointer's modifications (in this file) in a more permissive license. See +** the discussion at the above blog, and also here: +** http://opengameart.org/forumtopic/how-to-submit-art-using-the-3-clause-bsd-license +** +** Feb 21, 2016: Conversion from Linux BDF --> Adafruit GFX font, +** with the help of this Python script: +** https://gist.github.com/skelliam/322d421f028545f16f6d +** William Skellenger (williamj@skellenger.net) +** Twitter: @skelliam +** +*/ + +#define TOMTHUMB_USE_EXTENDED 0 + +const uint8_t TomThumbBitmaps[] PROGMEM = { + 0x00, /* 0x20 space */ + 0x80, 0x80, 0x80, 0x00, 0x80, /* 0x21 exclam */ + 0xA0, 0xA0, /* 0x22 quotedbl */ + 0xA0, 0xE0, 0xA0, 0xE0, 0xA0, /* 0x23 numbersign */ + 0x60, 0xC0, 0x60, 0xC0, 0x40, /* 0x24 dollar */ + 0x80, 0x20, 0x40, 0x80, 0x20, /* 0x25 percent */ + 0xC0, 0xC0, 0xE0, 0xA0, 0x60, /* 0x26 ampersand */ + 0x80, 0x80, /* 0x27 quotesingle */ + 0x40, 0x80, 0x80, 0x80, 0x40, /* 0x28 parenleft */ + 0x80, 0x40, 0x40, 0x40, 0x80, /* 0x29 parenright */ + 0xA0, 0x40, 0xA0, /* 0x2A asterisk */ + 0x40, 0xE0, 0x40, /* 0x2B plus */ + 0x40, 0x80, /* 0x2C comma */ + 0xE0, /* 0x2D hyphen */ + 0x80, /* 0x2E period */ + 0x20, 0x20, 0x40, 0x80, 0x80, /* 0x2F slash */ + 0x60, 0xA0, 0xA0, 0xA0, 0xC0, /* 0x30 zero */ + 0x40, 0xC0, 0x40, 0x40, 0x40, /* 0x31 one */ + 0xC0, 0x20, 0x40, 0x80, 0xE0, /* 0x32 two */ + 0xC0, 0x20, 0x40, 0x20, 0xC0, /* 0x33 three */ + 0xA0, 0xA0, 0xE0, 0x20, 0x20, /* 0x34 four */ + 0xE0, 0x80, 0xC0, 0x20, 0xC0, /* 0x35 five */ + 0x60, 0x80, 0xE0, 0xA0, 0xE0, /* 0x36 six */ + 0xE0, 0x20, 0x40, 0x80, 0x80, /* 0x37 seven */ + 0xE0, 0xA0, 0xE0, 0xA0, 0xE0, /* 0x38 eight */ + 0xE0, 0xA0, 0xE0, 0x20, 0xC0, /* 0x39 nine */ + 0x80, 0x00, 0x80, /* 0x3A colon */ + 0x40, 0x00, 0x40, 0x80, /* 0x3B semicolon */ + 0x20, 0x40, 0x80, 0x40, 0x20, /* 0x3C less */ + 0xE0, 0x00, 0xE0, /* 0x3D equal */ + 0x80, 0x40, 0x20, 0x40, 0x80, /* 0x3E greater */ + 0xE0, 0x20, 0x40, 0x00, 0x40, /* 0x3F question */ + 0x40, 0xA0, 0xE0, 0x80, 0x60, /* 0x40 at */ + 0x40, 0xA0, 0xE0, 0xA0, 0xA0, /* 0x41 A */ + 0xC0, 0xA0, 0xC0, 0xA0, 0xC0, /* 0x42 B */ + 0x60, 0x80, 0x80, 0x80, 0x60, /* 0x43 C */ + 0xC0, 0xA0, 0xA0, 0xA0, 0xC0, /* 0x44 D */ + 0xE0, 0x80, 0xE0, 0x80, 0xE0, /* 0x45 E */ + 0xE0, 0x80, 0xE0, 0x80, 0x80, /* 0x46 F */ + 0x60, 0x80, 0xE0, 0xA0, 0x60, /* 0x47 G */ + 0xA0, 0xA0, 0xE0, 0xA0, 0xA0, /* 0x48 H */ + 0xE0, 0x40, 0x40, 0x40, 0xE0, /* 0x49 I */ + 0x20, 0x20, 0x20, 0xA0, 0x40, /* 0x4A J */ + 0xA0, 0xA0, 0xC0, 0xA0, 0xA0, /* 0x4B K */ + 0x80, 0x80, 0x80, 0x80, 0xE0, /* 0x4C L */ + 0xA0, 0xE0, 0xE0, 0xA0, 0xA0, /* 0x4D M */ + 0xA0, 0xE0, 0xE0, 0xE0, 0xA0, /* 0x4E N */ + 0x40, 0xA0, 0xA0, 0xA0, 0x40, /* 0x4F O */ + 0xC0, 0xA0, 0xC0, 0x80, 0x80, /* 0x50 P */ + 0x40, 0xA0, 0xA0, 0xE0, 0x60, /* 0x51 Q */ + 0xC0, 0xA0, 0xE0, 0xC0, 0xA0, /* 0x52 R */ + 0x60, 0x80, 0x40, 0x20, 0xC0, /* 0x53 S */ + 0xE0, 0x40, 0x40, 0x40, 0x40, /* 0x54 T */ + 0xA0, 0xA0, 0xA0, 0xA0, 0x60, /* 0x55 U */ + 0xA0, 0xA0, 0xA0, 0x40, 0x40, /* 0x56 V */ + 0xA0, 0xA0, 0xE0, 0xE0, 0xA0, /* 0x57 W */ + 0xA0, 0xA0, 0x40, 0xA0, 0xA0, /* 0x58 X */ + 0xA0, 0xA0, 0x40, 0x40, 0x40, /* 0x59 Y */ + 0xE0, 0x20, 0x40, 0x80, 0xE0, /* 0x5A Z */ + 0xE0, 0x80, 0x80, 0x80, 0xE0, /* 0x5B bracketleft */ + 0x80, 0x40, 0x20, /* 0x5C backslash */ + 0xE0, 0x20, 0x20, 0x20, 0xE0, /* 0x5D bracketright */ + 0x40, 0xA0, /* 0x5E asciicircum */ + 0xE0, /* 0x5F underscore */ + 0x80, 0x40, /* 0x60 grave */ + 0xC0, 0x60, 0xA0, 0xE0, /* 0x61 a */ + 0x80, 0xC0, 0xA0, 0xA0, 0xC0, /* 0x62 b */ + 0x60, 0x80, 0x80, 0x60, /* 0x63 c */ + 0x20, 0x60, 0xA0, 0xA0, 0x60, /* 0x64 d */ + 0x60, 0xA0, 0xC0, 0x60, /* 0x65 e */ + 0x20, 0x40, 0xE0, 0x40, 0x40, /* 0x66 f */ + 0x60, 0xA0, 0xE0, 0x20, 0x40, /* 0x67 g */ + 0x80, 0xC0, 0xA0, 0xA0, 0xA0, /* 0x68 h */ + 0x80, 0x00, 0x80, 0x80, 0x80, /* 0x69 i */ + 0x20, 0x00, 0x20, 0x20, 0xA0, 0x40, /* 0x6A j */ + 0x80, 0xA0, 0xC0, 0xC0, 0xA0, /* 0x6B k */ + 0xC0, 0x40, 0x40, 0x40, 0xE0, /* 0x6C l */ + 0xE0, 0xE0, 0xE0, 0xA0, /* 0x6D m */ + 0xC0, 0xA0, 0xA0, 0xA0, /* 0x6E n */ + 0x40, 0xA0, 0xA0, 0x40, /* 0x6F o */ + 0xC0, 0xA0, 0xA0, 0xC0, 0x80, /* 0x70 p */ + 0x60, 0xA0, 0xA0, 0x60, 0x20, /* 0x71 q */ + 0x60, 0x80, 0x80, 0x80, /* 0x72 r */ + 0x60, 0xC0, 0x60, 0xC0, /* 0x73 s */ + 0x40, 0xE0, 0x40, 0x40, 0x60, /* 0x74 t */ + 0xA0, 0xA0, 0xA0, 0x60, /* 0x75 u */ + 0xA0, 0xA0, 0xE0, 0x40, /* 0x76 v */ + 0xA0, 0xE0, 0xE0, 0xE0, /* 0x77 w */ + 0xA0, 0x40, 0x40, 0xA0, /* 0x78 x */ + 0xA0, 0xA0, 0x60, 0x20, 0x40, /* 0x79 y */ + 0xE0, 0x60, 0xC0, 0xE0, /* 0x7A z */ + 0x60, 0x40, 0x80, 0x40, 0x60, /* 0x7B braceleft */ + 0x80, 0x80, 0x00, 0x80, 0x80, /* 0x7C bar */ + 0xC0, 0x40, 0x20, 0x40, 0xC0, /* 0x7D braceright */ + 0x60, 0xC0, /* 0x7E asciitilde */ +#if (TOMTHUMB_USE_EXTENDED) + 0x80, 0x00, 0x80, 0x80, 0x80, /* 0xA1 exclamdown */ + 0x40, 0xE0, 0x80, 0xE0, 0x40, /* 0xA2 cent */ + 0x60, 0x40, 0xE0, 0x40, 0xE0, /* 0xA3 sterling */ + 0xA0, 0x40, 0xE0, 0x40, 0xA0, /* 0xA4 currency */ + 0xA0, 0xA0, 0x40, 0xE0, 0x40, /* 0xA5 yen */ + 0x80, 0x80, 0x00, 0x80, 0x80, /* 0xA6 brokenbar */ + 0x60, 0x40, 0xA0, 0x40, 0xC0, /* 0xA7 section */ + 0xA0, /* 0xA8 dieresis */ + 0x60, 0x80, 0x60, /* 0xA9 copyright */ + 0x60, 0xA0, 0xE0, 0x00, 0xE0, /* 0xAA ordfeminine */ + 0x40, 0x80, 0x40, /* 0xAB guillemotleft */ + 0xE0, 0x20, /* 0xAC logicalnot */ + 0xC0, /* 0xAD softhyphen */ + 0xC0, 0xC0, 0xA0, /* 0xAE registered */ + 0xE0, /* 0xAF macron */ + 0x40, 0xA0, 0x40, /* 0xB0 degree */ + 0x40, 0xE0, 0x40, 0x00, 0xE0, /* 0xB1 plusminus */ + 0xC0, 0x40, 0x60, /* 0xB2 twosuperior */ + 0xE0, 0x60, 0xE0, /* 0xB3 threesuperior */ + 0x40, 0x80, /* 0xB4 acute */ + 0xA0, 0xA0, 0xA0, 0xC0, 0x80, /* 0xB5 mu */ + 0x60, 0xA0, 0x60, 0x60, 0x60, /* 0xB6 paragraph */ + 0xE0, 0xE0, 0xE0, /* 0xB7 periodcentered */ + 0x40, 0x20, 0xC0, /* 0xB8 cedilla */ + 0x80, 0x80, 0x80, /* 0xB9 onesuperior */ + 0x40, 0xA0, 0x40, 0x00, 0xE0, /* 0xBA ordmasculine */ + 0x80, 0x40, 0x80, /* 0xBB guillemotright */ + 0x80, 0x80, 0x00, 0x60, 0x20, /* 0xBC onequarter */ + 0x80, 0x80, 0x00, 0xC0, 0x60, /* 0xBD onehalf */ + 0xC0, 0xC0, 0x00, 0x60, 0x20, /* 0xBE threequarters */ + 0x40, 0x00, 0x40, 0x80, 0xE0, /* 0xBF questiondown */ + 0x40, 0x20, 0x40, 0xE0, 0xA0, /* 0xC0 Agrave */ + 0x40, 0x80, 0x40, 0xE0, 0xA0, /* 0xC1 Aacute */ + 0xE0, 0x00, 0x40, 0xE0, 0xA0, /* 0xC2 Acircumflex */ + 0x60, 0xC0, 0x40, 0xE0, 0xA0, /* 0xC3 Atilde */ + 0xA0, 0x40, 0xA0, 0xE0, 0xA0, /* 0xC4 Adieresis */ + 0xC0, 0xC0, 0xA0, 0xE0, 0xA0, /* 0xC5 Aring */ + 0x60, 0xC0, 0xE0, 0xC0, 0xE0, /* 0xC6 AE */ + 0x60, 0x80, 0x80, 0x60, 0x20, 0x40, /* 0xC7 Ccedilla */ + 0x40, 0x20, 0xE0, 0xC0, 0xE0, /* 0xC8 Egrave */ + 0x40, 0x80, 0xE0, 0xC0, 0xE0, /* 0xC9 Eacute */ + 0xE0, 0x00, 0xE0, 0xC0, 0xE0, /* 0xCA Ecircumflex */ + 0xA0, 0x00, 0xE0, 0xC0, 0xE0, /* 0xCB Edieresis */ + 0x40, 0x20, 0xE0, 0x40, 0xE0, /* 0xCC Igrave */ + 0x40, 0x80, 0xE0, 0x40, 0xE0, /* 0xCD Iacute */ + 0xE0, 0x00, 0xE0, 0x40, 0xE0, /* 0xCE Icircumflex */ + 0xA0, 0x00, 0xE0, 0x40, 0xE0, /* 0xCF Idieresis */ + 0xC0, 0xA0, 0xE0, 0xA0, 0xC0, /* 0xD0 Eth */ + 0xC0, 0x60, 0xA0, 0xE0, 0xA0, /* 0xD1 Ntilde */ + 0x40, 0x20, 0xE0, 0xA0, 0xE0, /* 0xD2 Ograve */ + 0x40, 0x80, 0xE0, 0xA0, 0xE0, /* 0xD3 Oacute */ + 0xE0, 0x00, 0xE0, 0xA0, 0xE0, /* 0xD4 Ocircumflex */ + 0xC0, 0x60, 0xE0, 0xA0, 0xE0, /* 0xD5 Otilde */ + 0xA0, 0x00, 0xE0, 0xA0, 0xE0, /* 0xD6 Odieresis */ + 0xA0, 0x40, 0xA0, /* 0xD7 multiply */ + 0x60, 0xA0, 0xE0, 0xA0, 0xC0, /* 0xD8 Oslash */ + 0x80, 0x40, 0xA0, 0xA0, 0xE0, /* 0xD9 Ugrave */ + 0x20, 0x40, 0xA0, 0xA0, 0xE0, /* 0xDA Uacute */ + 0xE0, 0x00, 0xA0, 0xA0, 0xE0, /* 0xDB Ucircumflex */ + 0xA0, 0x00, 0xA0, 0xA0, 0xE0, /* 0xDC Udieresis */ + 0x20, 0x40, 0xA0, 0xE0, 0x40, /* 0xDD Yacute */ + 0x80, 0xE0, 0xA0, 0xE0, 0x80, /* 0xDE Thorn */ + 0x60, 0xA0, 0xC0, 0xA0, 0xC0, 0x80, /* 0xDF germandbls */ + 0x40, 0x20, 0x60, 0xA0, 0xE0, /* 0xE0 agrave */ + 0x40, 0x80, 0x60, 0xA0, 0xE0, /* 0xE1 aacute */ + 0xE0, 0x00, 0x60, 0xA0, 0xE0, /* 0xE2 acircumflex */ + 0x60, 0xC0, 0x60, 0xA0, 0xE0, /* 0xE3 atilde */ + 0xA0, 0x00, 0x60, 0xA0, 0xE0, /* 0xE4 adieresis */ + 0x60, 0x60, 0x60, 0xA0, 0xE0, /* 0xE5 aring */ + 0x60, 0xE0, 0xE0, 0xC0, /* 0xE6 ae */ + 0x60, 0x80, 0x60, 0x20, 0x40, /* 0xE7 ccedilla */ + 0x40, 0x20, 0x60, 0xE0, 0x60, /* 0xE8 egrave */ + 0x40, 0x80, 0x60, 0xE0, 0x60, /* 0xE9 eacute */ + 0xE0, 0x00, 0x60, 0xE0, 0x60, /* 0xEA ecircumflex */ + 0xA0, 0x00, 0x60, 0xE0, 0x60, /* 0xEB edieresis */ + 0x80, 0x40, 0x80, 0x80, 0x80, /* 0xEC igrave */ + 0x40, 0x80, 0x40, 0x40, 0x40, /* 0xED iacute */ + 0xE0, 0x00, 0x40, 0x40, 0x40, /* 0xEE icircumflex */ + 0xA0, 0x00, 0x40, 0x40, 0x40, /* 0xEF idieresis */ + 0x60, 0xC0, 0x60, 0xA0, 0x60, /* 0xF0 eth */ + 0xC0, 0x60, 0xC0, 0xA0, 0xA0, /* 0xF1 ntilde */ + 0x40, 0x20, 0x40, 0xA0, 0x40, /* 0xF2 ograve */ + 0x40, 0x80, 0x40, 0xA0, 0x40, /* 0xF3 oacute */ + 0xE0, 0x00, 0x40, 0xA0, 0x40, /* 0xF4 ocircumflex */ + 0xC0, 0x60, 0x40, 0xA0, 0x40, /* 0xF5 otilde */ + 0xA0, 0x00, 0x40, 0xA0, 0x40, /* 0xF6 odieresis */ + 0x40, 0x00, 0xE0, 0x00, 0x40, /* 0xF7 divide */ + 0x60, 0xE0, 0xA0, 0xC0, /* 0xF8 oslash */ + 0x80, 0x40, 0xA0, 0xA0, 0x60, /* 0xF9 ugrave */ + 0x20, 0x40, 0xA0, 0xA0, 0x60, /* 0xFA uacute */ + 0xE0, 0x00, 0xA0, 0xA0, 0x60, /* 0xFB ucircumflex */ + 0xA0, 0x00, 0xA0, 0xA0, 0x60, /* 0xFC udieresis */ + 0x20, 0x40, 0xA0, 0x60, 0x20, 0x40, /* 0xFD yacute */ + 0x80, 0xC0, 0xA0, 0xC0, 0x80, /* 0xFE thorn */ + 0xA0, 0x00, 0xA0, 0x60, 0x20, 0x40, /* 0xFF ydieresis */ + 0x00, /* 0x11D gcircumflex */ + 0x60, 0xC0, 0xE0, 0xC0, 0x60, /* 0x152 OE */ + 0x60, 0xE0, 0xC0, 0xE0, /* 0x153 oe */ + 0xA0, 0x60, 0xC0, 0x60, 0xC0, /* 0x160 Scaron */ + 0xA0, 0x60, 0xC0, 0x60, 0xC0, /* 0x161 scaron */ + 0xA0, 0x00, 0xA0, 0x40, 0x40, /* 0x178 Ydieresis */ + 0xA0, 0xE0, 0x60, 0xC0, 0xE0, /* 0x17D Zcaron */ + 0xA0, 0xE0, 0x60, 0xC0, 0xE0, /* 0x17E zcaron */ + 0x00, /* 0xEA4 uni0EA4 */ + 0x00, /* 0x13A0 uni13A0 */ + 0x80, /* 0x2022 bullet */ + 0xA0, /* 0x2026 ellipsis */ + 0x60, 0xE0, 0xE0, 0xC0, 0x60, /* 0x20AC Euro */ + 0xE0, 0xA0, 0xA0, 0xA0, 0xE0, /* 0xFFFD uniFFFD */ +#endif /* (TOMTHUMB_USE_EXTENDED) */ + }; + + +/* {offset, width, height, advance cursor, x offset, y offset} */ +const GFXglyph TomThumbGlyphs[] PROGMEM = { + { 0, 8, 1, 2, 0, -5 }, /* 0x20 space */ + { 1, 8, 5, 2, 0, -5 }, /* 0x21 exclam */ + { 6, 8, 2, 4, 0, -5 }, /* 0x22 quotedbl */ + { 8, 8, 5, 4, 0, -5 }, /* 0x23 numbersign */ + { 13, 8, 5, 4, 0, -5 }, /* 0x24 dollar */ + { 18, 8, 5, 4, 0, -5 }, /* 0x25 percent */ + { 23, 8, 5, 4, 0, -5 }, /* 0x26 ampersand */ + { 28, 8, 2, 2, 0, -5 }, /* 0x27 quotesingle */ + { 30, 8, 5, 3, 0, -5 }, /* 0x28 parenleft */ + { 35, 8, 5, 3, 0, -5 }, /* 0x29 parenright */ + { 40, 8, 3, 4, 0, -5 }, /* 0x2A asterisk */ + { 43, 8, 3, 4, 0, -4 }, /* 0x2B plus */ + { 46, 8, 2, 3, 0, -2 }, /* 0x2C comma */ + { 48, 8, 1, 4, 0, -3 }, /* 0x2D hyphen */ + { 49, 8, 1, 2, 0, -1 }, /* 0x2E period */ + { 50, 8, 5, 4, 0, -5 }, /* 0x2F slash */ + { 55, 8, 5, 4, 0, -5 }, /* 0x30 zero */ + { 60, 8, 5, 3, 0, -5 }, /* 0x31 one */ + { 65, 8, 5, 4, 0, -5 }, /* 0x32 two */ + { 70, 8, 5, 4, 0, -5 }, /* 0x33 three */ + { 75, 8, 5, 4, 0, -5 }, /* 0x34 four */ + { 80, 8, 5, 4, 0, -5 }, /* 0x35 five */ + { 85, 8, 5, 4, 0, -5 }, /* 0x36 six */ + { 90, 8, 5, 4, 0, -5 }, /* 0x37 seven */ + { 95, 8, 5, 4, 0, -5 }, /* 0x38 eight */ + { 100, 8, 5, 4, 0, -5 }, /* 0x39 nine */ + { 105, 8, 3, 2, 0, -4 }, /* 0x3A colon */ + { 108, 8, 4, 3, 0, -4 }, /* 0x3B semicolon */ + { 112, 8, 5, 4, 0, -5 }, /* 0x3C less */ + { 117, 8, 3, 4, 0, -4 }, /* 0x3D equal */ + { 120, 8, 5, 4, 0, -5 }, /* 0x3E greater */ + { 125, 8, 5, 4, 0, -5 }, /* 0x3F question */ + { 130, 8, 5, 4, 0, -5 }, /* 0x40 at */ + { 135, 8, 5, 4, 0, -5 }, /* 0x41 A */ + { 140, 8, 5, 4, 0, -5 }, /* 0x42 B */ + { 145, 8, 5, 4, 0, -5 }, /* 0x43 C */ + { 150, 8, 5, 4, 0, -5 }, /* 0x44 D */ + { 155, 8, 5, 4, 0, -5 }, /* 0x45 E */ + { 160, 8, 5, 4, 0, -5 }, /* 0x46 F */ + { 165, 8, 5, 4, 0, -5 }, /* 0x47 G */ + { 170, 8, 5, 4, 0, -5 }, /* 0x48 H */ + { 175, 8, 5, 4, 0, -5 }, /* 0x49 I */ + { 180, 8, 5, 4, 0, -5 }, /* 0x4A J */ + { 185, 8, 5, 4, 0, -5 }, /* 0x4B K */ + { 190, 8, 5, 4, 0, -5 }, /* 0x4C L */ + { 195, 8, 5, 4, 0, -5 }, /* 0x4D M */ + { 200, 8, 5, 4, 0, -5 }, /* 0x4E N */ + { 205, 8, 5, 4, 0, -5 }, /* 0x4F O */ + { 210, 8, 5, 4, 0, -5 }, /* 0x50 P */ + { 215, 8, 5, 4, 0, -5 }, /* 0x51 Q */ + { 220, 8, 5, 4, 0, -5 }, /* 0x52 R */ + { 225, 8, 5, 4, 0, -5 }, /* 0x53 S */ + { 230, 8, 5, 4, 0, -5 }, /* 0x54 T */ + { 235, 8, 5, 4, 0, -5 }, /* 0x55 U */ + { 240, 8, 5, 4, 0, -5 }, /* 0x56 V */ + { 245, 8, 5, 4, 0, -5 }, /* 0x57 W */ + { 250, 8, 5, 4, 0, -5 }, /* 0x58 X */ + { 255, 8, 5, 4, 0, -5 }, /* 0x59 Y */ + { 260, 8, 5, 4, 0, -5 }, /* 0x5A Z */ + { 265, 8, 5, 4, 0, -5 }, /* 0x5B bracketleft */ + { 270, 8, 3, 4, 0, -4 }, /* 0x5C backslash */ + { 273, 8, 5, 4, 0, -5 }, /* 0x5D bracketright */ + { 278, 8, 2, 4, 0, -5 }, /* 0x5E asciicircum */ + { 280, 8, 1, 4, 0, -1 }, /* 0x5F underscore */ + { 281, 8, 2, 3, 0, -5 }, /* 0x60 grave */ + { 283, 8, 4, 4, 0, -4 }, /* 0x61 a */ + { 287, 8, 5, 4, 0, -5 }, /* 0x62 b */ + { 292, 8, 4, 4, 0, -4 }, /* 0x63 c */ + { 296, 8, 5, 4, 0, -5 }, /* 0x64 d */ + { 301, 8, 4, 4, 0, -4 }, /* 0x65 e */ + { 305, 8, 5, 4, 0, -5 }, /* 0x66 f */ + { 310, 8, 5, 4, 0, -4 }, /* 0x67 g */ + { 315, 8, 5, 4, 0, -5 }, /* 0x68 h */ + { 320, 8, 5, 2, 0, -5 }, /* 0x69 i */ + { 325, 8, 6, 4, 0, -5 }, /* 0x6A j */ + { 331, 8, 5, 4, 0, -5 }, /* 0x6B k */ + { 336, 8, 5, 4, 0, -5 }, /* 0x6C l */ + { 341, 8, 4, 4, 0, -4 }, /* 0x6D m */ + { 345, 8, 4, 4, 0, -4 }, /* 0x6E n */ + { 349, 8, 4, 4, 0, -4 }, /* 0x6F o */ + { 353, 8, 5, 4, 0, -4 }, /* 0x70 p */ + { 358, 8, 5, 4, 0, -4 }, /* 0x71 q */ + { 363, 8, 4, 4, 0, -4 }, /* 0x72 r */ + { 367, 8, 4, 4, 0, -4 }, /* 0x73 s */ + { 371, 8, 5, 4, 0, -5 }, /* 0x74 t */ + { 376, 8, 4, 4, 0, -4 }, /* 0x75 u */ + { 380, 8, 4, 4, 0, -4 }, /* 0x76 v */ + { 384, 8, 4, 4, 0, -4 }, /* 0x77 w */ + { 388, 8, 4, 4, 0, -4 }, /* 0x78 x */ + { 392, 8, 5, 4, 0, -4 }, /* 0x79 y */ + { 397, 8, 4, 4, 0, -4 }, /* 0x7A z */ + { 401, 8, 5, 4, 0, -5 }, /* 0x7B braceleft */ + { 406, 8, 5, 2, 0, -5 }, /* 0x7C bar */ + { 411, 8, 5, 4, 0, -5 }, /* 0x7D braceright */ + { 416, 8, 2, 4, 0, -5 }, /* 0x7E asciitilde */ +#if (TOMTHUMB_USE_EXTENDED) + { 418, 8, 5, 2, 0, -5 }, /* 0xA1 exclamdown */ + { 423, 8, 5, 4, 0, -5 }, /* 0xA2 cent */ + { 428, 8, 5, 4, 0, -5 }, /* 0xA3 sterling */ + { 433, 8, 5, 4, 0, -5 }, /* 0xA4 currency */ + { 438, 8, 5, 4, 0, -5 }, /* 0xA5 yen */ + { 443, 8, 5, 2, 0, -5 }, /* 0xA6 brokenbar */ + { 448, 8, 5, 4, 0, -5 }, /* 0xA7 section */ + { 453, 8, 1, 4, 0, -5 }, /* 0xA8 dieresis */ + { 454, 8, 3, 4, 0, -5 }, /* 0xA9 copyright */ + { 457, 8, 5, 4, 0, -5 }, /* 0xAA ordfeminine */ + { 462, 8, 3, 3, 0, -5 }, /* 0xAB guillemotleft */ + { 465, 8, 2, 4, 0, -4 }, /* 0xAC logicalnot */ + { 467, 8, 1, 3, 0, -3 }, /* 0xAD softhyphen */ + { 468, 8, 3, 4, 0, -5 }, /* 0xAE registered */ + { 471, 8, 1, 4, 0, -5 }, /* 0xAF macron */ + { 472, 8, 3, 4, 0, -5 }, /* 0xB0 degree */ + { 475, 8, 5, 4, 0, -5 }, /* 0xB1 plusminus */ + { 480, 8, 3, 4, 0, -5 }, /* 0xB2 twosuperior */ + { 483, 8, 3, 4, 0, -5 }, /* 0xB3 threesuperior */ + { 486, 8, 2, 3, 0, -5 }, /* 0xB4 acute */ + { 488, 8, 5, 4, 0, -5 }, /* 0xB5 mu */ + { 493, 8, 5, 4, 0, -5 }, /* 0xB6 paragraph */ + { 498, 8, 3, 4, 0, -4 }, /* 0xB7 periodcentered */ + { 501, 8, 3, 4, 0, -3 }, /* 0xB8 cedilla */ + { 504, 8, 3, 2, 0, -5 }, /* 0xB9 onesuperior */ + { 507, 8, 5, 4, 0, -5 }, /* 0xBA ordmasculine */ + { 512, 8, 3, 3, 0, -5 }, /* 0xBB guillemotright */ + { 515, 8, 5, 4, 0, -5 }, /* 0xBC onequarter */ + { 520, 8, 5, 4, 0, -5 }, /* 0xBD onehalf */ + { 525, 8, 5, 4, 0, -5 }, /* 0xBE threequarters */ + { 530, 8, 5, 4, 0, -5 }, /* 0xBF questiondown */ + { 535, 8, 5, 4, 0, -5 }, /* 0xC0 Agrave */ + { 540, 8, 5, 4, 0, -5 }, /* 0xC1 Aacute */ + { 545, 8, 5, 4, 0, -5 }, /* 0xC2 Acircumflex */ + { 550, 8, 5, 4, 0, -5 }, /* 0xC3 Atilde */ + { 555, 8, 5, 4, 0, -5 }, /* 0xC4 Adieresis */ + { 560, 8, 5, 4, 0, -5 }, /* 0xC5 Aring */ + { 565, 8, 5, 4, 0, -5 }, /* 0xC6 AE */ + { 570, 8, 6, 4, 0, -5 }, /* 0xC7 Ccedilla */ + { 576, 8, 5, 4, 0, -5 }, /* 0xC8 Egrave */ + { 581, 8, 5, 4, 0, -5 }, /* 0xC9 Eacute */ + { 586, 8, 5, 4, 0, -5 }, /* 0xCA Ecircumflex */ + { 591, 8, 5, 4, 0, -5 }, /* 0xCB Edieresis */ + { 596, 8, 5, 4, 0, -5 }, /* 0xCC Igrave */ + { 601, 8, 5, 4, 0, -5 }, /* 0xCD Iacute */ + { 606, 8, 5, 4, 0, -5 }, /* 0xCE Icircumflex */ + { 611, 8, 5, 4, 0, -5 }, /* 0xCF Idieresis */ + { 616, 8, 5, 4, 0, -5 }, /* 0xD0 Eth */ + { 621, 8, 5, 4, 0, -5 }, /* 0xD1 Ntilde */ + { 626, 8, 5, 4, 0, -5 }, /* 0xD2 Ograve */ + { 631, 8, 5, 4, 0, -5 }, /* 0xD3 Oacute */ + { 636, 8, 5, 4, 0, -5 }, /* 0xD4 Ocircumflex */ + { 641, 8, 5, 4, 0, -5 }, /* 0xD5 Otilde */ + { 646, 8, 5, 4, 0, -5 }, /* 0xD6 Odieresis */ + { 651, 8, 3, 4, 0, -4 }, /* 0xD7 multiply */ + { 654, 8, 5, 4, 0, -5 }, /* 0xD8 Oslash */ + { 659, 8, 5, 4, 0, -5 }, /* 0xD9 Ugrave */ + { 664, 8, 5, 4, 0, -5 }, /* 0xDA Uacute */ + { 669, 8, 5, 4, 0, -5 }, /* 0xDB Ucircumflex */ + { 674, 8, 5, 4, 0, -5 }, /* 0xDC Udieresis */ + { 679, 8, 5, 4, 0, -5 }, /* 0xDD Yacute */ + { 684, 8, 5, 4, 0, -5 }, /* 0xDE Thorn */ + { 689, 8, 6, 4, 0, -5 }, /* 0xDF germandbls */ + { 695, 8, 5, 4, 0, -5 }, /* 0xE0 agrave */ + { 700, 8, 5, 4, 0, -5 }, /* 0xE1 aacute */ + { 705, 8, 5, 4, 0, -5 }, /* 0xE2 acircumflex */ + { 710, 8, 5, 4, 0, -5 }, /* 0xE3 atilde */ + { 715, 8, 5, 4, 0, -5 }, /* 0xE4 adieresis */ + { 720, 8, 5, 4, 0, -5 }, /* 0xE5 aring */ + { 725, 8, 4, 4, 0, -4 }, /* 0xE6 ae */ + { 729, 8, 5, 4, 0, -4 }, /* 0xE7 ccedilla */ + { 734, 8, 5, 4, 0, -5 }, /* 0xE8 egrave */ + { 739, 8, 5, 4, 0, -5 }, /* 0xE9 eacute */ + { 744, 8, 5, 4, 0, -5 }, /* 0xEA ecircumflex */ + { 749, 8, 5, 4, 0, -5 }, /* 0xEB edieresis */ + { 754, 8, 5, 3, 0, -5 }, /* 0xEC igrave */ + { 759, 8, 5, 3, 0, -5 }, /* 0xED iacute */ + { 764, 8, 5, 4, 0, -5 }, /* 0xEE icircumflex */ + { 769, 8, 5, 4, 0, -5 }, /* 0xEF idieresis */ + { 774, 8, 5, 4, 0, -5 }, /* 0xF0 eth */ + { 779, 8, 5, 4, 0, -5 }, /* 0xF1 ntilde */ + { 784, 8, 5, 4, 0, -5 }, /* 0xF2 ograve */ + { 789, 8, 5, 4, 0, -5 }, /* 0xF3 oacute */ + { 794, 8, 5, 4, 0, -5 }, /* 0xF4 ocircumflex */ + { 799, 8, 5, 4, 0, -5 }, /* 0xF5 otilde */ + { 804, 8, 5, 4, 0, -5 }, /* 0xF6 odieresis */ + { 809, 8, 5, 4, 0, -5 }, /* 0xF7 divide */ + { 814, 8, 4, 4, 0, -4 }, /* 0xF8 oslash */ + { 818, 8, 5, 4, 0, -5 }, /* 0xF9 ugrave */ + { 823, 8, 5, 4, 0, -5 }, /* 0xFA uacute */ + { 828, 8, 5, 4, 0, -5 }, /* 0xFB ucircumflex */ + { 833, 8, 5, 4, 0, -5 }, /* 0xFC udieresis */ + { 838, 8, 6, 4, 0, -5 }, /* 0xFD yacute */ + { 844, 8, 5, 4, 0, -4 }, /* 0xFE thorn */ + { 849, 8, 6, 4, 0, -5 }, /* 0xFF ydieresis */ + { 855, 8, 1, 2, 0, -1 }, /* 0x11D gcircumflex */ + { 856, 8, 5, 4, 0, -5 }, /* 0x152 OE */ + { 861, 8, 4, 4, 0, -4 }, /* 0x153 oe */ + { 865, 8, 5, 4, 0, -5 }, /* 0x160 Scaron */ + { 870, 8, 5, 4, 0, -5 }, /* 0x161 scaron */ + { 875, 8, 5, 4, 0, -5 }, /* 0x178 Ydieresis */ + { 880, 8, 5, 4, 0, -5 }, /* 0x17D Zcaron */ + { 885, 8, 5, 4, 0, -5 }, /* 0x17E zcaron */ + { 890, 8, 1, 2, 0, -1 }, /* 0xEA4 uni0EA4 */ + { 891, 8, 1, 2, 0, -1 }, /* 0x13A0 uni13A0 */ + { 892, 8, 1, 2, 0, -3 }, /* 0x2022 bullet */ + { 893, 8, 1, 4, 0, -1 }, /* 0x2026 ellipsis */ + { 894, 8, 5, 4, 0, -5 }, /* 0x20AC Euro */ + { 899, 8, 5, 4, 0, -5 }, /* 0xFFFD uniFFFD */ +#endif /* (TOMTHUMB_USE_EXTENDED) */ +}; + +const GFXfont TomThumb PROGMEM = { + (uint8_t *)TomThumbBitmaps, + (GFXglyph *)TomThumbGlyphs, + 0x20, 0x7E, 6 }; diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/README.md b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/README.md new file mode 100644 index 0000000..972c966 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/README.md @@ -0,0 +1,21 @@ +# Adafruit GFX Library + +This is the core graphics library for all our displays, providing a common set of graphics primitives (points, lines, circles, etc.). It needs to be paired with a hardware-specific library for each display device we carry (to handle the lower-level functions). + +Adafruit invests time and resources providing this open source code, please support Adafruit and open-source hardware by purchasing products from Adafruit! + +Written by Limor Fried/Ladyada for Adafruit Industries. +BSD license, check license.txt for more information. +All text above must be included in any redistribution. + +Recent Arduino IDE releases include the Library Manager for easy installation. Otherwise, to download, click the DOWNLOAD ZIP button, uncompress and rename the uncompressed folder Adafruit_GFX. Confirm that the Adafruit_GFX folder contains Adafruit_GFX.cpp and Adafruit_GFX.h. Place the Adafruit_GFX library folder your /Libraries/ folder. You may need to create the Libraries subfolder if its your first library. Restart the IDE. + +# Useful Resources + +- Image2Code: This is a handy Java GUI utility to convert a BMP file into the array code necessary to display the image with the drawBitmap function. Check out the code at ehubin's GitHub repository: https://github.com/ehubin/Adafruit-GFX-Library/tree/master/Img2Code + +- drawXBitmap function: You can use the GIMP photo editor to save a .xbm file and use the array saved in the file to draw a bitmap with the drawXBitmap function. See the pull request here for more details: https://github.com/adafruit/Adafruit-GFX-Library/pull/31 + +- 'Fonts' folder contains bitmap fonts for use with recent (1.1 and later) Adafruit_GFX. To use a font in your Arduino sketch, #include the corresponding .h file and pass address of GFXfont struct to setFont(). Pass NULL to revert to 'classic' fixed-space bitmap font. + +- 'fontconvert' folder contains a command-line tool for converting TTF fonts to Adafruit_GFX .h format. diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/fontconvert/Makefile b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/fontconvert/Makefile new file mode 100644 index 0000000..47f5a0e --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/fontconvert/Makefile @@ -0,0 +1,12 @@ +all: fontconvert + +CC = gcc +CFLAGS = -Wall -I/usr/local/include/freetype2 -I/usr/include/freetype2 -I/usr/include +LIBS = -lfreetype + +fontconvert: fontconvert.c + $(CC) $(CFLAGS) $< $(LIBS) -o $@ + strip $@ + +clean: + rm -f fontconvert diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/fontconvert/fontconvert.c b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/fontconvert/fontconvert.c new file mode 100644 index 0000000..c6d6498 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/fontconvert/fontconvert.c @@ -0,0 +1,278 @@ +/* +TrueType to Adafruit_GFX font converter. Derived from Peter Jakobs' +Adafruit_ftGFX fork & makefont tool, and Paul Kourany's Adafruit_mfGFX. + +NOT AN ARDUINO SKETCH. This is a command-line tool for preprocessing +fonts to be used with the Adafruit_GFX Arduino library. + +For UNIX-like systems. Outputs to stdout; redirect to header file, e.g.: + ./fontconvert ~/Library/Fonts/FreeSans.ttf 18 > FreeSans18pt7b.h + +REQUIRES FREETYPE LIBRARY. www.freetype.org + +Currently this only extracts the printable 7-bit ASCII chars of a font. +Will eventually extend with some int'l chars a la ftGFX, not there yet. +Keep 7-bit fonts around as an option in that case, more compact. + +See notes at end for glyph nomenclature & other tidbits. +*/ + +#include +#include +#include +#include +#include FT_GLYPH_H +#include "../gfxfont.h" // Adafruit_GFX font structures + +#define DPI 141 // Approximate res. of Adafruit 2.8" TFT + +// Accumulate bits for output, with periodic hexadecimal byte write +void enbit(uint8_t value) { + static uint8_t row = 0, sum = 0, bit = 0x80, firstCall = 1; + if(value) sum |= bit; // Set bit if needed + if(!(bit >>= 1)) { // Advance to next bit, end of byte reached? + if(!firstCall) { // Format output table nicely + if(++row >= 12) { // Last entry on line? + printf(",\n "); // Newline format output + row = 0; // Reset row counter + } else { // Not end of line + printf(", "); // Simple comma delim + } + } + printf("0x%02X", sum); // Write byte value + sum = 0; // Clear for next byte + bit = 0x80; // Reset bit counter + firstCall = 0; // Formatting flag + } +} + +int main(int argc, char *argv[]) { + int i, j, err, size, first=' ', last='~', + bitmapOffset = 0, x, y, byte; + char *fontName, c, *ptr; + FT_Library library; + FT_Face face; + FT_Glyph glyph; + FT_Bitmap *bitmap; + FT_BitmapGlyphRec *g; + GFXglyph *table; + uint8_t bit; + + // Parse command line. Valid syntaxes are: + // fontconvert [filename] [size] + // fontconvert [filename] [size] [last char] + // fontconvert [filename] [size] [first char] [last char] + // Unless overridden, default first and last chars are + // ' ' (space) and '~', respectively + + if(argc < 3) { + fprintf(stderr, "Usage: %s fontfile size [first] [last]\n", + argv[0]); + return 1; + } + + size = atoi(argv[2]); + + if(argc == 4) { + last = atoi(argv[3]); + } else if(argc == 5) { + first = atoi(argv[3]); + last = atoi(argv[4]); + } + + if(last < first) { + i = first; + first = last; + last = i; + } + + ptr = strrchr(argv[1], '/'); // Find last slash in filename + if(ptr) ptr++; // First character of filename (path stripped) + else ptr = argv[1]; // No path; font in local dir. + + // Allocate space for font name and glyph table + if((!(fontName = malloc(strlen(ptr) + 20))) || + (!(table = (GFXglyph *)malloc((last - first + 1) * + sizeof(GFXglyph))))) { + fprintf(stderr, "Malloc error\n"); + return 1; + } + + // Derive font table names from filename. Period (filename + // extension) is truncated and replaced with the font size & bits. + strcpy(fontName, ptr); + ptr = strrchr(fontName, '.'); // Find last period (file ext) + if(!ptr) ptr = &fontName[strlen(fontName)]; // If none, append + // Insert font size and 7/8 bit. fontName was alloc'd w/extra + // space to allow this, we're not sprintfing into Forbidden Zone. + sprintf(ptr, "%dpt%db", size, (last > 127) ? 8 : 7); + // Space and punctuation chars in name replaced w/ underscores. + for(i=0; (c=fontName[i]); i++) { + if(isspace(c) || ispunct(c)) fontName[i] = '_'; + } + + // Init FreeType lib, load font + if((err = FT_Init_FreeType(&library))) { + fprintf(stderr, "FreeType init error: %d", err); + return err; + } + if((err = FT_New_Face(library, argv[1], 0, &face))) { + fprintf(stderr, "Font load error: %d", err); + FT_Done_FreeType(library); + return err; + } + + // << 6 because '26dot6' fixed-point format + FT_Set_Char_Size(face, size << 6, 0, DPI, 0); + + // Currently all symbols from 'first' to 'last' are processed. + // Fonts may contain WAY more glyphs than that, but this code + // will need to handle encoding stuff to deal with extracting + // the right symbols, and that's not done yet. + // fprintf(stderr, "%ld glyphs\n", face->num_glyphs); + + printf("const uint8_t %sBitmaps[] PROGMEM = {\n ", fontName); + + // Process glyphs and output huge bitmap data array + for(i=first, j=0; i<=last; i++, j++) { + // MONO renderer provides clean image with perfect crop + // (no wasted pixels) via bitmap struct. + if((err = FT_Load_Char(face, i, FT_LOAD_TARGET_MONO))) { + fprintf(stderr, "Error %d loading char '%c'\n", + err, i); + continue; + } + + if((err = FT_Render_Glyph(face->glyph, + FT_RENDER_MODE_MONO))) { + fprintf(stderr, "Error %d rendering char '%c'\n", + err, i); + continue; + } + + if((err = FT_Get_Glyph(face->glyph, &glyph))) { + fprintf(stderr, "Error %d getting glyph '%c'\n", + err, i); + continue; + } + + bitmap = &face->glyph->bitmap; + g = (FT_BitmapGlyphRec *)glyph; + + // Minimal font and per-glyph information is stored to + // reduce flash space requirements. Glyph bitmaps are + // fully bit-packed; no per-scanline pad, though end of + // each character may be padded to next byte boundary + // when needed. 16-bit offset means 64K max for bitmaps, + // code currently doesn't check for overflow. (Doesn't + // check that size & offsets are within bounds either for + // that matter...please convert fonts responsibly.) + table[j].bitmapOffset = bitmapOffset; + table[j].width = bitmap->width; + table[j].height = bitmap->rows; + table[j].xAdvance = face->glyph->advance.x >> 6; + table[j].xOffset = g->left; + table[j].yOffset = 1 - g->top; + + for(y=0; y < bitmap->rows; y++) { + for(x=0;x < bitmap->width; x++) { + byte = x / 8; + bit = 0x80 >> (x & 7); + enbit(bitmap->buffer[ + y * bitmap->pitch + byte] & bit); + } + } + + // Pad end of char bitmap to next byte boundary if needed + int n = (bitmap->width * bitmap->rows) & 7; + if(n) { // Pixel count not an even multiple of 8? + n = 8 - n; // # bits to next multiple + while(n--) enbit(0); + } + bitmapOffset += (bitmap->width * bitmap->rows + 7) / 8; + + FT_Done_Glyph(glyph); + } + + printf(" };\n\n"); // End bitmap array + + // Output glyph attributes table (one per character) + printf("const GFXglyph %sGlyphs[] PROGMEM = {\n", fontName); + for(i=first, j=0; i<=last; i++, j++) { + printf(" { %5d, %3d, %3d, %3d, %4d, %4d }", + table[j].bitmapOffset, + table[j].width, + table[j].height, + table[j].xAdvance, + table[j].xOffset, + table[j].yOffset); + if(i < last) { + printf(", // 0x%02X", i); + if((i >= ' ') && (i <= '~')) { + printf(" '%c'", i); + } + putchar('\n'); + } + } + printf(" }; // 0x%02X", last); + if((last >= ' ') && (last <= '~')) printf(" '%c'", last); + printf("\n\n"); + + // Output font structure + printf("const GFXfont %s PROGMEM = {\n", fontName); + printf(" (uint8_t *)%sBitmaps,\n", fontName); + printf(" (GFXglyph *)%sGlyphs,\n", fontName); + printf(" 0x%02X, 0x%02X, %ld };\n\n", + first, last, face->size->metrics.height >> 6); + printf("// Approx. %d bytes\n", + bitmapOffset + (last - first + 1) * 7 + 7); + // Size estimate is based on AVR struct and pointer sizes; + // actual size may vary. + + FT_Done_FreeType(library); + + return 0; +} + +/* ------------------------------------------------------------------------- + +Character metrics are slightly different from classic GFX & ftGFX. +In classic GFX: cursor position is the upper-left pixel of each 5x7 +character; lower extent of most glyphs (except those w/descenders) +is +6 pixels in Y direction. +W/new GFX fonts: cursor position is on baseline, where baseline is +'inclusive' (containing the bottom-most row of pixels in most symbols, +except those with descenders; ftGFX is one pixel lower). + +Cursor Y will be moved automatically when switching between classic +and new fonts. If you switch fonts, any print() calls will continue +along the same baseline. + + ...........#####.. -- yOffset + ..........######.. + ..........######.. + .........#######.. + ........#########. + * = Cursor pos. ........#########. + .......##########. + ......#####..####. + ......#####..####. + *.#.. .....#####...####. + .#.#. ....############## + #...# ...############### + #...# ...############### + ##### ..#####......##### + #...# .#####.......##### +====== #...# ====== #*###.........#### ======= Baseline + || xOffset + +glyph->xOffset and yOffset are pixel offsets, in GFX coordinate space +(+Y is down), from the cursor position to the top-left pixel of the +glyph bitmap. i.e. yOffset is typically negative, xOffset is typically +zero but a few glyphs will have other values (even negative xOffsets +sometimes, totally normal). glyph->xAdvance is the distance to move +the cursor on the X axis after drawing the corresponding symbol. + +There's also some changes with regard to 'background' color and new GFX +fonts (classic fonts unchanged). See Adafruit_GFX.cpp for explanation. +*/ diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/fontconvert/fontconvert_win.md b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/fontconvert/fontconvert_win.md new file mode 100644 index 0000000..361078b --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/fontconvert/fontconvert_win.md @@ -0,0 +1,88 @@ +### A short guide to use fontconvert.c to create your own fonts using MinGW. + +#### STEP 1: INSTALL MinGW + +Install MinGW (Minimalist GNU for Windows) from [MinGW.org](http://www.mingw.org/). +Please read carefully the instructions found on [Getting started page](http://www.mingw.org/wiki/Getting_Started). +I suggest installing with the "Graphical User Interface Installer". +To complete your initial installation you should further install some "packages". +For our purpose you should only install the "Basic Setup" packages. +To do that: + +1. Open the MinGW Installation Manager +2. From the left panel click "Basic Setup". +3. On the right panel choose "mingw32-base", "mingw-gcc-g++", "mingw-gcc-objc" and "msys-base" +and click "Mark for installation" +4. From the Menu click "Installation" and then "Apply changes". In the pop-up window select "Apply". + + +#### STEP 2: INSTALL Freetype Library + +To read about the freetype project visit [freetype.org](https://www.freetype.org/). +To Download the latest version of freetype go to [download page](http://download.savannah.gnu.org/releases/freetype/) +and choose "freetype-2.7.tar.gz" file (or a newer version if available). +To avoid long cd commands later in the command prompt, I suggest you unzip the file in the C:\ directory. +(I also renamed the folder to "ft27") +Before you build the library it's good to read these articles: +* [Using MSYS with MinGW](http://www.mingw.org/wiki/MSYS) +* [Installation and Use of Supplementary Libraries with MinGW](http://www.mingw.org/wiki/LibraryPathHOWTO) +* [Include Path](http://www.mingw.org/wiki/IncludePathHOWTO) + +Inside the unzipped folder there is another folder named "docs". Open it and read the INSTALL.UNIX (using notepad). +Pay attention to paragraph 3 (Build and Install the Library). So, let's begin the installation. +To give the appropriate commands we will use the MSYS command prompt (not cmd.exe of windows) which is UNIX like. +Follow the path C:\MinGW\msys\1.0 and double click "msys.bat". The command prompt environment appears. +Enter "ft27" directory using the cd commands: +``` +cd /c +cd ft27 +``` + +and then type one by one the commands: +``` +./configure --prefix=/mingw +make +make install +``` +Once you're finished, go inside "C:\MinGW\include" and there should be a new folder named "freetype2". +That, hopefully, means that you have installed the library correctly !! + +#### STEP 3: Build fontconvert.c + +Before proceeding I suggest you make a copy of Adafruit_GFX_library folder in C:\ directory. +Then, inside "fontconvert" folder open the "makefile" with an editor ( I used notepad++). +Change the commands so in the end the program looks like : +``` +all: fontconvert + +CC = gcc +CFLAGS = -Wall -I c:/mingw/include/freetype2 +LIBS = -lfreetype + +fontconvert: fontconvert.c + $(CC) $(CFLAGS) $< $(LIBS) -o $@ + +clean: + rm -f fontconvert +``` +Go back in the command prompt and with a cd command enter the fontconvert directory. +``` +cd /c/adafruit_gfx_library\fontconvert +``` +Give the command: +``` +make +``` +This command will, eventually, create a "fontconvert.exe" file inside fontconvert directory. + +#### STEP 4: Create your own font header files + +Now that you have an executable file, you can use it to create your own fonts to work with Adafruit GFX lib. +So, if we suppose that you already have a .ttf file with your favorite fonts, jump to the command prompt and type: +``` +./fontconvert yourfonts.ttf 9 > yourfonts9pt7b.h +``` +You can read more details at: [learn.adafruit](https://learn.adafruit.com/adafruit-gfx-graphics-library/using-fonts). + +Taraaaaaammm !! you've just created your new font header file. Put it inside the "Fonts" folder, grab a cup of coffee +and start playing with your Arduino (or whatever else ....)+ display module project. diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/fontconvert/makefonts.sh b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/fontconvert/makefonts.sh new file mode 100644 index 0000000..35f07ea --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/fontconvert/makefonts.sh @@ -0,0 +1,38 @@ +#!/bin/bash + +# Ugly little Bash script, generates a set of .h files for GFX using +# GNU FreeFont sources. There are three fonts: 'Mono' (Courier-like), +# 'Sans' (Helvetica-like) and 'Serif' (Times-like); four styles: regular, +# bold, oblique or italic, and bold+oblique or bold+italic; and four +# sizes: 9, 12, 18 and 24 point. No real error checking or anything, +# this just powers through all the combinations, calling the fontconvert +# utility and redirecting the output to a .h file for each combo. + +# Adafruit_GFX repository does not include the source outline fonts +# (huge zipfile, different license) but they're easily acquired: +# http://savannah.gnu.org/projects/freefont/ + +convert=./fontconvert +inpath=~/Desktop/freefont/ +outpath=../Fonts/ +fonts=(FreeMono FreeSans FreeSerif) +styles=("" Bold Italic BoldItalic Oblique BoldOblique) +sizes=(9 12 18 24) + +for f in ${fonts[*]} +do + for index in ${!styles[*]} + do + st=${styles[$index]} + for si in ${sizes[*]} + do + infile=$inpath$f$st".ttf" + if [ -f $infile ] # Does source combination exist? + then + outfile=$outpath$f$st$si"pt7b.h" +# printf "%s %s %s > %s\n" $convert $infile $si $outfile + $convert $infile $si > $outfile + fi + done + done +done diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/gfxfont.h b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/gfxfont.h new file mode 100644 index 0000000..07381ed --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/gfxfont.h @@ -0,0 +1,24 @@ +// Font structures for newer Adafruit_GFX (1.1 and later). +// Example fonts are included in 'Fonts' directory. +// To use a font in your Arduino sketch, #include the corresponding .h +// file and pass address of GFXfont struct to setFont(). Pass NULL to +// revert to 'classic' fixed-space bitmap font. + +#ifndef _GFXFONT_H_ +#define _GFXFONT_H_ + +typedef struct { // Data stored PER GLYPH + uint16_t bitmapOffset; // Pointer into GFXfont->bitmap + uint8_t width, height; // Bitmap dimensions in pixels + uint8_t xAdvance; // Distance to advance cursor (x axis) + int8_t xOffset, yOffset; // Dist from cursor pos to UL corner +} GFXglyph; + +typedef struct { // Data stored for FONT AS A WHOLE: + uint8_t *bitmap; // Glyph bitmaps, concatenated + GFXglyph *glyph; // Glyph array + uint8_t first, last; // ASCII extents + uint8_t yAdvance; // Newline distance (y axis) +} GFXfont; + +#endif // _GFXFONT_H_ diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/glcdfont.c b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/glcdfont.c new file mode 100644 index 0000000..6f88bd2 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/glcdfont.c @@ -0,0 +1,276 @@ +// This is the 'classic' fixed-space bitmap font for Adafruit_GFX since 1.0. +// See gfxfont.h for newer custom bitmap font info. + +#ifndef FONT5X7_H +#define FONT5X7_H + +#ifdef __AVR__ + #include + #include +#elif defined(ESP8266) + #include +#else + #define PROGMEM +#endif + +// Standard ASCII 5x7 font + +static const unsigned char font[] PROGMEM = { + 0x00, 0x00, 0x00, 0x00, 0x00, + 0x3E, 0x5B, 0x4F, 0x5B, 0x3E, + 0x3E, 0x6B, 0x4F, 0x6B, 0x3E, + 0x1C, 0x3E, 0x7C, 0x3E, 0x1C, + 0x18, 0x3C, 0x7E, 0x3C, 0x18, + 0x1C, 0x57, 0x7D, 0x57, 0x1C, + 0x1C, 0x5E, 0x7F, 0x5E, 0x1C, + 0x00, 0x18, 0x3C, 0x18, 0x00, + 0xFF, 0xE7, 0xC3, 0xE7, 0xFF, + 0x00, 0x18, 0x24, 0x18, 0x00, + 0xFF, 0xE7, 0xDB, 0xE7, 0xFF, + 0x30, 0x48, 0x3A, 0x06, 0x0E, + 0x26, 0x29, 0x79, 0x29, 0x26, + 0x40, 0x7F, 0x05, 0x05, 0x07, + 0x40, 0x7F, 0x05, 0x25, 0x3F, + 0x5A, 0x3C, 0xE7, 0x3C, 0x5A, + 0x7F, 0x3E, 0x1C, 0x1C, 0x08, + 0x08, 0x1C, 0x1C, 0x3E, 0x7F, + 0x14, 0x22, 0x7F, 0x22, 0x14, + 0x5F, 0x5F, 0x00, 0x5F, 0x5F, + 0x06, 0x09, 0x7F, 0x01, 0x7F, + 0x00, 0x66, 0x89, 0x95, 0x6A, + 0x60, 0x60, 0x60, 0x60, 0x60, + 0x94, 0xA2, 0xFF, 0xA2, 0x94, + 0x08, 0x04, 0x7E, 0x04, 0x08, + 0x10, 0x20, 0x7E, 0x20, 0x10, + 0x08, 0x08, 0x2A, 0x1C, 0x08, + 0x08, 0x1C, 0x2A, 0x08, 0x08, + 0x1E, 0x10, 0x10, 0x10, 0x10, + 0x0C, 0x1E, 0x0C, 0x1E, 0x0C, + 0x30, 0x38, 0x3E, 0x38, 0x30, + 0x06, 0x0E, 0x3E, 0x0E, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x5F, 0x00, 0x00, + 0x00, 0x07, 0x00, 0x07, 0x00, + 0x14, 0x7F, 0x14, 0x7F, 0x14, + 0x24, 0x2A, 0x7F, 0x2A, 0x12, + 0x23, 0x13, 0x08, 0x64, 0x62, + 0x36, 0x49, 0x56, 0x20, 0x50, + 0x00, 0x08, 0x07, 0x03, 0x00, + 0x00, 0x1C, 0x22, 0x41, 0x00, + 0x00, 0x41, 0x22, 0x1C, 0x00, + 0x2A, 0x1C, 0x7F, 0x1C, 0x2A, + 0x08, 0x08, 0x3E, 0x08, 0x08, + 0x00, 0x80, 0x70, 0x30, 0x00, + 0x08, 0x08, 0x08, 0x08, 0x08, + 0x00, 0x00, 0x60, 0x60, 0x00, + 0x20, 0x10, 0x08, 0x04, 0x02, + 0x3E, 0x51, 0x49, 0x45, 0x3E, + 0x00, 0x42, 0x7F, 0x40, 0x00, + 0x72, 0x49, 0x49, 0x49, 0x46, + 0x21, 0x41, 0x49, 0x4D, 0x33, + 0x18, 0x14, 0x12, 0x7F, 0x10, + 0x27, 0x45, 0x45, 0x45, 0x39, + 0x3C, 0x4A, 0x49, 0x49, 0x31, + 0x41, 0x21, 0x11, 0x09, 0x07, + 0x36, 0x49, 0x49, 0x49, 0x36, + 0x46, 0x49, 0x49, 0x29, 0x1E, + 0x00, 0x00, 0x14, 0x00, 0x00, + 0x00, 0x40, 0x34, 0x00, 0x00, + 0x00, 0x08, 0x14, 0x22, 0x41, + 0x14, 0x14, 0x14, 0x14, 0x14, + 0x00, 0x41, 0x22, 0x14, 0x08, + 0x02, 0x01, 0x59, 0x09, 0x06, + 0x3E, 0x41, 0x5D, 0x59, 0x4E, + 0x7C, 0x12, 0x11, 0x12, 0x7C, + 0x7F, 0x49, 0x49, 0x49, 0x36, + 0x3E, 0x41, 0x41, 0x41, 0x22, + 0x7F, 0x41, 0x41, 0x41, 0x3E, + 0x7F, 0x49, 0x49, 0x49, 0x41, + 0x7F, 0x09, 0x09, 0x09, 0x01, + 0x3E, 0x41, 0x41, 0x51, 0x73, + 0x7F, 0x08, 0x08, 0x08, 0x7F, + 0x00, 0x41, 0x7F, 0x41, 0x00, + 0x20, 0x40, 0x41, 0x3F, 0x01, + 0x7F, 0x08, 0x14, 0x22, 0x41, + 0x7F, 0x40, 0x40, 0x40, 0x40, + 0x7F, 0x02, 0x1C, 0x02, 0x7F, + 0x7F, 0x04, 0x08, 0x10, 0x7F, + 0x3E, 0x41, 0x41, 0x41, 0x3E, + 0x7F, 0x09, 0x09, 0x09, 0x06, + 0x3E, 0x41, 0x51, 0x21, 0x5E, + 0x7F, 0x09, 0x19, 0x29, 0x46, + 0x26, 0x49, 0x49, 0x49, 0x32, + 0x03, 0x01, 0x7F, 0x01, 0x03, + 0x3F, 0x40, 0x40, 0x40, 0x3F, + 0x1F, 0x20, 0x40, 0x20, 0x1F, + 0x3F, 0x40, 0x38, 0x40, 0x3F, + 0x63, 0x14, 0x08, 0x14, 0x63, + 0x03, 0x04, 0x78, 0x04, 0x03, + 0x61, 0x59, 0x49, 0x4D, 0x43, + 0x00, 0x7F, 0x41, 0x41, 0x41, + 0x02, 0x04, 0x08, 0x10, 0x20, + 0x00, 0x41, 0x41, 0x41, 0x7F, + 0x04, 0x02, 0x01, 0x02, 0x04, + 0x40, 0x40, 0x40, 0x40, 0x40, + 0x00, 0x03, 0x07, 0x08, 0x00, + 0x20, 0x54, 0x54, 0x78, 0x40, + 0x7F, 0x28, 0x44, 0x44, 0x38, + 0x38, 0x44, 0x44, 0x44, 0x28, + 0x38, 0x44, 0x44, 0x28, 0x7F, + 0x38, 0x54, 0x54, 0x54, 0x18, + 0x00, 0x08, 0x7E, 0x09, 0x02, + 0x18, 0xA4, 0xA4, 0x9C, 0x78, + 0x7F, 0x08, 0x04, 0x04, 0x78, + 0x00, 0x44, 0x7D, 0x40, 0x00, + 0x20, 0x40, 0x40, 0x3D, 0x00, + 0x7F, 0x10, 0x28, 0x44, 0x00, + 0x00, 0x41, 0x7F, 0x40, 0x00, + 0x7C, 0x04, 0x78, 0x04, 0x78, + 0x7C, 0x08, 0x04, 0x04, 0x78, + 0x38, 0x44, 0x44, 0x44, 0x38, + 0xFC, 0x18, 0x24, 0x24, 0x18, + 0x18, 0x24, 0x24, 0x18, 0xFC, + 0x7C, 0x08, 0x04, 0x04, 0x08, + 0x48, 0x54, 0x54, 0x54, 0x24, + 0x04, 0x04, 0x3F, 0x44, 0x24, + 0x3C, 0x40, 0x40, 0x20, 0x7C, + 0x1C, 0x20, 0x40, 0x20, 0x1C, + 0x3C, 0x40, 0x30, 0x40, 0x3C, + 0x44, 0x28, 0x10, 0x28, 0x44, + 0x4C, 0x90, 0x90, 0x90, 0x7C, + 0x44, 0x64, 0x54, 0x4C, 0x44, + 0x00, 0x08, 0x36, 0x41, 0x00, + 0x00, 0x00, 0x77, 0x00, 0x00, + 0x00, 0x41, 0x36, 0x08, 0x00, + 0x02, 0x01, 0x02, 0x04, 0x02, + 0x3C, 0x26, 0x23, 0x26, 0x3C, + 0x1E, 0xA1, 0xA1, 0x61, 0x12, + 0x3A, 0x40, 0x40, 0x20, 0x7A, + 0x38, 0x54, 0x54, 0x55, 0x59, + 0x21, 0x55, 0x55, 0x79, 0x41, + 0x22, 0x54, 0x54, 0x78, 0x42, // a-umlaut + 0x21, 0x55, 0x54, 0x78, 0x40, + 0x20, 0x54, 0x55, 0x79, 0x40, + 0x0C, 0x1E, 0x52, 0x72, 0x12, + 0x39, 0x55, 0x55, 0x55, 0x59, + 0x39, 0x54, 0x54, 0x54, 0x59, + 0x39, 0x55, 0x54, 0x54, 0x58, + 0x00, 0x00, 0x45, 0x7C, 0x41, + 0x00, 0x02, 0x45, 0x7D, 0x42, + 0x00, 0x01, 0x45, 0x7C, 0x40, + 0x7D, 0x12, 0x11, 0x12, 0x7D, // A-umlaut + 0xF0, 0x28, 0x25, 0x28, 0xF0, + 0x7C, 0x54, 0x55, 0x45, 0x00, + 0x20, 0x54, 0x54, 0x7C, 0x54, + 0x7C, 0x0A, 0x09, 0x7F, 0x49, + 0x32, 0x49, 0x49, 0x49, 0x32, + 0x3A, 0x44, 0x44, 0x44, 0x3A, // o-umlaut + 0x32, 0x4A, 0x48, 0x48, 0x30, + 0x3A, 0x41, 0x41, 0x21, 0x7A, + 0x3A, 0x42, 0x40, 0x20, 0x78, + 0x00, 0x9D, 0xA0, 0xA0, 0x7D, + 0x3D, 0x42, 0x42, 0x42, 0x3D, // O-umlaut + 0x3D, 0x40, 0x40, 0x40, 0x3D, + 0x3C, 0x24, 0xFF, 0x24, 0x24, + 0x48, 0x7E, 0x49, 0x43, 0x66, + 0x2B, 0x2F, 0xFC, 0x2F, 0x2B, + 0xFF, 0x09, 0x29, 0xF6, 0x20, + 0xC0, 0x88, 0x7E, 0x09, 0x03, + 0x20, 0x54, 0x54, 0x79, 0x41, + 0x00, 0x00, 0x44, 0x7D, 0x41, + 0x30, 0x48, 0x48, 0x4A, 0x32, + 0x38, 0x40, 0x40, 0x22, 0x7A, + 0x00, 0x7A, 0x0A, 0x0A, 0x72, + 0x7D, 0x0D, 0x19, 0x31, 0x7D, + 0x26, 0x29, 0x29, 0x2F, 0x28, + 0x26, 0x29, 0x29, 0x29, 0x26, + 0x30, 0x48, 0x4D, 0x40, 0x20, + 0x38, 0x08, 0x08, 0x08, 0x08, + 0x08, 0x08, 0x08, 0x08, 0x38, + 0x2F, 0x10, 0xC8, 0xAC, 0xBA, + 0x2F, 0x10, 0x28, 0x34, 0xFA, + 0x00, 0x00, 0x7B, 0x00, 0x00, + 0x08, 0x14, 0x2A, 0x14, 0x22, + 0x22, 0x14, 0x2A, 0x14, 0x08, + 0x55, 0x00, 0x55, 0x00, 0x55, // #176 (25% block) missing in old code + 0xAA, 0x55, 0xAA, 0x55, 0xAA, // 50% block + 0xFF, 0x55, 0xFF, 0x55, 0xFF, // 75% block + 0x00, 0x00, 0x00, 0xFF, 0x00, + 0x10, 0x10, 0x10, 0xFF, 0x00, + 0x14, 0x14, 0x14, 0xFF, 0x00, + 0x10, 0x10, 0xFF, 0x00, 0xFF, + 0x10, 0x10, 0xF0, 0x10, 0xF0, + 0x14, 0x14, 0x14, 0xFC, 0x00, + 0x14, 0x14, 0xF7, 0x00, 0xFF, + 0x00, 0x00, 0xFF, 0x00, 0xFF, + 0x14, 0x14, 0xF4, 0x04, 0xFC, + 0x14, 0x14, 0x17, 0x10, 0x1F, + 0x10, 0x10, 0x1F, 0x10, 0x1F, + 0x14, 0x14, 0x14, 0x1F, 0x00, + 0x10, 0x10, 0x10, 0xF0, 0x00, + 0x00, 0x00, 0x00, 0x1F, 0x10, + 0x10, 0x10, 0x10, 0x1F, 0x10, + 0x10, 0x10, 0x10, 0xF0, 0x10, + 0x00, 0x00, 0x00, 0xFF, 0x10, + 0x10, 0x10, 0x10, 0x10, 0x10, + 0x10, 0x10, 0x10, 0xFF, 0x10, + 0x00, 0x00, 0x00, 0xFF, 0x14, + 0x00, 0x00, 0xFF, 0x00, 0xFF, + 0x00, 0x00, 0x1F, 0x10, 0x17, + 0x00, 0x00, 0xFC, 0x04, 0xF4, + 0x14, 0x14, 0x17, 0x10, 0x17, + 0x14, 0x14, 0xF4, 0x04, 0xF4, + 0x00, 0x00, 0xFF, 0x00, 0xF7, + 0x14, 0x14, 0x14, 0x14, 0x14, + 0x14, 0x14, 0xF7, 0x00, 0xF7, + 0x14, 0x14, 0x14, 0x17, 0x14, + 0x10, 0x10, 0x1F, 0x10, 0x1F, + 0x14, 0x14, 0x14, 0xF4, 0x14, + 0x10, 0x10, 0xF0, 0x10, 0xF0, + 0x00, 0x00, 0x1F, 0x10, 0x1F, + 0x00, 0x00, 0x00, 0x1F, 0x14, + 0x00, 0x00, 0x00, 0xFC, 0x14, + 0x00, 0x00, 0xF0, 0x10, 0xF0, + 0x10, 0x10, 0xFF, 0x10, 0xFF, + 0x14, 0x14, 0x14, 0xFF, 0x14, + 0x10, 0x10, 0x10, 0x1F, 0x00, + 0x00, 0x00, 0x00, 0xF0, 0x10, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xFF, 0xFF, 0xFF, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xFF, 0xFF, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x38, 0x44, 0x44, 0x38, 0x44, + 0xFC, 0x4A, 0x4A, 0x4A, 0x34, // sharp-s or beta + 0x7E, 0x02, 0x02, 0x06, 0x06, + 0x02, 0x7E, 0x02, 0x7E, 0x02, + 0x63, 0x55, 0x49, 0x41, 0x63, + 0x38, 0x44, 0x44, 0x3C, 0x04, + 0x40, 0x7E, 0x20, 0x1E, 0x20, + 0x06, 0x02, 0x7E, 0x02, 0x02, + 0x99, 0xA5, 0xE7, 0xA5, 0x99, + 0x1C, 0x2A, 0x49, 0x2A, 0x1C, + 0x4C, 0x72, 0x01, 0x72, 0x4C, + 0x30, 0x4A, 0x4D, 0x4D, 0x30, + 0x30, 0x48, 0x78, 0x48, 0x30, + 0xBC, 0x62, 0x5A, 0x46, 0x3D, + 0x3E, 0x49, 0x49, 0x49, 0x00, + 0x7E, 0x01, 0x01, 0x01, 0x7E, + 0x2A, 0x2A, 0x2A, 0x2A, 0x2A, + 0x44, 0x44, 0x5F, 0x44, 0x44, + 0x40, 0x51, 0x4A, 0x44, 0x40, + 0x40, 0x44, 0x4A, 0x51, 0x40, + 0x00, 0x00, 0xFF, 0x01, 0x03, + 0xE0, 0x80, 0xFF, 0x00, 0x00, + 0x08, 0x08, 0x6B, 0x6B, 0x08, + 0x36, 0x12, 0x36, 0x24, 0x36, + 0x06, 0x0F, 0x09, 0x0F, 0x06, + 0x00, 0x00, 0x18, 0x18, 0x00, + 0x00, 0x00, 0x10, 0x10, 0x00, + 0x30, 0x40, 0xFF, 0x01, 0x01, + 0x00, 0x1F, 0x01, 0x01, 0x1E, + 0x00, 0x19, 0x1D, 0x17, 0x12, + 0x00, 0x3C, 0x3C, 0x3C, 0x3C, + 0x00, 0x00, 0x00, 0x00, 0x00 // #255 NBSP +}; +#endif // FONT5X7_H diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/library.properties b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/library.properties new file mode 100644 index 0000000..8a83286 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/library.properties @@ -0,0 +1,9 @@ +name=Adafruit GFX Library +version=1.1.5 +author=Adafruit +maintainer=Adafruit +sentence=Adafruit GFX graphics core library, this is the 'core' class that all our other graphics libraries derive from. +paragraph=Install this library in addition to the display library for your hardware. +category=Display +url=https://github.com/adafruit/Adafruit-GFX-Library +architectures=* diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/license.txt b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/license.txt new file mode 100644 index 0000000..7492e93 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit-GFX-Library-master/license.txt @@ -0,0 +1,24 @@ +Software License Agreement (BSD License) + +Copyright (c) 2012 Adafruit Industries. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +- Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. +- Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit_GFX.cpp b/libraries/Adafruit-GFX-Library-master/Adafruit_GFX.cpp new file mode 100644 index 0000000..46d4d54 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit_GFX.cpp @@ -0,0 +1,1071 @@ +/* +This is the core graphics library for all our displays, providing a common +set of graphics primitives (points, lines, circles, etc.). It needs to be +paired with a hardware-specific library for each display device we carry +(to handle the lower-level functions). + +Adafruit invests time and resources providing this open source code, please +support Adafruit & open-source hardware by purchasing products from Adafruit! + +Copyright (c) 2013 Adafruit Industries. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +- Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. +- Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. +*/ + +#ifdef __AVR__ + #include +#elif defined(ESP8266) + #include +#endif +#include "Adafruit_GFX.h" +#include "glcdfont.c" + +// Many (but maybe not all) non-AVR board installs define macros +// for compatibility with existing PROGMEM-reading AVR code. +// Do our own checks and defines here for good measure... + +#ifndef pgm_read_byte + #define pgm_read_byte(addr) (*(const unsigned char *)(addr)) +#endif +#ifndef pgm_read_word + #define pgm_read_word(addr) (*(const unsigned short *)(addr)) +#endif +#ifndef pgm_read_dword + #define pgm_read_dword(addr) (*(const unsigned long *)(addr)) +#endif + +// Pointers are a peculiar case...typically 16-bit on AVR boards, +// 32 bits elsewhere. Try to accommodate both... + +#if !defined(__INT_MAX__) || (__INT_MAX__ > 0xFFFF) + #define pgm_read_pointer(addr) ((void *)pgm_read_dword(addr)) +#else + #define pgm_read_pointer(addr) ((void *)pgm_read_word(addr)) +#endif + +#ifndef min +#define min(a,b) (((a) < (b)) ? (a) : (b)) +#endif + +#ifndef _swap_int16_t +#define _swap_int16_t(a, b) { int16_t t = a; a = b; b = t; } +#endif + +Adafruit_GFX::Adafruit_GFX(int16_t w, int16_t h): + WIDTH(w), HEIGHT(h) +{ + _width = WIDTH; + _height = HEIGHT; + rotation = 0; + cursor_y = cursor_x = 0; + textsize = 1; + textcolor = textbgcolor = 0xFFFF; + wrap = true; + _cp437 = false; + gfxFont = NULL; +} + +// Draw a circle outline +void Adafruit_GFX::drawCircle(int16_t x0, int16_t y0, int16_t r, + uint16_t color) { + int16_t f = 1 - r; + int16_t ddF_x = 1; + int16_t ddF_y = -2 * r; + int16_t x = 0; + int16_t y = r; + + drawPixel(x0 , y0+r, color); + drawPixel(x0 , y0-r, color); + drawPixel(x0+r, y0 , color); + drawPixel(x0-r, y0 , color); + + while (x= 0) { + y--; + ddF_y += 2; + f += ddF_y; + } + x++; + ddF_x += 2; + f += ddF_x; + + drawPixel(x0 + x, y0 + y, color); + drawPixel(x0 - x, y0 + y, color); + drawPixel(x0 + x, y0 - y, color); + drawPixel(x0 - x, y0 - y, color); + drawPixel(x0 + y, y0 + x, color); + drawPixel(x0 - y, y0 + x, color); + drawPixel(x0 + y, y0 - x, color); + drawPixel(x0 - y, y0 - x, color); + } +} + +void Adafruit_GFX::drawCircleHelper( int16_t x0, int16_t y0, + int16_t r, uint8_t cornername, uint16_t color) { + int16_t f = 1 - r; + int16_t ddF_x = 1; + int16_t ddF_y = -2 * r; + int16_t x = 0; + int16_t y = r; + + while (x= 0) { + y--; + ddF_y += 2; + f += ddF_y; + } + x++; + ddF_x += 2; + f += ddF_x; + if (cornername & 0x4) { + drawPixel(x0 + x, y0 + y, color); + drawPixel(x0 + y, y0 + x, color); + } + if (cornername & 0x2) { + drawPixel(x0 + x, y0 - y, color); + drawPixel(x0 + y, y0 - x, color); + } + if (cornername & 0x8) { + drawPixel(x0 - y, y0 + x, color); + drawPixel(x0 - x, y0 + y, color); + } + if (cornername & 0x1) { + drawPixel(x0 - y, y0 - x, color); + drawPixel(x0 - x, y0 - y, color); + } + } +} + +void Adafruit_GFX::fillCircle(int16_t x0, int16_t y0, int16_t r, + uint16_t color) { + drawFastVLine(x0, y0-r, 2*r+1, color); + fillCircleHelper(x0, y0, r, 3, 0, color); +} + +// Used to do circles and roundrects +void Adafruit_GFX::fillCircleHelper(int16_t x0, int16_t y0, int16_t r, + uint8_t cornername, int16_t delta, uint16_t color) { + + int16_t f = 1 - r; + int16_t ddF_x = 1; + int16_t ddF_y = -2 * r; + int16_t x = 0; + int16_t y = r; + + while (x= 0) { + y--; + ddF_y += 2; + f += ddF_y; + } + x++; + ddF_x += 2; + f += ddF_x; + + if (cornername & 0x1) { + drawFastVLine(x0+x, y0-y, 2*y+1+delta, color); + drawFastVLine(x0+y, y0-x, 2*x+1+delta, color); + } + if (cornername & 0x2) { + drawFastVLine(x0-x, y0-y, 2*y+1+delta, color); + drawFastVLine(x0-y, y0-x, 2*x+1+delta, color); + } + } +} + +// Bresenham's algorithm - thx wikpedia +void Adafruit_GFX::drawLine(int16_t x0, int16_t y0, int16_t x1, int16_t y1, + uint16_t color) { + int16_t steep = abs(y1 - y0) > abs(x1 - x0); + if (steep) { + _swap_int16_t(x0, y0); + _swap_int16_t(x1, y1); + } + + if (x0 > x1) { + _swap_int16_t(x0, x1); + _swap_int16_t(y0, y1); + } + + int16_t dx, dy; + dx = x1 - x0; + dy = abs(y1 - y0); + + int16_t err = dx / 2; + int16_t ystep; + + if (y0 < y1) { + ystep = 1; + } else { + ystep = -1; + } + + for (; x0<=x1; x0++) { + if (steep) { + drawPixel(y0, x0, color); + } else { + drawPixel(x0, y0, color); + } + err -= dy; + if (err < 0) { + y0 += ystep; + err += dx; + } + } +} + +// Draw a rectangle +void Adafruit_GFX::drawRect(int16_t x, int16_t y, int16_t w, int16_t h, + uint16_t color) { + drawFastHLine(x, y, w, color); + drawFastHLine(x, y+h-1, w, color); + drawFastVLine(x, y, h, color); + drawFastVLine(x+w-1, y, h, color); +} + +void Adafruit_GFX::drawFastVLine(int16_t x, int16_t y, + int16_t h, uint16_t color) { + // Update in subclasses if desired! + drawLine(x, y, x, y+h-1, color); +} + +void Adafruit_GFX::drawFastHLine(int16_t x, int16_t y, + int16_t w, uint16_t color) { + // Update in subclasses if desired! + drawLine(x, y, x+w-1, y, color); +} + +void Adafruit_GFX::fillRect(int16_t x, int16_t y, int16_t w, int16_t h, + uint16_t color) { + // Update in subclasses if desired! + for (int16_t i=x; i= y1 >= y0) + if (y0 > y1) { + _swap_int16_t(y0, y1); _swap_int16_t(x0, x1); + } + if (y1 > y2) { + _swap_int16_t(y2, y1); _swap_int16_t(x2, x1); + } + if (y0 > y1) { + _swap_int16_t(y0, y1); _swap_int16_t(x0, x1); + } + + if(y0 == y2) { // Handle awkward all-on-same-line case as its own thing + a = b = x0; + if(x1 < a) a = x1; + else if(x1 > b) b = x1; + if(x2 < a) a = x2; + else if(x2 > b) b = x2; + drawFastHLine(a, y0, b-a+1, color); + return; + } + + int16_t + dx01 = x1 - x0, + dy01 = y1 - y0, + dx02 = x2 - x0, + dy02 = y2 - y0, + dx12 = x2 - x1, + dy12 = y2 - y1; + int32_t + sa = 0, + sb = 0; + + // For upper part of triangle, find scanline crossings for segments + // 0-1 and 0-2. If y1=y2 (flat-bottomed triangle), the scanline y1 + // is included here (and second loop will be skipped, avoiding a /0 + // error there), otherwise scanline y1 is skipped here and handled + // in the second loop...which also avoids a /0 error here if y0=y1 + // (flat-topped triangle). + if(y1 == y2) last = y1; // Include y1 scanline + else last = y1-1; // Skip it + + for(y=y0; y<=last; y++) { + a = x0 + sa / dy01; + b = x0 + sb / dy02; + sa += dx01; + sb += dx02; + /* longhand: + a = x0 + (x1 - x0) * (y - y0) / (y1 - y0); + b = x0 + (x2 - x0) * (y - y0) / (y2 - y0); + */ + if(a > b) _swap_int16_t(a,b); + drawFastHLine(a, y, b-a+1, color); + } + + // For lower part of triangle, find scanline crossings for segments + // 0-2 and 1-2. This loop is skipped if y1=y2. + sa = dx12 * (y - y1); + sb = dx02 * (y - y0); + for(; y<=y2; y++) { + a = x1 + sa / dy12; + b = x0 + sb / dy02; + sa += dx12; + sb += dx02; + /* longhand: + a = x1 + (x2 - x1) * (y - y1) / (y2 - y1); + b = x0 + (x2 - x0) * (y - y0) / (y2 - y0); + */ + if(a > b) _swap_int16_t(a,b); + drawFastHLine(a, y, b-a+1, color); + } +} + +// Draw a 1-bit image (bitmap) at the specified (x,y) position from the +// provided bitmap buffer (must be PROGMEM memory) using the specified +// foreground color (unset bits are transparent). +void Adafruit_GFX::drawBitmap(int16_t x, int16_t y, + const uint8_t *bitmap, int16_t w, int16_t h, uint16_t color) { + + int16_t i, j, byteWidth = (w + 7) / 8; + uint8_t byte; + + for(j=0; j>= 1; + else byte = pgm_read_byte(bitmap + j * byteWidth + i / 8); + if(byte & 0x01) drawPixel(x+i, y+j, color); + } + } +} + +#if ARDUINO >= 100 +size_t Adafruit_GFX::write(uint8_t c) { +#else +void Adafruit_GFX::write(uint8_t c) { +#endif + + if(!gfxFont) { // 'Classic' built-in font + + if(c == '\n') { + cursor_y += textsize*8; + cursor_x = 0; + } else if(c == '\r') { + // skip em + } else { + if(wrap && ((cursor_x + textsize * 6) >= _width)) { // Heading off edge? + cursor_x = 0; // Reset x to zero + cursor_y += textsize * 8; // Advance y one line + } + drawChar(cursor_x, cursor_y, c, textcolor, textbgcolor, textsize); + cursor_x += textsize * 6; + } + + } else { // Custom font + + if(c == '\n') { + cursor_x = 0; + cursor_y += (int16_t)textsize * + (uint8_t)pgm_read_byte(&gfxFont->yAdvance); + } else if(c != '\r') { + uint8_t first = pgm_read_byte(&gfxFont->first); + if((c >= first) && (c <= (uint8_t)pgm_read_byte(&gfxFont->last))) { + uint8_t c2 = c - pgm_read_byte(&gfxFont->first); + GFXglyph *glyph = &(((GFXglyph *)pgm_read_pointer(&gfxFont->glyph))[c2]); + uint8_t w = pgm_read_byte(&glyph->width), + h = pgm_read_byte(&glyph->height); + if((w > 0) && (h > 0)) { // Is there an associated bitmap? + int16_t xo = (int8_t)pgm_read_byte(&glyph->xOffset); // sic + if(wrap && ((cursor_x + textsize * (xo + w)) >= _width)) { + // Drawing character would go off right edge; wrap to new line + cursor_x = 0; + cursor_y += (int16_t)textsize * + (uint8_t)pgm_read_byte(&gfxFont->yAdvance); + } + drawChar(cursor_x, cursor_y, c, textcolor, textbgcolor, textsize); + } + cursor_x += pgm_read_byte(&glyph->xAdvance) * (int16_t)textsize; + } + } + + } +#if ARDUINO >= 100 + return 1; +#endif +} + +// Draw a character +void Adafruit_GFX::drawChar(int16_t x, int16_t y, unsigned char c, + uint16_t color, uint16_t bg, uint8_t size) { + + if(!gfxFont) { // 'Classic' built-in font + + if((x >= _width) || // Clip right + (y >= _height) || // Clip bottom + ((x + 6 * size - 1) < 0) || // Clip left + ((y + 8 * size - 1) < 0)) // Clip top + return; + + if(!_cp437 && (c >= 176)) c++; // Handle 'classic' charset behavior + + for(int8_t i=0; i<6; i++ ) { + uint8_t line; + if(i < 5) line = pgm_read_byte(font+(c*5)+i); + else line = 0x0; + for(int8_t j=0; j<8; j++, line >>= 1) { + if(line & 0x1) { + if(size == 1) drawPixel(x+i, y+j, color); + else fillRect(x+(i*size), y+(j*size), size, size, color); + } else if(bg != color) { + if(size == 1) drawPixel(x+i, y+j, bg); + else fillRect(x+i*size, y+j*size, size, size, bg); + } + } + } + + } else { // Custom font + + // Character is assumed previously filtered by write() to eliminate + // newlines, returns, non-printable characters, etc. Calling drawChar() + // directly with 'bad' characters of font may cause mayhem! + + c -= pgm_read_byte(&gfxFont->first); + GFXglyph *glyph = &(((GFXglyph *)pgm_read_pointer(&gfxFont->glyph))[c]); + uint8_t *bitmap = (uint8_t *)pgm_read_pointer(&gfxFont->bitmap); + + uint16_t bo = pgm_read_word(&glyph->bitmapOffset); + uint8_t w = pgm_read_byte(&glyph->width), + h = pgm_read_byte(&glyph->height), + xa = pgm_read_byte(&glyph->xAdvance); + int8_t xo = pgm_read_byte(&glyph->xOffset), + yo = pgm_read_byte(&glyph->yOffset); + uint8_t xx, yy, bits, bit = 0; + int16_t xo16, yo16; + + if(size > 1) { + xo16 = xo; + yo16 = yo; + } + + // Todo: Add character clipping here + + // NOTE: THERE IS NO 'BACKGROUND' COLOR OPTION ON CUSTOM FONTS. + // THIS IS ON PURPOSE AND BY DESIGN. The background color feature + // has typically been used with the 'classic' font to overwrite old + // screen contents with new data. This ONLY works because the + // characters are a uniform size; it's not a sensible thing to do with + // proportionally-spaced fonts with glyphs of varying sizes (and that + // may overlap). To replace previously-drawn text when using a custom + // font, use the getTextBounds() function to determine the smallest + // rectangle encompassing a string, erase the area with fillRect(), + // then draw new text. This WILL infortunately 'blink' the text, but + // is unavoidable. Drawing 'background' pixels will NOT fix this, + // only creates a new set of problems. Have an idea to work around + // this (a canvas object type for MCUs that can afford the RAM and + // displays supporting setAddrWindow() and pushColors()), but haven't + // implemented this yet. + + for(yy=0; yy 0) ? s : 1; +} + +void Adafruit_GFX::setTextColor(uint16_t c) { + // For 'transparent' background, we'll set the bg + // to the same as fg instead of using a flag + textcolor = textbgcolor = c; +} + +void Adafruit_GFX::setTextColor(uint16_t c, uint16_t b) { + textcolor = c; + textbgcolor = b; +} + +void Adafruit_GFX::setTextWrap(boolean w) { + wrap = w; +} + +uint8_t Adafruit_GFX::getRotation(void) const { + return rotation; +} + +void Adafruit_GFX::setRotation(uint8_t x) { + rotation = (x & 3); + switch(rotation) { + case 0: + case 2: + _width = WIDTH; + _height = HEIGHT; + break; + case 1: + case 3: + _width = HEIGHT; + _height = WIDTH; + break; + } +} + +// Enable (or disable) Code Page 437-compatible charset. +// There was an error in glcdfont.c for the longest time -- one character +// (#176, the 'light shade' block) was missing -- this threw off the index +// of every character that followed it. But a TON of code has been written +// with the erroneous character indices. By default, the library uses the +// original 'wrong' behavior and old sketches will still work. Pass 'true' +// to this function to use correct CP437 character values in your code. +void Adafruit_GFX::cp437(boolean x) { + _cp437 = x; +} + +void Adafruit_GFX::setFont(const GFXfont *f) { + if(f) { // Font struct pointer passed in? + if(!gfxFont) { // And no current font struct? + // Switching from classic to new font behavior. + // Move cursor pos down 6 pixels so it's on baseline. + cursor_y += 6; + } + } else if(gfxFont) { // NULL passed. Current font struct defined? + // Switching from new to classic font behavior. + // Move cursor pos up 6 pixels so it's at top-left of char. + cursor_y -= 6; + } + gfxFont = (GFXfont *)f; +} + +// Pass string and a cursor position, returns UL corner and W,H. +void Adafruit_GFX::getTextBounds(char *str, int16_t x, int16_t y, + int16_t *x1, int16_t *y1, uint16_t *w, uint16_t *h) { + uint8_t c; // Current character + + *x1 = x; + *y1 = y; + *w = *h = 0; + + if(gfxFont) { + + GFXglyph *glyph; + uint8_t first = pgm_read_byte(&gfxFont->first), + last = pgm_read_byte(&gfxFont->last), + gw, gh, xa; + int8_t xo, yo; + int16_t minx = _width, miny = _height, maxx = -1, maxy = -1, + gx1, gy1, gx2, gy2, ts = (int16_t)textsize, + ya = ts * (uint8_t)pgm_read_byte(&gfxFont->yAdvance); + + while((c = *str++)) { + if(c != '\n') { // Not a newline + if(c != '\r') { // Not a carriage return, is normal char + if((c >= first) && (c <= last)) { // Char present in current font + c -= first; + glyph = &(((GFXglyph *)pgm_read_pointer(&gfxFont->glyph))[c]); + gw = pgm_read_byte(&glyph->width); + gh = pgm_read_byte(&glyph->height); + xa = pgm_read_byte(&glyph->xAdvance); + xo = pgm_read_byte(&glyph->xOffset); + yo = pgm_read_byte(&glyph->yOffset); + if(wrap && ((x + (((int16_t)xo + gw) * ts)) >= _width)) { + // Line wrap + x = 0; // Reset x to 0 + y += ya; // Advance y by 1 line + } + gx1 = x + xo * ts; + gy1 = y + yo * ts; + gx2 = gx1 + gw * ts - 1; + gy2 = gy1 + gh * ts - 1; + if(gx1 < minx) minx = gx1; + if(gy1 < miny) miny = gy1; + if(gx2 > maxx) maxx = gx2; + if(gy2 > maxy) maxy = gy2; + x += xa * ts; + } + } // Carriage return = do nothing + } else { // Newline + x = 0; // Reset x + y += ya; // Advance y by 1 line + } + } + // End of string + *x1 = minx; + *y1 = miny; + if(maxx >= minx) *w = maxx - minx + 1; + if(maxy >= miny) *h = maxy - miny + 1; + + } else { // Default font + + uint16_t lineWidth = 0, maxWidth = 0; // Width of current, all lines + + while((c = *str++)) { + if(c != '\n') { // Not a newline + if(c != '\r') { // Not a carriage return, is normal char + if(wrap && ((x + textsize * 6) >= _width)) { + x = 0; // Reset x to 0 + y += textsize * 8; // Advance y by 1 line + if(lineWidth > maxWidth) maxWidth = lineWidth; // Save widest line + lineWidth = textsize * 6; // First char on new line + } else { // No line wrap, just keep incrementing X + lineWidth += textsize * 6; // Includes interchar x gap + } + } // Carriage return = do nothing + } else { // Newline + x = 0; // Reset x to 0 + y += textsize * 8; // Advance y by 1 line + if(lineWidth > maxWidth) maxWidth = lineWidth; // Save widest line + lineWidth = 0; // Reset lineWidth for new line + } + } + // End of string + if(lineWidth) y += textsize * 8; // Add height of last (or only) line + if(lineWidth > maxWidth) maxWidth = lineWidth; // Is the last or only line the widest? + *w = maxWidth - 1; // Don't include last interchar x gap + *h = y - *y1; + + } // End classic vs custom font +} + +// Same as above, but for PROGMEM strings +void Adafruit_GFX::getTextBounds(const __FlashStringHelper *str, + int16_t x, int16_t y, int16_t *x1, int16_t *y1, uint16_t *w, uint16_t *h) { + uint8_t *s = (uint8_t *)str, c; + + *x1 = x; + *y1 = y; + *w = *h = 0; + + if(gfxFont) { + + GFXglyph *glyph; + uint8_t first = pgm_read_byte(&gfxFont->first), + last = pgm_read_byte(&gfxFont->last), + gw, gh, xa; + int8_t xo, yo; + int16_t minx = _width, miny = _height, maxx = -1, maxy = -1, + gx1, gy1, gx2, gy2, ts = (int16_t)textsize, + ya = ts * (uint8_t)pgm_read_byte(&gfxFont->yAdvance); + + while((c = pgm_read_byte(s++))) { + if(c != '\n') { // Not a newline + if(c != '\r') { // Not a carriage return, is normal char + if((c >= first) && (c <= last)) { // Char present in current font + c -= first; + glyph = &(((GFXglyph *)pgm_read_pointer(&gfxFont->glyph))[c]); + gw = pgm_read_byte(&glyph->width); + gh = pgm_read_byte(&glyph->height); + xa = pgm_read_byte(&glyph->xAdvance); + xo = pgm_read_byte(&glyph->xOffset); + yo = pgm_read_byte(&glyph->yOffset); + if(wrap && ((x + (((int16_t)xo + gw) * ts)) >= _width)) { + // Line wrap + x = 0; // Reset x to 0 + y += ya; // Advance y by 1 line + } + gx1 = x + xo * ts; + gy1 = y + yo * ts; + gx2 = gx1 + gw * ts - 1; + gy2 = gy1 + gh * ts - 1; + if(gx1 < minx) minx = gx1; + if(gy1 < miny) miny = gy1; + if(gx2 > maxx) maxx = gx2; + if(gy2 > maxy) maxy = gy2; + x += xa * ts; + } + } // Carriage return = do nothing + } else { // Newline + x = 0; // Reset x + y += ya; // Advance y by 1 line + } + } + // End of string + *x1 = minx; + *y1 = miny; + if(maxx >= minx) *w = maxx - minx + 1; + if(maxy >= miny) *h = maxy - miny + 1; + + } else { // Default font + + uint16_t lineWidth = 0, maxWidth = 0; // Width of current, all lines + + while((c = pgm_read_byte(s++))) { + if(c != '\n') { // Not a newline + if(c != '\r') { // Not a carriage return, is normal char + if(wrap && ((x + textsize * 6) >= _width)) { + x = 0; // Reset x to 0 + y += textsize * 8; // Advance y by 1 line + if(lineWidth > maxWidth) maxWidth = lineWidth; // Save widest line + lineWidth = textsize * 6; // First char on new line + } else { // No line wrap, just keep incrementing X + lineWidth += textsize * 6; // Includes interchar x gap + } + } // Carriage return = do nothing + } else { // Newline + x = 0; // Reset x to 0 + y += textsize * 8; // Advance y by 1 line + if(lineWidth > maxWidth) maxWidth = lineWidth; // Save widest line + lineWidth = 0; // Reset lineWidth for new line + } + } + // End of string + if(lineWidth) y += textsize * 8; // Add height of last (or only) line + if(lineWidth > maxWidth) maxWidth = lineWidth; // Is the last or only line the widest? + *w = maxWidth - 1; // Don't include last interchar x gap + *h = y - *y1; + + } // End classic vs custom font +} + +// Return the size of the display (per current rotation) +int16_t Adafruit_GFX::width(void) const { + return _width; +} + +int16_t Adafruit_GFX::height(void) const { + return _height; +} + +void Adafruit_GFX::invertDisplay(boolean i) { + // Do nothing, must be subclassed if supported by hardware +} + +/***************************************************************************/ +// code for the GFX button UI element + +Adafruit_GFX_Button::Adafruit_GFX_Button(void) { + _gfx = 0; +} + +void Adafruit_GFX_Button::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) +{ + _x = x; + _y = y; + _w = w; + _h = h; + _outlinecolor = outline; + _fillcolor = fill; + _textcolor = textcolor; + _textsize = textsize; + _gfx = gfx; + strncpy(_label, label, 9); + _label[9] = 0; +} + +void Adafruit_GFX_Button::drawButton(boolean inverted) { + uint16_t fill, outline, text; + + if(!inverted) { + fill = _fillcolor; + outline = _outlinecolor; + text = _textcolor; + } else { + fill = _textcolor; + outline = _outlinecolor; + text = _fillcolor; + } + + _gfx->fillRoundRect(_x - (_w/2), _y - (_h/2), _w, _h, min(_w,_h)/4, fill); + _gfx->drawRoundRect(_x - (_w/2), _y - (_h/2), _w, _h, min(_w,_h)/4, outline); + + _gfx->setCursor(_x - strlen(_label)*3*_textsize, _y-4*_textsize); + _gfx->setTextColor(text); + _gfx->setTextSize(_textsize); + _gfx->print(_label); +} + +boolean Adafruit_GFX_Button::contains(int16_t x, int16_t y) { + if ((x < (_x - _w/2)) || (x > (_x + _w/2))) return false; + if ((y < (_y - _h/2)) || (y > (_y + _h/2))) return false; + return true; +} + +void Adafruit_GFX_Button::press(boolean p) { + laststate = currstate; + currstate = p; +} + +boolean Adafruit_GFX_Button::isPressed() { return currstate; } +boolean Adafruit_GFX_Button::justPressed() { return (currstate && !laststate); } +boolean Adafruit_GFX_Button::justReleased() { return (!currstate && laststate); } + +// ------------------------------------------------------------------------- + +// GFXcanvas1 and GFXcanvas16 (currently a WIP, don't get too comfy with the +// implementation) provide 1- and 16-bit offscreen canvases, the address of +// which can be passed to drawBitmap() or pushColors() (the latter appears +// to only be in Adafruit_TFTLCD at this time). This is here mostly to +// help with the recently-added proportionally-spaced fonts; adds a way to +// refresh a section of the screen without a massive flickering clear-and- +// redraw...but maybe you'll find other uses too. VERY RAM-intensive, since +// the buffer is in MCU memory and not the display driver...GXFcanvas1 might +// be minimally useful on an Uno-class board, but this and GFXcanvas16 are +// much more likely to require at least a Mega or various recent ARM-type +// boards (recomment, as the text+bitmap draw can be pokey). GFXcanvas1 +// requires 1 bit per pixel (rounded up to nearest byte per scanline), +// GFXcanvas16 requires 2 bytes per pixel (no scanline pad). +// NOT EXTENSIVELY TESTED YET. MAY CONTAIN WORST BUGS KNOWN TO HUMANKIND. + +GFXcanvas1::GFXcanvas1(uint16_t w, uint16_t h) : Adafruit_GFX(w, h) { + uint16_t bytes = ((w + 7) / 8) * h; + if((buffer = (uint8_t *)malloc(bytes))) { + memset(buffer, 0, bytes); + } +} + +GFXcanvas1::~GFXcanvas1(void) { + if(buffer) free(buffer); +} + +uint8_t* GFXcanvas1::getBuffer(void) { + return buffer; +} + +void GFXcanvas1::drawPixel(int16_t x, int16_t y, uint16_t color) { + // Bitmask tables of 0x80>>X and ~(0x80>>X), because X>>Y is slow on AVR + static const uint8_t PROGMEM + GFXsetBit[] = { 0x80, 0x40, 0x20, 0x10, 0x08, 0x04, 0x02, 0x01 }, + GFXclrBit[] = { 0x7F, 0xBF, 0xDF, 0xEF, 0xF7, 0xFB, 0xFD, 0xFE }; + + if(buffer) { + if((x < 0) || (y < 0) || (x >= _width) || (y >= _height)) return; + + int16_t t; + switch(rotation) { + case 1: + t = x; + x = WIDTH - 1 - y; + y = t; + break; + case 2: + x = WIDTH - 1 - x; + y = HEIGHT - 1 - y; + break; + case 3: + t = x; + x = y; + y = HEIGHT - 1 - t; + break; + } + + uint8_t *ptr = &buffer[(x / 8) + y * ((WIDTH + 7) / 8)]; + if(color) *ptr |= pgm_read_byte(&GFXsetBit[x & 7]); + else *ptr &= pgm_read_byte(&GFXclrBit[x & 7]); + } +} + +void GFXcanvas1::fillScreen(uint16_t color) { + if(buffer) { + uint16_t bytes = ((WIDTH + 7) / 8) * HEIGHT; + memset(buffer, color ? 0xFF : 0x00, bytes); + } +} + +GFXcanvas16::GFXcanvas16(uint16_t w, uint16_t h) : Adafruit_GFX(w, h) { + uint16_t bytes = w * h * 2; + if((buffer = (uint16_t *)malloc(bytes))) { + memset(buffer, 0, bytes); + } +} + +GFXcanvas16::~GFXcanvas16(void) { + if(buffer) free(buffer); +} + +uint16_t* GFXcanvas16::getBuffer(void) { + return buffer; +} + +void GFXcanvas16::drawPixel(int16_t x, int16_t y, uint16_t color) { + if(buffer) { + if((x < 0) || (y < 0) || (x >= _width) || (y >= _height)) return; + + int16_t t; + switch(rotation) { + case 1: + t = x; + x = WIDTH - 1 - y; + y = t; + break; + case 2: + x = WIDTH - 1 - x; + y = HEIGHT - 1 - y; + break; + case 3: + t = x; + x = y; + y = HEIGHT - 1 - t; + break; + } + + buffer[x + y * WIDTH] = color; + } +} + +void GFXcanvas16::fillScreen(uint16_t color) { + if(buffer) { + uint8_t hi = color >> 8, lo = color & 0xFF; + if(hi == lo) { + memset(buffer, lo, WIDTH * HEIGHT * 2); + } else { + uint16_t i, pixels = WIDTH * HEIGHT; + for(i=0; i= 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 diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit_PCD8544.cpp b/libraries/Adafruit-GFX-Library-master/Adafruit_PCD8544.cpp new file mode 100644 index 0000000..a6d4f4d --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit_PCD8544.cpp @@ -0,0 +1,370 @@ +/********************************************************************* +This is a library for our Monochrome Nokia 5110 LCD Displays + + Pick one up today in the adafruit shop! + ------> http://www.adafruit.com/products/338 + +These displays use SPI to communicate, 4 or 5 pins are required to +interface + +Adafruit invests time and resources providing this open source code, +please support Adafruit and open-source hardware by purchasing +products from Adafruit! + +Written by Limor Fried/Ladyada for Adafruit Industries. +BSD license, check license.txt for more information +All text above, and the splash screen below must be included in any redistribution +*********************************************************************/ + +//#include +#include +#if defined(ARDUINO) && ARDUINO >= 100 + #include "Arduino.h" +#else + #include "WProgram.h" +#endif + +#ifdef __AVR__ + #include +#endif + +#ifndef _BV + #define _BV(x) (1 << (x)) +#endif + +#include + +#include +#include "Adafruit_PCD8544.h" + +#ifndef _BV + #define _BV(bit) (1<<(bit)) +#endif + + +// the memory buffer for the LCD +uint8_t pcd8544_buffer[LCDWIDTH * LCDHEIGHT / 8] = { +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xC0, 0xE0, 0xF0, 0xF8, 0xFC, 0xFC, 0xFE, 0xFF, 0xFC, 0xE0, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, +0xF8, 0xF0, 0xF0, 0xE0, 0xE0, 0xC0, 0x80, 0xC0, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x3F, 0x7F, +0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x1F, 0x3F, 0x7F, 0xFF, 0xFF, +0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE7, 0xC7, 0xC7, 0x87, 0x8F, 0x9F, 0x9F, 0xFF, 0xFF, 0xFF, +0xC1, 0xC0, 0xE0, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFC, 0xFC, 0xFC, 0xFE, 0xFE, 0xFE, +0xFC, 0xFC, 0xF8, 0xF8, 0xF0, 0xE0, 0xC0, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x80, 0xC0, 0xE0, 0xF1, 0xFB, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x1F, 0x0F, 0x0F, 0x87, +0xE7, 0xFF, 0xFF, 0xFF, 0x1F, 0x1F, 0x3F, 0xF9, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xFD, 0xFF, +0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x3F, 0x0F, 0x07, 0x01, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0xF0, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, +0x7E, 0x3F, 0x3F, 0x0F, 0x1F, 0xFF, 0xFF, 0xFF, 0xFC, 0xF0, 0xE0, 0xF1, 0xFF, 0xFF, 0xFF, 0xFF, +0xFF, 0xFC, 0xF0, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x01, +0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x0F, 0x1F, 0x3F, 0x7F, 0x7F, +0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0x7F, 0x1F, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, +}; + + +// reduces how much is refreshed, which speeds it up! +// originally derived from Steve Evans/JCW's mod but cleaned up and +// optimized +//#define enablePartialUpdate + +#ifdef enablePartialUpdate +static uint8_t xUpdateMin, xUpdateMax, yUpdateMin, yUpdateMax; +#endif + + + +static void updateBoundingBox(uint8_t xmin, uint8_t ymin, uint8_t xmax, uint8_t ymax) { +#ifdef enablePartialUpdate + if (xmin < xUpdateMin) xUpdateMin = xmin; + if (xmax > xUpdateMax) xUpdateMax = xmax; + if (ymin < yUpdateMin) yUpdateMin = ymin; + if (ymax > yUpdateMax) yUpdateMax = ymax; +#endif +} + +Adafruit_PCD8544::Adafruit_PCD8544(int8_t SCLK, int8_t DIN, int8_t DC, + int8_t CS, int8_t RST) : Adafruit_GFX(LCDWIDTH, LCDHEIGHT) { + _din = DIN; + _sclk = SCLK; + _dc = DC; + _rst = RST; + _cs = CS; +} + +Adafruit_PCD8544::Adafruit_PCD8544(int8_t SCLK, int8_t DIN, int8_t DC, + int8_t RST) : Adafruit_GFX(LCDWIDTH, LCDHEIGHT) { + _din = DIN; + _sclk = SCLK; + _dc = DC; + _rst = RST; + _cs = -1; +} + +Adafruit_PCD8544::Adafruit_PCD8544(int8_t DC, int8_t CS, int8_t RST): + Adafruit_GFX(LCDWIDTH, LCDHEIGHT) { + // -1 for din and sclk specify using hardware SPI + _din = -1; + _sclk = -1; + _dc = DC; + _rst = RST; + _cs = CS; +} + + +// the most basic function, set a single pixel +void Adafruit_PCD8544::drawPixel(int16_t x, int16_t y, uint16_t color) { + if ((x < 0) || (x >= _width) || (y < 0) || (y >= _height)) + return; + + int16_t t; + switch(rotation){ + case 1: + t = x; + x = y; + y = LCDHEIGHT - 1 - t; + break; + case 2: + x = LCDWIDTH - 1 - x; + y = LCDHEIGHT - 1 - y; + break; + case 3: + t = x; + x = LCDWIDTH - 1 - y; + y = t; + break; + } + + if ((x < 0) || (x >= LCDWIDTH) || (y < 0) || (y >= LCDHEIGHT)) + return; + + // x is which column + if (color) + pcd8544_buffer[x+ (y/8)*LCDWIDTH] |= _BV(y%8); + else + pcd8544_buffer[x+ (y/8)*LCDWIDTH] &= ~_BV(y%8); + + updateBoundingBox(x,y,x,y); +} + + +// the most basic function, get a single pixel +uint8_t Adafruit_PCD8544::getPixel(int8_t x, int8_t y) { + if ((x < 0) || (x >= LCDWIDTH) || (y < 0) || (y >= LCDHEIGHT)) + return 0; + + return (pcd8544_buffer[x+ (y/8)*LCDWIDTH] >> (y%8)) & 0x1; +} + + +void Adafruit_PCD8544::begin(uint8_t contrast, uint8_t bias) { + if (isHardwareSPI()) { + // Setup hardware SPI. + SPI.begin(); + SPI.setClockDivider(PCD8544_SPI_CLOCK_DIV); + SPI.setDataMode(SPI_MODE0); + SPI.setBitOrder(MSBFIRST); + } + else { + // Setup software SPI. + + // Set software SPI specific pin outputs. + pinMode(_din, OUTPUT); + pinMode(_sclk, OUTPUT); + + // Set software SPI ports and masks. + clkport = portOutputRegister(digitalPinToPort(_sclk)); + clkpinmask = digitalPinToBitMask(_sclk); + mosiport = portOutputRegister(digitalPinToPort(_din)); + mosipinmask = digitalPinToBitMask(_din); + } + + // Set common pin outputs. + pinMode(_dc, OUTPUT); + if (_rst > 0) + pinMode(_rst, OUTPUT); + if (_cs > 0) + pinMode(_cs, OUTPUT); + + // toggle RST low to reset + if (_rst > 0) { + digitalWrite(_rst, LOW); + delay(500); + digitalWrite(_rst, HIGH); + } + + // get into the EXTENDED mode! + command(PCD8544_FUNCTIONSET | PCD8544_EXTENDEDINSTRUCTION ); + + // LCD bias select (4 is optimal?) + command(PCD8544_SETBIAS | bias); + + // set VOP + if (contrast > 0x7f) + contrast = 0x7f; + + command( PCD8544_SETVOP | contrast); // Experimentally determined + + + // normal mode + command(PCD8544_FUNCTIONSET); + + // Set display to Normal + command(PCD8544_DISPLAYCONTROL | PCD8544_DISPLAYNORMAL); + + // initial display line + // set page address + // set column address + // write display data + + // set up a bounding box for screen updates + + updateBoundingBox(0, 0, LCDWIDTH-1, LCDHEIGHT-1); + // Push out pcd8544_buffer to the Display (will show the AFI logo) + display(); +} + + +inline void Adafruit_PCD8544::spiWrite(uint8_t d) { + if (isHardwareSPI()) { + // Hardware SPI write. + SPI.transfer(d); + } + else { + // Software SPI write with bit banging. + for(uint8_t bit = 0x80; bit; bit >>= 1) { + *clkport &= ~clkpinmask; + if(d & bit) *mosiport |= mosipinmask; + else *mosiport &= ~mosipinmask; + *clkport |= clkpinmask; + } + } +} + +bool Adafruit_PCD8544::isHardwareSPI() { + return (_din == -1 && _sclk == -1); +} + +void Adafruit_PCD8544::command(uint8_t c) { + digitalWrite(_dc, LOW); + if (_cs > 0) + digitalWrite(_cs, LOW); + spiWrite(c); + if (_cs > 0) + digitalWrite(_cs, HIGH); +} + +void Adafruit_PCD8544::data(uint8_t c) { + digitalWrite(_dc, HIGH); + if (_cs > 0) + digitalWrite(_cs, LOW); + spiWrite(c); + if (_cs > 0) + digitalWrite(_cs, HIGH); +} + +void Adafruit_PCD8544::setContrast(uint8_t val) { + if (val > 0x7f) { + val = 0x7f; + } + command(PCD8544_FUNCTIONSET | PCD8544_EXTENDEDINSTRUCTION ); + command( PCD8544_SETVOP | val); + command(PCD8544_FUNCTIONSET); + + } + + + +void Adafruit_PCD8544::display(void) { + uint8_t col, maxcol, p; + + for(p = 0; p < 6; p++) { +#ifdef enablePartialUpdate + // check if this page is part of update + if ( yUpdateMin >= ((p+1)*8) ) { + continue; // nope, skip it! + } + if (yUpdateMax < p*8) { + break; + } +#endif + + command(PCD8544_SETYADDR | p); + + +#ifdef enablePartialUpdate + col = xUpdateMin; + maxcol = xUpdateMax; +#else + // start at the beginning of the row + col = 0; + maxcol = LCDWIDTH-1; +#endif + + command(PCD8544_SETXADDR | col); + + digitalWrite(_dc, HIGH); + if (_cs > 0) + digitalWrite(_cs, LOW); + for(; col <= maxcol; col++) { + spiWrite(pcd8544_buffer[(LCDWIDTH*p)+col]); + } + if (_cs > 0) + digitalWrite(_cs, HIGH); + + } + + command(PCD8544_SETYADDR ); // no idea why this is necessary but it is to finish the last byte? +#ifdef enablePartialUpdate + xUpdateMin = LCDWIDTH - 1; + xUpdateMax = 0; + yUpdateMin = LCDHEIGHT-1; + yUpdateMax = 0; +#endif + +} + +// clear everything +void Adafruit_PCD8544::clearDisplay(void) { + memset(pcd8544_buffer, 0, LCDWIDTH*LCDHEIGHT/8); + updateBoundingBox(0, 0, LCDWIDTH-1, LCDHEIGHT-1); + cursor_y = cursor_x = 0; +} + +/* +// this doesnt touch the buffer, just clears the display RAM - might be handy +void Adafruit_PCD8544::clearDisplay(void) { + + uint8_t p, c; + + for(p = 0; p < 8; p++) { + + st7565_command(CMD_SET_PAGE | p); + for(c = 0; c < 129; c++) { + //uart_putw_dec(c); + //uart_putchar(' '); + st7565_command(CMD_SET_COLUMN_LOWER | (c & 0xf)); + st7565_command(CMD_SET_COLUMN_UPPER | ((c >> 4) & 0xf)); + st7565_data(0x0); + } + } + +} + +*/ diff --git a/libraries/Adafruit-GFX-Library-master/Adafruit_PCD8544.h b/libraries/Adafruit-GFX-Library-master/Adafruit_PCD8544.h new file mode 100644 index 0000000..80aa285 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Adafruit_PCD8544.h @@ -0,0 +1,100 @@ +/********************************************************************* +This is a library for our Monochrome Nokia 5110 LCD Displays + + Pick one up today in the adafruit shop! + ------> http://www.adafruit.com/products/338 + +These displays use SPI to communicate, 4 or 5 pins are required to +interface + +Adafruit invests time and resources providing this open source code, +please support Adafruit and open-source hardware by purchasing +products from Adafruit! + +Written by Limor Fried/Ladyada for Adafruit Industries. +BSD license, check license.txt for more information +All text above, and the splash screen must be included in any redistribution +*********************************************************************/ +#ifndef _ADAFRUIT_PCD8544_H +#define _ADAFRUIT_PCD8544_H + +#if defined(ARDUINO) && ARDUINO >= 100 + #include "Arduino.h" +#else + #include "WProgram.h" + #include "pins_arduino.h" +#endif + +#include + +#if defined(__SAM3X8E__) || defined(ARDUINO_ARCH_SAMD) + typedef volatile RwReg PortReg; + typedef uint32_t PortMask; +#else + typedef volatile uint8_t PortReg; + typedef uint8_t PortMask; +#endif + + +#define BLACK 1 +#define WHITE 0 + +#define LCDWIDTH 84 +#define LCDHEIGHT 48 + +#define PCD8544_POWERDOWN 0x04 +#define PCD8544_ENTRYMODE 0x02 +#define PCD8544_EXTENDEDINSTRUCTION 0x01 + +#define PCD8544_DISPLAYBLANK 0x0 +#define PCD8544_DISPLAYNORMAL 0x4 +#define PCD8544_DISPLAYALLON 0x1 +#define PCD8544_DISPLAYINVERTED 0x5 + +// H = 0 +#define PCD8544_FUNCTIONSET 0x20 +#define PCD8544_DISPLAYCONTROL 0x08 +#define PCD8544_SETYADDR 0x40 +#define PCD8544_SETXADDR 0x80 + +// H = 1 +#define PCD8544_SETTEMP 0x04 +#define PCD8544_SETBIAS 0x10 +#define PCD8544_SETVOP 0x80 + +// Default to max SPI clock speed for PCD8544 of 4 mhz (16mhz / 4) for normal Arduinos. +// This can be modified to change the clock speed if necessary (like for supporting other hardware). +#define PCD8544_SPI_CLOCK_DIV SPI_CLOCK_DIV4 + +class Adafruit_PCD8544 : public Adafruit_GFX { + public: + // Software SPI with explicit CS pin. + Adafruit_PCD8544(int8_t SCLK, int8_t DIN, int8_t DC, int8_t CS, int8_t RST); + // Software SPI with CS tied to ground. Saves a pin but other pins can't be shared with other hardware. + Adafruit_PCD8544(int8_t SCLK, int8_t DIN, int8_t DC, int8_t RST); + // Hardware SPI based on hardware controlled SCK (SCLK) and MOSI (DIN) pins. CS is still controlled by any IO pin. + // NOTE: MISO and SS will be set as an input and output respectively, so be careful sharing those pins! + Adafruit_PCD8544(int8_t DC, int8_t CS, int8_t RST); + + void begin(uint8_t contrast = 40, uint8_t bias = 0x04); + + void command(uint8_t c); + void data(uint8_t c); + + void setContrast(uint8_t val); + void clearDisplay(void); + void display(); + + void drawPixel(int16_t x, int16_t y, uint16_t color); + uint8_t getPixel(int8_t x, int8_t y); + + private: + int8_t _din, _sclk, _dc, _rst, _cs; + volatile PortReg *mosiport, *clkport; + PortMask mosipinmask, clkpinmask; + + void spiWrite(uint8_t c); + bool isHardwareSPI(); +}; + +#endif diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMono12pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMono12pt7b.h new file mode 100644 index 0000000..94ecb88 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMono12pt7b.h @@ -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 diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMono18pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMono18pt7b.h new file mode 100644 index 0000000..c605d29 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMono18pt7b.h @@ -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 diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMono24pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMono24pt7b.h new file mode 100644 index 0000000..4c8bd15 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMono24pt7b.h @@ -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 diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMono9pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMono9pt7b.h new file mode 100644 index 0000000..c82d786 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMono9pt7b.h @@ -0,0 +1,176 @@ +const uint8_t FreeMono9pt7bBitmaps[] PROGMEM = { + 0xAA, 0xA8, 0x0C, 0xED, 0x24, 0x92, 0x48, 0x24, 0x48, 0x91, 0x2F, 0xE4, + 0x89, 0x7F, 0x28, 0x51, 0x22, 0x40, 0x08, 0x3E, 0x62, 0x40, 0x30, 0x0E, + 0x01, 0x81, 0xC3, 0xBE, 0x08, 0x08, 0x71, 0x12, 0x23, 0x80, 0x23, 0xB8, + 0x0E, 0x22, 0x44, 0x70, 0x38, 0x81, 0x02, 0x06, 0x1A, 0x65, 0x46, 0xC8, + 0xEC, 0xE9, 0x24, 0x5A, 0xAA, 0xA9, 0x40, 0xA9, 0x55, 0x5A, 0x80, 0x10, + 0x22, 0x4B, 0xE3, 0x05, 0x11, 0x00, 0x10, 0x20, 0x47, 0xF1, 0x02, 0x04, + 0x00, 0x6B, 0x48, 0xFF, 0x00, 0xF0, 0x02, 0x08, 0x10, 0x60, 0x81, 0x04, + 0x08, 0x20, 0x41, 0x02, 0x08, 0x00, 0x38, 0x8A, 0x0C, 0x18, 0x30, 0x60, + 0xC1, 0x82, 0x88, 0xE0, 0x27, 0x28, 0x42, 0x10, 0x84, 0x21, 0x3E, 0x38, + 0x8A, 0x08, 0x10, 0x20, 0x82, 0x08, 0x61, 0x03, 0xF8, 0x7C, 0x06, 0x02, + 0x02, 0x1C, 0x06, 0x01, 0x01, 0x01, 0x42, 0x3C, 0x18, 0xA2, 0x92, 0x8A, + 0x28, 0xBF, 0x08, 0x21, 0xC0, 0x7C, 0x81, 0x03, 0xE4, 0x40, 0x40, 0x81, + 0x03, 0x88, 0xE0, 0x1E, 0x41, 0x04, 0x0B, 0x98, 0xB0, 0xC1, 0xC2, 0x88, + 0xE0, 0xFE, 0x04, 0x08, 0x20, 0x40, 0x82, 0x04, 0x08, 0x20, 0x40, 0x38, + 0x8A, 0x0C, 0x14, 0x47, 0x11, 0x41, 0x83, 0x8C, 0xE0, 0x38, 0x8A, 0x1C, + 0x18, 0x68, 0xCE, 0x81, 0x04, 0x13, 0xC0, 0xF0, 0x0F, 0x6C, 0x00, 0xD2, + 0xD2, 0x00, 0x03, 0x04, 0x18, 0x60, 0x60, 0x18, 0x04, 0x03, 0xFF, 0x80, + 0x00, 0x1F, 0xF0, 0x40, 0x18, 0x03, 0x00, 0x60, 0x20, 0x60, 0xC0, 0x80, + 0x3D, 0x84, 0x08, 0x30, 0xC2, 0x00, 0x00, 0x00, 0x30, 0x3C, 0x46, 0x82, + 0x8E, 0xB2, 0xA2, 0xA2, 0x9F, 0x80, 0x80, 0x40, 0x3C, 0x3C, 0x01, 0x40, + 0x28, 0x09, 0x01, 0x10, 0x42, 0x0F, 0xC1, 0x04, 0x40, 0x9E, 0x3C, 0xFE, + 0x21, 0x90, 0x48, 0x67, 0xE2, 0x09, 0x02, 0x81, 0x41, 0xFF, 0x80, 0x3E, + 0xB0, 0xF0, 0x30, 0x08, 0x04, 0x02, 0x00, 0x80, 0x60, 0x8F, 0x80, 0xFE, + 0x21, 0x90, 0x68, 0x14, 0x0A, 0x05, 0x02, 0x83, 0x43, 0x7F, 0x00, 0xFF, + 0x20, 0x90, 0x08, 0x87, 0xC2, 0x21, 0x00, 0x81, 0x40, 0xFF, 0xC0, 0xFF, + 0xA0, 0x50, 0x08, 0x87, 0xC2, 0x21, 0x00, 0x80, 0x40, 0x78, 0x00, 0x1E, + 0x98, 0x6C, 0x0A, 0x00, 0x80, 0x20, 0xF8, 0x0B, 0x02, 0x60, 0x87, 0xC0, + 0xE3, 0xA0, 0x90, 0x48, 0x27, 0xF2, 0x09, 0x04, 0x82, 0x41, 0x71, 0xC0, + 0xF9, 0x08, 0x42, 0x10, 0x84, 0x27, 0xC0, 0x1F, 0x02, 0x02, 0x02, 0x02, + 0x02, 0x82, 0x82, 0xC6, 0x78, 0xE3, 0xA1, 0x11, 0x09, 0x05, 0x83, 0x21, + 0x08, 0x84, 0x41, 0x70, 0xC0, 0xE0, 0x40, 0x40, 0x40, 0x40, 0x40, 0x41, + 0x41, 0x41, 0xFF, 0xE0, 0xEC, 0x19, 0x45, 0x28, 0xA4, 0xA4, 0x94, 0x91, + 0x12, 0x02, 0x40, 0x5C, 0x1C, 0xC3, 0xB0, 0x94, 0x4A, 0x24, 0x92, 0x49, + 0x14, 0x8A, 0x43, 0x70, 0x80, 0x1E, 0x31, 0x90, 0x50, 0x18, 0x0C, 0x06, + 0x02, 0x82, 0x63, 0x0F, 0x00, 0xFE, 0x43, 0x41, 0x41, 0x42, 0x7C, 0x40, + 0x40, 0x40, 0xF0, 0x1C, 0x31, 0x90, 0x50, 0x18, 0x0C, 0x06, 0x02, 0x82, + 0x63, 0x1F, 0x04, 0x07, 0x92, 0x30, 0xFE, 0x21, 0x90, 0x48, 0x24, 0x23, + 0xE1, 0x10, 0x84, 0x41, 0x70, 0xC0, 0x3A, 0xCD, 0x0A, 0x03, 0x01, 0x80, + 0xC1, 0xC7, 0x78, 0xFF, 0xC4, 0x62, 0x21, 0x00, 0x80, 0x40, 0x20, 0x10, + 0x08, 0x1F, 0x00, 0xE3, 0xA0, 0x90, 0x48, 0x24, 0x12, 0x09, 0x04, 0x82, + 0x22, 0x0E, 0x00, 0xF1, 0xE8, 0x10, 0x82, 0x10, 0x42, 0x10, 0x22, 0x04, + 0x80, 0x50, 0x0C, 0x00, 0x80, 0xF1, 0xE8, 0x09, 0x11, 0x25, 0x44, 0xA8, + 0x55, 0x0C, 0xA1, 0x8C, 0x31, 0x84, 0x30, 0xE3, 0xA0, 0x88, 0x82, 0x80, + 0x80, 0xC0, 0x90, 0x44, 0x41, 0x71, 0xC0, 0xE3, 0xA0, 0x88, 0x82, 0x81, + 0x40, 0x40, 0x20, 0x10, 0x08, 0x1F, 0x00, 0xFD, 0x0A, 0x20, 0x81, 0x04, + 0x10, 0x21, 0x83, 0xFC, 0xEA, 0xAA, 0xAA, 0xC0, 0x80, 0x81, 0x03, 0x02, + 0x04, 0x04, 0x08, 0x08, 0x10, 0x10, 0x20, 0x20, 0xD5, 0x55, 0x55, 0xC0, + 0x10, 0x51, 0x22, 0x28, 0x20, 0xFF, 0xE0, 0x88, 0x80, 0x7E, 0x00, 0x80, + 0x47, 0xEC, 0x14, 0x0A, 0x0C, 0xFB, 0xC0, 0x20, 0x10, 0x0B, 0xC6, 0x12, + 0x05, 0x02, 0x81, 0x40, 0xB0, 0xB7, 0x80, 0x3A, 0x8E, 0x0C, 0x08, 0x10, + 0x10, 0x9E, 0x03, 0x00, 0x80, 0x47, 0xA4, 0x34, 0x0A, 0x05, 0x02, 0x81, + 0x21, 0x8F, 0x60, 0x3C, 0x43, 0x81, 0xFF, 0x80, 0x80, 0x61, 0x3E, 0x3D, + 0x04, 0x3E, 0x41, 0x04, 0x10, 0x41, 0x0F, 0x80, 0x3D, 0xA1, 0xA0, 0x50, + 0x28, 0x14, 0x09, 0x0C, 0x7A, 0x01, 0x01, 0x87, 0x80, 0xC0, 0x20, 0x10, + 0x0B, 0xC6, 0x32, 0x09, 0x04, 0x82, 0x41, 0x20, 0xB8, 0xE0, 0x10, 0x01, + 0xC0, 0x81, 0x02, 0x04, 0x08, 0x11, 0xFC, 0x10, 0x3E, 0x10, 0x84, 0x21, + 0x08, 0x42, 0x3F, 0x00, 0xC0, 0x40, 0x40, 0x4F, 0x44, 0x58, 0x70, 0x48, + 0x44, 0x42, 0xC7, 0x70, 0x20, 0x40, 0x81, 0x02, 0x04, 0x08, 0x10, 0x23, + 0xF8, 0xB7, 0x64, 0x62, 0x31, 0x18, 0x8C, 0x46, 0x23, 0x91, 0x5E, 0x31, + 0x90, 0x48, 0x24, 0x12, 0x09, 0x05, 0xC7, 0x3E, 0x31, 0xA0, 0x30, 0x18, + 0x0C, 0x05, 0x8C, 0x7C, 0xDE, 0x30, 0x90, 0x28, 0x14, 0x0A, 0x05, 0x84, + 0xBC, 0x40, 0x20, 0x38, 0x00, 0x3D, 0xA1, 0xA0, 0x50, 0x28, 0x14, 0x09, + 0x0C, 0x7A, 0x01, 0x00, 0x80, 0xE0, 0xCE, 0xA1, 0x82, 0x04, 0x08, 0x10, + 0x7C, 0x3A, 0x8D, 0x0B, 0x80, 0xF0, 0x70, 0xDE, 0x40, 0x40, 0xFC, 0x40, + 0x40, 0x40, 0x40, 0x40, 0x41, 0x3E, 0xC3, 0x41, 0x41, 0x41, 0x41, 0x41, + 0x43, 0x3D, 0xE3, 0xA0, 0x90, 0x84, 0x42, 0x20, 0xA0, 0x50, 0x10, 0xE3, + 0xC0, 0x92, 0x4B, 0x25, 0x92, 0xA9, 0x98, 0x44, 0xE3, 0x31, 0x05, 0x01, + 0x01, 0x41, 0x11, 0x05, 0xC7, 0xE3, 0xA0, 0x90, 0x84, 0x42, 0x40, 0xA0, + 0x60, 0x10, 0x10, 0x08, 0x3E, 0x00, 0xFD, 0x08, 0x20, 0x82, 0x08, 0x10, + 0xBF, 0x29, 0x24, 0xA2, 0x49, 0x26, 0xFF, 0xF8, 0x89, 0x24, 0x8A, 0x49, + 0x2C, 0x61, 0x24, 0x30 }; + +const GFXglyph FreeMono9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 11, 0, 1 }, // 0x20 ' ' + { 0, 2, 11, 11, 4, -10 }, // 0x21 '!' + { 3, 6, 5, 11, 2, -10 }, // 0x22 '"' + { 7, 7, 12, 11, 2, -10 }, // 0x23 '#' + { 18, 8, 12, 11, 1, -10 }, // 0x24 '$' + { 30, 7, 11, 11, 2, -10 }, // 0x25 '%' + { 40, 7, 10, 11, 2, -9 }, // 0x26 '&' + { 49, 3, 5, 11, 4, -10 }, // 0x27 ''' + { 51, 2, 13, 11, 5, -10 }, // 0x28 '(' + { 55, 2, 13, 11, 4, -10 }, // 0x29 ')' + { 59, 7, 7, 11, 2, -10 }, // 0x2A '*' + { 66, 7, 7, 11, 2, -8 }, // 0x2B '+' + { 73, 3, 5, 11, 2, -1 }, // 0x2C ',' + { 75, 9, 1, 11, 1, -5 }, // 0x2D '-' + { 77, 2, 2, 11, 4, -1 }, // 0x2E '.' + { 78, 7, 13, 11, 2, -11 }, // 0x2F '/' + { 90, 7, 11, 11, 2, -10 }, // 0x30 '0' + { 100, 5, 11, 11, 3, -10 }, // 0x31 '1' + { 107, 7, 11, 11, 2, -10 }, // 0x32 '2' + { 117, 8, 11, 11, 1, -10 }, // 0x33 '3' + { 128, 6, 11, 11, 3, -10 }, // 0x34 '4' + { 137, 7, 11, 11, 2, -10 }, // 0x35 '5' + { 147, 7, 11, 11, 2, -10 }, // 0x36 '6' + { 157, 7, 11, 11, 2, -10 }, // 0x37 '7' + { 167, 7, 11, 11, 2, -10 }, // 0x38 '8' + { 177, 7, 11, 11, 2, -10 }, // 0x39 '9' + { 187, 2, 8, 11, 4, -7 }, // 0x3A ':' + { 189, 3, 11, 11, 3, -7 }, // 0x3B ';' + { 194, 8, 8, 11, 1, -8 }, // 0x3C '<' + { 202, 9, 4, 11, 1, -6 }, // 0x3D '=' + { 207, 9, 8, 11, 1, -8 }, // 0x3E '>' + { 216, 7, 10, 11, 2, -9 }, // 0x3F '?' + { 225, 8, 12, 11, 2, -10 }, // 0x40 '@' + { 237, 11, 10, 11, 0, -9 }, // 0x41 'A' + { 251, 9, 10, 11, 1, -9 }, // 0x42 'B' + { 263, 9, 10, 11, 1, -9 }, // 0x43 'C' + { 275, 9, 10, 11, 1, -9 }, // 0x44 'D' + { 287, 9, 10, 11, 1, -9 }, // 0x45 'E' + { 299, 9, 10, 11, 1, -9 }, // 0x46 'F' + { 311, 10, 10, 11, 1, -9 }, // 0x47 'G' + { 324, 9, 10, 11, 1, -9 }, // 0x48 'H' + { 336, 5, 10, 11, 3, -9 }, // 0x49 'I' + { 343, 8, 10, 11, 2, -9 }, // 0x4A 'J' + { 353, 9, 10, 11, 1, -9 }, // 0x4B 'K' + { 365, 8, 10, 11, 2, -9 }, // 0x4C 'L' + { 375, 11, 10, 11, 0, -9 }, // 0x4D 'M' + { 389, 9, 10, 11, 1, -9 }, // 0x4E 'N' + { 401, 9, 10, 11, 1, -9 }, // 0x4F 'O' + { 413, 8, 10, 11, 1, -9 }, // 0x50 'P' + { 423, 9, 13, 11, 1, -9 }, // 0x51 'Q' + { 438, 9, 10, 11, 1, -9 }, // 0x52 'R' + { 450, 7, 10, 11, 2, -9 }, // 0x53 'S' + { 459, 9, 10, 11, 1, -9 }, // 0x54 'T' + { 471, 9, 10, 11, 1, -9 }, // 0x55 'U' + { 483, 11, 10, 11, 0, -9 }, // 0x56 'V' + { 497, 11, 10, 11, 0, -9 }, // 0x57 'W' + { 511, 9, 10, 11, 1, -9 }, // 0x58 'X' + { 523, 9, 10, 11, 1, -9 }, // 0x59 'Y' + { 535, 7, 10, 11, 2, -9 }, // 0x5A 'Z' + { 544, 2, 13, 11, 5, -10 }, // 0x5B '[' + { 548, 7, 13, 11, 2, -11 }, // 0x5C '\' + { 560, 2, 13, 11, 4, -10 }, // 0x5D ']' + { 564, 7, 5, 11, 2, -10 }, // 0x5E '^' + { 569, 11, 1, 11, 0, 2 }, // 0x5F '_' + { 571, 3, 3, 11, 3, -11 }, // 0x60 '`' + { 573, 9, 8, 11, 1, -7 }, // 0x61 'a' + { 582, 9, 11, 11, 1, -10 }, // 0x62 'b' + { 595, 7, 8, 11, 2, -7 }, // 0x63 'c' + { 602, 9, 11, 11, 1, -10 }, // 0x64 'd' + { 615, 8, 8, 11, 1, -7 }, // 0x65 'e' + { 623, 6, 11, 11, 3, -10 }, // 0x66 'f' + { 632, 9, 11, 11, 1, -7 }, // 0x67 'g' + { 645, 9, 11, 11, 1, -10 }, // 0x68 'h' + { 658, 7, 10, 11, 2, -9 }, // 0x69 'i' + { 667, 5, 13, 11, 3, -9 }, // 0x6A 'j' + { 676, 8, 11, 11, 2, -10 }, // 0x6B 'k' + { 687, 7, 11, 11, 2, -10 }, // 0x6C 'l' + { 697, 9, 8, 11, 1, -7 }, // 0x6D 'm' + { 706, 9, 8, 11, 1, -7 }, // 0x6E 'n' + { 715, 9, 8, 11, 1, -7 }, // 0x6F 'o' + { 724, 9, 11, 11, 1, -7 }, // 0x70 'p' + { 737, 9, 11, 11, 1, -7 }, // 0x71 'q' + { 750, 7, 8, 11, 3, -7 }, // 0x72 'r' + { 757, 7, 8, 11, 2, -7 }, // 0x73 's' + { 764, 8, 10, 11, 2, -9 }, // 0x74 't' + { 774, 8, 8, 11, 1, -7 }, // 0x75 'u' + { 782, 9, 8, 11, 1, -7 }, // 0x76 'v' + { 791, 9, 8, 11, 1, -7 }, // 0x77 'w' + { 800, 9, 8, 11, 1, -7 }, // 0x78 'x' + { 809, 9, 11, 11, 1, -7 }, // 0x79 'y' + { 822, 7, 8, 11, 2, -7 }, // 0x7A 'z' + { 829, 3, 13, 11, 4, -10 }, // 0x7B '{' + { 834, 1, 13, 11, 5, -10 }, // 0x7C '|' + { 836, 3, 13, 11, 4, -10 }, // 0x7D '}' + { 841, 7, 3, 11, 2, -6 } }; // 0x7E '~' + +const GFXfont FreeMono9pt7b PROGMEM = { + (uint8_t *)FreeMono9pt7bBitmaps, + (GFXglyph *)FreeMono9pt7bGlyphs, + 0x20, 0x7E, 18 }; + +// Approx. 1516 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBold12pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBold12pt7b.h new file mode 100644 index 0000000..4ad9d1a --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBold12pt7b.h @@ -0,0 +1,250 @@ +const uint8_t FreeMonoBold12pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xF6, 0x66, 0x60, 0x6F, 0x60, 0xE7, 0xE7, 0x62, 0x42, + 0x42, 0x42, 0x42, 0x11, 0x87, 0x30, 0xC6, 0x18, 0xC3, 0x31, 0xFF, 0xFF, + 0xF9, 0x98, 0x33, 0x06, 0x60, 0xCC, 0x7F, 0xEF, 0xFC, 0x66, 0x0C, 0xC3, + 0x98, 0x63, 0x04, 0x40, 0x0C, 0x03, 0x00, 0xC0, 0xFE, 0x7F, 0x9C, 0x66, + 0x09, 0x80, 0x78, 0x0F, 0xE0, 0x7F, 0x03, 0xE0, 0xF8, 0x7F, 0xFB, 0xFC, + 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x38, 0x1F, 0x0C, 0x42, 0x10, 0xC4, 0x1F, + 0x03, 0x9C, 0x3C, 0x7F, 0x33, 0xE0, 0x8C, 0x21, 0x08, 0xC3, 0xE0, 0x70, + 0x3E, 0x1F, 0xC6, 0x61, 0x80, 0x70, 0x0C, 0x07, 0x83, 0xEE, 0xDF, 0xB3, + 0xCC, 0x73, 0xFE, 0x7F, 0x80, 0xFD, 0x24, 0x90, 0x39, 0xDC, 0xE6, 0x73, + 0x18, 0xC6, 0x31, 0x8C, 0x31, 0x8E, 0x31, 0xC4, 0xE7, 0x1C, 0xE3, 0x1C, + 0x63, 0x18, 0xC6, 0x31, 0x98, 0xCE, 0x67, 0x10, 0x0C, 0x03, 0x00, 0xC3, + 0xB7, 0xFF, 0xDF, 0xE1, 0xE0, 0xFC, 0x33, 0x0C, 0xC0, 0x06, 0x00, 0x60, + 0x06, 0x00, 0x60, 0x06, 0x0F, 0xFF, 0xFF, 0xF0, 0x60, 0x06, 0x00, 0x60, + 0x06, 0x00, 0x60, 0x06, 0x00, 0x3B, 0x9C, 0xCE, 0x62, 0x00, 0xFF, 0xFF, + 0xFF, 0xFF, 0x80, 0x00, 0x40, 0x30, 0x1C, 0x07, 0x03, 0x80, 0xE0, 0x30, + 0x1C, 0x06, 0x03, 0x80, 0xC0, 0x70, 0x18, 0x0E, 0x03, 0x01, 0xC0, 0x60, + 0x38, 0x0E, 0x01, 0x00, 0x1E, 0x0F, 0xC6, 0x1B, 0x87, 0xC0, 0xF0, 0x3C, + 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x87, 0x61, 0x8F, 0xC1, 0xE0, 0x1C, + 0x0F, 0x0F, 0xC3, 0xB0, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x0C, 0x03, 0x00, + 0xC0, 0x30, 0x0C, 0x3F, 0xFF, 0xFC, 0x1F, 0x1F, 0xEE, 0x1F, 0x83, 0xC0, + 0xC0, 0x70, 0x38, 0x1E, 0x0F, 0x07, 0x83, 0xC1, 0xE3, 0xF0, 0xFF, 0xFF, + 0xFC, 0x3F, 0x0F, 0xF1, 0x87, 0x00, 0x60, 0x0C, 0x03, 0x83, 0xE0, 0x7C, + 0x01, 0xC0, 0x0C, 0x01, 0x80, 0x3C, 0x0F, 0xFF, 0x9F, 0xC0, 0x07, 0x07, + 0x83, 0xC3, 0xE1, 0xB1, 0xD8, 0xCC, 0xC6, 0xE3, 0x7F, 0xFF, 0xE0, 0x61, + 0xF8, 0xFC, 0x7F, 0x9F, 0xE6, 0x01, 0x80, 0x60, 0x1F, 0x87, 0xF9, 0x86, + 0x00, 0xC0, 0x30, 0x0C, 0x03, 0xC1, 0xBF, 0xE7, 0xE0, 0x07, 0xC7, 0xF3, + 0xC1, 0xC0, 0x60, 0x38, 0x0E, 0xF3, 0xFE, 0xF1, 0xF8, 0x3E, 0x0F, 0x83, + 0x71, 0xCF, 0xE1, 0xF0, 0xFF, 0xFF, 0xFC, 0x1F, 0x07, 0x01, 0x80, 0x60, + 0x38, 0x0C, 0x03, 0x01, 0xC0, 0x60, 0x18, 0x0E, 0x03, 0x00, 0xC0, 0x1E, + 0x1F, 0xEE, 0x1F, 0x03, 0xC0, 0xF0, 0x36, 0x19, 0xFE, 0x7F, 0xB8, 0x7C, + 0x0F, 0x03, 0xE1, 0xDF, 0xE3, 0xF0, 0x3E, 0x1F, 0xCE, 0x3B, 0x07, 0xC1, + 0xF0, 0x7E, 0x3D, 0xFF, 0x3D, 0xC0, 0x70, 0x18, 0x0E, 0x0F, 0x3F, 0x8F, + 0x80, 0xFF, 0x80, 0x00, 0xFF, 0x80, 0x77, 0x70, 0x00, 0x00, 0x76, 0x6C, + 0xC8, 0x80, 0x00, 0x30, 0x0F, 0x03, 0xE0, 0xF8, 0x3E, 0x0F, 0x80, 0x3E, + 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x00, 0x20, 0xFF, 0xFF, 0xFF, 0x00, 0x00, + 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xF0, 0x60, 0x0F, 0x80, 0x3E, 0x00, 0xF8, + 0x03, 0xE0, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x0F, 0x00, 0x40, 0x00, 0x7C, + 0x7F, 0xB0, 0xF8, 0x30, 0x18, 0x1C, 0x3C, 0x3C, 0x18, 0x08, 0x00, 0x07, + 0x03, 0x81, 0xC0, 0x1E, 0x07, 0xF1, 0xC7, 0x30, 0x6C, 0x0D, 0x87, 0xB3, + 0xF6, 0xE6, 0xD8, 0xDB, 0x1B, 0x73, 0x67, 0xFC, 0x7F, 0x80, 0x30, 0x03, + 0x00, 0x71, 0xC7, 0xF8, 0x7C, 0x00, 0x3F, 0x80, 0x7F, 0x80, 0x1F, 0x00, + 0x76, 0x00, 0xEE, 0x01, 0x8C, 0x07, 0x18, 0x0E, 0x38, 0x1F, 0xF0, 0x7F, + 0xF0, 0xC0, 0x61, 0x80, 0xCF, 0xC7, 0xFF, 0x8F, 0xC0, 0xFF, 0xC7, 0xFF, + 0x0C, 0x1C, 0x60, 0x63, 0x03, 0x18, 0x38, 0xFF, 0x87, 0xFE, 0x30, 0x39, + 0x80, 0xCC, 0x06, 0x60, 0x7F, 0xFF, 0x7F, 0xF0, 0x0F, 0xF3, 0xFF, 0x70, + 0x76, 0x03, 0xC0, 0x3C, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0x60, + 0x37, 0x07, 0x3F, 0xF0, 0xFC, 0xFF, 0x0F, 0xFC, 0x60, 0xE6, 0x06, 0x60, + 0x36, 0x03, 0x60, 0x36, 0x03, 0x60, 0x36, 0x03, 0x60, 0x76, 0x0E, 0xFF, + 0xCF, 0xF8, 0xFF, 0xF7, 0xFF, 0x8C, 0x0C, 0x60, 0x63, 0x1B, 0x18, 0xC0, + 0xFE, 0x07, 0xF0, 0x31, 0x81, 0x8C, 0xCC, 0x06, 0x60, 0x3F, 0xFF, 0xFF, + 0xFC, 0xFF, 0xFF, 0xFF, 0xCC, 0x06, 0x60, 0x33, 0x19, 0x98, 0xC0, 0xFE, + 0x07, 0xF0, 0x31, 0x81, 0x8C, 0x0C, 0x00, 0x60, 0x0F, 0xF0, 0x7F, 0x80, + 0x0F, 0xF1, 0xFF, 0x9C, 0x1C, 0xC0, 0x6C, 0x03, 0x60, 0x03, 0x00, 0x18, + 0x7F, 0xC3, 0xFE, 0x01, 0xB8, 0x0C, 0xE0, 0xE3, 0xFF, 0x07, 0xE0, 0x7C, + 0xF9, 0xF3, 0xE3, 0x03, 0x0C, 0x0C, 0x30, 0x30, 0xC0, 0xC3, 0xFF, 0x0F, + 0xFC, 0x30, 0x30, 0xC0, 0xC3, 0x03, 0x0C, 0x0C, 0xFC, 0xFF, 0xF3, 0xF0, + 0xFF, 0xFF, 0xF0, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x0C, 0x03, + 0x00, 0xC0, 0x30, 0xFF, 0xFF, 0xF0, 0x0F, 0xF8, 0x7F, 0xC0, 0x30, 0x01, + 0x80, 0x0C, 0x00, 0x60, 0x03, 0x18, 0x18, 0xC0, 0xC6, 0x06, 0x30, 0x31, + 0xC3, 0x0F, 0xF8, 0x1F, 0x00, 0xFC, 0xFB, 0xF3, 0xE3, 0x0E, 0x0C, 0x70, + 0x33, 0x80, 0xFC, 0x03, 0xF0, 0x0F, 0xE0, 0x39, 0xC0, 0xC3, 0x03, 0x0E, + 0x0C, 0x18, 0xFC, 0x7F, 0xF0, 0xF0, 0xFF, 0x0F, 0xF0, 0x18, 0x01, 0x80, + 0x18, 0x01, 0x80, 0x18, 0x01, 0x80, 0x18, 0x31, 0x83, 0x18, 0x31, 0x83, + 0xFF, 0xFF, 0xFF, 0xF0, 0x3F, 0xC0, 0xF7, 0x87, 0x9E, 0x1E, 0x7C, 0xF9, + 0xB3, 0xE6, 0xFD, 0x99, 0xF6, 0x67, 0x99, 0x8E, 0x66, 0x31, 0x98, 0x06, + 0xFC, 0xFF, 0xF3, 0xF0, 0xF1, 0xFF, 0xCF, 0xCF, 0x0C, 0x78, 0x63, 0xE3, + 0x1B, 0x18, 0xDC, 0xC6, 0x76, 0x31, 0xB1, 0x8F, 0x8C, 0x3C, 0x61, 0xE7, + 0xE7, 0x3F, 0x18, 0x0F, 0x03, 0xFC, 0x70, 0xE6, 0x06, 0xE0, 0x7C, 0x03, + 0xC0, 0x3C, 0x03, 0xC0, 0x3E, 0x07, 0x60, 0x67, 0x0E, 0x3F, 0xC0, 0xF0, + 0xFF, 0x8F, 0xFE, 0x30, 0x73, 0x03, 0x30, 0x33, 0x03, 0x30, 0x73, 0xFE, + 0x3F, 0x83, 0x00, 0x30, 0x03, 0x00, 0xFF, 0x0F, 0xF0, 0x0F, 0x03, 0xFC, + 0x70, 0xE6, 0x06, 0xE0, 0x7C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3E, 0x07, + 0x60, 0x67, 0x0E, 0x3F, 0xC1, 0xF0, 0x18, 0x33, 0xFF, 0x3F, 0xE0, 0xFF, + 0x83, 0xFF, 0x83, 0x07, 0x0C, 0x0C, 0x30, 0x30, 0xC1, 0xC3, 0xFE, 0x0F, + 0xF0, 0x31, 0xE0, 0xC3, 0x83, 0x07, 0x0C, 0x0C, 0xFE, 0x3F, 0xF8, 0x70, + 0x3F, 0xDF, 0xFE, 0x1F, 0x03, 0xC0, 0xF8, 0x07, 0xE0, 0x7E, 0x01, 0xF0, + 0x3C, 0x0F, 0x87, 0xFF, 0xBF, 0xC0, 0xFF, 0xFF, 0xFF, 0xC6, 0x3C, 0x63, + 0xC6, 0x3C, 0x63, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x3F, 0xC3, 0xFC, 0xFF, 0xFF, 0xFF, 0x60, 0x66, 0x06, 0x60, 0x66, 0x06, + 0x60, 0x66, 0x06, 0x60, 0x66, 0x06, 0x60, 0x63, 0x9C, 0x1F, 0xC0, 0xF0, + 0xFC, 0x3F, 0xFC, 0x3F, 0x30, 0x0C, 0x38, 0x1C, 0x18, 0x18, 0x1C, 0x38, + 0x1C, 0x38, 0x0E, 0x70, 0x0E, 0x70, 0x0F, 0x60, 0x07, 0xE0, 0x07, 0xE0, + 0x03, 0xC0, 0x03, 0xC0, 0xFC, 0xFF, 0xF3, 0xF6, 0x01, 0xDC, 0xC6, 0x77, + 0x99, 0xDE, 0x67, 0x79, 0x8D, 0xFE, 0x3F, 0xF8, 0xF3, 0xE3, 0xCF, 0x8F, + 0x3C, 0x38, 0x70, 0xE1, 0xC0, 0xF8, 0xFB, 0xE3, 0xE3, 0x86, 0x0F, 0x38, + 0x1F, 0xC0, 0x3E, 0x00, 0x70, 0x03, 0xE0, 0x0F, 0x80, 0x77, 0x03, 0x8E, + 0x1E, 0x1C, 0xFC, 0xFF, 0xF3, 0xF0, 0xF9, 0xFF, 0x9F, 0x30, 0xC3, 0x9C, + 0x19, 0x81, 0xF8, 0x0F, 0x00, 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x3F, 0xC3, 0xFC, 0xFF, 0xBF, 0xEC, 0x3B, 0x0C, 0xC6, 0x33, 0x80, 0xC0, + 0x60, 0x38, 0xCC, 0x36, 0x0F, 0x03, 0xFF, 0xFF, 0xF0, 0xFF, 0xF1, 0x8C, + 0x63, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0xC7, 0xFE, 0x40, 0x30, 0x0E, + 0x01, 0x80, 0x70, 0x0C, 0x03, 0x80, 0x60, 0x1C, 0x03, 0x00, 0xE0, 0x18, + 0x07, 0x00, 0xC0, 0x38, 0x0E, 0x01, 0xC0, 0x70, 0x0C, 0x01, 0xFF, 0xC6, + 0x31, 0x8C, 0x63, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x1F, 0xFE, 0x04, 0x03, + 0x01, 0xE0, 0xFC, 0x7B, 0x9C, 0x7E, 0x1F, 0x03, 0xFF, 0xFF, 0xFF, 0xF0, + 0xCE, 0x73, 0x3F, 0x07, 0xF8, 0x00, 0xC0, 0x0C, 0x1F, 0xC7, 0xFC, 0x60, + 0xCC, 0x0C, 0xC1, 0xCF, 0xFF, 0x3F, 0xF0, 0xF0, 0x07, 0x80, 0x0C, 0x00, + 0x60, 0x03, 0x7C, 0x1F, 0xF8, 0xF1, 0xC7, 0x07, 0x30, 0x19, 0x80, 0xCC, + 0x06, 0x60, 0x73, 0xC7, 0x7F, 0xFB, 0xDF, 0x00, 0x1F, 0xB3, 0xFF, 0x70, + 0xFE, 0x07, 0xC0, 0x3C, 0x00, 0xC0, 0x0C, 0x00, 0x70, 0x77, 0xFF, 0x1F, + 0xC0, 0x01, 0xE0, 0x0F, 0x00, 0x18, 0x00, 0xC1, 0xF6, 0x3F, 0xF1, 0xC7, + 0x9C, 0x1C, 0xC0, 0x66, 0x03, 0x30, 0x19, 0x81, 0xC7, 0x1E, 0x3F, 0xFC, + 0x7D, 0xE0, 0x1F, 0x83, 0xFC, 0x70, 0xEE, 0x07, 0xFF, 0xFF, 0xFF, 0xE0, + 0x0E, 0x00, 0x70, 0x73, 0xFF, 0x1F, 0xC0, 0x07, 0xC3, 0xFC, 0x60, 0x0C, + 0x0F, 0xFD, 0xFF, 0x86, 0x00, 0xC0, 0x18, 0x03, 0x00, 0x60, 0x0C, 0x01, + 0x81, 0xFF, 0xBF, 0xF0, 0x1F, 0x79, 0xFF, 0xDC, 0x79, 0x81, 0xCC, 0x06, + 0x60, 0x33, 0x01, 0x9C, 0x1C, 0x71, 0xE1, 0xFF, 0x07, 0xD8, 0x00, 0xC0, + 0x06, 0x00, 0x70, 0x7F, 0x03, 0xF0, 0xF0, 0x03, 0xC0, 0x03, 0x00, 0x0C, + 0x00, 0x37, 0xC0, 0xFF, 0x83, 0xC7, 0x0C, 0x0C, 0x30, 0x30, 0xC0, 0xC3, + 0x03, 0x0C, 0x0C, 0x30, 0x33, 0xF3, 0xFF, 0xCF, 0xC0, 0x06, 0x00, 0xC0, + 0x00, 0x3F, 0x07, 0xE0, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, 0x18, + 0x03, 0x0F, 0xFF, 0xFF, 0xC0, 0x06, 0x06, 0x00, 0xFF, 0xFF, 0x03, 0x03, + 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x07, 0xFE, 0xFC, + 0xF0, 0x07, 0x80, 0x0C, 0x00, 0x60, 0x03, 0x3F, 0x19, 0xF8, 0xDE, 0x07, + 0xE0, 0x3E, 0x01, 0xF0, 0x0F, 0xC0, 0x6F, 0x03, 0x1C, 0x78, 0xFF, 0xC7, + 0xE0, 0x7E, 0x0F, 0xC0, 0x18, 0x03, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x30, + 0x06, 0x00, 0xC0, 0x18, 0x03, 0x00, 0x61, 0xFF, 0xFF, 0xF8, 0xFE, 0xF1, + 0xFF, 0xF1, 0xCE, 0x63, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0xC6, 0x31, + 0x8C, 0x63, 0x19, 0xF7, 0xBF, 0xEF, 0x78, 0x77, 0xC1, 0xFF, 0x83, 0xC7, + 0x0C, 0x0C, 0x30, 0x30, 0xC0, 0xC3, 0x03, 0x0C, 0x0C, 0x30, 0x33, 0xF1, + 0xFF, 0xC7, 0xC0, 0x1F, 0x83, 0xFC, 0x70, 0xEE, 0x07, 0xC0, 0x3C, 0x03, + 0xC0, 0x3E, 0x07, 0x70, 0xE3, 0xFC, 0x1F, 0x80, 0xF7, 0xE3, 0xFF, 0xC3, + 0xC3, 0x8E, 0x07, 0x30, 0x0C, 0xC0, 0x33, 0x00, 0xCE, 0x07, 0x3C, 0x38, + 0xFF, 0xC3, 0x7E, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x0F, 0xE0, 0x3F, 0x80, + 0x1F, 0xBC, 0xFF, 0xF7, 0x0F, 0x38, 0x1C, 0xC0, 0x33, 0x00, 0xCC, 0x03, + 0x38, 0x1C, 0x70, 0xF0, 0xFF, 0xC1, 0xFB, 0x00, 0x0C, 0x00, 0x30, 0x00, + 0xC0, 0x1F, 0xC0, 0x7F, 0x79, 0xE7, 0xFF, 0x1F, 0x31, 0xC0, 0x18, 0x01, + 0x80, 0x18, 0x01, 0x80, 0x18, 0x0F, 0xFC, 0xFF, 0xC0, 0x3F, 0x9F, 0xFE, + 0x1F, 0x82, 0xFE, 0x1F, 0xE0, 0xFF, 0x03, 0xE0, 0xFF, 0xFF, 0xF0, 0x30, + 0x06, 0x00, 0xC0, 0x7F, 0xEF, 0xFC, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, + 0x00, 0xC0, 0x18, 0x71, 0xFE, 0x1F, 0x00, 0xF1, 0xF7, 0x8F, 0x8C, 0x0C, + 0x60, 0x63, 0x03, 0x18, 0x18, 0xC0, 0xC6, 0x06, 0x38, 0xF0, 0xFF, 0xC3, + 0xEE, 0xFC, 0xFF, 0xF3, 0xF3, 0x87, 0x0E, 0x1C, 0x1C, 0x60, 0x73, 0x80, + 0xEC, 0x03, 0xF0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x00, 0xF8, 0x7F, 0xE1, + 0xF7, 0x39, 0x8C, 0xE6, 0x37, 0xB0, 0xFF, 0xC3, 0xFF, 0x07, 0xBC, 0x1C, + 0xF0, 0x73, 0x81, 0x86, 0x00, 0x7C, 0xF9, 0xF3, 0xE3, 0xCF, 0x07, 0xF8, + 0x0F, 0xC0, 0x1E, 0x00, 0xFC, 0x07, 0x38, 0x38, 0x73, 0xF3, 0xFF, 0xCF, + 0xC0, 0xF9, 0xFF, 0x9F, 0x70, 0xE3, 0x0C, 0x39, 0xC1, 0x98, 0x19, 0x81, + 0xF8, 0x0F, 0x00, 0xF0, 0x06, 0x00, 0x60, 0x0E, 0x00, 0xC0, 0xFF, 0x0F, + 0xF0, 0x7F, 0xCF, 0xF9, 0x8E, 0x33, 0x80, 0x70, 0x1C, 0x07, 0x01, 0xC6, + 0x70, 0xFF, 0xFF, 0xFF, 0x80, 0x0E, 0x3C, 0x60, 0xC1, 0x83, 0x06, 0x0C, + 0x39, 0xE3, 0xC0, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x3C, 0x38, 0xFF, 0xFF, + 0xFF, 0xFF, 0xF0, 0xE1, 0xC0, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x30, 0x3C, + 0x79, 0x83, 0x06, 0x0C, 0x18, 0x31, 0xE3, 0x80, 0x3C, 0x37, 0xE7, 0x67, + 0xE6, 0x1C }; + +const GFXglyph FreeMonoBold12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 14, 0, 1 }, // 0x20 ' ' + { 0, 4, 15, 14, 5, -14 }, // 0x21 '!' + { 8, 8, 7, 14, 3, -13 }, // 0x22 '"' + { 15, 11, 18, 14, 2, -15 }, // 0x23 '#' + { 40, 10, 20, 14, 2, -16 }, // 0x24 '$' + { 65, 10, 15, 14, 2, -14 }, // 0x25 '%' + { 84, 10, 13, 14, 2, -12 }, // 0x26 '&' + { 101, 3, 7, 14, 5, -13 }, // 0x27 ''' + { 104, 5, 19, 14, 6, -14 }, // 0x28 '(' + { 116, 5, 19, 14, 3, -14 }, // 0x29 ')' + { 128, 10, 10, 14, 2, -14 }, // 0x2A '*' + { 141, 12, 13, 14, 1, -12 }, // 0x2B '+' + { 161, 5, 7, 14, 4, -2 }, // 0x2C ',' + { 166, 12, 2, 14, 1, -7 }, // 0x2D '-' + { 169, 3, 3, 14, 5, -2 }, // 0x2E '.' + { 171, 10, 20, 14, 2, -16 }, // 0x2F '/' + { 196, 10, 15, 14, 2, -14 }, // 0x30 '0' + { 215, 10, 15, 14, 2, -14 }, // 0x31 '1' + { 234, 10, 15, 14, 2, -14 }, // 0x32 '2' + { 253, 11, 15, 14, 1, -14 }, // 0x33 '3' + { 274, 9, 14, 14, 2, -13 }, // 0x34 '4' + { 290, 10, 15, 14, 2, -14 }, // 0x35 '5' + { 309, 10, 15, 14, 2, -14 }, // 0x36 '6' + { 328, 10, 15, 14, 2, -14 }, // 0x37 '7' + { 347, 10, 15, 14, 2, -14 }, // 0x38 '8' + { 366, 10, 15, 14, 3, -14 }, // 0x39 '9' + { 385, 3, 11, 14, 5, -10 }, // 0x3A ':' + { 390, 4, 15, 14, 4, -10 }, // 0x3B ';' + { 398, 12, 11, 14, 1, -11 }, // 0x3C '<' + { 415, 12, 7, 14, 1, -9 }, // 0x3D '=' + { 426, 12, 11, 14, 1, -11 }, // 0x3E '>' + { 443, 9, 14, 14, 3, -13 }, // 0x3F '?' + { 459, 11, 19, 14, 2, -14 }, // 0x40 '@' + { 486, 15, 14, 14, -1, -13 }, // 0x41 'A' + { 513, 13, 14, 14, 0, -13 }, // 0x42 'B' + { 536, 12, 14, 14, 1, -13 }, // 0x43 'C' + { 557, 12, 14, 14, 1, -13 }, // 0x44 'D' + { 578, 13, 14, 14, 0, -13 }, // 0x45 'E' + { 601, 13, 14, 14, 0, -13 }, // 0x46 'F' + { 624, 13, 14, 14, 1, -13 }, // 0x47 'G' + { 647, 14, 14, 14, 0, -13 }, // 0x48 'H' + { 672, 10, 14, 14, 2, -13 }, // 0x49 'I' + { 690, 13, 14, 14, 1, -13 }, // 0x4A 'J' + { 713, 14, 14, 14, 0, -13 }, // 0x4B 'K' + { 738, 12, 14, 14, 1, -13 }, // 0x4C 'L' + { 759, 14, 14, 14, 0, -13 }, // 0x4D 'M' + { 784, 13, 14, 14, 0, -13 }, // 0x4E 'N' + { 807, 12, 14, 14, 1, -13 }, // 0x4F 'O' + { 828, 12, 14, 14, 0, -13 }, // 0x50 'P' + { 849, 12, 17, 14, 1, -13 }, // 0x51 'Q' + { 875, 14, 14, 14, 0, -13 }, // 0x52 'R' + { 900, 10, 14, 14, 2, -13 }, // 0x53 'S' + { 918, 12, 14, 14, 1, -13 }, // 0x54 'T' + { 939, 12, 14, 14, 1, -13 }, // 0x55 'U' + { 960, 16, 14, 14, -1, -13 }, // 0x56 'V' + { 988, 14, 14, 14, 0, -13 }, // 0x57 'W' + { 1013, 14, 14, 14, 0, -13 }, // 0x58 'X' + { 1038, 12, 14, 14, 1, -13 }, // 0x59 'Y' + { 1059, 10, 14, 14, 2, -13 }, // 0x5A 'Z' + { 1077, 5, 19, 14, 6, -14 }, // 0x5B '[' + { 1089, 10, 20, 14, 2, -16 }, // 0x5C '\' + { 1114, 5, 19, 14, 3, -14 }, // 0x5D ']' + { 1126, 10, 8, 14, 2, -15 }, // 0x5E '^' + { 1136, 14, 2, 14, 0, 4 }, // 0x5F '_' + { 1140, 4, 4, 14, 4, -15 }, // 0x60 '`' + { 1142, 12, 11, 14, 1, -10 }, // 0x61 'a' + { 1159, 13, 15, 14, 0, -14 }, // 0x62 'b' + { 1184, 12, 11, 14, 1, -10 }, // 0x63 'c' + { 1201, 13, 15, 14, 1, -14 }, // 0x64 'd' + { 1226, 12, 11, 14, 1, -10 }, // 0x65 'e' + { 1243, 11, 15, 14, 2, -14 }, // 0x66 'f' + { 1264, 13, 16, 14, 1, -10 }, // 0x67 'g' + { 1290, 14, 15, 14, 0, -14 }, // 0x68 'h' + { 1317, 11, 14, 14, 1, -13 }, // 0x69 'i' + { 1337, 8, 19, 15, 3, -13 }, // 0x6A 'j' + { 1356, 13, 15, 14, 1, -14 }, // 0x6B 'k' + { 1381, 11, 15, 14, 1, -14 }, // 0x6C 'l' + { 1402, 15, 11, 14, 0, -10 }, // 0x6D 'm' + { 1423, 14, 11, 14, 0, -10 }, // 0x6E 'n' + { 1443, 12, 11, 14, 1, -10 }, // 0x6F 'o' + { 1460, 14, 16, 14, 0, -10 }, // 0x70 'p' + { 1488, 14, 16, 14, 0, -10 }, // 0x71 'q' + { 1516, 12, 11, 14, 1, -10 }, // 0x72 'r' + { 1533, 10, 11, 14, 2, -10 }, // 0x73 's' + { 1547, 11, 14, 14, 1, -13 }, // 0x74 't' + { 1567, 13, 11, 14, 0, -10 }, // 0x75 'u' + { 1585, 14, 11, 14, 0, -10 }, // 0x76 'v' + { 1605, 14, 11, 14, 0, -10 }, // 0x77 'w' + { 1625, 14, 11, 14, 0, -10 }, // 0x78 'x' + { 1645, 12, 16, 14, 1, -10 }, // 0x79 'y' + { 1669, 11, 11, 14, 1, -10 }, // 0x7A 'z' + { 1685, 7, 19, 14, 3, -14 }, // 0x7B '{' + { 1702, 2, 19, 14, 6, -14 }, // 0x7C '|' + { 1707, 7, 19, 14, 4, -14 }, // 0x7D '}' + { 1724, 12, 4, 14, 1, -7 } }; // 0x7E '~' + +const GFXfont FreeMonoBold12pt7b PROGMEM = { + (uint8_t *)FreeMonoBold12pt7bBitmaps, + (GFXglyph *)FreeMonoBold12pt7bGlyphs, + 0x20, 0x7E, 24 }; + +// Approx. 2402 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBold18pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBold18pt7b.h new file mode 100644 index 0000000..36e0be0 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBold18pt7b.h @@ -0,0 +1,423 @@ +const uint8_t FreeMonoBold18pt7bBitmaps[] PROGMEM = { + 0x77, 0xFF, 0xFF, 0xFF, 0xFF, 0xFB, 0x9C, 0xE7, 0x39, 0xC4, 0x03, 0xBF, + 0xFF, 0xB8, 0xF1, 0xFE, 0x3F, 0xC7, 0xF8, 0xFF, 0x1E, 0xC1, 0x98, 0x33, + 0x06, 0x60, 0xCC, 0x18, 0x0E, 0x1C, 0x0F, 0x3C, 0x1F, 0x3C, 0x1E, 0x3C, + 0x1E, 0x3C, 0x1E, 0x78, 0x1E, 0x78, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFE, 0x1E, 0x78, 0x1E, 0x78, 0x1E, 0x78, 0x7F, 0xFE, 0x7F, 0xFE, + 0x7F, 0xFE, 0x7F, 0xFE, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0xF0, + 0x3C, 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, 0x03, 0x00, 0x1E, 0x00, 0x78, 0x01, + 0xE0, 0x1F, 0xF1, 0xFF, 0xE7, 0xFF, 0xBE, 0x1E, 0xF0, 0x3B, 0xC0, 0xCF, + 0xE0, 0x3F, 0xF8, 0x7F, 0xF0, 0x7F, 0xE0, 0x1F, 0xF0, 0x0F, 0xE0, 0x3F, + 0x80, 0xFF, 0x87, 0xFF, 0xFE, 0xFF, 0xF3, 0x7F, 0x80, 0x78, 0x01, 0xE0, + 0x07, 0x80, 0x1E, 0x00, 0x78, 0x00, 0xC0, 0x1E, 0x00, 0xFF, 0x03, 0x86, + 0x06, 0x06, 0x0C, 0x0C, 0x18, 0x18, 0x38, 0x70, 0x3F, 0xC2, 0x1E, 0x3E, + 0x03, 0xF8, 0x3F, 0x83, 0xF8, 0x0F, 0x8F, 0x18, 0x7F, 0x01, 0xC7, 0x03, + 0x06, 0x06, 0x0C, 0x0C, 0x18, 0x1C, 0x70, 0x1F, 0xC0, 0x0F, 0x00, 0x03, + 0xD0, 0x1F, 0xF0, 0x7F, 0xE1, 0xFF, 0xC3, 0xE6, 0x07, 0x80, 0x0F, 0x00, + 0x0F, 0x00, 0x1F, 0x00, 0x3E, 0x00, 0xFE, 0x03, 0xFE, 0xFF, 0xBD, 0xFE, + 0x3F, 0xFC, 0x3F, 0x7C, 0x7C, 0xFF, 0xFE, 0xFF, 0xFC, 0xFF, 0xF8, 0x7E, + 0xF0, 0xFF, 0xFF, 0xF6, 0x66, 0x66, 0x07, 0x0F, 0x1F, 0x1E, 0x3E, 0x3C, + 0x78, 0x78, 0x78, 0x70, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0x78, 0x78, 0x78, 0x3C, 0x3C, 0x1E, 0x1F, 0x0F, 0x07, 0xE0, 0xF0, 0xF8, + 0x78, 0x7C, 0x3C, 0x3E, 0x1E, 0x1E, 0x1E, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0E, 0x1E, 0x1E, 0x1E, 0x3C, 0x3C, 0x78, 0xF8, 0xF0, 0xE0, + 0x01, 0x80, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0xFF, 0xFF, + 0xFF, 0xFF, 0x7F, 0xFE, 0x1F, 0xF8, 0x07, 0xE0, 0x0F, 0xF0, 0x1F, 0xF8, + 0x1E, 0x78, 0x1C, 0x38, 0x18, 0x18, 0x01, 0xC0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x01, 0x80, 0x3E, 0x78, 0xF3, 0xC7, + 0x8E, 0x1C, 0x70, 0xE1, 0x80, 0x7F, 0xFF, 0xDF, 0xFF, 0xF9, 0xFF, 0xFF, + 0x3F, 0xFF, 0xE0, 0x77, 0xFF, 0xF7, 0x00, 0x00, 0x0E, 0x00, 0x3C, 0x00, + 0x78, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x1E, 0x00, 0x38, 0x00, 0xF0, + 0x01, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x3C, 0x00, 0x78, 0x01, 0xE0, 0x03, + 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x78, 0x00, 0xF0, 0x03, 0xC0, 0x07, 0x80, + 0x1E, 0x00, 0x3C, 0x00, 0x70, 0x01, 0xE0, 0x03, 0x80, 0x03, 0x00, 0x00, + 0x07, 0xE0, 0x1F, 0xF8, 0x3F, 0xFC, 0x3F, 0xFC, 0x7C, 0x3E, 0x78, 0x1E, + 0xF8, 0x1F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, + 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF8, 0x1F, 0x78, 0x1E, + 0x7C, 0x3E, 0x3F, 0xFC, 0x3F, 0xFC, 0x1F, 0xF8, 0x07, 0xE0, 0x07, 0xC0, + 0x1F, 0x80, 0xFF, 0x03, 0xFE, 0x0F, 0xBC, 0x0C, 0x78, 0x00, 0xF0, 0x01, + 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, + 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x81, 0xFF, 0xFB, 0xFF, 0xF7, + 0xFF, 0xE7, 0xFF, 0x80, 0x0F, 0xC0, 0x7F, 0xE1, 0xFF, 0xE3, 0xFF, 0xEF, + 0x87, 0xDE, 0x07, 0xF8, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x7C, 0x01, + 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, + 0x78, 0x03, 0xE0, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, + 0x0F, 0xC0, 0x7F, 0xF0, 0xFF, 0xF8, 0xFF, 0xFC, 0x70, 0x3E, 0x00, 0x1E, + 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x3C, 0x03, 0xFC, 0x03, 0xF0, 0x03, 0xF0, + 0x03, 0xFC, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0F, + 0xE0, 0x3F, 0xFF, 0xFE, 0xFF, 0xFC, 0x7F, 0xF8, 0x1F, 0xE0, 0x00, 0xF8, + 0x03, 0xF0, 0x07, 0xE0, 0x1F, 0xC0, 0x77, 0x80, 0xEF, 0x03, 0x9E, 0x0F, + 0x3C, 0x1C, 0x78, 0x70, 0xF1, 0xE1, 0xE3, 0x83, 0xCF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x78, 0x07, 0xFC, 0x0F, 0xF8, 0x1F, 0xF0, + 0x1F, 0xC0, 0x3F, 0xFC, 0x1F, 0xFE, 0x0F, 0xFF, 0x07, 0xFF, 0x83, 0xC0, + 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x7B, 0xE0, 0x3F, 0xFC, 0x1F, 0xFF, 0x0F, + 0xFF, 0xC3, 0x83, 0xE0, 0x00, 0xF8, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x0F, + 0x00, 0x0F, 0xB8, 0x0F, 0xBF, 0xFF, 0xCF, 0xFF, 0xC3, 0xFF, 0xC0, 0x7F, + 0x80, 0x00, 0xFC, 0x07, 0xFC, 0x3F, 0xF8, 0xFF, 0xF1, 0xF8, 0x07, 0xC0, + 0x1F, 0x00, 0x3C, 0x00, 0xF0, 0x01, 0xE7, 0xC3, 0xDF, 0xC7, 0x7F, 0xCF, + 0xFF, 0xDF, 0x8F, 0xFC, 0x07, 0xF0, 0x0F, 0xF0, 0x1F, 0xE0, 0x3D, 0xE0, + 0xFB, 0xFF, 0xE3, 0xFF, 0xC3, 0xFF, 0x01, 0xF8, 0x00, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x01, 0xE0, 0x03, 0x80, 0x0F, 0x00, 0x1E, + 0x00, 0x38, 0x00, 0xF0, 0x01, 0xE0, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, + 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x38, + 0x00, 0x70, 0x00, 0x07, 0xC0, 0x3F, 0xE0, 0xFF, 0xE3, 0xFF, 0xEF, 0x83, + 0xFE, 0x03, 0xFC, 0x07, 0xF8, 0x0F, 0xF0, 0x1E, 0xF0, 0x78, 0xFF, 0xE0, + 0xFF, 0x81, 0xFF, 0x0F, 0xFF, 0x9E, 0x0F, 0x78, 0x0F, 0xF0, 0x1F, 0xE0, + 0x3F, 0xE0, 0xFB, 0xFF, 0xE7, 0xFF, 0xC7, 0xFF, 0x03, 0xF8, 0x00, 0x0F, + 0xC0, 0x3F, 0xE0, 0xFF, 0xE3, 0xFF, 0xEF, 0xC3, 0xDF, 0x03, 0xBC, 0x07, + 0xF8, 0x0F, 0xF0, 0x1F, 0xF0, 0x3D, 0xF1, 0xFB, 0xFF, 0xF3, 0xFE, 0xE3, + 0xFB, 0xC3, 0xE7, 0x80, 0x1E, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xE7, 0xFF, + 0x8F, 0xFE, 0x1F, 0xF0, 0x1F, 0x80, 0x00, 0x77, 0xFF, 0xF7, 0x00, 0x00, + 0x00, 0x00, 0xEF, 0xFF, 0xEE, 0x1C, 0x7C, 0xF9, 0xF1, 0xC0, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xF3, 0xC7, 0x8E, 0x3C, 0x70, 0xE1, 0x87, 0x0C, 0x00, + 0x00, 0x00, 0x00, 0x80, 0x00, 0xF0, 0x00, 0xFC, 0x00, 0xFE, 0x00, 0xFE, + 0x00, 0xFE, 0x00, 0xFE, 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x07, 0xF0, 0x00, + 0x7F, 0x00, 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xF0, 0x00, 0x7C, 0x00, + 0x07, 0x7F, 0xFF, 0xDF, 0xFF, 0xF9, 0xFF, 0xFF, 0x3F, 0xFF, 0xE0, 0x00, + 0x00, 0x00, 0x00, 0x1F, 0xFF, 0xF7, 0xFF, 0xFE, 0x7F, 0xFF, 0xCF, 0xFF, + 0xF8, 0x00, 0x00, 0x3C, 0x00, 0x0F, 0xC0, 0x01, 0xFC, 0x00, 0x1F, 0xC0, + 0x01, 0xFC, 0x00, 0x1F, 0xC0, 0x01, 0xFC, 0x00, 0x3F, 0x80, 0x3F, 0x80, + 0x3F, 0x80, 0x3F, 0x80, 0x3F, 0x80, 0x3F, 0x80, 0x0F, 0x80, 0x03, 0x80, + 0x00, 0x1F, 0xC0, 0xFF, 0xE3, 0xFF, 0xF7, 0xFF, 0xEF, 0x07, 0xFE, 0x03, + 0xDC, 0x07, 0x80, 0x0F, 0x00, 0x7C, 0x03, 0xF8, 0x1F, 0xC0, 0x1E, 0x00, + 0x30, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0x1F, 0x00, 0x3E, + 0x00, 0x7C, 0x00, 0x70, 0x00, 0x07, 0xE0, 0x1F, 0xE0, 0x7F, 0xE1, 0xE1, + 0xC7, 0x83, 0xCE, 0x03, 0xBC, 0x07, 0x70, 0x0E, 0xE0, 0x7D, 0xC3, 0xFB, + 0x8F, 0xF7, 0x3C, 0xEE, 0x71, 0xDC, 0xE3, 0xB9, 0xC7, 0x73, 0xCE, 0xE3, + 0xFF, 0xC3, 0xFF, 0x83, 0xFF, 0x00, 0x07, 0x00, 0x0E, 0x00, 0x1E, 0x02, + 0x1E, 0x1E, 0x3F, 0xFC, 0x1F, 0xF0, 0x1F, 0x80, 0x0F, 0xF8, 0x00, 0x7F, + 0xF0, 0x01, 0xFF, 0xC0, 0x03, 0xFF, 0x00, 0x01, 0xFE, 0x00, 0x07, 0xF8, + 0x00, 0x1C, 0xF0, 0x00, 0xF3, 0xC0, 0x03, 0xCF, 0x00, 0x1E, 0x1E, 0x00, + 0x78, 0x78, 0x03, 0xC0, 0xF0, 0x0F, 0xFF, 0xC0, 0x3F, 0xFF, 0x01, 0xFF, + 0xFE, 0x07, 0xFF, 0xF8, 0x3C, 0x00, 0xF3, 0xFC, 0x1F, 0xEF, 0xF8, 0x7F, + 0xFF, 0xE1, 0xFF, 0x7F, 0x03, 0xF8, 0x7F, 0xFC, 0x0F, 0xFF, 0xF0, 0xFF, + 0xFF, 0x8F, 0xFF, 0xF8, 0x3C, 0x07, 0xC3, 0xC0, 0x3C, 0x3C, 0x03, 0xC3, + 0xC0, 0x7C, 0x3F, 0xFF, 0x83, 0xFF, 0xF0, 0x3F, 0xFF, 0x83, 0xFF, 0xFE, + 0x3C, 0x03, 0xE3, 0xC0, 0x1F, 0x3C, 0x00, 0xF3, 0xC0, 0x0F, 0x3C, 0x01, + 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xEF, 0xFF, 0xFC, 0x7F, 0xFF, 0x00, 0x01, + 0xF8, 0xC1, 0xFF, 0xFC, 0x7F, 0xFF, 0x9F, 0xFF, 0xF7, 0xE0, 0x7E, 0xF8, + 0x07, 0xFE, 0x00, 0x7F, 0x80, 0x0E, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, + 0x00, 0x78, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xE0, + 0x07, 0x7F, 0x03, 0xE7, 0xFF, 0xFC, 0x7F, 0xFF, 0x03, 0xFF, 0xC0, 0x1F, + 0xE0, 0xFF, 0xF0, 0x3F, 0xFF, 0x0F, 0xFF, 0xE3, 0xFF, 0xFC, 0x78, 0x1F, + 0x9E, 0x03, 0xE7, 0x80, 0x79, 0xE0, 0x0F, 0x78, 0x03, 0xDE, 0x00, 0xF7, + 0x80, 0x3D, 0xE0, 0x0F, 0x78, 0x03, 0xDE, 0x00, 0xF7, 0x80, 0x7D, 0xE0, + 0x1E, 0x78, 0x1F, 0xBF, 0xFF, 0xCF, 0xFF, 0xF3, 0xFF, 0xF0, 0x7F, 0xF0, + 0x00, 0x7F, 0xFF, 0xDF, 0xFF, 0xFB, 0xFF, 0xFF, 0x7F, 0xFF, 0xE3, 0xC0, + 0x3C, 0x78, 0x07, 0x8F, 0x1C, 0xF1, 0xE3, 0xCC, 0x3F, 0xF8, 0x07, 0xFF, + 0x00, 0xFF, 0xE0, 0x1F, 0xFC, 0x03, 0xC7, 0x80, 0x78, 0xF1, 0x8F, 0x0C, + 0x79, 0xE0, 0x0F, 0x3C, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF7, 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF3, 0xC0, 0x1E, 0x78, 0x63, 0xCF, 0x1E, 0x79, 0xE3, 0xC6, 0x3F, 0xF8, + 0x07, 0xFF, 0x00, 0xFF, 0xE0, 0x1F, 0xFC, 0x03, 0xC7, 0x80, 0x78, 0xE0, + 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x1F, 0xFC, 0x03, 0xFF, 0x80, + 0x7F, 0xF0, 0x07, 0xFC, 0x00, 0x01, 0xFC, 0xE0, 0x7F, 0xFE, 0x1F, 0xFF, + 0xE3, 0xFF, 0xFE, 0x7F, 0x03, 0xE7, 0xC0, 0x1E, 0xF8, 0x00, 0xEF, 0x00, + 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x03, 0xFE, 0xF0, + 0x3F, 0xFF, 0x03, 0xFF, 0xF8, 0x3F, 0xF7, 0x80, 0x1E, 0x7E, 0x01, 0xE3, + 0xFF, 0xFE, 0x1F, 0xFF, 0xE0, 0xFF, 0xF8, 0x01, 0xFE, 0x00, 0x7F, 0x0F, + 0xE3, 0xFC, 0x7F, 0x9F, 0xE3, 0xFC, 0x7F, 0x1F, 0xC1, 0xE0, 0x3C, 0x0F, + 0x01, 0xE0, 0x78, 0x0F, 0x03, 0xC0, 0x78, 0x1E, 0x03, 0xC0, 0xFF, 0xFE, + 0x07, 0xFF, 0xF0, 0x3F, 0xFF, 0x81, 0xFF, 0xFC, 0x0F, 0x01, 0xE0, 0x78, + 0x0F, 0x03, 0xC0, 0x78, 0x1E, 0x03, 0xC3, 0xFC, 0x7F, 0xBF, 0xE3, 0xFF, + 0xFF, 0x1F, 0xF7, 0xF0, 0x7F, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, + 0x78, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, 0xE0, 0x07, 0x83, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0xF8, 0x01, 0xFF, 0xE0, 0x3F, 0xFC, + 0x07, 0xFF, 0x80, 0xFF, 0xF0, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, + 0x00, 0x78, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x38, 0x07, 0x8F, + 0x00, 0xF1, 0xE0, 0x1E, 0x3C, 0x03, 0xC7, 0x80, 0xF8, 0xF8, 0x3F, 0x1F, + 0xFF, 0xC3, 0xFF, 0xF0, 0x1F, 0xFC, 0x00, 0x7E, 0x00, 0xFF, 0x0F, 0xCF, + 0xF9, 0xFE, 0xFF, 0x9F, 0xEF, 0xF8, 0xFC, 0x3C, 0x1F, 0x03, 0xC3, 0xE0, + 0x3C, 0x7C, 0x03, 0xCF, 0x80, 0x3D, 0xF0, 0x03, 0xFE, 0x00, 0x3F, 0xF8, + 0x03, 0xFF, 0x80, 0x3E, 0x7C, 0x03, 0xC3, 0xE0, 0x3C, 0x1E, 0x03, 0xC0, + 0xF0, 0x3C, 0x0F, 0x0F, 0xF8, 0x7E, 0xFF, 0x87, 0xFF, 0xF8, 0x7F, 0x7F, + 0x03, 0xE0, 0xFF, 0xC0, 0x3F, 0xF0, 0x0F, 0xFC, 0x03, 0xFF, 0x00, 0x1E, + 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, + 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x01, 0x87, 0x80, 0xF1, 0xE0, 0x3C, + 0x78, 0x0F, 0x1E, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, + 0xFF, 0xC0, 0x3E, 0x00, 0xF8, 0xFC, 0x01, 0xF9, 0xFC, 0x07, 0xF3, 0xF8, + 0x0F, 0xE3, 0xF8, 0x3F, 0x87, 0xF0, 0x7F, 0x0F, 0xF1, 0xFE, 0x1F, 0xE3, + 0xFC, 0x3D, 0xE7, 0x78, 0x7B, 0xDE, 0xF0, 0xF7, 0xBD, 0xE1, 0xE7, 0xF3, + 0xC3, 0xCF, 0xE7, 0x87, 0x8F, 0x8F, 0x0F, 0x1F, 0x1E, 0x1E, 0x1E, 0x3C, + 0x3C, 0x00, 0x79, 0xFF, 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xFC, 0x1F, 0xF7, + 0xF0, 0x1F, 0xC0, 0xFC, 0x1F, 0xEF, 0xE1, 0xFF, 0xFE, 0x1F, 0xFF, 0xF1, + 0xFF, 0x3F, 0x83, 0xC3, 0xF8, 0x3C, 0x3F, 0xC3, 0xC3, 0xFC, 0x3C, 0x3D, + 0xE3, 0xC3, 0xDE, 0x3C, 0x3C, 0xF3, 0xC3, 0xC7, 0xBC, 0x3C, 0x7B, 0xC3, + 0xC3, 0xFC, 0x3C, 0x3F, 0xC3, 0xC1, 0xFC, 0x3C, 0x1F, 0xCF, 0xF8, 0xFC, + 0xFF, 0x87, 0xCF, 0xF8, 0x7C, 0x7F, 0x03, 0xC0, 0x01, 0xF8, 0x00, 0x7F, + 0xE0, 0x0F, 0xFF, 0x81, 0xFF, 0xFC, 0x3F, 0x0F, 0xC7, 0xC0, 0x3E, 0x78, + 0x01, 0xEF, 0x80, 0x1F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, + 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x80, 0x1F, 0x78, 0x01, 0xE7, 0xC0, 0x3E, + 0x3F, 0x0F, 0xC1, 0xFF, 0xF8, 0x1F, 0xFF, 0x00, 0x7F, 0xE0, 0x01, 0xF8, + 0x00, 0x7F, 0xF8, 0x3F, 0xFF, 0x8F, 0xFF, 0xF3, 0xFF, 0xFE, 0x3C, 0x0F, + 0xCF, 0x00, 0xF3, 0xC0, 0x3C, 0xF0, 0x0F, 0x3C, 0x03, 0xCF, 0x03, 0xF3, + 0xFF, 0xF8, 0xFF, 0xFC, 0x3F, 0xFE, 0x0F, 0xFE, 0x03, 0xC0, 0x00, 0xF0, + 0x00, 0x3C, 0x00, 0x3F, 0xF8, 0x0F, 0xFE, 0x03, 0xFF, 0x80, 0x7F, 0xC0, + 0x00, 0x01, 0xF8, 0x00, 0x7F, 0xE0, 0x0F, 0xFF, 0x01, 0xFF, 0xF8, 0x3F, + 0x0F, 0xC7, 0xC0, 0x3E, 0x78, 0x01, 0xEF, 0x80, 0x1F, 0xF0, 0x00, 0xFF, + 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x80, 0x1F, + 0x78, 0x01, 0xE7, 0xC0, 0x3E, 0x3F, 0x0F, 0xC1, 0xFF, 0xF8, 0x0F, 0xFF, + 0x00, 0x7F, 0xE0, 0x03, 0xF8, 0x00, 0x3F, 0x8E, 0x07, 0xFF, 0xF0, 0xFF, + 0xFF, 0x0F, 0xFF, 0xE0, 0x60, 0x78, 0x7F, 0xF8, 0x07, 0xFF, 0xF0, 0x3F, + 0xFF, 0xE0, 0xFF, 0xFF, 0x01, 0xE0, 0x7C, 0x0F, 0x01, 0xE0, 0x78, 0x0F, + 0x03, 0xC0, 0x78, 0x1E, 0x0F, 0xC0, 0xFF, 0xFC, 0x07, 0xFF, 0xC0, 0x3F, + 0xF8, 0x01, 0xFF, 0xE0, 0x0F, 0x0F, 0x80, 0x78, 0x3C, 0x03, 0xC0, 0xF0, + 0x1E, 0x07, 0xC3, 0xFE, 0x1F, 0xBF, 0xF0, 0x7F, 0xFF, 0x83, 0xF7, 0xF8, + 0x0F, 0x00, 0x07, 0xE7, 0x07, 0xFF, 0x8F, 0xFF, 0xC7, 0xFF, 0xE7, 0xC1, + 0xF3, 0xC0, 0x79, 0xE0, 0x3C, 0xF8, 0x00, 0x7F, 0x80, 0x1F, 0xFC, 0x07, + 0xFF, 0x81, 0xFF, 0xE0, 0x0F, 0xFB, 0x00, 0x7F, 0xC0, 0x1F, 0xE0, 0x0F, + 0xFC, 0x1F, 0xFF, 0xFF, 0xBF, 0xFF, 0x8D, 0xFF, 0x80, 0x3F, 0x00, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x0F, 0x1F, 0xE1, + 0xE3, 0xFC, 0x3C, 0x7F, 0x87, 0x8F, 0x60, 0xF0, 0xC0, 0x1E, 0x00, 0x03, + 0xC0, 0x00, 0x78, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x07, + 0x80, 0x00, 0xF0, 0x01, 0xFF, 0xE0, 0x3F, 0xFC, 0x07, 0xFF, 0x80, 0x7F, + 0xE0, 0xFF, 0x0F, 0xF7, 0xFC, 0x7F, 0xFF, 0xE3, 0xFE, 0xFF, 0x1F, 0xF3, + 0xC0, 0x1E, 0x1E, 0x00, 0xF0, 0xF0, 0x07, 0x87, 0x80, 0x3C, 0x3C, 0x01, + 0xE1, 0xE0, 0x0F, 0x0F, 0x00, 0x78, 0x78, 0x03, 0xC3, 0xC0, 0x1E, 0x1E, + 0x00, 0xF0, 0xF0, 0x07, 0x87, 0xC0, 0x7C, 0x1F, 0x07, 0xC0, 0xFF, 0xFE, + 0x03, 0xFF, 0xE0, 0x0F, 0xFE, 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0x03, 0xFD, + 0xFF, 0x07, 0xFF, 0xFE, 0x0F, 0xFB, 0xF8, 0x1F, 0xE1, 0xC0, 0x07, 0x03, + 0xC0, 0x1E, 0x07, 0x80, 0x3C, 0x07, 0x80, 0xF0, 0x0F, 0x01, 0xE0, 0x0F, + 0x03, 0x80, 0x1E, 0x0F, 0x00, 0x3E, 0x1E, 0x00, 0x3C, 0x78, 0x00, 0x78, + 0xF0, 0x00, 0x7B, 0xC0, 0x00, 0xF7, 0x80, 0x01, 0xFF, 0x00, 0x01, 0xFC, + 0x00, 0x03, 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0xFF, 0x0F, + 0xF7, 0xFC, 0x7F, 0xFF, 0xE3, 0xFF, 0xFE, 0x0F, 0xF7, 0x80, 0x0F, 0x3C, + 0x38, 0x78, 0xE3, 0xE3, 0x87, 0x1F, 0x1C, 0x38, 0xF8, 0xE1, 0xEF, 0xE7, + 0x0F, 0x7F, 0x78, 0x7B, 0xBB, 0xC3, 0xFD, 0xFE, 0x0F, 0xEF, 0xF0, 0x7E, + 0x3F, 0x03, 0xF1, 0xF8, 0x1F, 0x8F, 0xC0, 0xFC, 0x3E, 0x07, 0xC1, 0xF0, + 0x3E, 0x0F, 0x81, 0xF0, 0x7C, 0x00, 0x7E, 0x0F, 0xDF, 0xE3, 0xFF, 0xFC, + 0x7F, 0xBF, 0x07, 0xE1, 0xE0, 0xF8, 0x3E, 0x3E, 0x03, 0xEF, 0x80, 0x3D, + 0xE0, 0x03, 0xF8, 0x00, 0x3E, 0x00, 0x03, 0xC0, 0x00, 0xF8, 0x00, 0x3F, + 0x80, 0x0F, 0x78, 0x03, 0xC7, 0x80, 0xF8, 0x78, 0x3E, 0x0F, 0x8F, 0xE3, + 0xFF, 0xFC, 0x7F, 0xFF, 0x8F, 0xF7, 0xE0, 0xFC, 0x7E, 0x07, 0xEF, 0xF0, + 0xFF, 0xFF, 0x0F, 0xF7, 0xE0, 0x7E, 0x1E, 0x07, 0x81, 0xF0, 0xF8, 0x0F, + 0x0F, 0x00, 0x79, 0xE0, 0x07, 0xFE, 0x00, 0x3F, 0xC0, 0x01, 0xF8, 0x00, + 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, + 0x00, 0xF0, 0x00, 0xFF, 0xE0, 0x0F, 0xFF, 0x00, 0xFF, 0xF0, 0x07, 0xFE, + 0x00, 0xFF, 0xFC, 0xFF, 0xFC, 0xFF, 0xFC, 0xFF, 0xFC, 0xF0, 0x3C, 0xF0, + 0x78, 0xF0, 0xF0, 0x70, 0xE0, 0x01, 0xE0, 0x03, 0xC0, 0x03, 0x80, 0x07, + 0x00, 0x0F, 0x00, 0x1E, 0x0E, 0x1C, 0x0F, 0x38, 0x0F, 0x78, 0x0F, 0x7F, + 0xFF, 0x7F, 0xFF, 0x7F, 0xFF, 0x7F, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xFE, 0xFF, 0xFF, 0xFE, 0xE0, 0x01, + 0xE0, 0x03, 0xC0, 0x03, 0xC0, 0x07, 0x80, 0x07, 0x00, 0x0F, 0x00, 0x0E, + 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x3C, 0x00, 0x78, 0x00, 0x78, 0x00, 0xF0, + 0x00, 0xF0, 0x01, 0xE0, 0x01, 0xE0, 0x03, 0xC0, 0x03, 0xC0, 0x07, 0x80, + 0x07, 0x80, 0x0F, 0x00, 0x0F, 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x3C, 0x00, + 0x38, 0x00, 0x70, 0x7F, 0xFF, 0xFF, 0xFF, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x7F, 0xFF, 0xFF, 0xFF, 0x01, 0x00, 0x07, 0x00, 0x1F, 0x00, + 0x7F, 0x00, 0xFE, 0x03, 0xDE, 0x0F, 0x1E, 0x3E, 0x3E, 0xF8, 0x3F, 0xE0, + 0x3F, 0x80, 0x38, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xF0, 0xC3, 0x87, 0x0E, 0x1C, 0x30, 0x01, 0xFC, 0x01, 0xFF, 0xC0, + 0x3F, 0xFC, 0x07, 0xFF, 0xC0, 0x00, 0x78, 0x0F, 0xFF, 0x07, 0xFF, 0xE1, + 0xFF, 0xFC, 0x7F, 0xFF, 0x9F, 0x80, 0xF3, 0xC0, 0x1E, 0x78, 0x0F, 0xCF, + 0xFF, 0xFE, 0xFF, 0xFF, 0xCF, 0xFF, 0xF8, 0x7F, 0x3E, 0x7C, 0x00, 0x1F, + 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x0F, + 0x3F, 0x01, 0xFF, 0xF8, 0x3F, 0xFF, 0x87, 0xFF, 0xF0, 0xFC, 0x1F, 0x1F, + 0x01, 0xF3, 0xC0, 0x1E, 0x78, 0x03, 0xCF, 0x00, 0x79, 0xE0, 0x0F, 0x3E, + 0x03, 0xE7, 0xE0, 0xFB, 0xFF, 0xFF, 0x7F, 0xFF, 0xCF, 0xFF, 0xF0, 0xF9, + 0xF8, 0x00, 0x03, 0xF3, 0x87, 0xFF, 0xCF, 0xFF, 0xEF, 0xFF, 0xF7, 0xE0, + 0xFF, 0xC0, 0x3F, 0xC0, 0x0F, 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3E, + 0x00, 0x4F, 0x80, 0xF7, 0xFF, 0xF9, 0xFF, 0xF8, 0x7F, 0xF8, 0x0F, 0xF0, + 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x03, + 0xC0, 0x00, 0x3C, 0x03, 0xF3, 0xC0, 0xFF, 0xBC, 0x1F, 0xFF, 0xC3, 0xFF, + 0xFC, 0x7E, 0x0F, 0xC7, 0x80, 0x7C, 0xF0, 0x03, 0xCF, 0x00, 0x3C, 0xF0, + 0x03, 0xCF, 0x00, 0x3C, 0xF8, 0x07, 0xC7, 0xE0, 0xFC, 0x7F, 0xFF, 0xF3, + 0xFF, 0xFF, 0x0F, 0xFF, 0xF0, 0x3F, 0x3E, 0x03, 0xF0, 0x03, 0xFF, 0x01, + 0xFF, 0xE0, 0xFF, 0xFC, 0x7E, 0x0F, 0x9E, 0x01, 0xEF, 0x00, 0x3F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFD, 0xE0, 0x00, 0x7F, 0xFF, + 0xCF, 0xFF, 0xF1, 0xFF, 0xF8, 0x0F, 0xF0, 0x03, 0xFC, 0x07, 0xFF, 0x0F, + 0xFF, 0x1F, 0xFF, 0x1E, 0x00, 0x1E, 0x00, 0xFF, 0xF8, 0xFF, 0xFC, 0xFF, + 0xFC, 0xFF, 0xF8, 0x1E, 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x1E, + 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x1E, 0x00, 0xFF, 0xF8, 0xFF, 0xF8, 0xFF, + 0xF8, 0xFF, 0xF8, 0x07, 0xE7, 0xC3, 0xFF, 0xFC, 0xFF, 0xFF, 0xBF, 0xFF, + 0xF7, 0xC1, 0xF9, 0xF0, 0x1F, 0x3C, 0x01, 0xE7, 0x80, 0x3C, 0xF0, 0x07, + 0x9E, 0x00, 0xF3, 0xE0, 0x3E, 0x3E, 0x0F, 0xC7, 0xFF, 0xF8, 0x7F, 0xFF, + 0x07, 0xFD, 0xE0, 0x3F, 0x3C, 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x3E, + 0x03, 0xFF, 0x80, 0x7F, 0xF0, 0x0F, 0xFC, 0x00, 0xFE, 0x00, 0x3E, 0x00, + 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x01, 0xE0, 0x00, 0x0F, + 0x00, 0x00, 0x78, 0xF8, 0x03, 0xDF, 0xE0, 0x1F, 0xFF, 0x80, 0xFF, 0xFE, + 0x07, 0xE1, 0xF0, 0x3E, 0x07, 0x81, 0xE0, 0x3C, 0x0F, 0x01, 0xE0, 0x78, + 0x0F, 0x03, 0xC0, 0x78, 0x1E, 0x03, 0xC0, 0xF0, 0x1E, 0x1F, 0xC1, 0xFD, + 0xFE, 0x0F, 0xFF, 0xF0, 0x7F, 0xBF, 0x01, 0xF8, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xC0, 0x3F, 0xC0, + 0x3F, 0xC0, 0x3F, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0xFF, 0xFE, 0xFF, 0xFF, + 0xFF, 0xFF, 0x7F, 0xFE, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x00, 0x00, + 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xF7, 0xFF, 0x00, 0xF0, 0x0F, 0x00, 0xF0, + 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, + 0x0F, 0x00, 0xF0, 0x0F, 0x01, 0xFF, 0xFE, 0xFF, 0xEF, 0xFC, 0x7F, 0x00, + 0x7C, 0x00, 0x3F, 0x00, 0x0F, 0xC0, 0x03, 0xF0, 0x00, 0x3C, 0x00, 0x0F, + 0x00, 0x03, 0xC7, 0xF0, 0xF3, 0xFC, 0x3C, 0xFF, 0x0F, 0x3F, 0x83, 0xDF, + 0x00, 0xFF, 0x80, 0x3F, 0xC0, 0x0F, 0xE0, 0x03, 0xFC, 0x00, 0xF7, 0x80, + 0x3C, 0xF0, 0x0F, 0x1F, 0x0F, 0xC3, 0xFB, 0xF1, 0xFF, 0xFC, 0x7F, 0xDF, + 0x0F, 0xE0, 0x3F, 0xC0, 0x3F, 0xC0, 0x3F, 0xC0, 0x3F, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0xFE, 0x3D, 0xE3, + 0xC1, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0x1F, 0xFF, 0xFE, 0x3E, 0x3C, 0x78, + 0xF0, 0xF1, 0xE3, 0xC3, 0xC7, 0x8F, 0x0F, 0x1E, 0x3C, 0x3C, 0x78, 0xF0, + 0xF1, 0xE3, 0xC3, 0xC7, 0x8F, 0x0F, 0x1E, 0xFE, 0x3E, 0x7F, 0xF8, 0xF9, + 0xFF, 0xE3, 0xE7, 0xDF, 0x0F, 0x1E, 0x1E, 0x7C, 0x03, 0xEF, 0xF0, 0x3F, + 0xFF, 0x83, 0xFF, 0xFC, 0x1F, 0x87, 0xC1, 0xE0, 0x3C, 0x1E, 0x03, 0xC1, + 0xE0, 0x3C, 0x1E, 0x03, 0xC1, 0xE0, 0x3C, 0x1E, 0x03, 0xC1, 0xE0, 0x3C, + 0x7F, 0x0F, 0xFF, 0xF0, 0xFF, 0xFF, 0x0F, 0xF7, 0xE0, 0x7E, 0x03, 0xF8, + 0x01, 0xFF, 0xC0, 0x7F, 0xFC, 0x1F, 0xFF, 0xC7, 0xE0, 0xFD, 0xF0, 0x07, + 0xFC, 0x00, 0x7F, 0x80, 0x0F, 0xF0, 0x01, 0xFE, 0x00, 0x3F, 0xE0, 0x0F, + 0xBF, 0x07, 0xE3, 0xFF, 0xF8, 0x3F, 0xFE, 0x03, 0xFF, 0x80, 0x1F, 0xC0, + 0x3E, 0x7E, 0x03, 0xF7, 0xFC, 0x1F, 0xFF, 0xF0, 0xFF, 0xFF, 0xC1, 0xF8, + 0x3F, 0x0F, 0x80, 0x7C, 0x78, 0x01, 0xE3, 0xC0, 0x0F, 0x1E, 0x00, 0x78, + 0xF0, 0x03, 0xC7, 0xC0, 0x3E, 0x3F, 0x07, 0xE1, 0xFF, 0xFE, 0x0F, 0xFF, + 0xE0, 0x7B, 0xFE, 0x03, 0xCF, 0xC0, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, + 0x80, 0x00, 0xFF, 0x80, 0x0F, 0xFC, 0x00, 0x7F, 0xE0, 0x01, 0xFE, 0x00, + 0x00, 0x03, 0xF3, 0xE0, 0x7F, 0xDF, 0x87, 0xFF, 0xFC, 0x7F, 0xFF, 0xE7, + 0xE0, 0xFC, 0x7C, 0x03, 0xE3, 0xC0, 0x0F, 0x1E, 0x00, 0x78, 0xF0, 0x03, + 0xC7, 0x80, 0x1E, 0x3E, 0x01, 0xF0, 0xFC, 0x1F, 0x83, 0xFF, 0xFC, 0x1F, + 0xFF, 0xE0, 0x3F, 0xEF, 0x00, 0x7E, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, + 0x00, 0x00, 0xF0, 0x00, 0x3F, 0xE0, 0x01, 0xFF, 0x80, 0x0F, 0xFC, 0x00, + 0x3F, 0xC0, 0x7E, 0x1E, 0x7F, 0x3F, 0xFF, 0xBF, 0xFF, 0xFF, 0xF1, 0xFE, + 0x00, 0xFC, 0x00, 0x7C, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x0F, 0x00, 0x07, + 0x80, 0x03, 0xC0, 0x0F, 0xFF, 0x87, 0xFF, 0xC3, 0xFF, 0xE1, 0xFF, 0xE0, + 0x07, 0xE6, 0x1F, 0xFE, 0x7F, 0xFE, 0x7F, 0xFE, 0x78, 0x1E, 0x78, 0x0E, + 0x7F, 0xE0, 0x3F, 0xFC, 0x03, 0xFE, 0x60, 0x1F, 0xE0, 0x0F, 0xF8, 0x1F, + 0xFF, 0xFF, 0xFF, 0xFE, 0x7F, 0xFC, 0x07, 0xE0, 0x0C, 0x00, 0x0F, 0x00, + 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x07, 0xFF, 0xF3, 0xFF, 0xF9, 0xFF, + 0xFC, 0xFF, 0xFC, 0x0F, 0x00, 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x00, + 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1E, 0x07, 0x8F, 0xFF, 0xC3, 0xFF, + 0xC1, 0xFF, 0xC0, 0x3F, 0x80, 0xFC, 0x1F, 0xBF, 0x0F, 0xEF, 0xC3, 0xFB, + 0xF0, 0xFE, 0x3C, 0x07, 0x8F, 0x01, 0xE3, 0xC0, 0x78, 0xF0, 0x1E, 0x3C, + 0x07, 0x8F, 0x01, 0xE3, 0xC0, 0x78, 0xF8, 0x7E, 0x3F, 0xFF, 0xC7, 0xFF, + 0xF0, 0xFF, 0x7C, 0x0F, 0x9E, 0x7F, 0x07, 0xF7, 0xFC, 0x7F, 0xFF, 0xE3, + 0xFE, 0xFE, 0x0F, 0xE1, 0xE0, 0x3C, 0x0F, 0x01, 0xE0, 0x3C, 0x1E, 0x01, + 0xE0, 0xF0, 0x07, 0x8F, 0x00, 0x3E, 0x78, 0x00, 0xF7, 0x80, 0x07, 0xFC, + 0x00, 0x1F, 0xC0, 0x00, 0xFE, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x7E, + 0x03, 0xF7, 0xF8, 0x3F, 0xFF, 0xC1, 0xFE, 0xFC, 0x07, 0xF3, 0xC7, 0x0F, + 0x1E, 0x7C, 0xF0, 0x73, 0xE7, 0x83, 0x9F, 0x7C, 0x1F, 0xFF, 0xC0, 0xFF, + 0xFE, 0x03, 0xF7, 0xF0, 0x1F, 0xBF, 0x80, 0xFC, 0xF8, 0x07, 0xC7, 0xC0, + 0x1E, 0x3E, 0x00, 0xE0, 0xE0, 0x7E, 0x0F, 0xDF, 0xE3, 0xFF, 0xFC, 0x7F, + 0xBF, 0x07, 0xE1, 0xF1, 0xF0, 0x1F, 0xFC, 0x01, 0xFF, 0x00, 0x1F, 0xC0, + 0x07, 0xF8, 0x01, 0xFF, 0xC0, 0x7E, 0xFC, 0x1F, 0x8F, 0xC7, 0xE0, 0xFD, + 0xFE, 0x3F, 0xFF, 0xC7, 0xFF, 0xF0, 0x7F, 0x7E, 0x0F, 0xDF, 0xE3, 0xFF, + 0xFC, 0x7F, 0xBF, 0x07, 0xE3, 0xC0, 0x78, 0x3C, 0x0E, 0x07, 0x83, 0xC0, + 0x78, 0x70, 0x0F, 0x1E, 0x00, 0xE3, 0x80, 0x1E, 0xF0, 0x01, 0xDC, 0x00, + 0x3F, 0x80, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0x00, 0x01, 0xE0, 0x00, + 0x38, 0x00, 0x0F, 0x00, 0x3F, 0xF0, 0x0F, 0xFF, 0x01, 0xFF, 0xE0, 0x1F, + 0xF8, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xF9, 0xC7, + 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x78, 0x03, 0xC0, 0x1E, 0x07, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0x81, 0xF0, 0xFC, 0x7E, 0x1F, + 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0xF8, 0xFC, 0x3E, 0x0F, + 0x83, 0xF0, 0x3E, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xF0, 0x7E, + 0x0F, 0xC3, 0xF0, 0x38, 0x6F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x70, 0x3E, 0x0F, 0xC1, 0xF8, 0x3E, + 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x7C, 0x0F, 0xC1, 0xF0, + 0x7C, 0x3F, 0x1F, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x83, 0xE1, 0xF8, + 0xFC, 0x3F, 0x07, 0x00, 0x1E, 0x00, 0x1F, 0xC0, 0x1F, 0xF0, 0xDF, 0xFC, + 0xFF, 0x3F, 0xFB, 0x0F, 0xF8, 0x03, 0xF8, 0x00, 0x78 }; + +const GFXglyph FreeMonoBold18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 21, 0, 1 }, // 0x20 ' ' + { 0, 5, 22, 21, 8, -21 }, // 0x21 '!' + { 14, 11, 10, 21, 5, -20 }, // 0x22 '"' + { 28, 16, 25, 21, 3, -22 }, // 0x23 '#' + { 78, 14, 28, 21, 4, -23 }, // 0x24 '$' + { 127, 15, 21, 21, 3, -20 }, // 0x25 '%' + { 167, 15, 20, 21, 3, -19 }, // 0x26 '&' + { 205, 4, 10, 21, 8, -20 }, // 0x27 ''' + { 210, 8, 27, 21, 9, -21 }, // 0x28 '(' + { 237, 8, 27, 21, 4, -21 }, // 0x29 ')' + { 264, 16, 15, 21, 3, -21 }, // 0x2A '*' + { 294, 16, 19, 21, 3, -18 }, // 0x2B '+' + { 332, 7, 10, 21, 5, -3 }, // 0x2C ',' + { 341, 19, 4, 21, 1, -11 }, // 0x2D '-' + { 351, 5, 5, 21, 8, -4 }, // 0x2E '.' + { 355, 15, 28, 21, 3, -23 }, // 0x2F '/' + { 408, 16, 23, 21, 3, -22 }, // 0x30 '0' + { 454, 15, 22, 21, 3, -21 }, // 0x31 '1' + { 496, 15, 23, 21, 3, -22 }, // 0x32 '2' + { 540, 16, 23, 21, 3, -22 }, // 0x33 '3' + { 586, 15, 21, 21, 3, -20 }, // 0x34 '4' + { 626, 17, 22, 21, 2, -21 }, // 0x35 '5' + { 673, 15, 23, 21, 4, -22 }, // 0x36 '6' + { 717, 15, 22, 21, 3, -21 }, // 0x37 '7' + { 759, 15, 23, 21, 3, -22 }, // 0x38 '8' + { 803, 15, 23, 21, 4, -22 }, // 0x39 '9' + { 847, 5, 16, 21, 8, -15 }, // 0x3A ':' + { 857, 7, 22, 21, 5, -15 }, // 0x3B ';' + { 877, 18, 16, 21, 1, -17 }, // 0x3C '<' + { 913, 19, 10, 21, 1, -14 }, // 0x3D '=' + { 937, 18, 16, 21, 2, -17 }, // 0x3E '>' + { 973, 15, 21, 21, 4, -20 }, // 0x3F '?' + { 1013, 15, 27, 21, 3, -21 }, // 0x40 '@' + { 1064, 22, 21, 21, -1, -20 }, // 0x41 'A' + { 1122, 20, 21, 21, 1, -20 }, // 0x42 'B' + { 1175, 19, 21, 21, 1, -20 }, // 0x43 'C' + { 1225, 18, 21, 21, 2, -20 }, // 0x44 'D' + { 1273, 19, 21, 21, 1, -20 }, // 0x45 'E' + { 1323, 19, 21, 21, 1, -20 }, // 0x46 'F' + { 1373, 20, 21, 21, 1, -20 }, // 0x47 'G' + { 1426, 21, 21, 21, 0, -20 }, // 0x48 'H' + { 1482, 14, 21, 21, 4, -20 }, // 0x49 'I' + { 1519, 19, 21, 21, 2, -20 }, // 0x4A 'J' + { 1569, 20, 21, 21, 1, -20 }, // 0x4B 'K' + { 1622, 18, 21, 21, 2, -20 }, // 0x4C 'L' + { 1670, 23, 21, 21, -1, -20 }, // 0x4D 'M' + { 1731, 20, 21, 21, 1, -20 }, // 0x4E 'N' + { 1784, 20, 21, 21, 1, -20 }, // 0x4F 'O' + { 1837, 18, 21, 21, 1, -20 }, // 0x50 'P' + { 1885, 20, 26, 21, 1, -20 }, // 0x51 'Q' + { 1950, 21, 21, 21, 0, -20 }, // 0x52 'R' + { 2006, 17, 21, 21, 2, -20 }, // 0x53 'S' + { 2051, 19, 21, 21, 1, -20 }, // 0x54 'T' + { 2101, 21, 21, 21, 0, -20 }, // 0x55 'U' + { 2157, 23, 21, 21, -1, -20 }, // 0x56 'V' + { 2218, 21, 21, 21, 0, -20 }, // 0x57 'W' + { 2274, 19, 21, 21, 1, -20 }, // 0x58 'X' + { 2324, 20, 21, 21, 1, -20 }, // 0x59 'Y' + { 2377, 16, 21, 21, 3, -20 }, // 0x5A 'Z' + { 2419, 8, 27, 21, 9, -21 }, // 0x5B '[' + { 2446, 15, 28, 21, 3, -23 }, // 0x5C '\' + { 2499, 8, 27, 21, 4, -21 }, // 0x5D ']' + { 2526, 15, 11, 21, 3, -21 }, // 0x5E '^' + { 2547, 21, 4, 21, 0, 4 }, // 0x5F '_' + { 2558, 6, 6, 21, 6, -22 }, // 0x60 '`' + { 2563, 19, 16, 21, 1, -15 }, // 0x61 'a' + { 2601, 19, 22, 21, 1, -21 }, // 0x62 'b' + { 2654, 17, 16, 21, 2, -15 }, // 0x63 'c' + { 2688, 20, 22, 21, 1, -21 }, // 0x64 'd' + { 2743, 18, 16, 21, 1, -15 }, // 0x65 'e' + { 2779, 16, 22, 21, 4, -21 }, // 0x66 'f' + { 2823, 19, 23, 21, 1, -15 }, // 0x67 'g' + { 2878, 21, 22, 21, 0, -21 }, // 0x68 'h' + { 2936, 16, 22, 21, 3, -21 }, // 0x69 'i' + { 2980, 12, 29, 21, 5, -21 }, // 0x6A 'j' + { 3024, 18, 22, 21, 2, -21 }, // 0x6B 'k' + { 3074, 16, 22, 21, 3, -21 }, // 0x6C 'l' + { 3118, 22, 16, 21, -1, -15 }, // 0x6D 'm' + { 3162, 20, 16, 21, 0, -15 }, // 0x6E 'n' + { 3202, 19, 16, 21, 1, -15 }, // 0x6F 'o' + { 3240, 21, 23, 21, 0, -15 }, // 0x70 'p' + { 3301, 21, 23, 22, 1, -15 }, // 0x71 'q' + { 3362, 17, 16, 21, 3, -15 }, // 0x72 'r' + { 3396, 16, 16, 21, 3, -15 }, // 0x73 's' + { 3428, 17, 21, 21, 1, -20 }, // 0x74 't' + { 3473, 18, 16, 21, 1, -15 }, // 0x75 'u' + { 3509, 21, 16, 21, 0, -15 }, // 0x76 'v' + { 3551, 21, 16, 21, 0, -15 }, // 0x77 'w' + { 3593, 19, 16, 21, 1, -15 }, // 0x78 'x' + { 3631, 19, 23, 21, 1, -15 }, // 0x79 'y' + { 3686, 14, 16, 21, 3, -15 }, // 0x7A 'z' + { 3714, 10, 27, 21, 6, -21 }, // 0x7B '{' + { 3748, 4, 27, 21, 9, -21 }, // 0x7C '|' + { 3762, 10, 27, 21, 6, -21 }, // 0x7D '}' + { 3796, 17, 8, 21, 2, -13 } }; // 0x7E '~' + +const GFXfont FreeMonoBold18pt7b PROGMEM = { + (uint8_t *)FreeMonoBold18pt7bBitmaps, + (GFXglyph *)FreeMonoBold18pt7bGlyphs, + 0x20, 0x7E, 35 }; + +// Approx. 4485 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBold24pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBold24pt7b.h new file mode 100644 index 0000000..aa0dcd0 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBold24pt7b.h @@ -0,0 +1,672 @@ +const uint8_t FreeMonoBold24pt7bBitmaps[] PROGMEM = { + 0x38, 0xFB, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFD, 0xF3, 0xE7, 0xCF, + 0x9F, 0x3E, 0x7C, 0xF9, 0xF3, 0xE3, 0x82, 0x00, 0x00, 0x00, 0x71, 0xF7, + 0xFF, 0xEF, 0x9E, 0x00, 0xFC, 0x7E, 0xF8, 0x7D, 0xF0, 0xFB, 0xE1, 0xF7, + 0xC3, 0xEF, 0x87, 0xDF, 0x0F, 0xBE, 0x1F, 0x38, 0x1C, 0x70, 0x38, 0xE0, + 0x71, 0xC0, 0xE3, 0x81, 0xC7, 0x03, 0x80, 0x01, 0xC1, 0xC0, 0x0F, 0x8F, + 0x80, 0x3E, 0x3E, 0x00, 0xF8, 0xF8, 0x03, 0xE3, 0xE0, 0x0F, 0x8F, 0x80, + 0x7E, 0x3E, 0x01, 0xF0, 0xF8, 0x07, 0xC7, 0xC0, 0x1F, 0x1F, 0x03, 0xFF, + 0xFF, 0x9F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFD, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, + 0x81, 0xF1, 0xF0, 0x07, 0xC7, 0xC0, 0x1F, 0x1F, 0x00, 0x7C, 0x7C, 0x1F, + 0xFF, 0xFC, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0x9F, 0xFF, + 0xFC, 0x0F, 0x8F, 0x80, 0x3E, 0x3E, 0x00, 0xF8, 0xF8, 0x03, 0xE3, 0xE0, + 0x0F, 0x8F, 0x80, 0x3E, 0x3E, 0x00, 0xF8, 0xF8, 0x03, 0xE3, 0xE0, 0x0F, + 0x8F, 0x80, 0x3C, 0x3C, 0x00, 0x00, 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x1F, 0xFF, 0x07, 0xFF, 0xF1, 0xFF, 0xFE, + 0x7F, 0xFF, 0xDF, 0xC1, 0xFB, 0xF0, 0x1F, 0x7C, 0x01, 0xEF, 0x80, 0x39, + 0xF8, 0x00, 0x3F, 0xF8, 0x03, 0xFF, 0xE0, 0x3F, 0xFF, 0x03, 0xFF, 0xF0, + 0x0F, 0xFF, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0xC0, 0x07, 0xF8, 0x00, 0xFF, + 0x80, 0x1F, 0xF8, 0x07, 0xFF, 0x81, 0xFB, 0xFF, 0xFF, 0x7F, 0xFF, 0xCF, + 0xFF, 0xF1, 0xDF, 0xFC, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, + 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x01, 0xC0, 0x00, + 0x0F, 0x80, 0x00, 0xFF, 0x00, 0x1F, 0xFC, 0x00, 0xF0, 0xE0, 0x0F, 0x07, + 0x80, 0x70, 0x1C, 0x03, 0x80, 0xE0, 0x1C, 0x07, 0x00, 0xF0, 0x78, 0x03, + 0xC3, 0x80, 0x1F, 0xFC, 0x00, 0x7F, 0xC1, 0xF0, 0xF8, 0x7F, 0x00, 0x3F, + 0xF0, 0x0F, 0xFC, 0x03, 0xFF, 0x00, 0xFF, 0xC0, 0x07, 0xE0, 0xF8, 0x38, + 0x1F, 0xE0, 0x01, 0xFF, 0x80, 0x0F, 0x1E, 0x00, 0xF0, 0x78, 0x07, 0x01, + 0xC0, 0x38, 0x0E, 0x01, 0xC0, 0x70, 0x0F, 0x07, 0x80, 0x38, 0x78, 0x01, + 0xFF, 0xC0, 0x07, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x1F, 0xFC, + 0x01, 0xFF, 0xE0, 0x1F, 0xFF, 0x00, 0xFF, 0xF8, 0x0F, 0xC7, 0x00, 0x7C, + 0x10, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xF0, 0x00, + 0x1F, 0x80, 0x00, 0xFE, 0x00, 0x0F, 0xF8, 0x00, 0xFF, 0xC7, 0xCF, 0xFF, + 0x3F, 0x7E, 0xFF, 0xFF, 0xE7, 0xFF, 0xBE, 0x1F, 0xF9, 0xF0, 0x7F, 0x8F, + 0x83, 0xFC, 0x7C, 0x0F, 0xE3, 0xF0, 0x7F, 0xCF, 0xFF, 0xFF, 0x7F, 0xFF, + 0xF9, 0xFF, 0xFF, 0xC7, 0xFF, 0xFC, 0x0F, 0xE0, 0x00, 0xFD, 0xF7, 0xDF, + 0x7D, 0xF7, 0xDF, 0x38, 0xE3, 0x8E, 0x38, 0xE0, 0x01, 0x80, 0xF0, 0x7C, + 0x3F, 0x0F, 0xC7, 0xE1, 0xF8, 0xFC, 0x3E, 0x0F, 0x87, 0xC1, 0xF0, 0x7C, + 0x1F, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, + 0x81, 0xF0, 0x7C, 0x1F, 0x07, 0xC0, 0xF8, 0x3E, 0x0F, 0xC1, 0xF0, 0x7E, + 0x0F, 0x83, 0xF0, 0x7C, 0x1F, 0x03, 0xC0, 0x60, 0x3C, 0x0F, 0x83, 0xF0, + 0xFC, 0x1F, 0x83, 0xE0, 0xFC, 0x1F, 0x07, 0xC1, 0xF8, 0x3E, 0x0F, 0x83, + 0xE0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, + 0x1E, 0x0F, 0x83, 0xE0, 0xF8, 0x7C, 0x1F, 0x0F, 0xC3, 0xE1, 0xF8, 0x7C, + 0x3F, 0x0F, 0x83, 0xE0, 0xF0, 0x00, 0x00, 0x70, 0x00, 0x07, 0xC0, 0x00, + 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x10, 0x7C, 0x11, 0xF3, 0xE7, + 0xDF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, 0x87, 0xFF, 0xF0, 0x07, + 0xFC, 0x00, 0x3F, 0xE0, 0x03, 0xFF, 0x80, 0x3F, 0x7E, 0x01, 0xFB, 0xF0, + 0x1F, 0x8F, 0xC0, 0xF8, 0x3E, 0x03, 0x80, 0xE0, 0x00, 0x38, 0x00, 0x00, + 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, + 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, + 0x01, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xDF, 0xFF, 0xFF, 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, + 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, + 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x70, 0x00, 0x1F, + 0x8F, 0x87, 0xC7, 0xC3, 0xE1, 0xE1, 0xF0, 0xF0, 0x78, 0x38, 0x3C, 0x1C, + 0x0E, 0x06, 0x00, 0x7F, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, 0xFE, 0x7D, 0xFF, 0xFF, 0xFF, 0xEF, 0x80, + 0x00, 0x00, 0x60, 0x00, 0x0F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, + 0xF0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, + 0xF8, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, + 0x3E, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x0F, 0xC0, 0x00, 0xF8, 0x00, + 0x1F, 0x80, 0x01, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, + 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x1F, 0x00, + 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0xC0, + 0x00, 0xFC, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x00, 0x00, 0x01, + 0xFC, 0x00, 0x3F, 0xF8, 0x03, 0xFF, 0xE0, 0x3F, 0xFF, 0x83, 0xFF, 0xFE, + 0x1F, 0x83, 0xF1, 0xF8, 0x0F, 0xCF, 0x80, 0x3E, 0x7C, 0x01, 0xF7, 0xC0, + 0x07, 0xFE, 0x00, 0x3F, 0xF0, 0x01, 0xFF, 0x80, 0x0F, 0xFC, 0x00, 0x7F, + 0xE0, 0x03, 0xFF, 0x00, 0x1F, 0xF8, 0x00, 0xFF, 0xC0, 0x07, 0xFE, 0x00, + 0x3F, 0xF0, 0x01, 0xFF, 0x80, 0x0F, 0xFC, 0x00, 0x7D, 0xF0, 0x07, 0xCF, + 0x80, 0x3E, 0x7E, 0x03, 0xF1, 0xF8, 0x3F, 0x0F, 0xFF, 0xF8, 0x3F, 0xFF, + 0x80, 0xFF, 0xF8, 0x03, 0xFF, 0x80, 0x07, 0xF0, 0x00, 0x01, 0xF8, 0x00, + 0x3F, 0x80, 0x0F, 0xF8, 0x01, 0xFF, 0x80, 0x7F, 0xF8, 0x0F, 0xEF, 0x80, + 0xFC, 0xF8, 0x07, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, + 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, + 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, + 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x3F, 0xFF, 0xE7, + 0xFF, 0xFF, 0x7F, 0xFF, 0xF7, 0xFF, 0xFF, 0x3F, 0xFF, 0xE0, 0x01, 0xFC, + 0x00, 0x3F, 0xF8, 0x07, 0xFF, 0xF0, 0x7F, 0xFF, 0xC7, 0xFF, 0xFF, 0x3F, + 0x03, 0xFB, 0xF0, 0x07, 0xFF, 0x00, 0x1F, 0xF8, 0x00, 0xFB, 0x80, 0x07, + 0xC0, 0x00, 0x3E, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xF8, 0x00, + 0x3F, 0x80, 0x03, 0xF8, 0x00, 0x3F, 0x80, 0x03, 0xF8, 0x00, 0x3F, 0x00, + 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xE0, + 0x0E, 0xFE, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x03, 0xF8, 0x00, 0xFF, 0xF8, 0x0F, 0xFF, + 0xE0, 0xFF, 0xFF, 0x8F, 0xFF, 0xFE, 0x7E, 0x03, 0xF1, 0xC0, 0x0F, 0xC0, + 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, 0x0F, + 0xC0, 0x0F, 0xFC, 0x00, 0xFF, 0xC0, 0x07, 0xFC, 0x00, 0x3F, 0xF0, 0x00, + 0xFF, 0xC0, 0x00, 0x7F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xF0, 0x00, 0x0F, + 0x80, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x01, 0xFF, 0xC0, + 0x3F, 0xBF, 0xFF, 0xFD, 0xFF, 0xFF, 0xC7, 0xFF, 0xFC, 0x1F, 0xFF, 0xC0, + 0x1F, 0xF0, 0x00, 0x00, 0x3F, 0x80, 0x03, 0xF8, 0x00, 0x7F, 0x80, 0x07, + 0xF8, 0x00, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xEF, 0x80, 0x3E, 0xF8, 0x03, + 0xCF, 0x80, 0x7C, 0xF8, 0x0F, 0x8F, 0x80, 0xF0, 0xF8, 0x1F, 0x0F, 0x81, + 0xE0, 0xF8, 0x3E, 0x0F, 0x87, 0xC0, 0xF8, 0x78, 0x0F, 0x8F, 0xFF, 0xFE, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x0F, + 0x80, 0x07, 0xFE, 0x00, 0xFF, 0xF0, 0x0F, 0xFF, 0x00, 0xFF, 0xF0, 0x07, + 0xFE, 0x3F, 0xFF, 0xC1, 0xFF, 0xFF, 0x0F, 0xFF, 0xF8, 0x7F, 0xFF, 0xC3, + 0xFF, 0xFC, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, + 0x01, 0xF0, 0x00, 0x0F, 0xBF, 0x00, 0x7F, 0xFF, 0x03, 0xFF, 0xFC, 0x1F, + 0xFF, 0xF0, 0xFF, 0xFF, 0x83, 0xC0, 0xFE, 0x00, 0x01, 0xF0, 0x00, 0x0F, + 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, + 0x03, 0xE0, 0x00, 0x3F, 0xF0, 0x03, 0xF7, 0xE0, 0x3F, 0xBF, 0xFF, 0xF9, + 0xFF, 0xFF, 0xC7, 0xFF, 0xFC, 0x1F, 0xFF, 0x80, 0x1F, 0xF0, 0x00, 0x00, + 0x1F, 0xC0, 0x0F, 0xFF, 0x01, 0xFF, 0xF0, 0x7F, 0xFF, 0x0F, 0xFF, 0xE1, + 0xFF, 0x00, 0x1F, 0xC0, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x07, 0xE0, 0x00, + 0x7C, 0x00, 0x0F, 0x8F, 0xC0, 0xF9, 0xFF, 0x0F, 0xFF, 0xF8, 0xFF, 0xFF, + 0xCF, 0xFF, 0xFC, 0xFF, 0x0F, 0xEF, 0xE0, 0x3E, 0xFC, 0x03, 0xFF, 0x80, + 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xF7, 0xC0, 0x3F, 0x7E, + 0x03, 0xF3, 0xF0, 0x7E, 0x3F, 0xFF, 0xE1, 0xFF, 0xFC, 0x0F, 0xFF, 0x80, + 0x7F, 0xF0, 0x01, 0xFC, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x1F, 0xF0, 0x03, 0xE0, 0x00, + 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, + 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x1F, 0x00, + 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, + 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x06, 0x00, 0x01, 0xF8, 0x00, 0xFF, + 0xF0, 0x1F, 0xFF, 0x83, 0xFF, 0xFC, 0x7F, 0xFF, 0xE7, 0xE0, 0x7E, 0xFC, + 0x03, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xF7, + 0xC0, 0x3E, 0x7E, 0x07, 0xE3, 0xFF, 0xFC, 0x0F, 0xFF, 0x00, 0xFF, 0xF0, + 0x1F, 0xFF, 0x83, 0xFF, 0xFC, 0x7F, 0x0F, 0xE7, 0xC0, 0x3E, 0xF8, 0x01, + 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xFC, 0x03, 0xF7, 0xE0, + 0x7E, 0x7F, 0xFF, 0xE3, 0xFF, 0xFC, 0x1F, 0xFF, 0x80, 0xFF, 0xF0, 0x03, + 0xFC, 0x00, 0x03, 0xF8, 0x00, 0xFF, 0xE0, 0x1F, 0xFF, 0x83, 0xFF, 0xF8, + 0x7F, 0xFF, 0xC7, 0xE0, 0xFE, 0xFC, 0x03, 0xEF, 0x80, 0x3E, 0xF8, 0x01, + 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x3F, 0xFC, 0x07, 0xF7, 0xE0, + 0xFF, 0x7F, 0xFF, 0xF3, 0xFF, 0xFF, 0x1F, 0xFF, 0xF0, 0xFF, 0x9F, 0x03, + 0xF1, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xE0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, + 0x01, 0xFC, 0x00, 0x3F, 0x80, 0x0F, 0xF0, 0x7F, 0xFE, 0x0F, 0xFF, 0xC0, + 0xFF, 0xF8, 0x0F, 0xFF, 0x00, 0x3F, 0x80, 0x00, 0x7D, 0xFF, 0xFF, 0xFF, + 0xEF, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7D, 0xFF, + 0xFF, 0xFF, 0xEF, 0x80, 0x0F, 0x87, 0xF1, 0xFC, 0x7F, 0x1F, 0xC3, 0xE0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, + 0x1F, 0x87, 0xE1, 0xF0, 0xFC, 0x3E, 0x0F, 0x03, 0xC1, 0xE0, 0x78, 0x1C, + 0x07, 0x01, 0x80, 0x00, 0x00, 0x04, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x7F, + 0x00, 0x01, 0xFE, 0x00, 0x07, 0xFC, 0x00, 0x1F, 0xF0, 0x00, 0x7F, 0xC0, + 0x01, 0xFF, 0x00, 0x07, 0xFE, 0x00, 0x1F, 0xF8, 0x00, 0x7F, 0xE0, 0x00, + 0xFF, 0xE0, 0x00, 0x1F, 0xF8, 0x00, 0x07, 0xFE, 0x00, 0x01, 0xFF, 0x80, + 0x00, 0x7F, 0xE0, 0x00, 0x1F, 0xF8, 0x00, 0x07, 0xFC, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x7F, 0x00, 0x00, 0x1E, 0x7F, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, 0xFE, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xFE, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, 0xFE, + 0x00, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x07, + 0xFC, 0x00, 0x03, 0xFE, 0x00, 0x01, 0xFF, 0x00, 0x00, 0xFF, 0x80, 0x00, + 0x7F, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0xF0, 0x00, 0x3F, 0xF0, 0x01, + 0xFF, 0x00, 0x0F, 0xF8, 0x00, 0x7F, 0xC0, 0x03, 0xFE, 0x00, 0x1F, 0xF0, + 0x00, 0xFF, 0x80, 0x03, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x0F, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x03, 0xF8, 0x01, 0xFF, 0xF0, 0xFF, 0xFF, 0x8F, + 0xFF, 0xFC, 0xFF, 0xFF, 0xEF, 0xC0, 0x7E, 0xF8, 0x03, 0xFF, 0x80, 0x1F, + 0x70, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x3F, + 0xE0, 0x0F, 0xFC, 0x01, 0xFF, 0x00, 0x0F, 0xC0, 0x00, 0xF0, 0x00, 0x0F, + 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x1F, 0x00, 0x03, 0xF8, 0x00, 0x3F, 0x80, 0x03, 0xF8, 0x00, + 0x3F, 0x80, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0xFF, 0x80, 0x3F, 0xF8, + 0x0F, 0xFF, 0x83, 0xE0, 0xF8, 0x78, 0x07, 0x1E, 0x00, 0xF3, 0x80, 0x0E, + 0x70, 0x01, 0xDE, 0x00, 0x3B, 0x80, 0x3F, 0x70, 0x1F, 0xEE, 0x07, 0xFD, + 0xC1, 0xFF, 0xB8, 0x7E, 0x77, 0x0F, 0x0E, 0xE3, 0xC1, 0xDC, 0x70, 0x3B, + 0x8E, 0x07, 0x71, 0xC0, 0xEE, 0x3C, 0x1D, 0xC3, 0xC3, 0xB8, 0x7F, 0xF7, + 0x07, 0xFF, 0xE0, 0x7F, 0xFC, 0x03, 0xFB, 0xC0, 0x00, 0x38, 0x00, 0x07, + 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x61, 0xF0, 0x3E, 0x1F, 0xFF, 0xC3, + 0xFF, 0xF0, 0x1F, 0xFC, 0x01, 0xFC, 0x00, 0x07, 0xFF, 0x80, 0x00, 0x7F, + 0xFE, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x7F, 0xFE, + 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x01, 0xF7, 0xC0, 0x00, 0x0F, 0xBE, 0x00, + 0x00, 0x7D, 0xF8, 0x00, 0x07, 0xC7, 0xC0, 0x00, 0x3E, 0x3E, 0x00, 0x03, + 0xE0, 0xF8, 0x00, 0x1F, 0x07, 0xC0, 0x00, 0xF0, 0x3F, 0x00, 0x0F, 0x80, + 0xF8, 0x00, 0x7F, 0xFF, 0xC0, 0x07, 0xFF, 0xFF, 0x00, 0x3F, 0xFF, 0xF8, + 0x03, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0x00, 0xF8, 0x00, 0xF8, 0x0F, + 0x80, 0x03, 0xE1, 0xFF, 0x80, 0xFF, 0xDF, 0xFE, 0x0F, 0xFF, 0xFF, 0xF0, + 0x7F, 0xFF, 0xFF, 0x83, 0xFF, 0xDF, 0xF8, 0x0F, 0xFC, 0x7F, 0xFF, 0xC0, + 0x3F, 0xFF, 0xFC, 0x0F, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, + 0xFE, 0x07, 0xC0, 0x1F, 0xC1, 0xF0, 0x01, 0xF0, 0x7C, 0x00, 0x7C, 0x1F, + 0x00, 0x1F, 0x07, 0xC0, 0x0F, 0xC1, 0xF0, 0x07, 0xE0, 0x7F, 0xFF, 0xF0, + 0x1F, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, + 0xFC, 0x1F, 0x00, 0x3F, 0x87, 0xC0, 0x03, 0xF1, 0xF0, 0x00, 0x7C, 0x7C, + 0x00, 0x1F, 0x1F, 0x00, 0x07, 0xC7, 0xC0, 0x03, 0xF7, 0xFF, 0xFF, 0xFB, + 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, + 0x00, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0xE7, 0x01, 0xFF, 0xFF, 0xC1, 0xFF, + 0xFF, 0xE1, 0xFF, 0xFF, 0xF1, 0xFE, 0x07, 0xF8, 0xFC, 0x01, 0xFC, 0xFC, + 0x00, 0x7E, 0x7C, 0x00, 0x1F, 0x7E, 0x00, 0x0F, 0xBE, 0x00, 0x03, 0x9F, + 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, + 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0x1F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xF0, 0x00, 0x39, 0xFC, 0x00, + 0x7C, 0x7F, 0x80, 0xFF, 0x1F, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0x81, 0xFF, + 0xFF, 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x7F, + 0xFF, 0xF0, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xC1, + 0xF0, 0x0F, 0xF0, 0xF8, 0x01, 0xF8, 0x7C, 0x00, 0x7E, 0x3E, 0x00, 0x1F, + 0x1F, 0x00, 0x0F, 0xCF, 0x80, 0x03, 0xE7, 0xC0, 0x01, 0xF3, 0xE0, 0x00, + 0xF9, 0xF0, 0x00, 0x7C, 0xF8, 0x00, 0x3E, 0x7C, 0x00, 0x1F, 0x3E, 0x00, + 0x0F, 0x9F, 0x00, 0x07, 0xCF, 0x80, 0x07, 0xE7, 0xC0, 0x03, 0xE3, 0xE0, + 0x03, 0xF1, 0xF0, 0x07, 0xF1, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, 0xF8, 0xFF, + 0xFF, 0xF8, 0x7F, 0xFF, 0xF0, 0x1F, 0xFF, 0xE0, 0x00, 0x7F, 0xFF, 0xFF, + 0x7F, 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, + 0xF0, 0xF8, 0x00, 0xF8, 0x7C, 0x00, 0x7C, 0x3E, 0x0E, 0x3E, 0x1F, 0x0F, + 0x9F, 0x0F, 0x87, 0xC7, 0x07, 0xC3, 0xE0, 0x03, 0xFF, 0xF0, 0x01, 0xFF, + 0xF8, 0x00, 0xFF, 0xFC, 0x00, 0x7F, 0xFE, 0x00, 0x3F, 0xFF, 0x00, 0x1F, + 0x0F, 0x80, 0x0F, 0x87, 0xC3, 0x87, 0xC1, 0xC3, 0xE3, 0xE0, 0x01, 0xF1, + 0xF0, 0x00, 0xF8, 0xF8, 0x00, 0x7D, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF7, 0xFF, + 0xFF, 0xF8, 0xF8, 0x00, 0x7C, 0x7C, 0x00, 0x3E, 0x3E, 0x00, 0x1F, 0x1F, + 0x07, 0x0F, 0x8F, 0x87, 0xC3, 0x87, 0xC3, 0xE0, 0x03, 0xFF, 0xF0, 0x01, + 0xFF, 0xF8, 0x00, 0xFF, 0xFC, 0x00, 0x7F, 0xFE, 0x00, 0x3F, 0xFF, 0x00, + 0x1F, 0x0F, 0x80, 0x0F, 0x87, 0xC0, 0x07, 0xC3, 0xE0, 0x03, 0xE0, 0xE0, + 0x01, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xFF, 0xF0, 0x01, 0xFF, 0xFC, + 0x00, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0x00, 0x1F, 0xFF, 0x00, 0x00, 0x00, + 0x7F, 0x8E, 0x00, 0xFF, 0xF7, 0x81, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, 0xE1, + 0xFF, 0xFF, 0xF1, 0xFE, 0x03, 0xF8, 0xFC, 0x00, 0xFC, 0xFC, 0x00, 0x3E, + 0x7C, 0x00, 0x1F, 0x7E, 0x00, 0x07, 0x3E, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, 0xF0, 0x0F, + 0xFE, 0xF8, 0x0F, 0xFF, 0xFC, 0x07, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0x00, + 0xFF, 0xFF, 0xC0, 0x01, 0xF3, 0xF0, 0x00, 0xF9, 0xFC, 0x00, 0x7C, 0x7F, + 0x80, 0xFE, 0x3F, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0x80, + 0x7F, 0xFF, 0x00, 0x07, 0xFC, 0x00, 0x3F, 0xE1, 0xFF, 0x1F, 0xFC, 0xFF, + 0xE7, 0xFF, 0x3F, 0xF9, 0xFF, 0xCF, 0xFE, 0x3F, 0xE1, 0xFF, 0x07, 0xC0, + 0x0F, 0x81, 0xF0, 0x03, 0xE0, 0x7C, 0x00, 0xF8, 0x1F, 0x00, 0x3E, 0x07, + 0xC0, 0x0F, 0x81, 0xF0, 0x03, 0xE0, 0x7F, 0xFF, 0xF8, 0x1F, 0xFF, 0xFE, + 0x07, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0xF8, 0x1F, 0x00, + 0x3E, 0x07, 0xC0, 0x0F, 0x81, 0xF0, 0x03, 0xE0, 0x7C, 0x00, 0xF8, 0x1F, + 0x00, 0x3E, 0x07, 0xC0, 0x0F, 0x87, 0xFE, 0x1F, 0xFB, 0xFF, 0xCF, 0xFF, + 0xFF, 0xF3, 0xFF, 0xFF, 0xFC, 0xFF, 0xF7, 0xFE, 0x1F, 0xF8, 0x7F, 0xFF, + 0xDF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF7, 0xFF, 0xFC, 0x03, 0xE0, + 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, + 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, + 0x03, 0xE0, 0x1F, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFD, + 0xFF, 0xFF, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, + 0xE0, 0x3F, 0xFF, 0xF0, 0x0F, 0xFF, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x07, + 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x07, 0xC0, 0xE0, 0x03, 0xE0, 0xF8, 0x01, 0xF0, 0x7C, 0x00, 0xF8, 0x3E, + 0x00, 0x7C, 0x1F, 0x00, 0x3E, 0x0F, 0x80, 0x1F, 0x07, 0xC0, 0x1F, 0x83, + 0xF8, 0x3F, 0x81, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xC0, + 0x07, 0xFF, 0xC0, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0xE0, 0xFF, 0x9F, 0xFE, + 0x3F, 0xFB, 0xFF, 0xC7, 0xFF, 0x7F, 0xF8, 0xFF, 0xE7, 0xFE, 0x0F, 0xF8, + 0x3E, 0x01, 0xF8, 0x07, 0xC0, 0xFE, 0x00, 0xF8, 0x3F, 0x80, 0x1F, 0x0F, + 0xE0, 0x03, 0xE3, 0xF8, 0x00, 0x7D, 0xFC, 0x00, 0x0F, 0xFF, 0x00, 0x01, + 0xFF, 0xF0, 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFF, 0xF0, 0x00, 0xFE, 0x7F, + 0x00, 0x1F, 0x87, 0xF0, 0x03, 0xE0, 0x7E, 0x00, 0x7C, 0x07, 0xE0, 0x0F, + 0x80, 0x7E, 0x01, 0xF0, 0x0F, 0xC0, 0x3E, 0x00, 0xF8, 0x1F, 0xF8, 0x1F, + 0xF7, 0xFF, 0x81, 0xFF, 0xFF, 0xF0, 0x3F, 0xFF, 0xFE, 0x07, 0xFD, 0xFF, + 0x80, 0x7F, 0x00, 0x7F, 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x3F, 0xFF, 0x80, + 0x1F, 0xFF, 0xC0, 0x07, 0xFF, 0xC0, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x0F, 0x80, 0x0E, 0x07, 0xC0, 0x0F, 0x83, 0xE0, 0x07, 0xC1, + 0xF0, 0x03, 0xE0, 0xF8, 0x01, 0xF0, 0x7C, 0x00, 0xF8, 0x3E, 0x00, 0x7D, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xDF, 0xFF, 0xFF, 0xE0, 0x3F, 0x80, 0x03, 0xF8, 0xFF, 0x80, 0x0F, 0xF9, + 0xFF, 0x00, 0x1F, 0xF3, 0xFF, 0x00, 0x7F, 0xE3, 0xFE, 0x00, 0xFF, 0x83, + 0xFE, 0x03, 0xFE, 0x07, 0xFC, 0x07, 0xFC, 0x0F, 0xFC, 0x1F, 0xF8, 0x1F, + 0xF8, 0x3F, 0xF0, 0x3F, 0xF0, 0x7F, 0xE0, 0x7D, 0xF1, 0xF7, 0xC0, 0xFB, + 0xE3, 0xEF, 0x81, 0xF7, 0xEF, 0xDF, 0x03, 0xE7, 0xDF, 0x3E, 0x07, 0xCF, + 0xFE, 0x7C, 0x0F, 0x8F, 0xF8, 0xF8, 0x1F, 0x1F, 0xF1, 0xF0, 0x3E, 0x1F, + 0xE3, 0xE0, 0x7C, 0x3F, 0x87, 0xC0, 0xF8, 0x3F, 0x0F, 0x81, 0xF0, 0x00, + 0x1F, 0x03, 0xE0, 0x00, 0x3E, 0x1F, 0xF8, 0x03, 0xFF, 0x7F, 0xF8, 0x0F, + 0xFF, 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0xE0, 0x3F, 0xFD, 0xFF, 0x80, 0x3F, + 0xF0, 0x7F, 0x00, 0x7F, 0xEF, 0xF8, 0x0F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, + 0xFC, 0x0F, 0xFF, 0x7F, 0xE0, 0x7F, 0xE1, 0xFF, 0x00, 0xF8, 0x1F, 0xF0, + 0x0F, 0x81, 0xFF, 0x80, 0xF8, 0x1F, 0xFC, 0x0F, 0x81, 0xFF, 0xC0, 0xF8, + 0x1F, 0x7E, 0x0F, 0x81, 0xF3, 0xF0, 0xF8, 0x1F, 0x3F, 0x0F, 0x81, 0xF1, + 0xF8, 0xF8, 0x1F, 0x0F, 0xCF, 0x81, 0xF0, 0xFC, 0xF8, 0x1F, 0x07, 0xEF, + 0x81, 0xF0, 0x3F, 0xF8, 0x1F, 0x03, 0xFF, 0x81, 0xF0, 0x1F, 0xF8, 0x1F, + 0x00, 0xFF, 0x81, 0xF0, 0x0F, 0xF8, 0x7F, 0xE0, 0x7F, 0x8F, 0xFF, 0x03, + 0xF8, 0xFF, 0xF0, 0x3F, 0x8F, 0xFF, 0x01, 0xF8, 0x7F, 0xE0, 0x0F, 0x80, + 0x00, 0x3F, 0x80, 0x00, 0x3F, 0xFC, 0x00, 0x0F, 0xFF, 0xE0, 0x03, 0xFF, + 0xFE, 0x00, 0xFF, 0xFF, 0xE0, 0x3F, 0xC1, 0xFE, 0x0F, 0xE0, 0x0F, 0xE1, + 0xF8, 0x00, 0xFC, 0x7E, 0x00, 0x0F, 0xCF, 0x80, 0x00, 0xFB, 0xF0, 0x00, + 0x1F, 0xFC, 0x00, 0x01, 0xFF, 0x80, 0x00, 0x3F, 0xF0, 0x00, 0x07, 0xFE, + 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x1F, 0xF8, 0x00, 0x03, 0xFF, 0x00, 0x00, + 0x7F, 0xF0, 0x00, 0x1F, 0xBE, 0x00, 0x03, 0xE7, 0xE0, 0x00, 0xFC, 0x7E, + 0x00, 0x3F, 0x0F, 0xE0, 0x0F, 0xE0, 0xFF, 0x07, 0xF8, 0x0F, 0xFF, 0xFE, + 0x00, 0xFF, 0xFF, 0x80, 0x0F, 0xFF, 0xE0, 0x00, 0xFF, 0xF8, 0x00, 0x03, + 0xF8, 0x00, 0x7F, 0xFF, 0x80, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xF8, 0xFF, + 0xFF, 0xFC, 0x7F, 0xFF, 0xFE, 0x1F, 0x00, 0xFE, 0x1F, 0x00, 0x3F, 0x1F, + 0x00, 0x1F, 0x1F, 0x00, 0x1F, 0x1F, 0x00, 0x1F, 0x1F, 0x00, 0x1F, 0x1F, + 0x00, 0x3F, 0x1F, 0x00, 0x7E, 0x1F, 0xFF, 0xFE, 0x1F, 0xFF, 0xFC, 0x1F, + 0xFF, 0xF8, 0x1F, 0xFF, 0xF0, 0x1F, 0xFF, 0x80, 0x1F, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x7F, 0xFC, 0x00, 0xFF, + 0xFE, 0x00, 0xFF, 0xFE, 0x00, 0xFF, 0xFE, 0x00, 0x7F, 0xFC, 0x00, 0x00, + 0x3F, 0x80, 0x00, 0x3F, 0xFC, 0x00, 0x0F, 0xFF, 0xE0, 0x03, 0xFF, 0xFE, + 0x00, 0xFF, 0xFF, 0xE0, 0x3F, 0xC1, 0xFE, 0x0F, 0xE0, 0x0F, 0xE1, 0xF8, + 0x00, 0xFC, 0x7E, 0x00, 0x0F, 0xCF, 0x80, 0x00, 0xFB, 0xF0, 0x00, 0x1F, + 0xFC, 0x00, 0x01, 0xFF, 0x80, 0x00, 0x3F, 0xF0, 0x00, 0x07, 0xFE, 0x00, + 0x00, 0xFF, 0xC0, 0x00, 0x1F, 0xF8, 0x00, 0x03, 0xFF, 0x80, 0x00, 0xFD, + 0xF0, 0x00, 0x1F, 0x3F, 0x00, 0x07, 0xE7, 0xF0, 0x01, 0xF8, 0x7F, 0x00, + 0x7F, 0x07, 0xF8, 0x3F, 0xC0, 0xFF, 0xFF, 0xF0, 0x07, 0xFF, 0xFC, 0x00, + 0x7F, 0xFF, 0x00, 0x07, 0xFF, 0xC0, 0x00, 0x7F, 0xC0, 0x00, 0x0F, 0x00, + 0x00, 0x03, 0xFF, 0x87, 0x80, 0xFF, 0xFF, 0xF8, 0x3F, 0xFF, 0xFF, 0x07, + 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xF0, 0x0F, 0x01, 0xF8, 0x00, 0x7F, 0xFF, + 0x80, 0x0F, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xC0, + 0x7F, 0xFF, 0xFE, 0x00, 0xF8, 0x07, 0xE0, 0x0F, 0x80, 0x3F, 0x00, 0xF8, + 0x01, 0xF0, 0x0F, 0x80, 0x1F, 0x00, 0xF8, 0x01, 0xF0, 0x0F, 0x80, 0x3F, + 0x00, 0xF8, 0x0F, 0xE0, 0x0F, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0xC0, 0x0F, + 0xFF, 0xF0, 0x00, 0xFF, 0xFE, 0x00, 0x0F, 0xFF, 0xF0, 0x00, 0xF8, 0x3F, + 0x80, 0x0F, 0x81, 0xFC, 0x00, 0xF8, 0x0F, 0xE0, 0x0F, 0x80, 0x7E, 0x00, + 0xF8, 0x03, 0xF0, 0x7F, 0xF0, 0x1F, 0xEF, 0xFF, 0x81, 0xFF, 0xFF, 0xF8, + 0x0F, 0xFF, 0xFF, 0x80, 0x7F, 0x7F, 0xF0, 0x07, 0xE0, 0x01, 0xFC, 0x70, + 0x1F, 0xFD, 0xE0, 0xFF, 0xFF, 0x87, 0xFF, 0xFE, 0x3F, 0xFF, 0xF8, 0xFC, + 0x0F, 0xE7, 0xE0, 0x1F, 0x9F, 0x00, 0x3E, 0x7C, 0x00, 0xF9, 0xF0, 0x01, + 0xC7, 0xF0, 0x00, 0x0F, 0xF8, 0x00, 0x3F, 0xFF, 0x00, 0x7F, 0xFF, 0x00, + 0xFF, 0xFF, 0x00, 0xFF, 0xFC, 0x00, 0x1F, 0xF8, 0x00, 0x07, 0xE0, 0x00, + 0x0F, 0xDC, 0x00, 0x1F, 0xF8, 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0xC0, 0x0F, + 0xFF, 0xC0, 0xFE, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, 0xCF, 0xFF, 0xFE, 0x1C, + 0xFF, 0xF0, 0x00, 0xFE, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC1, 0xF0, 0x7F, + 0xE0, 0xF8, 0x3F, 0xF0, 0x7C, 0x1F, 0xF8, 0x3E, 0x0F, 0xFC, 0x1F, 0x07, + 0xFE, 0x0F, 0x83, 0xEE, 0x07, 0xC0, 0xE0, 0x03, 0xE0, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, + 0xF0, 0x00, 0x0F, 0xFF, 0x80, 0x0F, 0xFF, 0xE0, 0x07, 0xFF, 0xF0, 0x03, + 0xFF, 0xF8, 0x00, 0xFF, 0xF8, 0x00, 0x7F, 0xE0, 0x7F, 0xEF, 0xFF, 0x0F, + 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0x0F, 0xFF, 0x7F, 0xE0, 0x7F, 0xE1, + 0xF0, 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0xF8, 0x1F, 0x00, + 0x0F, 0x81, 0xF0, 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0xF8, + 0x1F, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0x81, 0xF0, + 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0xF8, 0x1F, 0x00, 0x0F, + 0x81, 0xF0, 0x00, 0xF8, 0x1F, 0x80, 0x1F, 0x80, 0xF8, 0x01, 0xF0, 0x0F, + 0xE0, 0x7F, 0x00, 0x7F, 0xFF, 0xE0, 0x03, 0xFF, 0xFE, 0x00, 0x1F, 0xFF, + 0x80, 0x00, 0xFF, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x7F, 0xE0, 0x1F, 0xFB, + 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFC, 0x0F, 0xFF, 0x7F, + 0xE0, 0x1F, 0xF8, 0x7C, 0x00, 0x0F, 0x80, 0xF8, 0x00, 0x7C, 0x03, 0xE0, + 0x01, 0xF0, 0x07, 0xC0, 0x0F, 0x80, 0x1F, 0x00, 0x3E, 0x00, 0x7E, 0x00, + 0xF8, 0x00, 0xF8, 0x07, 0xC0, 0x03, 0xF0, 0x1F, 0x00, 0x07, 0xC0, 0xF8, + 0x00, 0x1F, 0x03, 0xE0, 0x00, 0x7E, 0x1F, 0x00, 0x00, 0xF8, 0x7C, 0x00, + 0x03, 0xF3, 0xF0, 0x00, 0x07, 0xCF, 0x80, 0x00, 0x1F, 0xBE, 0x00, 0x00, + 0x3F, 0xF0, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x07, + 0xF8, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00, 0xFC, + 0x00, 0x00, 0x7F, 0xE0, 0x7F, 0xEF, 0xFF, 0x0F, 0xFF, 0xFF, 0xF0, 0xFF, + 0xFF, 0xFF, 0x0F, 0xFF, 0x7F, 0xE0, 0x7F, 0xE3, 0xE0, 0x00, 0x3C, 0x3E, + 0x0F, 0x83, 0xC3, 0xE1, 0xF8, 0x3C, 0x3E, 0x1F, 0x87, 0xC3, 0xE1, 0xFC, + 0x7C, 0x3E, 0x3F, 0xC7, 0xC1, 0xE3, 0xFC, 0x7C, 0x1F, 0x3F, 0xE7, 0xC1, + 0xF7, 0xFE, 0x78, 0x1F, 0x7F, 0xE7, 0x81, 0xF7, 0x9F, 0xF8, 0x1F, 0xF9, + 0xFF, 0x81, 0xFF, 0x9F, 0xF8, 0x0F, 0xF9, 0xFF, 0x80, 0xFF, 0x0F, 0xF8, + 0x0F, 0xF0, 0xFF, 0x80, 0xFF, 0x0F, 0xF0, 0x0F, 0xE0, 0x7F, 0x00, 0xFE, + 0x07, 0xF0, 0x0F, 0xE0, 0x7F, 0x00, 0xFC, 0x03, 0xF0, 0x07, 0xC0, 0x3F, + 0x00, 0x7F, 0x80, 0xFF, 0x3F, 0xF0, 0x7F, 0xEF, 0xFC, 0x1F, 0xFB, 0xFF, + 0x07, 0xFE, 0x7F, 0x80, 0xFF, 0x07, 0xE0, 0x3F, 0x00, 0xFC, 0x0F, 0x80, + 0x1F, 0x87, 0xC0, 0x03, 0xF3, 0xE0, 0x00, 0xFF, 0xF8, 0x00, 0x1F, 0xFC, + 0x00, 0x03, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x07, + 0xF0, 0x00, 0x03, 0xFE, 0x00, 0x01, 0xFF, 0xC0, 0x00, 0xFC, 0xF8, 0x00, + 0x7E, 0x3F, 0x00, 0x3F, 0x07, 0xE0, 0x1F, 0x80, 0xFC, 0x07, 0xE0, 0x1F, + 0x07, 0xFC, 0x0F, 0xFB, 0xFF, 0x87, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xF8, + 0x7F, 0xF7, 0xFC, 0x0F, 0xF8, 0x7F, 0x80, 0x7F, 0xBF, 0xF0, 0x3F, 0xFF, + 0xFC, 0x0F, 0xFF, 0xFF, 0x03, 0xFF, 0x7F, 0x80, 0x7F, 0x87, 0xE0, 0x1F, + 0x80, 0xFC, 0x07, 0xC0, 0x1F, 0x03, 0xE0, 0x03, 0xE1, 0xF8, 0x00, 0xFC, + 0x7C, 0x00, 0x1F, 0xBE, 0x00, 0x03, 0xFF, 0x80, 0x00, 0x7F, 0xC0, 0x00, + 0x1F, 0xE0, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x00, + 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x07, 0xC0, 0x00, 0x1F, 0xFF, 0x00, 0x0F, 0xFF, 0xE0, 0x03, + 0xFF, 0xF8, 0x00, 0xFF, 0xFE, 0x00, 0x1F, 0xFF, 0x00, 0x7F, 0xFF, 0xF3, + 0xFF, 0xFF, 0x9F, 0xFF, 0xFC, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0x3E, 0x03, + 0xF1, 0xF0, 0x1F, 0x8F, 0x81, 0xF8, 0x7C, 0x1F, 0x83, 0xE1, 0xF8, 0x0E, + 0x1F, 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, + 0x00, 0xFC, 0x00, 0x0F, 0xE0, 0x70, 0x7E, 0x07, 0xC7, 0xE0, 0x3E, 0x7E, + 0x01, 0xF7, 0xE0, 0x0F, 0xFF, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xFF, 0xBF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xBE, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, + 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, + 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, + 0xFF, 0xBF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x60, 0x00, 0x0F, 0x00, 0x00, + 0xF8, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7E, 0x00, + 0x03, 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x00, 0xF8, + 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x03, + 0xE0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, + 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xF0, + 0x00, 0x1F, 0x00, 0x01, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x07, + 0xC0, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, + 0x1F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0x7F, + 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, + 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, + 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x7F, 0xFF, + 0xFF, 0xFF, 0xFF, 0x7F, 0xC0, 0x00, 0x40, 0x00, 0x06, 0x00, 0x00, 0xF0, + 0x00, 0x1F, 0x80, 0x03, 0xFC, 0x00, 0x7F, 0xE0, 0x0F, 0xFF, 0x00, 0xFF, + 0xF8, 0x1F, 0x9F, 0x83, 0xF0, 0xFC, 0x7E, 0x07, 0xEF, 0xC0, 0x3F, 0xF8, + 0x01, 0xFF, 0x80, 0x0F, 0x70, 0x00, 0x60, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF0, 0xE0, 0x78, 0x3E, 0x0F, 0xC3, 0xF0, 0x7C, 0x1E, 0x06, 0x01, 0xFF, + 0x00, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0xE0, 0x1F, 0xFF, 0xF0, 0x0F, 0xFF, + 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x01, 0xFF, + 0xF8, 0x07, 0xFF, 0xF8, 0x1F, 0xFF, 0xF8, 0x3F, 0xFF, 0xF8, 0x7F, 0xFF, + 0xF8, 0x7F, 0x00, 0xF8, 0xFC, 0x00, 0xF8, 0xF8, 0x00, 0xF8, 0xF8, 0x03, + 0xF8, 0xFC, 0x0F, 0xFE, 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x3F, 0xFF, + 0xFF, 0x1F, 0xFE, 0xFE, 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x00, 0x1F, 0xE0, + 0x00, 0x03, 0xFC, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, + 0x3E, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x0F, + 0xE0, 0x03, 0xEF, 0xFF, 0x00, 0x7F, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0x81, + 0xFF, 0xFF, 0xF8, 0x3F, 0xE0, 0x7F, 0x07, 0xF0, 0x03, 0xF0, 0xFC, 0x00, + 0x3E, 0x1F, 0x80, 0x07, 0xE3, 0xE0, 0x00, 0x7C, 0x7C, 0x00, 0x0F, 0x8F, + 0x80, 0x01, 0xF1, 0xF0, 0x00, 0x3E, 0x3E, 0x00, 0x07, 0xC7, 0xE0, 0x01, + 0xF8, 0xFC, 0x00, 0x3E, 0x1F, 0xC0, 0x0F, 0xCF, 0xFE, 0x07, 0xF3, 0xFF, + 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, 0x8F, 0xFF, 0xFF, 0xE0, 0xFE, 0x7F, 0xF0, + 0x00, 0x03, 0xF8, 0x00, 0x00, 0xFF, 0x18, 0x03, 0xFF, 0xFC, 0x0F, 0xFF, + 0xFC, 0x1F, 0xFF, 0xFC, 0x3F, 0xFF, 0xFC, 0x3F, 0x81, 0xFC, 0x7E, 0x00, + 0x7C, 0x7C, 0x00, 0x7C, 0xFC, 0x00, 0x3C, 0xF8, 0x00, 0x38, 0xF8, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0x7C, 0x00, 0x06, 0x7E, 0x00, 0x1F, 0x7F, 0x80, 0x7F, 0x3F, 0xFF, + 0xFF, 0x1F, 0xFF, 0xFE, 0x0F, 0xFF, 0xFC, 0x07, 0xFF, 0xF8, 0x00, 0xFF, + 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x1F, 0xE0, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0xF8, 0x00, 0xFE, 0x3E, 0x00, 0xFF, 0xEF, 0x80, 0xFF, 0xFF, + 0xE0, 0x7F, 0xFF, 0xF8, 0x3F, 0xFF, 0xFE, 0x1F, 0xE0, 0xFF, 0x87, 0xE0, + 0x0F, 0xE1, 0xF0, 0x01, 0xF8, 0xFC, 0x00, 0x7E, 0x3E, 0x00, 0x0F, 0x8F, + 0x80, 0x03, 0xE3, 0xE0, 0x00, 0xF8, 0xF8, 0x00, 0x3E, 0x3E, 0x00, 0x0F, + 0x8F, 0xC0, 0x07, 0xE1, 0xF0, 0x01, 0xF8, 0x7E, 0x00, 0xFE, 0x0F, 0xE0, + 0x7F, 0xE3, 0xFF, 0xFF, 0xFC, 0x7F, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xC0, + 0xFF, 0xEF, 0xE0, 0x0F, 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x03, 0xFF, 0xC0, + 0x0F, 0xFF, 0xE0, 0x1F, 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, 0x7F, 0x81, 0xFC, + 0x7E, 0x00, 0x7E, 0xFC, 0x00, 0x3E, 0xF8, 0x00, 0x3E, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF8, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7F, 0x80, 0x7E, + 0x3F, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0x0F, 0xFF, 0xFE, 0x07, 0xFF, 0xF8, + 0x00, 0xFF, 0x80, 0x00, 0x3F, 0xE0, 0x03, 0xFF, 0xE0, 0x1F, 0xFF, 0xC0, + 0xFF, 0xFF, 0x07, 0xFF, 0xF8, 0x1F, 0x80, 0x00, 0x7C, 0x00, 0x01, 0xF0, + 0x00, 0x07, 0xC0, 0x01, 0xFF, 0xFF, 0x0F, 0xFF, 0xFE, 0x3F, 0xFF, 0xF8, + 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x07, + 0xC0, 0x00, 0x1F, 0x00, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x07, 0xC0, + 0x00, 0x1F, 0x00, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x07, 0xC0, 0x01, + 0xFF, 0xFF, 0x0F, 0xFF, 0xFE, 0x3F, 0xFF, 0xF8, 0xFF, 0xFF, 0xE1, 0xFF, + 0xFF, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xFF, 0xBF, 0x83, 0xFF, 0xFF, 0xE3, + 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xFB, 0xFC, 0x3F, 0xF9, 0xF8, 0x07, 0xF0, + 0xF8, 0x01, 0xF8, 0xFC, 0x00, 0xFC, 0x7C, 0x00, 0x3E, 0x3E, 0x00, 0x1F, + 0x1F, 0x00, 0x0F, 0x8F, 0x80, 0x07, 0xC7, 0xC0, 0x03, 0xE3, 0xF0, 0x03, + 0xF0, 0xF8, 0x01, 0xF8, 0x7E, 0x01, 0xFC, 0x3F, 0xC3, 0xFE, 0x0F, 0xFF, + 0xFF, 0x03, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xC0, 0x3F, 0xFB, 0xE0, 0x07, + 0xF1, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xFE, 0x00, + 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0x00, 0x3F, 0xFE, 0x00, + 0x0F, 0xFC, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, + 0x03, 0xFC, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x0F, 0xC0, 0x07, 0xCF, 0xFC, 0x01, + 0xF7, 0xFF, 0x80, 0x7F, 0xFF, 0xF0, 0x1F, 0xFF, 0xFC, 0x07, 0xFC, 0x1F, + 0x81, 0xFC, 0x03, 0xE0, 0x7E, 0x00, 0xF8, 0x1F, 0x00, 0x3E, 0x07, 0xC0, + 0x0F, 0x81, 0xF0, 0x03, 0xE0, 0x7C, 0x00, 0xF8, 0x1F, 0x00, 0x3E, 0x07, + 0xC0, 0x0F, 0x81, 0xF0, 0x03, 0xE0, 0x7C, 0x00, 0xF8, 0x1F, 0x00, 0x3E, + 0x1F, 0xF0, 0x3F, 0xEF, 0xFE, 0x1F, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xE1, + 0xFF, 0xDF, 0xF0, 0x3F, 0xE0, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, + 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x1F, 0xF8, 0x01, 0xFF, 0xC0, 0x0F, 0xFE, 0x00, 0x7F, 0xF0, + 0x01, 0xFF, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x00, + 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, + 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x7F, 0xFF, 0xF7, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0x00, 0x00, 0x7C, + 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF7, + 0xFF, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, + 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, + 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, + 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x3F, 0x00, 0x3F, 0xBF, 0xFF, 0xBF, 0xFF, + 0x9F, 0xFF, 0xCF, 0xFF, 0x83, 0xFF, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0x80, + 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xF8, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, + 0x87, 0xFC, 0x07, 0xC7, 0xFF, 0x03, 0xE3, 0xFF, 0x81, 0xF1, 0xFF, 0xC0, + 0xF8, 0x7F, 0xC0, 0x7C, 0xFE, 0x00, 0x3E, 0xFE, 0x00, 0x1F, 0xFE, 0x00, + 0x0F, 0xFE, 0x00, 0x07, 0xFE, 0x00, 0x03, 0xFF, 0x80, 0x01, 0xFF, 0xE0, + 0x00, 0xFF, 0xF8, 0x00, 0x7C, 0xFE, 0x00, 0x3E, 0x3F, 0x80, 0x1F, 0x0F, + 0xE0, 0x3F, 0x81, 0xFF, 0xBF, 0xC1, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xF0, + 0x7F, 0xFB, 0xF8, 0x1F, 0xF8, 0x1F, 0xF8, 0x01, 0xFF, 0xC0, 0x0F, 0xFE, + 0x00, 0x7F, 0xF0, 0x01, 0xFF, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, + 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, + 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x00, + 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, + 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x03, 0xFF, + 0xFF, 0xBF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xBF, 0xFF, 0xF8, + 0x00, 0x3C, 0x1F, 0x00, 0xFD, 0xFC, 0xFF, 0x07, 0xFF, 0xFF, 0xFE, 0x1F, + 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, 0xFF, 0xF0, 0xFF, 0x1F, 0x87, 0xC1, 0xF8, + 0x7E, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, + 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, + 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, + 0x1F, 0x07, 0xC1, 0xF1, 0xFE, 0x1F, 0x87, 0xEF, 0xFC, 0x7F, 0x1F, 0xFF, + 0xF1, 0xFC, 0x7F, 0xFF, 0xC7, 0xF1, 0xFD, 0xFE, 0x1F, 0x87, 0xE0, 0x00, + 0x1F, 0x80, 0x1F, 0x9F, 0xF8, 0x1F, 0xDF, 0xFE, 0x0F, 0xFF, 0xFF, 0x87, + 0xFF, 0xFF, 0xC1, 0xFF, 0x07, 0xF0, 0x7F, 0x01, 0xF8, 0x3F, 0x00, 0x7C, + 0x1F, 0x00, 0x3E, 0x0F, 0x80, 0x1F, 0x07, 0xC0, 0x0F, 0x83, 0xE0, 0x07, + 0xC1, 0xF0, 0x03, 0xE0, 0xF8, 0x01, 0xF0, 0x7C, 0x00, 0xF8, 0x3E, 0x00, + 0x7C, 0x1F, 0x00, 0x3E, 0x3F, 0xE0, 0x7F, 0xBF, 0xF8, 0x7F, 0xFF, 0xFC, + 0x3F, 0xFF, 0xFE, 0x1F, 0xFB, 0xFE, 0x07, 0xF8, 0x00, 0x7F, 0x00, 0x01, + 0xFF, 0xF0, 0x01, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0xC1, + 0xFE, 0x0F, 0xF1, 0xFC, 0x01, 0xFC, 0xFC, 0x00, 0x7E, 0xFC, 0x00, 0x1F, + 0xFC, 0x00, 0x07, 0xFE, 0x00, 0x03, 0xFF, 0x00, 0x01, 0xFF, 0x80, 0x00, + 0xFF, 0xC0, 0x00, 0x7F, 0xF0, 0x00, 0x7E, 0xF8, 0x00, 0x7E, 0x7F, 0x00, + 0x7F, 0x1F, 0xC0, 0xFF, 0x07, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0x80, 0x7F, + 0xFF, 0x00, 0x1F, 0xFF, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x07, 0xE0, 0x03, + 0xF9, 0xFF, 0xC0, 0x7F, 0xBF, 0xFE, 0x07, 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, + 0xFF, 0xC3, 0xFF, 0x83, 0xFC, 0x0F, 0xE0, 0x0F, 0xE0, 0xFC, 0x00, 0x7E, + 0x0F, 0xC0, 0x03, 0xF0, 0xF8, 0x00, 0x1F, 0x0F, 0x80, 0x01, 0xF0, 0xF8, + 0x00, 0x1F, 0x0F, 0x80, 0x01, 0xF0, 0xF8, 0x00, 0x3F, 0x0F, 0xC0, 0x03, + 0xF0, 0xFE, 0x00, 0x7E, 0x0F, 0xF8, 0x1F, 0xE0, 0xFF, 0xFF, 0xFC, 0x0F, + 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xF0, 0x0F, 0x9F, 0xFC, 0x00, 0xF8, 0x7F, + 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x7F, 0xF8, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0xFF, 0xFC, + 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x7F, 0xF8, 0x00, 0x00, 0x00, 0x7E, 0x00, + 0x00, 0x3F, 0xF9, 0xFC, 0x0F, 0xFF, 0xDF, 0xE1, 0xFF, 0xFF, 0xFE, 0x3F, + 0xFF, 0xFF, 0xE3, 0xF8, 0x1F, 0xFC, 0x7F, 0x00, 0x7F, 0x07, 0xC0, 0x03, + 0xF0, 0xFC, 0x00, 0x3F, 0x0F, 0x80, 0x01, 0xF0, 0xF8, 0x00, 0x1F, 0x0F, + 0x80, 0x01, 0xF0, 0xF8, 0x00, 0x1F, 0x0F, 0xC0, 0x01, 0xF0, 0xFC, 0x00, + 0x3F, 0x07, 0xE0, 0x07, 0xF0, 0x7F, 0x81, 0xFF, 0x03, 0xFF, 0xFF, 0xF0, + 0x1F, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xF0, 0x03, 0xFF, 0x9F, 0x00, 0x0F, + 0xE1, 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xFF, 0xE0, 0x00, 0x3F, 0xFF, 0x00, + 0x03, 0xFF, 0xF0, 0x00, 0x3F, 0xFF, 0x00, 0x01, 0xFF, 0xE0, 0x00, 0x01, + 0xF0, 0x3F, 0xC7, 0xFC, 0x7F, 0xCF, 0xFE, 0x7F, 0xDF, 0xFF, 0x7F, 0xFF, + 0xFF, 0x3F, 0xFF, 0x0E, 0x07, 0xFC, 0x00, 0x07, 0xF8, 0x00, 0x07, 0xF0, + 0x00, 0x07, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x07, 0xC0, 0x00, 0x07, 0xC0, + 0x00, 0x07, 0xC0, 0x00, 0x07, 0xC0, 0x00, 0x07, 0xC0, 0x00, 0x07, 0xC0, + 0x00, 0x7F, 0xFF, 0xC0, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, + 0xE0, 0x7F, 0xFF, 0xC0, 0x03, 0xFC, 0x60, 0x7F, 0xFF, 0x87, 0xFF, 0xFC, + 0x7F, 0xFF, 0xE7, 0xFF, 0xFF, 0x3F, 0x01, 0xF9, 0xF0, 0x07, 0xCF, 0xC0, + 0x1C, 0x7F, 0xF0, 0x03, 0xFF, 0xF8, 0x0F, 0xFF, 0xF0, 0x3F, 0xFF, 0xC0, + 0x3F, 0xFF, 0x00, 0x0F, 0xFD, 0xC0, 0x07, 0xFE, 0x00, 0x1F, 0xF8, 0x00, + 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0xFD, 0xFF, 0xFF, 0xEF, 0xFF, 0xFE, 0x3F, + 0xFF, 0xC0, 0x07, 0xF8, 0x00, 0x07, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0xFF, + 0xF8, 0x7F, 0xFF, 0xF8, 0xFF, 0xFF, 0xF1, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, + 0x80, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, + 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x03, 0x83, 0xF0, 0x1F, 0x87, + 0xFF, 0xFF, 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xF8, 0x07, 0xFF, 0xC0, 0x03, + 0xFC, 0x00, 0x7F, 0x01, 0xFE, 0x7F, 0x81, 0xFF, 0x3F, 0xC0, 0xFF, 0x9F, + 0xE0, 0x7F, 0xC7, 0xF0, 0x1F, 0xE0, 0xF8, 0x01, 0xF0, 0x7C, 0x00, 0xF8, + 0x3E, 0x00, 0x7C, 0x1F, 0x00, 0x3E, 0x0F, 0x80, 0x1F, 0x07, 0xC0, 0x0F, + 0x83, 0xE0, 0x07, 0xC1, 0xF0, 0x03, 0xE0, 0xF8, 0x01, 0xF0, 0x7C, 0x01, + 0xF8, 0x3F, 0x01, 0xFC, 0x1F, 0xC1, 0xFF, 0x07, 0xFF, 0xFF, 0xC3, 0xFF, + 0xFF, 0xE0, 0xFF, 0xF7, 0xF0, 0x3F, 0xF3, 0xF0, 0x03, 0xF0, 0x00, 0x7F, + 0xE0, 0x7F, 0xEF, 0xFF, 0x0F, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0x0F, + 0xFF, 0x7F, 0xE0, 0x7F, 0xE0, 0xF8, 0x01, 0xF0, 0x0F, 0xC0, 0x1F, 0x00, + 0x7C, 0x03, 0xE0, 0x07, 0xE0, 0x3E, 0x00, 0x3E, 0x07, 0xC0, 0x03, 0xF0, + 0x7C, 0x00, 0x1F, 0x0F, 0x80, 0x01, 0xF8, 0xF8, 0x00, 0x0F, 0x9F, 0x00, + 0x00, 0xFD, 0xF0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0x03, + 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x1F, 0x80, + 0x00, 0x7F, 0x80, 0x1F, 0xEF, 0xFC, 0x03, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, + 0xFC, 0x03, 0xFF, 0x7F, 0x80, 0x1F, 0xE1, 0xF0, 0xF8, 0x7C, 0x1F, 0x1F, + 0x87, 0xC1, 0xF1, 0xF8, 0xFC, 0x1F, 0x1F, 0xCF, 0x80, 0xFB, 0xFC, 0xF8, + 0x0F, 0xBF, 0xDF, 0x80, 0xFB, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0x00, 0x7F, + 0xDF, 0xF0, 0x07, 0xF9, 0xFF, 0x00, 0x7F, 0x9F, 0xE0, 0x07, 0xF0, 0xFE, + 0x00, 0x3F, 0x0F, 0xE0, 0x03, 0xF0, 0x7E, 0x00, 0x3E, 0x07, 0xC0, 0x03, + 0xE0, 0x3C, 0x00, 0x3F, 0xC0, 0xFF, 0x1F, 0xF8, 0x7F, 0xE7, 0xFE, 0x1F, + 0xF9, 0xFF, 0x87, 0xFE, 0x3F, 0xC0, 0xFF, 0x03, 0xF8, 0x7F, 0x00, 0x7F, + 0x3F, 0x80, 0x0F, 0xFF, 0xC0, 0x01, 0xFF, 0xE0, 0x00, 0x3F, 0xE0, 0x00, + 0x07, 0xF8, 0x00, 0x07, 0xFF, 0x00, 0x03, 0xFF, 0xE0, 0x01, 0xFF, 0xFE, + 0x00, 0xFE, 0x1F, 0xC0, 0x7F, 0x03, 0xF8, 0x7F, 0xC0, 0xFF, 0xBF, 0xF8, + 0x7F, 0xFF, 0xFE, 0x1F, 0xFF, 0xFF, 0x87, 0xFF, 0x7F, 0xC0, 0xFF, 0x80, + 0x7F, 0x80, 0x7F, 0xBF, 0xF0, 0x3F, 0xFF, 0xFC, 0x0F, 0xFF, 0xFF, 0x03, + 0xFF, 0x7F, 0x80, 0x7F, 0x8F, 0xC0, 0x07, 0x81, 0xF0, 0x03, 0xE0, 0x7E, + 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xF0, 0x3E, 0x00, 0x7C, 0x0F, 0x80, + 0x0F, 0x87, 0xC0, 0x03, 0xE1, 0xF0, 0x00, 0x7C, 0xF8, 0x00, 0x1F, 0xFE, + 0x00, 0x03, 0xFF, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x80, 0x00, + 0x07, 0xC0, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x1F, 0xFF, 0x80, + 0x0F, 0xFF, 0xF0, 0x03, 0xFF, 0xFC, 0x00, 0xFF, 0xFF, 0x00, 0x1F, 0xFF, + 0x80, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xF0, 0x3F, 0xBE, 0x0F, 0xC3, 0x83, 0xF0, 0x00, 0xFC, 0x00, + 0x3F, 0x00, 0x0F, 0xC0, 0x03, 0xF0, 0x00, 0xFC, 0x00, 0x3F, 0x00, 0x0F, + 0xC0, 0x3B, 0xF0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x78, 0x03, 0xF0, 0x1F, 0xC0, 0xFF, 0x07, + 0xF8, 0x1F, 0x80, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, + 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x0F, 0x81, 0xFE, 0x0F, + 0xF0, 0x3F, 0x80, 0xFF, 0x01, 0xFE, 0x00, 0xFC, 0x01, 0xF0, 0x07, 0xC0, + 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF8, + 0x07, 0xF8, 0x0F, 0xF0, 0x3F, 0xC0, 0x7F, 0x00, 0x78, 0x77, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xE0, 0x78, 0x03, 0xF0, 0x0F, + 0xE0, 0x3F, 0xC0, 0x7F, 0x00, 0x7E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, + 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, + 0x07, 0xC0, 0x1F, 0xE0, 0x3F, 0xC0, 0x7F, 0x03, 0xFC, 0x1F, 0xE0, 0xFC, + 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, + 0x00, 0xF8, 0x07, 0xE0, 0x7F, 0x83, 0xFC, 0x0F, 0xF0, 0x3F, 0x80, 0x78, + 0x00, 0x07, 0x80, 0x00, 0x7F, 0x80, 0x03, 0xFF, 0x03, 0x9F, 0xFE, 0x1F, + 0xFF, 0xFC, 0xFF, 0xF3, 0xFF, 0xFF, 0x87, 0xFF, 0x9C, 0x0F, 0xFC, 0x00, + 0x0F, 0xE0, 0x00, 0x1F, 0x00 }; + +const GFXglyph FreeMonoBold24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 28, 0, 1 }, // 0x20 ' ' + { 0, 7, 31, 28, 10, -29 }, // 0x21 '!' + { 28, 15, 14, 28, 6, -28 }, // 0x22 '"' + { 55, 22, 34, 28, 3, -30 }, // 0x23 '#' + { 149, 19, 38, 28, 5, -31 }, // 0x24 '$' + { 240, 21, 30, 28, 4, -28 }, // 0x25 '%' + { 319, 21, 28, 28, 4, -26 }, // 0x26 '&' + { 393, 6, 14, 28, 11, -28 }, // 0x27 ''' + { 404, 10, 37, 28, 12, -29 }, // 0x28 '(' + { 451, 10, 37, 28, 6, -29 }, // 0x29 ')' + { 498, 21, 19, 28, 4, -28 }, // 0x2A '*' + { 548, 23, 26, 28, 3, -25 }, // 0x2B '+' + { 623, 9, 14, 28, 7, -6 }, // 0x2C ',' + { 639, 24, 5, 28, 2, -15 }, // 0x2D '-' + { 654, 7, 6, 28, 11, -4 }, // 0x2E '.' + { 660, 20, 38, 28, 4, -32 }, // 0x2F '/' + { 755, 21, 31, 28, 4, -29 }, // 0x30 '0' + { 837, 20, 29, 28, 4, -28 }, // 0x31 '1' + { 910, 21, 30, 28, 3, -29 }, // 0x32 '2' + { 989, 21, 31, 28, 4, -29 }, // 0x33 '3' + { 1071, 20, 28, 28, 4, -27 }, // 0x34 '4' + { 1141, 21, 31, 28, 4, -29 }, // 0x35 '5' + { 1223, 20, 31, 28, 5, -29 }, // 0x36 '6' + { 1301, 20, 30, 28, 4, -29 }, // 0x37 '7' + { 1376, 20, 31, 28, 4, -29 }, // 0x38 '8' + { 1454, 20, 31, 28, 5, -29 }, // 0x39 '9' + { 1532, 7, 22, 28, 11, -20 }, // 0x3A ':' + { 1552, 10, 28, 28, 6, -20 }, // 0x3B ';' + { 1587, 24, 21, 28, 2, -23 }, // 0x3C '<' + { 1650, 24, 14, 28, 2, -19 }, // 0x3D '=' + { 1692, 23, 22, 28, 3, -23 }, // 0x3E '>' + { 1756, 20, 29, 28, 5, -27 }, // 0x3F '?' + { 1829, 19, 36, 28, 4, -28 }, // 0x40 '@' + { 1915, 29, 27, 28, -1, -26 }, // 0x41 'A' + { 2013, 26, 27, 28, 1, -26 }, // 0x42 'B' + { 2101, 25, 29, 28, 2, -27 }, // 0x43 'C' + { 2192, 25, 27, 28, 1, -26 }, // 0x44 'D' + { 2277, 25, 27, 28, 1, -26 }, // 0x45 'E' + { 2362, 25, 27, 28, 1, -26 }, // 0x46 'F' + { 2447, 25, 29, 28, 2, -27 }, // 0x47 'G' + { 2538, 26, 27, 28, 1, -26 }, // 0x48 'H' + { 2626, 19, 27, 28, 5, -26 }, // 0x49 'I' + { 2691, 25, 28, 28, 3, -26 }, // 0x4A 'J' + { 2779, 27, 27, 28, 1, -26 }, // 0x4B 'K' + { 2871, 25, 27, 28, 2, -26 }, // 0x4C 'L' + { 2956, 31, 27, 28, -1, -26 }, // 0x4D 'M' + { 3061, 28, 27, 28, 0, -26 }, // 0x4E 'N' + { 3156, 27, 29, 28, 1, -27 }, // 0x4F 'O' + { 3254, 24, 27, 28, 1, -26 }, // 0x50 'P' + { 3335, 27, 35, 28, 1, -27 }, // 0x51 'Q' + { 3454, 28, 27, 28, 0, -26 }, // 0x52 'R' + { 3549, 22, 29, 28, 3, -27 }, // 0x53 'S' + { 3629, 25, 27, 28, 2, -26 }, // 0x54 'T' + { 3714, 28, 28, 28, 0, -26 }, // 0x55 'U' + { 3812, 30, 27, 28, -1, -26 }, // 0x56 'V' + { 3914, 28, 27, 28, 0, -26 }, // 0x57 'W' + { 4009, 26, 27, 28, 1, -26 }, // 0x58 'X' + { 4097, 26, 27, 28, 1, -26 }, // 0x59 'Y' + { 4185, 21, 27, 28, 4, -26 }, // 0x5A 'Z' + { 4256, 10, 37, 28, 12, -29 }, // 0x5B '[' + { 4303, 20, 38, 28, 4, -32 }, // 0x5C '\' + { 4398, 10, 37, 28, 6, -29 }, // 0x5D ']' + { 4445, 20, 15, 28, 4, -29 }, // 0x5E '^' + { 4483, 28, 5, 28, 0, 5 }, // 0x5F '_' + { 4501, 9, 8, 28, 8, -30 }, // 0x60 '`' + { 4510, 24, 23, 28, 2, -21 }, // 0x61 'a' + { 4579, 27, 31, 28, 0, -29 }, // 0x62 'b' + { 4684, 24, 23, 28, 3, -21 }, // 0x63 'c' + { 4753, 26, 31, 28, 2, -29 }, // 0x64 'd' + { 4854, 24, 23, 28, 2, -21 }, // 0x65 'e' + { 4923, 22, 30, 28, 4, -29 }, // 0x66 'f' + { 5006, 25, 31, 28, 2, -21 }, // 0x67 'g' + { 5103, 26, 30, 28, 1, -29 }, // 0x68 'h' + { 5201, 21, 29, 28, 4, -28 }, // 0x69 'i' + { 5278, 17, 38, 28, 5, -28 }, // 0x6A 'j' + { 5359, 25, 30, 28, 2, -29 }, // 0x6B 'k' + { 5453, 21, 30, 28, 4, -29 }, // 0x6C 'l' + { 5532, 30, 22, 28, -1, -21 }, // 0x6D 'm' + { 5615, 25, 22, 28, 1, -21 }, // 0x6E 'n' + { 5684, 25, 23, 28, 2, -21 }, // 0x6F 'o' + { 5756, 28, 31, 28, 0, -21 }, // 0x70 'p' + { 5865, 28, 31, 28, 1, -21 }, // 0x71 'q' + { 5974, 24, 22, 28, 3, -21 }, // 0x72 'r' + { 6040, 21, 23, 28, 4, -21 }, // 0x73 's' + { 6101, 23, 28, 28, 1, -26 }, // 0x74 't' + { 6182, 25, 22, 28, 1, -20 }, // 0x75 'u' + { 6251, 28, 21, 28, 0, -20 }, // 0x76 'v' + { 6325, 28, 21, 28, 0, -20 }, // 0x77 'w' + { 6399, 26, 21, 28, 1, -20 }, // 0x78 'x' + { 6468, 26, 30, 28, 1, -20 }, // 0x79 'y' + { 6566, 19, 21, 28, 5, -20 }, // 0x7A 'z' + { 6616, 14, 37, 28, 7, -29 }, // 0x7B '{' + { 6681, 5, 36, 28, 12, -28 }, // 0x7C '|' + { 6704, 14, 37, 28, 8, -29 }, // 0x7D '}' + { 6769, 22, 10, 28, 3, -17 } }; // 0x7E '~' + +const GFXfont FreeMonoBold24pt7b PROGMEM = { + (uint8_t *)FreeMonoBold24pt7bBitmaps, + (GFXglyph *)FreeMonoBold24pt7bGlyphs, + 0x20, 0x7E, 47 }; + +// Approx. 7469 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBold9pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBold9pt7b.h new file mode 100644 index 0000000..75b1766 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBold9pt7b.h @@ -0,0 +1,189 @@ +const uint8_t FreeMonoBold9pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xD2, 0x1F, 0x80, 0xEC, 0x89, 0x12, 0x24, 0x40, 0x36, 0x36, + 0x36, 0x7F, 0x7F, 0x36, 0xFF, 0xFF, 0x3C, 0x3C, 0x3C, 0x00, 0x18, 0xFF, + 0xFE, 0x3C, 0x1F, 0x1F, 0x83, 0x46, 0x8D, 0xF0, 0xC1, 0x83, 0x00, 0x61, + 0x22, 0x44, 0x86, 0x67, 0x37, 0x11, 0x22, 0x4C, 0x70, 0x3C, 0x7E, 0x60, + 0x60, 0x30, 0x7B, 0xDF, 0xCE, 0xFF, 0x7F, 0xC9, 0x24, 0x37, 0x66, 0xCC, + 0xCC, 0xCC, 0x66, 0x31, 0xCE, 0x66, 0x33, 0x33, 0x33, 0x66, 0xC8, 0x18, + 0x18, 0xFF, 0xFF, 0x3C, 0x3C, 0x66, 0x18, 0x18, 0x18, 0xFF, 0xFF, 0x18, + 0x18, 0x18, 0x18, 0x6B, 0x48, 0xFF, 0xFF, 0xC0, 0xF0, 0x02, 0x0C, 0x18, + 0x60, 0xC3, 0x06, 0x0C, 0x30, 0x61, 0x83, 0x0C, 0x18, 0x20, 0x00, 0x38, + 0xFB, 0xBE, 0x3C, 0x78, 0xF1, 0xE3, 0xC7, 0xDD, 0xF1, 0xC0, 0x38, 0xF3, + 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0xFD, 0xF8, 0x3C, 0xFE, 0xC7, 0x03, + 0x03, 0x06, 0x0C, 0x18, 0x70, 0xE3, 0xFF, 0xFF, 0x7C, 0xFE, 0x03, 0x03, + 0x03, 0x1E, 0x1E, 0x07, 0x03, 0x03, 0xFE, 0x7C, 0x1C, 0x38, 0xB1, 0x64, + 0xD9, 0xBF, 0xFF, 0x3E, 0x7C, 0x7E, 0x3F, 0x18, 0x0F, 0xC7, 0xF3, 0x1C, + 0x06, 0x03, 0xC3, 0xFF, 0x9F, 0x80, 0x0F, 0x3F, 0x30, 0x60, 0x60, 0xDC, + 0xFE, 0xE3, 0xC3, 0x63, 0x7E, 0x3C, 0xFF, 0xFF, 0xC3, 0x03, 0x06, 0x06, + 0x06, 0x0C, 0x0C, 0x0C, 0x18, 0x38, 0xFB, 0x1E, 0x3C, 0x6F, 0x9F, 0x63, + 0xC7, 0x8F, 0xF1, 0xC0, 0x3C, 0x7E, 0xE6, 0xC3, 0xC3, 0xE7, 0x7F, 0x3B, + 0x06, 0x0E, 0xFC, 0xF0, 0xF0, 0x0F, 0x6C, 0x00, 0x1A, 0xD2, 0x00, 0x01, + 0x83, 0x87, 0x0E, 0x0F, 0x80, 0xE0, 0x1C, 0x03, 0xFF, 0xFF, 0xC0, 0x00, + 0x0F, 0xFF, 0xFC, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0xF9, 0xE3, 0xC1, 0x80, + 0x7C, 0xFE, 0xC7, 0x03, 0x0E, 0x1C, 0x00, 0x00, 0x00, 0x30, 0x30, 0x1E, + 0x1F, 0x1C, 0xDC, 0x6C, 0x76, 0x7B, 0x6D, 0xB6, 0xDB, 0x6F, 0xF3, 0xFC, + 0x06, 0x33, 0xF8, 0x78, 0x3C, 0x07, 0xC0, 0x38, 0x05, 0x81, 0xB0, 0x36, + 0x0F, 0xE1, 0xFC, 0x71, 0xDF, 0x7F, 0xEF, 0x80, 0xFF, 0x3F, 0xE6, 0x19, + 0x86, 0x7F, 0x1F, 0xE6, 0x1D, 0x83, 0x60, 0xFF, 0xFF, 0xF0, 0x1F, 0xBF, + 0xD8, 0xF8, 0x3C, 0x06, 0x03, 0x01, 0x80, 0x61, 0xBF, 0xC7, 0xC0, 0xFE, + 0x3F, 0xE6, 0x19, 0x83, 0x60, 0xD8, 0x36, 0x0D, 0x83, 0x61, 0xBF, 0xEF, + 0xE0, 0xFF, 0xFF, 0xD8, 0x6D, 0xB7, 0xC3, 0xE1, 0xB0, 0xC3, 0x61, 0xFF, + 0xFF, 0xE0, 0xFF, 0xFF, 0xD8, 0x6D, 0xB7, 0xC3, 0xE1, 0xB0, 0xC0, 0x60, + 0x7C, 0x3E, 0x00, 0x1F, 0x9F, 0xE6, 0x1B, 0x06, 0xC0, 0x30, 0x0C, 0x7F, + 0x1F, 0xE1, 0x9F, 0xE3, 0xF0, 0xF7, 0xFB, 0xD8, 0xCC, 0x66, 0x33, 0xF9, + 0xFC, 0xC6, 0x63, 0x7B, 0xFD, 0xE0, 0xFF, 0xF3, 0x0C, 0x30, 0xC3, 0x0C, + 0x33, 0xFF, 0xC0, 0x1F, 0xC7, 0xF0, 0x30, 0x0C, 0x03, 0x00, 0xCC, 0x33, + 0x0C, 0xC7, 0x3F, 0x87, 0xC0, 0xF7, 0xBD, 0xE6, 0x61, 0xB0, 0x78, 0x1F, + 0x06, 0xE1, 0x98, 0x63, 0x3C, 0xFF, 0x3C, 0xFC, 0x7E, 0x0C, 0x06, 0x03, + 0x01, 0x80, 0xC6, 0x63, 0x31, 0xFF, 0xFF, 0xE0, 0xE0, 0xFE, 0x3D, 0xC7, + 0x3D, 0xE7, 0xBC, 0xD7, 0x9B, 0xB3, 0x76, 0x60, 0xDE, 0x3F, 0xC7, 0x80, + 0xE1, 0xFE, 0x3D, 0xE3, 0x3C, 0x66, 0xCC, 0xDD, 0x99, 0xB3, 0x1E, 0x63, + 0xDE, 0x3B, 0xC3, 0x00, 0x1F, 0x07, 0xF1, 0xC7, 0x70, 0x7C, 0x07, 0x80, + 0xF0, 0x1F, 0x07, 0x71, 0xC7, 0xF0, 0x7C, 0x00, 0xFE, 0x7F, 0x98, 0x6C, + 0x36, 0x1B, 0xF9, 0xF8, 0xC0, 0x60, 0x7C, 0x3E, 0x00, 0x1F, 0x07, 0xF1, + 0xC7, 0x70, 0x7C, 0x07, 0x80, 0xF0, 0x1F, 0x07, 0x71, 0xC7, 0xF0, 0x7C, + 0x0C, 0x33, 0xFE, 0x7F, 0x80, 0xFC, 0x7F, 0x18, 0xCC, 0x66, 0x73, 0xF1, + 0xF0, 0xCC, 0x63, 0x7D, 0xFE, 0x60, 0x3F, 0xBF, 0xF0, 0x78, 0x0F, 0x03, + 0xF8, 0x3F, 0x83, 0xC3, 0xFF, 0xBF, 0x80, 0xFF, 0xFF, 0xF6, 0x7B, 0x3D, + 0x98, 0xC0, 0x60, 0x30, 0x18, 0x3F, 0x1F, 0x80, 0xF1, 0xFE, 0x3D, 0x83, + 0x30, 0x66, 0x0C, 0xC1, 0x98, 0x33, 0x06, 0x60, 0xC7, 0xF0, 0x7C, 0x00, + 0xFB, 0xFF, 0x7D, 0xC3, 0x18, 0xC3, 0x18, 0x36, 0x06, 0xC0, 0x50, 0x0E, + 0x01, 0xC0, 0x10, 0x00, 0xFB, 0xFE, 0xF6, 0x0D, 0x93, 0x6E, 0xDB, 0xB7, + 0xAD, 0xEE, 0x7B, 0x8E, 0xE3, 0x18, 0xF3, 0xFC, 0xF7, 0x38, 0xFC, 0x1E, + 0x03, 0x01, 0xE0, 0xCC, 0x73, 0xBC, 0xFF, 0x3C, 0xF3, 0xFC, 0xF7, 0x38, + 0xCC, 0x1E, 0x07, 0x80, 0xC0, 0x30, 0x0C, 0x0F, 0xC3, 0xF0, 0xFE, 0xFE, + 0xC6, 0xCC, 0x18, 0x18, 0x30, 0x63, 0xC3, 0xFF, 0xFF, 0xFF, 0xCC, 0xCC, + 0xCC, 0xCC, 0xCC, 0xFF, 0x01, 0x03, 0x06, 0x06, 0x0C, 0x0C, 0x18, 0x18, + 0x30, 0x30, 0x60, 0x60, 0xC0, 0x80, 0xFF, 0x33, 0x33, 0x33, 0x33, 0x33, + 0xFF, 0x10, 0x71, 0xE3, 0x6C, 0x70, 0x40, 0xFF, 0xFF, 0xFC, 0x88, 0x80, + 0x7E, 0x3F, 0x8F, 0xCF, 0xEE, 0x36, 0x1B, 0xFE, 0xFF, 0xE0, 0x38, 0x06, + 0x01, 0xBC, 0x7F, 0x9C, 0x76, 0x0D, 0x83, 0x71, 0xFF, 0xEE, 0xF0, 0x3F, + 0xBF, 0xF8, 0x78, 0x3C, 0x07, 0x05, 0xFE, 0x7E, 0x03, 0x80, 0xE0, 0x18, + 0xF6, 0x7F, 0xB8, 0xEC, 0x1B, 0x06, 0xE3, 0x9F, 0xF3, 0xFC, 0x3E, 0x3F, + 0xB0, 0xFF, 0xFF, 0xFE, 0x01, 0xFE, 0x7E, 0x1F, 0x3F, 0x30, 0x7E, 0x7E, + 0x30, 0x30, 0x30, 0x30, 0xFE, 0xFE, 0x3F, 0xBF, 0xF9, 0xD8, 0x6C, 0x37, + 0x39, 0xFC, 0x76, 0x03, 0x01, 0x8F, 0xC7, 0xC0, 0xE0, 0x70, 0x18, 0x0D, + 0xC7, 0xF3, 0x99, 0x8C, 0xC6, 0x63, 0x7B, 0xFD, 0xE0, 0x18, 0x18, 0x00, + 0x78, 0x78, 0x18, 0x18, 0x18, 0x18, 0xFF, 0xFF, 0x18, 0x60, 0x3F, 0xFC, + 0x30, 0xC3, 0x0C, 0x30, 0xC3, 0x0F, 0xFF, 0x80, 0xE0, 0x70, 0x18, 0x0D, + 0xE6, 0xF3, 0xE1, 0xE0, 0xF8, 0x6E, 0x73, 0xF9, 0xE0, 0x78, 0x78, 0x18, + 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0xFF, 0xFF, 0xFD, 0x9F, 0xF9, 0x9B, + 0x33, 0x66, 0x6C, 0xCD, 0xBD, 0xFF, 0xBF, 0xEE, 0x7F, 0x98, 0xCC, 0x66, + 0x33, 0x1B, 0xDF, 0xEF, 0x3E, 0x3F, 0xB8, 0xF8, 0x3C, 0x1F, 0x1D, 0xFC, + 0x7C, 0xEF, 0x1F, 0xF9, 0xC3, 0xB0, 0x36, 0x06, 0xE1, 0xDF, 0xF3, 0x78, + 0x60, 0x0C, 0x03, 0xE0, 0x7C, 0x00, 0x1E, 0xEF, 0xFF, 0x87, 0x60, 0x6C, + 0x0D, 0xC3, 0x9F, 0xF0, 0xF6, 0x00, 0xC0, 0x18, 0x0F, 0x81, 0xF0, 0x77, + 0xBF, 0xCF, 0x06, 0x03, 0x01, 0x83, 0xF9, 0xFC, 0x3F, 0xFF, 0xC3, 0xFC, + 0x3F, 0xC3, 0xFF, 0xFC, 0x60, 0x60, 0x60, 0xFE, 0xFE, 0x60, 0x60, 0x60, + 0x61, 0x7F, 0x3E, 0xE7, 0x73, 0x98, 0xCC, 0x66, 0x33, 0x19, 0xFE, 0x7F, + 0xFB, 0xFF, 0x7C, 0xC6, 0x18, 0xC1, 0xB0, 0x36, 0x03, 0x80, 0x70, 0xF1, + 0xFE, 0x3D, 0xBB, 0x37, 0x63, 0xF8, 0x77, 0x0E, 0xE1, 0x8C, 0xF7, 0xFB, + 0xCD, 0x83, 0x83, 0xC3, 0xBB, 0xDF, 0xEF, 0xF3, 0xFC, 0xF6, 0x18, 0xCC, + 0x33, 0x07, 0x81, 0xE0, 0x30, 0x0C, 0x06, 0x0F, 0xC3, 0xF0, 0xFF, 0xFF, + 0x30, 0xC3, 0x0C, 0x7F, 0xFF, 0x37, 0x66, 0x66, 0xCC, 0x66, 0x66, 0x73, + 0xFF, 0xFF, 0xFF, 0xF0, 0xCE, 0x66, 0x66, 0x33, 0x66, 0x66, 0xEC, 0x70, + 0x7C, 0xF3, 0xC0, 0xC0 }; + +const GFXglyph FreeMonoBold9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 11, 0, 1 }, // 0x20 ' ' + { 0, 3, 11, 11, 4, -10 }, // 0x21 '!' + { 5, 7, 5, 11, 2, -10 }, // 0x22 '"' + { 10, 8, 12, 11, 1, -10 }, // 0x23 '#' + { 22, 7, 14, 11, 2, -11 }, // 0x24 '$' + { 35, 7, 11, 11, 2, -10 }, // 0x25 '%' + { 45, 8, 10, 11, 1, -9 }, // 0x26 '&' + { 55, 3, 5, 11, 4, -10 }, // 0x27 ''' + { 57, 4, 14, 11, 5, -10 }, // 0x28 '(' + { 64, 4, 14, 11, 2, -10 }, // 0x29 ')' + { 71, 8, 7, 11, 2, -10 }, // 0x2A '*' + { 78, 8, 9, 11, 2, -8 }, // 0x2B '+' + { 87, 3, 5, 11, 3, -1 }, // 0x2C ',' + { 89, 9, 2, 11, 1, -5 }, // 0x2D '-' + { 92, 2, 2, 11, 4, -1 }, // 0x2E '.' + { 93, 7, 15, 11, 2, -12 }, // 0x2F '/' + { 107, 7, 12, 11, 2, -11 }, // 0x30 '0' + { 118, 7, 11, 11, 2, -10 }, // 0x31 '1' + { 128, 8, 12, 11, 1, -11 }, // 0x32 '2' + { 140, 8, 12, 11, 2, -11 }, // 0x33 '3' + { 152, 7, 10, 11, 2, -9 }, // 0x34 '4' + { 161, 9, 11, 11, 1, -10 }, // 0x35 '5' + { 174, 8, 12, 11, 2, -11 }, // 0x36 '6' + { 186, 8, 11, 11, 1, -10 }, // 0x37 '7' + { 197, 7, 12, 11, 2, -11 }, // 0x38 '8' + { 208, 8, 12, 11, 2, -11 }, // 0x39 '9' + { 220, 2, 8, 11, 4, -7 }, // 0x3A ':' + { 222, 3, 11, 11, 3, -7 }, // 0x3B ';' + { 227, 9, 8, 11, 1, -8 }, // 0x3C '<' + { 236, 9, 6, 11, 1, -7 }, // 0x3D '=' + { 243, 9, 8, 11, 1, -8 }, // 0x3E '>' + { 252, 8, 11, 11, 2, -10 }, // 0x3F '?' + { 263, 9, 15, 11, 1, -11 }, // 0x40 '@' + { 280, 11, 11, 11, 0, -10 }, // 0x41 'A' + { 296, 10, 11, 11, 1, -10 }, // 0x42 'B' + { 310, 9, 11, 11, 1, -10 }, // 0x43 'C' + { 323, 10, 11, 11, 0, -10 }, // 0x44 'D' + { 337, 9, 11, 11, 1, -10 }, // 0x45 'E' + { 350, 9, 11, 11, 1, -10 }, // 0x46 'F' + { 363, 10, 11, 11, 1, -10 }, // 0x47 'G' + { 377, 9, 11, 11, 1, -10 }, // 0x48 'H' + { 390, 6, 11, 11, 3, -10 }, // 0x49 'I' + { 399, 10, 11, 11, 1, -10 }, // 0x4A 'J' + { 413, 10, 11, 11, 1, -10 }, // 0x4B 'K' + { 427, 9, 11, 11, 1, -10 }, // 0x4C 'L' + { 440, 11, 11, 11, 0, -10 }, // 0x4D 'M' + { 456, 11, 11, 11, 0, -10 }, // 0x4E 'N' + { 472, 11, 11, 11, 0, -10 }, // 0x4F 'O' + { 488, 9, 11, 11, 1, -10 }, // 0x50 'P' + { 501, 11, 14, 11, 0, -10 }, // 0x51 'Q' + { 521, 9, 11, 11, 1, -10 }, // 0x52 'R' + { 534, 9, 11, 11, 1, -10 }, // 0x53 'S' + { 547, 9, 11, 11, 1, -10 }, // 0x54 'T' + { 560, 11, 11, 11, 0, -10 }, // 0x55 'U' + { 576, 11, 11, 11, 0, -10 }, // 0x56 'V' + { 592, 10, 11, 11, 0, -10 }, // 0x57 'W' + { 606, 10, 11, 11, 0, -10 }, // 0x58 'X' + { 620, 10, 11, 11, 0, -10 }, // 0x59 'Y' + { 634, 8, 11, 11, 2, -10 }, // 0x5A 'Z' + { 645, 4, 14, 11, 5, -10 }, // 0x5B '[' + { 652, 7, 15, 11, 2, -12 }, // 0x5C '\' + { 666, 4, 14, 11, 2, -10 }, // 0x5D ']' + { 673, 7, 6, 11, 2, -11 }, // 0x5E '^' + { 679, 11, 2, 11, 0, 3 }, // 0x5F '_' + { 682, 3, 3, 11, 3, -11 }, // 0x60 '`' + { 684, 9, 8, 11, 1, -7 }, // 0x61 'a' + { 693, 10, 11, 11, 0, -10 }, // 0x62 'b' + { 707, 9, 8, 11, 1, -7 }, // 0x63 'c' + { 716, 10, 11, 11, 1, -10 }, // 0x64 'd' + { 730, 9, 8, 11, 1, -7 }, // 0x65 'e' + { 739, 8, 11, 11, 2, -10 }, // 0x66 'f' + { 750, 9, 12, 11, 1, -7 }, // 0x67 'g' + { 764, 9, 11, 11, 1, -10 }, // 0x68 'h' + { 777, 8, 11, 11, 2, -10 }, // 0x69 'i' + { 788, 6, 15, 11, 2, -10 }, // 0x6A 'j' + { 800, 9, 11, 11, 1, -10 }, // 0x6B 'k' + { 813, 8, 11, 11, 2, -10 }, // 0x6C 'l' + { 824, 11, 8, 11, 0, -7 }, // 0x6D 'm' + { 835, 9, 8, 11, 1, -7 }, // 0x6E 'n' + { 844, 9, 8, 11, 1, -7 }, // 0x6F 'o' + { 853, 11, 12, 11, 0, -7 }, // 0x70 'p' + { 870, 11, 12, 11, 0, -7 }, // 0x71 'q' + { 887, 9, 8, 11, 1, -7 }, // 0x72 'r' + { 896, 8, 8, 11, 2, -7 }, // 0x73 's' + { 904, 8, 11, 11, 1, -10 }, // 0x74 't' + { 915, 9, 8, 11, 1, -7 }, // 0x75 'u' + { 924, 11, 8, 11, 0, -7 }, // 0x76 'v' + { 935, 11, 8, 11, 0, -7 }, // 0x77 'w' + { 946, 9, 8, 11, 1, -7 }, // 0x78 'x' + { 955, 10, 12, 11, 0, -7 }, // 0x79 'y' + { 970, 7, 8, 11, 2, -7 }, // 0x7A 'z' + { 977, 4, 14, 11, 3, -10 }, // 0x7B '{' + { 984, 2, 14, 11, 5, -10 }, // 0x7C '|' + { 988, 4, 14, 11, 4, -10 }, // 0x7D '}' + { 995, 9, 4, 11, 1, -6 } }; // 0x7E '~' + +const GFXfont FreeMonoBold9pt7b PROGMEM = { + (uint8_t *)FreeMonoBold9pt7bBitmaps, + (GFXglyph *)FreeMonoBold9pt7bGlyphs, + 0x20, 0x7E, 18 }; + +// Approx. 1672 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique12pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique12pt7b.h new file mode 100644 index 0000000..cc3ecb2 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique12pt7b.h @@ -0,0 +1,269 @@ +const uint8_t FreeMonoBoldOblique12pt7bBitmaps[] PROGMEM = { + 0x1C, 0xF3, 0xCE, 0x38, 0xE7, 0x1C, 0x61, 0x86, 0x00, 0x63, 0x8C, 0x00, + 0xE7, 0xE7, 0xE6, 0xC6, 0xC6, 0xC4, 0x84, 0x03, 0x30, 0x19, 0x81, 0xDC, + 0x0C, 0xE0, 0x66, 0x1F, 0xFC, 0xFF, 0xE1, 0x98, 0x0C, 0xC0, 0xEE, 0x06, + 0x70, 0xFF, 0xCF, 0xFE, 0x1D, 0xC0, 0xCC, 0x06, 0x60, 0x77, 0x03, 0x30, + 0x00, 0x01, 0x00, 0x70, 0x0C, 0x07, 0xF1, 0xFE, 0x71, 0xCC, 0x11, 0x80, + 0x3F, 0x03, 0xF0, 0x0F, 0x20, 0x6E, 0x0D, 0xC3, 0x3F, 0xE7, 0xF8, 0x1C, + 0x03, 0x00, 0x60, 0x0C, 0x00, 0x0E, 0x03, 0xE0, 0xC4, 0x10, 0x82, 0x30, + 0x7C, 0x07, 0x78, 0x7C, 0x7F, 0x19, 0xF0, 0x62, 0x08, 0x41, 0x18, 0x3E, + 0x03, 0x80, 0x07, 0xC1, 0xF8, 0x62, 0x0C, 0x01, 0x80, 0x38, 0x0F, 0x03, + 0xF7, 0x6F, 0xD8, 0xF3, 0x1E, 0x7F, 0xE7, 0xF8, 0xFF, 0x6D, 0x20, 0x06, + 0x1C, 0x70, 0xC3, 0x06, 0x18, 0x30, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x30, + 0x70, 0x60, 0xC1, 0x00, 0x0C, 0x18, 0x38, 0x30, 0x60, 0xC1, 0x83, 0x06, + 0x0C, 0x30, 0x61, 0xC3, 0x0E, 0x38, 0x61, 0xC2, 0x00, 0x06, 0x00, 0xC0, + 0x18, 0x3F, 0x7F, 0xFE, 0xFF, 0x07, 0x81, 0xF8, 0x77, 0x0C, 0x60, 0x03, + 0x00, 0x70, 0x07, 0x00, 0x60, 0x06, 0x0F, 0xFF, 0xFF, 0xF0, 0xE0, 0x0C, + 0x00, 0xC0, 0x0C, 0x01, 0xC0, 0x18, 0x00, 0x1C, 0xE3, 0x1C, 0x63, 0x08, + 0x00, 0x7F, 0xFF, 0xFF, 0xC0, 0x7F, 0x00, 0x00, 0x08, 0x00, 0x70, 0x01, + 0x80, 0x0E, 0x00, 0x70, 0x03, 0x80, 0x0C, 0x00, 0x70, 0x03, 0x80, 0x0C, + 0x00, 0x70, 0x03, 0x80, 0x0C, 0x00, 0x70, 0x03, 0x80, 0x0C, 0x00, 0x70, + 0x03, 0x80, 0x0C, 0x00, 0x20, 0x00, 0x07, 0x83, 0xF8, 0xE3, 0x98, 0x37, + 0x06, 0xC0, 0xD8, 0x1B, 0x03, 0xE0, 0xF8, 0x1B, 0x03, 0x60, 0xEE, 0x38, + 0xFE, 0x0F, 0x00, 0x03, 0xC1, 0xF0, 0x7E, 0x0C, 0xC0, 0x38, 0x07, 0x00, + 0xC0, 0x18, 0x07, 0x00, 0xE0, 0x18, 0x03, 0x00, 0x61, 0xFF, 0xFF, 0xF0, + 0x03, 0xE0, 0x3F, 0x83, 0x8E, 0x38, 0x31, 0x81, 0x80, 0x18, 0x01, 0xC0, + 0x1C, 0x01, 0xC0, 0x38, 0x03, 0x80, 0x38, 0x47, 0x87, 0x3F, 0xF3, 0xFF, + 0x80, 0x07, 0xC1, 0xFF, 0x18, 0x70, 0x03, 0x00, 0x30, 0x06, 0x07, 0xC0, + 0x7C, 0x00, 0xE0, 0x06, 0x00, 0x60, 0x06, 0xC1, 0xCF, 0xF8, 0x7E, 0x00, + 0x01, 0xE0, 0x3C, 0x0F, 0x03, 0x60, 0xCC, 0x3B, 0x8E, 0x63, 0x8C, 0x61, + 0x9F, 0xFB, 0xFF, 0x01, 0x81, 0xF8, 0x3F, 0x00, 0x0F, 0xF1, 0xFE, 0x18, + 0x01, 0x80, 0x18, 0x03, 0xF8, 0x3F, 0xC3, 0x8E, 0x00, 0x60, 0x06, 0x00, + 0x60, 0x0C, 0xC1, 0xCF, 0xF8, 0x7E, 0x00, 0x03, 0xE1, 0xFC, 0x70, 0x1C, + 0x03, 0x00, 0xC0, 0x1B, 0xC7, 0xFC, 0xF3, 0x98, 0x33, 0x06, 0x60, 0xCE, + 0x30, 0xFC, 0x0F, 0x00, 0xFF, 0xFF, 0xFB, 0x07, 0x60, 0xC0, 0x38, 0x06, + 0x01, 0xC0, 0x30, 0x0E, 0x01, 0x80, 0x70, 0x1C, 0x03, 0x80, 0x60, 0x08, + 0x00, 0x07, 0x83, 0xF8, 0xE3, 0xB0, 0x36, 0x06, 0xC0, 0xDC, 0x31, 0xFC, + 0x3F, 0x8C, 0x3B, 0x03, 0x60, 0x6C, 0x39, 0xFE, 0x1F, 0x00, 0x07, 0x81, + 0xF8, 0x63, 0x98, 0x33, 0x06, 0x60, 0xCE, 0x79, 0xFF, 0x1E, 0xC0, 0x18, + 0x06, 0x01, 0xC0, 0x71, 0xFC, 0x3E, 0x00, 0x19, 0xCC, 0x00, 0x00, 0x00, + 0x67, 0x30, 0x06, 0x1C, 0x30, 0x00, 0x00, 0x00, 0x00, 0x38, 0x71, 0xC3, + 0x0E, 0x18, 0x20, 0x00, 0x00, 0x18, 0x03, 0xC0, 0x7C, 0x1F, 0x03, 0xE0, + 0x3E, 0x00, 0x7C, 0x01, 0xF0, 0x03, 0xE0, 0x07, 0x80, 0x08, 0x7F, 0xFB, + 0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFB, 0xFF, 0xC0, 0x30, 0x01, + 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x3E, 0x00, 0x7C, 0x1F, 0x03, 0xE0, 0x7C, + 0x07, 0x80, 0x20, 0x00, 0x3E, 0x7F, 0xB0, 0xF8, 0x30, 0x18, 0x1C, 0x1C, + 0x3C, 0x38, 0x18, 0x00, 0x06, 0x07, 0x03, 0x00, 0x03, 0xC0, 0x7E, 0x0C, + 0x71, 0x83, 0x30, 0x33, 0x0F, 0x33, 0xE6, 0x76, 0x6C, 0x66, 0xC6, 0x6C, + 0x6C, 0xFC, 0xC7, 0xEC, 0x00, 0xC0, 0x0C, 0x00, 0xE3, 0x07, 0xF0, 0x3C, + 0x00, 0x07, 0xF0, 0x1F, 0xE0, 0x07, 0xC0, 0x1F, 0x80, 0x3B, 0x00, 0xE7, + 0x01, 0x8E, 0x07, 0x1C, 0x1F, 0xF8, 0x3F, 0xF0, 0xE0, 0x71, 0x80, 0xEF, + 0xC7, 0xFF, 0x8F, 0xC0, 0x3F, 0xF1, 0xFF, 0xC3, 0x06, 0x38, 0x31, 0xC1, + 0x8C, 0x18, 0x7F, 0xC3, 0xFE, 0x38, 0x39, 0xC0, 0xCC, 0x06, 0x60, 0x6F, + 0xFF, 0x7F, 0xE0, 0x03, 0xEC, 0x3F, 0xF1, 0xC3, 0x8C, 0x06, 0x60, 0x19, + 0x80, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x03, 0x00, 0x0C, 0x03, 0x3C, 0x1C, + 0x7F, 0xE0, 0x7E, 0x00, 0x3F, 0xE1, 0xFF, 0x87, 0x0C, 0x30, 0x31, 0x81, + 0x8C, 0x0C, 0xE0, 0x67, 0x03, 0x30, 0x31, 0x81, 0x8C, 0x0C, 0xE1, 0xCF, + 0xFC, 0x7F, 0x80, 0x1F, 0xFE, 0x3F, 0xFC, 0x38, 0x38, 0x70, 0x70, 0xCC, + 0xC1, 0x98, 0x03, 0xF0, 0x0F, 0xE0, 0x1D, 0x80, 0x31, 0x18, 0x60, 0x70, + 0xC0, 0xE7, 0xFF, 0x9F, 0xFF, 0x00, 0x1F, 0xFF, 0x1F, 0xFE, 0x0E, 0x06, + 0x0C, 0x0E, 0x0C, 0xC4, 0x0C, 0xC0, 0x1F, 0xC0, 0x1F, 0xC0, 0x19, 0xC0, + 0x19, 0x80, 0x18, 0x00, 0x38, 0x00, 0xFF, 0x00, 0xFF, 0x00, 0x07, 0xEC, + 0x7F, 0xF3, 0x83, 0x9C, 0x06, 0x60, 0x19, 0x80, 0x0C, 0x00, 0x30, 0xFE, + 0xC3, 0xFB, 0x01, 0xCC, 0x07, 0x3C, 0x38, 0x7F, 0xE0, 0x7E, 0x00, 0x0F, + 0xBF, 0x1F, 0xBE, 0x0E, 0x0C, 0x0C, 0x0C, 0x0C, 0x1C, 0x0C, 0x1C, 0x1F, + 0xF8, 0x1F, 0xF8, 0x18, 0x18, 0x18, 0x38, 0x18, 0x38, 0x38, 0x30, 0x7C, + 0xFC, 0xFC, 0xF8, 0x3F, 0xF3, 0xFF, 0x03, 0x00, 0x70, 0x07, 0x00, 0x60, + 0x06, 0x00, 0x60, 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xC0, 0xFF, 0xCF, 0xFC, + 0x03, 0xFF, 0x03, 0xFF, 0x00, 0x38, 0x00, 0x30, 0x00, 0x30, 0x00, 0x30, + 0x00, 0x70, 0x20, 0x70, 0x60, 0x60, 0x60, 0x60, 0x60, 0xE0, 0xE1, 0xC0, + 0xFF, 0x80, 0x3F, 0x00, 0x1F, 0x9F, 0x1F, 0x9E, 0x0E, 0x38, 0x0C, 0x70, + 0x0C, 0xE0, 0x0F, 0xC0, 0x1F, 0xC0, 0x1F, 0xE0, 0x1C, 0xE0, 0x18, 0x60, + 0x18, 0x70, 0x38, 0x70, 0xFE, 0x3C, 0xFC, 0x3C, 0x3F, 0xC1, 0xFE, 0x01, + 0x80, 0x1C, 0x00, 0xE0, 0x06, 0x00, 0x30, 0x01, 0x80, 0x1C, 0x18, 0xE0, + 0xC6, 0x06, 0x30, 0x7F, 0xFF, 0xFF, 0xF8, 0x1E, 0x07, 0x87, 0x81, 0xE0, + 0xF0, 0xF0, 0x7C, 0x7C, 0x1F, 0x1F, 0x06, 0xCF, 0x81, 0xBF, 0x60, 0xEF, + 0x98, 0x3B, 0xEE, 0x0C, 0x73, 0x83, 0x1C, 0xC0, 0xC0, 0x30, 0xFC, 0x7E, + 0x3F, 0x1F, 0x80, 0x3C, 0x3F, 0x3E, 0x3F, 0x1E, 0x0C, 0x1F, 0x1C, 0x1F, + 0x1C, 0x1B, 0x98, 0x3B, 0x98, 0x3B, 0x98, 0x31, 0xF8, 0x31, 0xF8, 0x30, + 0xF0, 0x70, 0xF0, 0xFC, 0x70, 0xF8, 0x70, 0x03, 0xE0, 0x3F, 0xE1, 0xC3, + 0x8C, 0x07, 0x60, 0x0D, 0x80, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x1B, 0x00, + 0x6E, 0x03, 0x1C, 0x38, 0x7F, 0xC0, 0x7C, 0x00, 0x3F, 0xE1, 0xFF, 0x83, + 0x0E, 0x38, 0x31, 0xC1, 0x8C, 0x0C, 0x60, 0xC3, 0xFC, 0x3F, 0xC1, 0xC0, + 0x0C, 0x00, 0x60, 0x0F, 0xF0, 0x7F, 0x80, 0x03, 0xE0, 0x3F, 0xE1, 0xC3, + 0x8C, 0x07, 0x60, 0x0D, 0x80, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x1B, 0x00, + 0x6E, 0x03, 0x1C, 0x38, 0x7F, 0xC0, 0xFC, 0x03, 0x02, 0x1F, 0xFC, 0xFF, + 0xE0, 0x1F, 0xF0, 0x3F, 0xF0, 0x38, 0x70, 0x60, 0x60, 0xC0, 0xC1, 0x87, + 0x07, 0xFC, 0x0F, 0xF0, 0x18, 0xF0, 0x30, 0xE0, 0x60, 0xC1, 0xC1, 0xCF, + 0xE1, 0xFF, 0xC3, 0xC0, 0x0F, 0xB1, 0xFF, 0x30, 0xE6, 0x06, 0x60, 0x67, + 0x80, 0x7F, 0x01, 0xFC, 0x01, 0xC4, 0x0C, 0xC0, 0xCE, 0x18, 0xFF, 0x8B, + 0xE0, 0x7F, 0xFB, 0xFF, 0xD9, 0xCF, 0xCE, 0x7C, 0x63, 0x63, 0x18, 0x18, + 0x01, 0xC0, 0x0E, 0x00, 0x60, 0x03, 0x00, 0x18, 0x0F, 0xF8, 0x7F, 0xC0, + 0x7E, 0xFF, 0xF3, 0xF3, 0x03, 0x1C, 0x0C, 0x60, 0x31, 0x81, 0xC6, 0x06, + 0x38, 0x18, 0xE0, 0x63, 0x03, 0x8C, 0x0C, 0x30, 0x70, 0x7F, 0x80, 0xF8, + 0x00, 0xFC, 0x7F, 0xF8, 0xFD, 0xC0, 0x61, 0x81, 0xC3, 0x87, 0x07, 0x0C, + 0x0E, 0x38, 0x0C, 0x60, 0x19, 0xC0, 0x3F, 0x00, 0x7C, 0x00, 0xF8, 0x00, + 0xE0, 0x01, 0x80, 0x00, 0x7E, 0x7E, 0xFC, 0xFD, 0xC0, 0x73, 0x9C, 0xE7, + 0x79, 0x8E, 0xF7, 0x1B, 0xEE, 0x36, 0xD8, 0x7D, 0xF0, 0xF3, 0xE1, 0xE7, + 0x83, 0x8F, 0x07, 0x1E, 0x1C, 0x38, 0x00, 0x1F, 0x1F, 0x1F, 0x1F, 0x0E, + 0x1C, 0x07, 0x38, 0x07, 0x70, 0x03, 0xE0, 0x03, 0xC0, 0x03, 0xC0, 0x07, + 0xE0, 0x0E, 0xE0, 0x1C, 0x70, 0x38, 0x70, 0xFC, 0xFC, 0xFC, 0xFC, 0xF8, + 0xFF, 0xC7, 0xCC, 0x38, 0x73, 0x83, 0x9C, 0x0F, 0xC0, 0x7C, 0x01, 0xC0, + 0x0C, 0x00, 0x60, 0x03, 0x00, 0x38, 0x0F, 0xF8, 0x7F, 0x80, 0x0F, 0xF8, + 0x7F, 0xE1, 0xC7, 0x86, 0x1C, 0x18, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xC0, + 0x0E, 0x00, 0x70, 0xC3, 0x83, 0x1C, 0x1C, 0x7F, 0xF3, 0xFF, 0x80, 0x0F, + 0x87, 0xC3, 0x03, 0x81, 0xC0, 0xC0, 0x60, 0x30, 0x38, 0x1C, 0x0C, 0x06, + 0x03, 0x03, 0x81, 0xC0, 0xC0, 0x60, 0x3E, 0x3F, 0x00, 0x41, 0xC3, 0x83, + 0x07, 0x0E, 0x1C, 0x18, 0x38, 0x70, 0xE0, 0xC1, 0xC3, 0x83, 0x06, 0x0E, + 0x1C, 0x18, 0x20, 0x1F, 0x0F, 0x80, 0xC0, 0xE0, 0x70, 0x30, 0x18, 0x0C, + 0x0E, 0x07, 0x03, 0x01, 0x80, 0xC0, 0xE0, 0x70, 0x30, 0x18, 0x7C, 0x3E, + 0x00, 0x02, 0x01, 0x80, 0xF0, 0x7E, 0x3B, 0x9C, 0x7E, 0x1F, 0x03, 0xFF, + 0xFF, 0xFF, 0xFC, 0xCE, 0x73, 0x1F, 0xC3, 0xFE, 0x00, 0x60, 0x06, 0x0F, + 0xE3, 0xFE, 0x70, 0xCC, 0x0C, 0xC3, 0xCF, 0xFF, 0x7F, 0xF0, 0x1E, 0x00, + 0x3C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xDF, 0x81, 0xFF, 0x83, 0xC3, 0x8F, + 0x03, 0x1C, 0x06, 0x38, 0x0C, 0x70, 0x18, 0xE0, 0x63, 0xE1, 0x9F, 0xFE, + 0x3D, 0xF8, 0x00, 0x0F, 0xF3, 0xFF, 0x30, 0x76, 0x07, 0xE0, 0x6C, 0x00, + 0xC0, 0x0C, 0x00, 0xE0, 0x67, 0xFE, 0x3F, 0x80, 0x00, 0x3C, 0x00, 0xF0, + 0x01, 0xC0, 0x06, 0x07, 0xD8, 0x7F, 0xE3, 0x0F, 0x98, 0x1E, 0x60, 0x73, + 0x01, 0xCC, 0x07, 0x30, 0x3C, 0xE1, 0xF1, 0xFF, 0xE3, 0xF7, 0x80, 0x0F, + 0xC1, 0xFE, 0x78, 0x76, 0x03, 0xFF, 0xFF, 0xFF, 0xC0, 0x0C, 0x00, 0xE0, + 0xE7, 0xFE, 0x1F, 0x80, 0x00, 0xFC, 0x07, 0xF8, 0x0C, 0x00, 0x38, 0x01, + 0xFF, 0x07, 0xFE, 0x01, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x18, 0x00, 0x30, + 0x00, 0x60, 0x01, 0xC0, 0x1F, 0xF8, 0x3F, 0xF0, 0x00, 0x0F, 0xBC, 0x7F, + 0xF3, 0x0F, 0x18, 0x1C, 0xC0, 0x73, 0x01, 0x8C, 0x0E, 0x30, 0x38, 0xE3, + 0xE1, 0xFF, 0x83, 0xEC, 0x00, 0x30, 0x01, 0xC0, 0x06, 0x07, 0xF0, 0x1F, + 0x80, 0x1E, 0x01, 0xF0, 0x03, 0x00, 0x18, 0x00, 0xDE, 0x0F, 0xF8, 0x78, + 0xC3, 0x86, 0x18, 0x30, 0xC1, 0x8E, 0x1C, 0x70, 0xE3, 0x06, 0x7E, 0xFF, + 0xE7, 0xE0, 0x03, 0x80, 0x70, 0x00, 0x0F, 0xC1, 0xF0, 0x06, 0x00, 0xC0, + 0x38, 0x07, 0x00, 0xC0, 0x18, 0x03, 0x0F, 0xFF, 0xFF, 0xC0, 0x00, 0x70, + 0x07, 0x00, 0x00, 0xFF, 0x1F, 0xF0, 0x07, 0x00, 0x70, 0x06, 0x00, 0x60, + 0x06, 0x00, 0xE0, 0x0E, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x1C, 0x03, 0x87, + 0xF0, 0xFE, 0x00, 0x1E, 0x00, 0x78, 0x00, 0xE0, 0x03, 0x80, 0x0C, 0xFC, + 0x33, 0xE0, 0xDE, 0x07, 0xE0, 0x1F, 0x00, 0x7C, 0x01, 0xF8, 0x06, 0xF0, + 0x39, 0xC3, 0xE7, 0xEF, 0x1F, 0x80, 0x0F, 0x81, 0xF0, 0x06, 0x01, 0xC0, + 0x38, 0x06, 0x00, 0xC0, 0x18, 0x07, 0x00, 0xE0, 0x18, 0x03, 0x00, 0x61, + 0xFF, 0xFF, 0xF8, 0x3F, 0xBC, 0x7F, 0xFC, 0xF3, 0x98, 0xC6, 0x33, 0x9C, + 0xE7, 0x39, 0xCC, 0x63, 0x18, 0xC6, 0x31, 0x8D, 0xF7, 0xBF, 0xEF, 0x78, + 0x3D, 0xE1, 0xFF, 0x8F, 0x8C, 0x38, 0x61, 0x83, 0x0C, 0x18, 0xE1, 0xC7, + 0x0E, 0x30, 0x67, 0xEF, 0xFE, 0x7E, 0x07, 0xC1, 0xFE, 0x38, 0x76, 0x03, + 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x06, 0xE1, 0xC7, 0xF8, 0x3E, 0x00, 0x1E, + 0xFC, 0x1F, 0xFE, 0x0F, 0x87, 0x0F, 0x03, 0x0E, 0x03, 0x0E, 0x03, 0x0E, + 0x07, 0x0E, 0x06, 0x1F, 0x0C, 0x1F, 0xF8, 0x19, 0xF0, 0x18, 0x00, 0x18, + 0x00, 0x38, 0x00, 0xFE, 0x00, 0xFE, 0x00, 0x0F, 0xDE, 0x3F, 0xFC, 0xC3, + 0xE3, 0x03, 0x84, 0x07, 0x18, 0x0E, 0x30, 0x1C, 0x60, 0x78, 0xE1, 0xE0, + 0xFF, 0xC0, 0xF9, 0x80, 0x03, 0x00, 0x0E, 0x00, 0x1C, 0x01, 0xFC, 0x03, + 0xF8, 0x1E, 0x78, 0x7F, 0xF0, 0x7C, 0xC3, 0xC0, 0x0E, 0x00, 0x30, 0x00, + 0xC0, 0x03, 0x00, 0x1C, 0x03, 0xFF, 0x0F, 0xFC, 0x00, 0x07, 0xF1, 0xFF, + 0x30, 0x73, 0x86, 0x3F, 0x81, 0xFE, 0x03, 0xE6, 0x06, 0xE0, 0xEF, 0xFC, + 0xFF, 0x00, 0x0C, 0x07, 0x01, 0x83, 0xFF, 0xFF, 0xCE, 0x03, 0x00, 0xC0, + 0x30, 0x1C, 0x07, 0x01, 0x83, 0x7F, 0xCF, 0xC0, 0xF0, 0xFF, 0x1F, 0x60, + 0x76, 0x07, 0x60, 0x76, 0x06, 0x60, 0x66, 0x0E, 0x61, 0xE7, 0xFF, 0x3E, + 0xF0, 0x7E, 0x7E, 0xFC, 0xFC, 0xE0, 0xC0, 0xC3, 0x81, 0x86, 0x03, 0x98, + 0x07, 0x70, 0x06, 0xC0, 0x0F, 0x80, 0x1E, 0x00, 0x38, 0x00, 0xF8, 0x7F, + 0xE3, 0xE6, 0x63, 0x1B, 0xDC, 0x6F, 0x61, 0xFF, 0x87, 0xFC, 0x1E, 0xF0, + 0x73, 0x81, 0xCE, 0x06, 0x38, 0x00, 0x3E, 0x7C, 0xF9, 0xF1, 0xE7, 0x03, + 0xF8, 0x07, 0xC0, 0x1F, 0x01, 0xFC, 0x0F, 0x38, 0x78, 0xFB, 0xF7, 0xEF, + 0x9F, 0x80, 0x1F, 0x1F, 0x3E, 0x1F, 0x1C, 0x1C, 0x0C, 0x18, 0x0E, 0x38, + 0x0E, 0x70, 0x06, 0x60, 0x07, 0xE0, 0x07, 0xC0, 0x07, 0xC0, 0x03, 0x80, + 0x07, 0x00, 0x07, 0x00, 0x0E, 0x00, 0xFF, 0x00, 0xFF, 0x00, 0x1F, 0xF1, + 0xFF, 0x38, 0xE3, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC6, 0x38, 0x67, + 0xFE, 0x7F, 0xE0, 0x01, 0xC0, 0xF0, 0x70, 0x18, 0x06, 0x03, 0x80, 0xE0, + 0x30, 0x1C, 0x3E, 0x0F, 0x00, 0x60, 0x18, 0x06, 0x03, 0x80, 0xC0, 0x30, + 0x0F, 0x01, 0xC0, 0x0C, 0x71, 0xC7, 0x18, 0x63, 0x8E, 0x30, 0xC3, 0x1C, + 0x71, 0x86, 0x38, 0xE3, 0x04, 0x00, 0x0E, 0x07, 0x80, 0xC0, 0x60, 0x70, + 0x30, 0x18, 0x0C, 0x06, 0x01, 0xC1, 0xE1, 0xC0, 0xC0, 0xE0, 0x70, 0x30, + 0x38, 0x78, 0x38, 0x00, 0x3C, 0x27, 0xE6, 0xEF, 0xCC, 0x38 }; + +const GFXglyph FreeMonoBoldOblique12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 14, 0, 1 }, // 0x20 ' ' + { 0, 6, 15, 14, 6, -14 }, // 0x21 '!' + { 12, 8, 7, 14, 6, -13 }, // 0x22 '"' + { 19, 13, 18, 14, 2, -15 }, // 0x23 '#' + { 49, 11, 20, 14, 3, -16 }, // 0x24 '$' + { 77, 11, 15, 14, 3, -14 }, // 0x25 '%' + { 98, 11, 13, 14, 2, -12 }, // 0x26 '&' + { 116, 3, 7, 14, 8, -13 }, // 0x27 ''' + { 119, 7, 19, 14, 7, -14 }, // 0x28 '(' + { 136, 7, 19, 14, 2, -14 }, // 0x29 ')' + { 153, 11, 10, 14, 4, -14 }, // 0x2A '*' + { 167, 12, 13, 14, 3, -12 }, // 0x2B '+' + { 187, 6, 7, 14, 3, -2 }, // 0x2C ',' + { 193, 13, 2, 14, 2, -7 }, // 0x2D '-' + { 197, 3, 3, 14, 6, -2 }, // 0x2E '.' + { 199, 14, 20, 14, 2, -16 }, // 0x2F '/' + { 234, 11, 15, 14, 3, -14 }, // 0x30 '0' + { 255, 11, 15, 14, 2, -14 }, // 0x31 '1' + { 276, 13, 15, 14, 1, -14 }, // 0x32 '2' + { 301, 12, 15, 14, 2, -14 }, // 0x33 '3' + { 324, 11, 14, 14, 3, -13 }, // 0x34 '4' + { 344, 12, 15, 14, 2, -14 }, // 0x35 '5' + { 367, 11, 15, 14, 4, -14 }, // 0x36 '6' + { 388, 11, 15, 14, 4, -14 }, // 0x37 '7' + { 409, 11, 15, 14, 3, -14 }, // 0x38 '8' + { 430, 11, 15, 14, 3, -14 }, // 0x39 '9' + { 451, 5, 11, 14, 5, -10 }, // 0x3A ':' + { 458, 7, 15, 14, 3, -10 }, // 0x3B ';' + { 472, 13, 11, 14, 2, -11 }, // 0x3C '<' + { 490, 13, 7, 14, 2, -9 }, // 0x3D '=' + { 502, 13, 11, 14, 2, -11 }, // 0x3E '>' + { 520, 9, 14, 14, 5, -13 }, // 0x3F '?' + { 536, 12, 19, 14, 2, -14 }, // 0x40 '@' + { 565, 15, 14, 14, 0, -13 }, // 0x41 'A' + { 592, 13, 14, 14, 1, -13 }, // 0x42 'B' + { 615, 14, 14, 14, 2, -13 }, // 0x43 'C' + { 640, 13, 14, 14, 1, -13 }, // 0x44 'D' + { 663, 15, 14, 14, 0, -13 }, // 0x45 'E' + { 690, 16, 14, 14, 0, -13 }, // 0x46 'F' + { 718, 14, 14, 14, 1, -13 }, // 0x47 'G' + { 743, 16, 14, 14, 0, -13 }, // 0x48 'H' + { 771, 12, 14, 14, 2, -13 }, // 0x49 'I' + { 792, 16, 14, 14, 0, -13 }, // 0x4A 'J' + { 820, 16, 14, 14, 0, -13 }, // 0x4B 'K' + { 848, 13, 14, 14, 1, -13 }, // 0x4C 'L' + { 871, 18, 14, 14, 0, -13 }, // 0x4D 'M' + { 903, 16, 14, 14, 1, -13 }, // 0x4E 'N' + { 931, 14, 14, 14, 1, -13 }, // 0x4F 'O' + { 956, 13, 14, 14, 1, -13 }, // 0x50 'P' + { 979, 14, 17, 14, 1, -13 }, // 0x51 'Q' + { 1009, 15, 14, 14, 0, -13 }, // 0x52 'R' + { 1036, 12, 14, 14, 3, -13 }, // 0x53 'S' + { 1057, 13, 14, 14, 2, -13 }, // 0x54 'T' + { 1080, 14, 14, 14, 2, -13 }, // 0x55 'U' + { 1105, 15, 14, 14, 1, -13 }, // 0x56 'V' + { 1132, 15, 14, 14, 1, -13 }, // 0x57 'W' + { 1159, 16, 14, 14, 0, -13 }, // 0x58 'X' + { 1187, 13, 14, 14, 2, -13 }, // 0x59 'Y' + { 1210, 14, 14, 14, 1, -13 }, // 0x5A 'Z' + { 1235, 9, 19, 14, 5, -14 }, // 0x5B '[' + { 1257, 7, 20, 14, 5, -16 }, // 0x5C '\' + { 1275, 9, 19, 14, 3, -14 }, // 0x5D ']' + { 1297, 10, 8, 14, 4, -15 }, // 0x5E '^' + { 1307, 15, 2, 14, -1, 4 }, // 0x5F '_' + { 1311, 4, 4, 14, 7, -15 }, // 0x60 '`' + { 1313, 12, 11, 14, 2, -10 }, // 0x61 'a' + { 1330, 15, 15, 14, -1, -14 }, // 0x62 'b' + { 1359, 12, 11, 14, 2, -10 }, // 0x63 'c' + { 1376, 14, 15, 14, 2, -14 }, // 0x64 'd' + { 1403, 12, 11, 14, 2, -10 }, // 0x65 'e' + { 1420, 15, 15, 14, 2, -14 }, // 0x66 'f' + { 1449, 14, 16, 14, 2, -10 }, // 0x67 'g' + { 1477, 13, 15, 14, 1, -14 }, // 0x68 'h' + { 1502, 11, 14, 14, 2, -13 }, // 0x69 'i' + { 1522, 12, 19, 14, 1, -13 }, // 0x6A 'j' + { 1551, 14, 15, 14, 1, -14 }, // 0x6B 'k' + { 1578, 11, 15, 14, 2, -14 }, // 0x6C 'l' + { 1599, 15, 11, 14, 0, -10 }, // 0x6D 'm' + { 1620, 13, 11, 14, 1, -10 }, // 0x6E 'n' + { 1638, 12, 11, 14, 2, -10 }, // 0x6F 'o' + { 1655, 16, 16, 14, -1, -10 }, // 0x70 'p' + { 1687, 15, 16, 14, 1, -10 }, // 0x71 'q' + { 1717, 14, 11, 14, 1, -10 }, // 0x72 'r' + { 1737, 12, 11, 14, 2, -10 }, // 0x73 's' + { 1754, 10, 14, 14, 2, -13 }, // 0x74 't' + { 1772, 12, 11, 14, 2, -10 }, // 0x75 'u' + { 1789, 15, 11, 14, 1, -10 }, // 0x76 'v' + { 1810, 14, 11, 14, 2, -10 }, // 0x77 'w' + { 1830, 14, 11, 14, 1, -10 }, // 0x78 'x' + { 1850, 16, 16, 14, 0, -10 }, // 0x79 'y' + { 1882, 12, 11, 14, 2, -10 }, // 0x7A 'z' + { 1899, 10, 19, 14, 4, -14 }, // 0x7B '{' + { 1923, 6, 19, 14, 5, -14 }, // 0x7C '|' + { 1938, 9, 19, 14, 3, -14 }, // 0x7D '}' + { 1960, 12, 4, 14, 3, -7 } }; // 0x7E '~' + +const GFXfont FreeMonoBoldOblique12pt7b PROGMEM = { + (uint8_t *)FreeMonoBoldOblique12pt7bBitmaps, + (GFXglyph *)FreeMonoBoldOblique12pt7bGlyphs, + 0x20, 0x7E, 24 }; + +// Approx. 2638 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique18pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique18pt7b.h new file mode 100644 index 0000000..bc4f20e --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique18pt7b.h @@ -0,0 +1,460 @@ +const uint8_t FreeMonoBoldOblique18pt7bBitmaps[] PROGMEM = { + 0x0F, 0x07, 0xC7, 0xE3, 0xF1, 0xF0, 0xF8, 0xFC, 0x7C, 0x3E, 0x1F, 0x0F, + 0x07, 0x87, 0xC3, 0xC1, 0xE0, 0x60, 0x00, 0x38, 0x3E, 0x1F, 0x0F, 0x83, + 0x80, 0xF8, 0xFF, 0x0E, 0xF1, 0xEF, 0x1E, 0xE1, 0xCE, 0x1C, 0xC1, 0xCC, + 0x18, 0xC1, 0x88, 0x18, 0x00, 0xE3, 0x80, 0x79, 0xE0, 0x1C, 0x70, 0x07, + 0x1C, 0x03, 0xCF, 0x00, 0xF3, 0xC0, 0x38, 0xE0, 0x7F, 0xFF, 0x3F, 0xFF, + 0xCF, 0xFF, 0xF3, 0xFF, 0xF8, 0x3C, 0xF0, 0x0F, 0x3C, 0x03, 0x8E, 0x0F, + 0xFF, 0xE3, 0xFF, 0xFC, 0xFF, 0xFF, 0x3F, 0xFF, 0x83, 0xCF, 0x00, 0xF3, + 0xC0, 0x38, 0xE0, 0x1E, 0x78, 0x07, 0x9E, 0x01, 0xC7, 0x00, 0x71, 0xC0, + 0x00, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x07, 0x80, 0x03, 0xF0, 0x03, 0xFF, + 0x81, 0xFF, 0xF0, 0xFF, 0xF8, 0x3C, 0x1E, 0x1E, 0x07, 0x87, 0x80, 0x01, + 0xF0, 0x00, 0x7F, 0xC0, 0x0F, 0xFC, 0x01, 0xFF, 0x80, 0x07, 0xF0, 0x00, + 0x3C, 0x70, 0x0F, 0x3C, 0x03, 0xCF, 0x83, 0xE3, 0xFF, 0xF8, 0xFF, 0xFC, + 0x3F, 0xFE, 0x0C, 0xFE, 0x00, 0x1C, 0x00, 0x07, 0x00, 0x03, 0xC0, 0x00, + 0xF0, 0x00, 0x18, 0x00, 0x03, 0xC0, 0x0F, 0xE0, 0x1C, 0x70, 0x30, 0x30, + 0x30, 0x30, 0x30, 0x70, 0x38, 0xE0, 0x1F, 0xC3, 0x0F, 0x1F, 0x01, 0xFC, + 0x0F, 0xE0, 0x7F, 0x00, 0xF8, 0xF0, 0x83, 0xF8, 0x07, 0x1C, 0x0E, 0x0C, + 0x0C, 0x0C, 0x0C, 0x1C, 0x0E, 0x38, 0x07, 0xF0, 0x03, 0xC0, 0x00, 0x7A, + 0x01, 0xFF, 0x03, 0xFF, 0x07, 0xFE, 0x0F, 0x9C, 0x0F, 0x00, 0x0F, 0x00, + 0x0F, 0x00, 0x07, 0x80, 0x1F, 0x80, 0x3F, 0xC0, 0x7F, 0xCF, 0x79, 0xFF, + 0xF1, 0xFE, 0xF1, 0xFC, 0xF0, 0xF8, 0xFF, 0xFE, 0xFF, 0xFE, 0x7F, 0xFE, + 0x1F, 0xBC, 0x7B, 0xFD, 0xEF, 0x73, 0x9C, 0xC6, 0x00, 0x01, 0xC0, 0xF0, + 0x3C, 0x1E, 0x0F, 0x03, 0xC1, 0xE0, 0x70, 0x3C, 0x0F, 0x07, 0x81, 0xE0, + 0x78, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3E, + 0x07, 0x81, 0xE0, 0x7C, 0x1F, 0x03, 0x80, 0x07, 0x03, 0xC0, 0xF8, 0x3E, + 0x07, 0x81, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, + 0xF0, 0x78, 0x1E, 0x07, 0x81, 0xC0, 0xF0, 0x3C, 0x1E, 0x07, 0x83, 0xC1, + 0xE0, 0x78, 0x3C, 0x0E, 0x00, 0x00, 0xC0, 0x03, 0xC0, 0x07, 0x00, 0x0E, + 0x02, 0x3C, 0x0F, 0xFF, 0xFF, 0xFF, 0xBF, 0xFE, 0x1F, 0xF0, 0x1F, 0x80, + 0x7F, 0x81, 0xEF, 0x07, 0x8F, 0x0F, 0x1E, 0x08, 0x10, 0x00, 0x00, 0x70, + 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xE0, 0x00, 0x38, 0x00, + 0x1E, 0x03, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x0F, + 0x00, 0x03, 0xC0, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x07, 0x80, + 0x01, 0xC0, 0x00, 0x70, 0x00, 0x0F, 0x87, 0x87, 0x83, 0x83, 0xC1, 0xC1, + 0xC0, 0xC0, 0xE0, 0x60, 0x00, 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFE, 0x77, 0xFF, 0xF7, 0x00, 0x00, 0x00, 0x38, 0x00, 0x03, 0xC0, + 0x00, 0x1C, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xE0, 0x00, 0x0F, + 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x07, 0x80, 0x00, + 0x78, 0x00, 0x03, 0xC0, 0x00, 0x3C, 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, + 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0xF0, + 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x07, 0x80, 0x00, 0x78, 0x00, 0x03, + 0xC0, 0x00, 0x3C, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x00, 0xFC, 0x01, 0xFF, + 0x01, 0xFF, 0xC1, 0xFF, 0xE1, 0xF1, 0xF9, 0xE0, 0x7C, 0xF0, 0x1E, 0xF0, + 0x0F, 0x78, 0x07, 0xB8, 0x03, 0x9C, 0x03, 0xDE, 0x01, 0xCF, 0x00, 0xE7, + 0x00, 0x73, 0xC0, 0x79, 0xE0, 0x3C, 0xF0, 0x1C, 0x78, 0x1E, 0x3E, 0x1E, + 0x0F, 0xFF, 0x07, 0xFF, 0x01, 0xFF, 0x00, 0x7E, 0x00, 0x00, 0x7C, 0x03, + 0xF8, 0x0F, 0xE0, 0x7F, 0xC0, 0xF7, 0x81, 0x8F, 0x00, 0x1C, 0x00, 0x38, + 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x0E, 0x00, 0x3C, 0x00, + 0x78, 0x00, 0xF0, 0x01, 0xC0, 0x03, 0x81, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xEF, 0xFF, 0xC0, 0x00, 0x1F, 0x00, 0x07, 0xFC, 0x00, 0xFF, 0xE0, 0x1F, + 0xFF, 0x03, 0xC1, 0xF0, 0x78, 0x0F, 0x07, 0x80, 0xF0, 0x70, 0x0F, 0x00, + 0x01, 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x3F, 0x00, + 0x07, 0xE0, 0x01, 0xFC, 0x00, 0x3F, 0x80, 0x07, 0xE0, 0x01, 0xF8, 0x00, + 0x3F, 0x03, 0x87, 0xFF, 0xF8, 0x7F, 0xFF, 0x87, 0xFF, 0xF8, 0xFF, 0xFF, + 0x00, 0x00, 0xFE, 0x00, 0xFF, 0xC0, 0x7F, 0xF8, 0x3F, 0xFF, 0x0E, 0x07, + 0xC0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, 0x00, 0x07, 0x80, 0x1F, 0xC0, + 0x0F, 0xE0, 0x03, 0xF0, 0x00, 0xFF, 0x00, 0x03, 0xE0, 0x00, 0x78, 0x00, + 0x1E, 0x00, 0x07, 0x80, 0x03, 0xC0, 0x03, 0xF1, 0xFF, 0xF8, 0xFF, 0xFC, + 0x3F, 0xFE, 0x03, 0xFE, 0x00, 0x00, 0x1F, 0x00, 0x3F, 0x00, 0x7F, 0x00, + 0xFE, 0x00, 0xFE, 0x01, 0xEE, 0x03, 0xDE, 0x07, 0x9E, 0x0F, 0x1C, 0x1E, + 0x1C, 0x3C, 0x3C, 0x78, 0x3C, 0xFF, 0xFE, 0xFF, 0xFE, 0xFF, 0xFE, 0xFF, + 0xFC, 0x00, 0x70, 0x03, 0xFC, 0x07, 0xFC, 0x07, 0xFC, 0x07, 0xF8, 0x07, + 0xFF, 0xC1, 0xFF, 0xF0, 0x7F, 0xFC, 0x3F, 0xFE, 0x0F, 0x00, 0x03, 0xC0, + 0x00, 0xE0, 0x00, 0x3B, 0xE0, 0x1F, 0xFE, 0x07, 0xFF, 0xC1, 0xFF, 0xF8, + 0x78, 0x3E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, + 0x0F, 0x18, 0x0F, 0xCF, 0xFF, 0xE3, 0xFF, 0xF0, 0x7F, 0xF8, 0x07, 0xF0, + 0x00, 0x00, 0x0F, 0xC0, 0x0F, 0xFC, 0x03, 0xFF, 0x81, 0xFF, 0xE0, 0x7F, + 0x00, 0x1F, 0x80, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x9F, + 0x01, 0xEF, 0xF0, 0x3F, 0xFF, 0x0F, 0xFF, 0xF1, 0xFC, 0x3E, 0x3E, 0x03, + 0xC7, 0x80, 0x78, 0xF0, 0x0F, 0x1E, 0x03, 0xC3, 0xE0, 0xF8, 0x7F, 0xFE, + 0x07, 0xFF, 0x80, 0x7F, 0xE0, 0x07, 0xF0, 0x00, 0x7F, 0xFF, 0x7F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x0E, 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x3C, + 0x00, 0x78, 0x00, 0x70, 0x00, 0xF0, 0x00, 0xE0, 0x01, 0xE0, 0x01, 0xC0, + 0x03, 0xC0, 0x07, 0x80, 0x07, 0x80, 0x0F, 0x00, 0x0E, 0x00, 0x1E, 0x00, + 0x1C, 0x00, 0x1C, 0x00, 0x00, 0x7E, 0x00, 0x3F, 0xF0, 0x0F, 0xFF, 0x03, + 0xFF, 0xF0, 0xF8, 0x3E, 0x3E, 0x03, 0xC7, 0x80, 0x78, 0xF0, 0x0F, 0x1E, + 0x03, 0xC3, 0xE0, 0xF0, 0x3F, 0xFC, 0x03, 0xFF, 0x00, 0xFF, 0xE0, 0x7F, + 0xFE, 0x1F, 0x83, 0xE3, 0xC0, 0x3C, 0xF0, 0x07, 0x9E, 0x01, 0xF3, 0xE0, + 0x7C, 0x7F, 0xFF, 0x87, 0xFF, 0xE0, 0x7F, 0xF0, 0x03, 0xF8, 0x00, 0x00, + 0x7E, 0x00, 0x7F, 0xC0, 0x3F, 0xF8, 0x1F, 0xFE, 0x0F, 0x87, 0xC3, 0xC0, + 0xF1, 0xE0, 0x3C, 0x78, 0x0F, 0x1E, 0x03, 0xC7, 0x81, 0xF1, 0xF1, 0xFC, + 0x7F, 0xFE, 0x0F, 0xFF, 0x81, 0xFD, 0xE0, 0x3E, 0xF0, 0x00, 0x7C, 0x00, + 0x3E, 0x00, 0x1F, 0x00, 0x1F, 0x81, 0xFF, 0xC0, 0xFF, 0xE0, 0x3F, 0xE0, + 0x07, 0xE0, 0x00, 0x1C, 0x7C, 0xF9, 0xF1, 0xC0, 0x00, 0x00, 0x00, 0x00, + 0x03, 0x8F, 0x9F, 0x3E, 0x38, 0x01, 0xC0, 0x7C, 0x0F, 0x81, 0xF0, 0x3C, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xC0, 0xF0, 0x1E, + 0x07, 0x80, 0xE0, 0x38, 0x07, 0x01, 0xC0, 0x30, 0x0E, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xFC, 0x00, 0xFE, 0x00, 0xFE, 0x00, + 0xFE, 0x01, 0xFE, 0x01, 0xFE, 0x00, 0xFE, 0x00, 0x0F, 0xE0, 0x00, 0xFE, + 0x00, 0x1F, 0xC0, 0x01, 0xFC, 0x00, 0x1F, 0xC0, 0x01, 0xF0, 0x00, 0x38, + 0x3F, 0xFF, 0xEF, 0xFF, 0xFD, 0xFF, 0xFF, 0x9F, 0xFF, 0xE0, 0x00, 0x00, + 0x00, 0x00, 0x1F, 0xFF, 0xF7, 0xFF, 0xFE, 0xFF, 0xFF, 0xDF, 0xFF, 0xF0, + 0x00, 0x00, 0x03, 0x80, 0x00, 0xFC, 0x00, 0x0F, 0xE0, 0x00, 0x7F, 0x00, + 0x07, 0xF0, 0x00, 0x3F, 0x80, 0x01, 0xFC, 0x00, 0x1F, 0xC0, 0x0F, 0xE0, + 0x07, 0xF0, 0x07, 0xF8, 0x03, 0xF8, 0x01, 0xFC, 0x00, 0x3E, 0x00, 0x07, + 0x00, 0x00, 0x07, 0xE0, 0xFF, 0xC7, 0xFF, 0xBF, 0xFF, 0xF0, 0x7F, 0x80, + 0xFE, 0x03, 0xC0, 0x0F, 0x00, 0x78, 0x0F, 0xE1, 0xFE, 0x0F, 0xF0, 0x7E, + 0x01, 0xE0, 0x07, 0x00, 0x00, 0x00, 0x70, 0x03, 0xE0, 0x0F, 0x80, 0x3E, + 0x00, 0x70, 0x00, 0x00, 0x3E, 0x00, 0x3F, 0xE0, 0x1F, 0xF8, 0x0F, 0x0F, + 0x07, 0x01, 0xC3, 0x80, 0x71, 0xE0, 0x1C, 0x70, 0x0E, 0x18, 0x0F, 0x8E, + 0x1F, 0xE3, 0x8F, 0xF0, 0xE7, 0x9C, 0x33, 0xC7, 0x1C, 0xE1, 0xC7, 0x38, + 0x71, 0xCF, 0x18, 0x73, 0xFE, 0x38, 0x7F, 0xCE, 0x0F, 0xF3, 0x80, 0x00, + 0xE0, 0x00, 0x38, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0xC0, 0x7F, 0xF0, 0x0F, + 0xF8, 0x01, 0xF8, 0x00, 0x01, 0xFF, 0x80, 0x07, 0xFE, 0x00, 0x1F, 0xF8, + 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x00, 0x07, 0xBC, 0x00, + 0x1C, 0xF0, 0x00, 0xF3, 0xC0, 0x07, 0x87, 0x80, 0x1E, 0x1E, 0x00, 0xF0, + 0x78, 0x07, 0xFF, 0xE0, 0x1F, 0xFF, 0x80, 0xFF, 0xFF, 0x07, 0xFF, 0xFC, + 0x1E, 0x00, 0xF1, 0xFE, 0x1F, 0xFF, 0xF8, 0x7F, 0xFF, 0xE1, 0xFF, 0xFF, + 0x07, 0xF8, 0x0F, 0xFF, 0xC0, 0x7F, 0xFF, 0x87, 0xFF, 0xFC, 0x1F, 0xFF, + 0xF0, 0x38, 0x0F, 0x81, 0xC0, 0x3C, 0x1E, 0x01, 0xE0, 0xF0, 0x3E, 0x07, + 0xFF, 0xE0, 0x3F, 0xFE, 0x03, 0xFF, 0xF8, 0x1F, 0xFF, 0xE0, 0xE0, 0x1F, + 0x87, 0x00, 0x3C, 0x38, 0x01, 0xE3, 0xC0, 0x0F, 0x1E, 0x00, 0xF3, 0xFF, + 0xFF, 0xBF, 0xFF, 0xF9, 0xFF, 0xFF, 0x8F, 0xFF, 0xF0, 0x00, 0x00, 0x7F, + 0x30, 0x0F, 0xFF, 0xC1, 0xFF, 0xFE, 0x1F, 0xFF, 0xF1, 0xF8, 0x3F, 0x1F, + 0x00, 0x78, 0xF0, 0x03, 0xCF, 0x80, 0x1C, 0x78, 0x00, 0x03, 0xC0, 0x00, + 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, + 0x00, 0x1F, 0x00, 0x38, 0x7E, 0x07, 0xC3, 0xFF, 0xFC, 0x0F, 0xFF, 0xC0, + 0x3F, 0xFC, 0x00, 0x7F, 0x80, 0x00, 0x0F, 0xFF, 0x80, 0x7F, 0xFE, 0x07, + 0xFF, 0xF8, 0x1F, 0xFF, 0xE0, 0x78, 0x1F, 0x03, 0x80, 0x7C, 0x1C, 0x01, + 0xE1, 0xE0, 0x0F, 0x0F, 0x00, 0x78, 0x70, 0x03, 0xC3, 0x80, 0x1E, 0x1C, + 0x00, 0xF1, 0xE0, 0x0F, 0x0F, 0x00, 0x78, 0x70, 0x07, 0xC3, 0x80, 0x7C, + 0x3C, 0x07, 0xC3, 0xFF, 0xFC, 0x3F, 0xFF, 0xC1, 0xFF, 0xFC, 0x0F, 0xFF, + 0x80, 0x00, 0x07, 0xFF, 0xFC, 0x3F, 0xFF, 0xF0, 0xFF, 0xFF, 0xC3, 0xFF, + 0xFF, 0x03, 0xC0, 0x3C, 0x0F, 0x00, 0xE0, 0x3C, 0x73, 0x80, 0xE3, 0xCC, + 0x03, 0xFF, 0x00, 0x1F, 0xFC, 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0x80, 0x07, + 0x1E, 0x00, 0x3C, 0x70, 0x00, 0xF0, 0x07, 0x03, 0xC0, 0x1C, 0x0E, 0x00, + 0xF1, 0xFF, 0xFF, 0xC7, 0xFF, 0xFE, 0x3F, 0xFF, 0xF8, 0x7F, 0xFF, 0xE0, + 0x07, 0xFF, 0xFE, 0x1F, 0xFF, 0xFC, 0x3F, 0xFF, 0xF0, 0x7F, 0xFF, 0xE0, + 0x3C, 0x01, 0xC0, 0x70, 0x07, 0x80, 0xE1, 0x8E, 0x03, 0xC7, 0x1C, 0x07, + 0xFE, 0x00, 0x0F, 0xFC, 0x00, 0x1F, 0xF8, 0x00, 0x3F, 0xF0, 0x00, 0xF1, + 0xC0, 0x01, 0xE3, 0x80, 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0xFF, 0xE0, 0x03, 0xFF, 0xC0, 0x07, 0xFF, 0x80, 0x0F, 0xFE, 0x00, + 0x00, 0x00, 0x3F, 0x18, 0x0F, 0xFF, 0xC0, 0xFF, 0xFE, 0x0F, 0xFF, 0xF0, + 0xFC, 0x0F, 0x0F, 0x80, 0x38, 0xF8, 0x01, 0x87, 0x80, 0x00, 0x78, 0x00, + 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x7F, 0xEF, 0x07, 0xFF, 0x78, + 0x3F, 0xFB, 0xC0, 0xFF, 0x9E, 0x00, 0x38, 0xFC, 0x03, 0xC3, 0xFF, 0xFE, + 0x1F, 0xFF, 0xE0, 0x3F, 0xFC, 0x00, 0x7F, 0x80, 0x00, 0x03, 0xF8, 0xFE, + 0x0F, 0xF3, 0xFC, 0x1F, 0xE7, 0xF8, 0x3F, 0x8F, 0xE0, 0x3C, 0x07, 0x80, + 0x70, 0x0E, 0x00, 0xE0, 0x1C, 0x03, 0xC0, 0x78, 0x07, 0x80, 0xF0, 0x0F, + 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x3F, 0xFF, 0x00, 0xFF, 0xFE, 0x01, 0xE0, + 0x3C, 0x03, 0x80, 0x70, 0x07, 0x00, 0xE0, 0x1E, 0x03, 0xC0, 0xFF, 0x1F, + 0xE1, 0xFE, 0x7F, 0xC7, 0xFC, 0xFF, 0x87, 0xF1, 0xFE, 0x00, 0x07, 0xFF, + 0xE1, 0xFF, 0xFC, 0x3F, 0xFF, 0x87, 0xFF, 0xE0, 0x07, 0x80, 0x00, 0xE0, + 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0x80, + 0x00, 0x70, 0x00, 0x1E, 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x0E, 0x00, + 0x01, 0xC0, 0x0F, 0xFF, 0xC3, 0xFF, 0xF8, 0x7F, 0xFF, 0x07, 0xFF, 0xE0, + 0x00, 0x3F, 0xFE, 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x03, 0xFF, 0xE0, + 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, 0x01, 0xE0, 0x00, + 0x03, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x80, 0x1C, 0x03, 0x80, + 0x78, 0x0F, 0x00, 0xF0, 0x1E, 0x01, 0xC0, 0x38, 0x07, 0x80, 0x70, 0x1F, + 0x01, 0xFF, 0xFC, 0x03, 0xFF, 0xF0, 0x03, 0xFF, 0xC0, 0x00, 0xFC, 0x00, + 0x00, 0x07, 0xF8, 0xFC, 0x1F, 0xFB, 0xFC, 0x3F, 0xE7, 0xF0, 0x7F, 0xCF, + 0xE0, 0x3C, 0x1E, 0x00, 0x70, 0xF8, 0x00, 0xE3, 0xE0, 0x03, 0xCF, 0x00, + 0x07, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xF0, 0x00, + 0xF9, 0xF0, 0x01, 0xE1, 0xE0, 0x03, 0x83, 0xE0, 0x07, 0x03, 0xC0, 0x1E, + 0x07, 0x80, 0xFF, 0x8F, 0xE3, 0xFF, 0x0F, 0xC7, 0xFE, 0x1F, 0x8F, 0xF8, + 0x3E, 0x00, 0x0F, 0xFE, 0x00, 0xFF, 0xF0, 0x1F, 0xFE, 0x00, 0xFF, 0xE0, + 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x03, 0xC0, + 0x00, 0x3C, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x07, 0x80, 0x60, 0x78, + 0x0F, 0x07, 0x80, 0xF0, 0x70, 0x0E, 0x07, 0x00, 0xE7, 0xFF, 0xFE, 0xFF, + 0xFF, 0xEF, 0xFF, 0xFE, 0xFF, 0xFF, 0xC0, 0x0F, 0xC0, 0x1F, 0x87, 0xE0, + 0x0F, 0xC7, 0xF8, 0x0F, 0xE1, 0xFC, 0x0F, 0xE0, 0x7E, 0x07, 0xE0, 0x3F, + 0x07, 0xF0, 0x3F, 0xC7, 0xF8, 0x1F, 0xE3, 0xF8, 0x0E, 0xF3, 0xDC, 0x07, + 0x7B, 0xDE, 0x03, 0x9F, 0xEF, 0x03, 0xCF, 0xE7, 0x81, 0xE7, 0xE3, 0x80, + 0xE3, 0xF1, 0xC0, 0x70, 0xF1, 0xE0, 0x38, 0x70, 0xF0, 0x3C, 0x00, 0x70, + 0x3F, 0xC1, 0xFE, 0x3F, 0xE1, 0xFF, 0x1F, 0xF0, 0xFF, 0x8F, 0xF0, 0x7F, + 0x80, 0x0F, 0xC1, 0xFE, 0x1F, 0xC1, 0xFF, 0x1F, 0xC3, 0xFE, 0x1F, 0xE1, + 0xFE, 0x07, 0xE0, 0x38, 0x07, 0xF0, 0x78, 0x07, 0xF0, 0x78, 0x0F, 0xF8, + 0x70, 0x0F, 0x78, 0x70, 0x0E, 0x78, 0xF0, 0x0E, 0x7C, 0xF0, 0x1E, 0x3C, + 0xF0, 0x1E, 0x3E, 0xE0, 0x1E, 0x1E, 0xE0, 0x1C, 0x1F, 0xE0, 0x1C, 0x0F, + 0xE0, 0x3C, 0x0F, 0xE0, 0x7F, 0x87, 0xC0, 0xFF, 0x87, 0xC0, 0xFF, 0x87, + 0xC0, 0xFF, 0x03, 0xC0, 0x00, 0x7E, 0x00, 0x1F, 0xF8, 0x07, 0xFF, 0xC0, + 0xFF, 0xFE, 0x1F, 0x87, 0xE3, 0xE0, 0x1F, 0x3C, 0x01, 0xF7, 0xC0, 0x0F, + 0x78, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x01, + 0xEF, 0x00, 0x3E, 0xF8, 0x03, 0xCF, 0x80, 0x7C, 0x7C, 0x1F, 0x87, 0xFF, + 0xF0, 0x3F, 0xFE, 0x01, 0xFF, 0x80, 0x07, 0xE0, 0x00, 0x0F, 0xFF, 0x80, + 0x7F, 0xFF, 0x07, 0xFF, 0xFC, 0x1F, 0xFF, 0xF0, 0x38, 0x0F, 0x81, 0xC0, + 0x3C, 0x1E, 0x01, 0xE0, 0xF0, 0x0F, 0x07, 0x00, 0xF0, 0x38, 0x0F, 0x83, + 0xFF, 0xF8, 0x1F, 0xFF, 0x80, 0xFF, 0xF8, 0x07, 0xFF, 0x00, 0x38, 0x00, + 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x03, 0xFF, 0x80, 0x3F, 0xFC, 0x01, 0xFF, + 0xE0, 0x0F, 0xFE, 0x00, 0x00, 0x00, 0x7E, 0x00, 0x1F, 0xF8, 0x07, 0xFF, + 0xC0, 0xFF, 0xFE, 0x1F, 0x87, 0xE3, 0xE0, 0x1F, 0x3C, 0x01, 0xF7, 0xC0, + 0x0F, 0x78, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, + 0x01, 0xEF, 0x00, 0x3E, 0xF8, 0x03, 0xCF, 0x80, 0x7C, 0x7C, 0x1F, 0x87, + 0xFF, 0xF0, 0x3F, 0xFE, 0x01, 0xFF, 0x80, 0x07, 0xE0, 0x01, 0xFE, 0x30, + 0x3F, 0xFF, 0x87, 0xFF, 0xF0, 0x7F, 0xFF, 0x07, 0x83, 0xC0, 0x07, 0xFF, + 0x80, 0x3F, 0xFF, 0x80, 0xFF, 0xFF, 0x03, 0xFF, 0xFE, 0x03, 0xC0, 0xF8, + 0x0E, 0x01, 0xE0, 0x38, 0x07, 0x81, 0xE0, 0x3E, 0x07, 0x83, 0xF0, 0x1F, + 0xFF, 0x80, 0x7F, 0xFC, 0x01, 0xFF, 0xC0, 0x0F, 0xFF, 0x80, 0x3C, 0x3E, + 0x00, 0xE0, 0x7C, 0x03, 0x80, 0xF0, 0x1E, 0x03, 0xE1, 0xFF, 0x07, 0xFF, + 0xFC, 0x1F, 0xFF, 0xF0, 0x3F, 0xFF, 0x80, 0xF8, 0x00, 0x7C, 0xE0, 0x7F, + 0xFC, 0x1F, 0xFF, 0x87, 0xFF, 0xE0, 0xF8, 0x7C, 0x3C, 0x07, 0x87, 0x80, + 0xE0, 0xF0, 0x00, 0x1F, 0x00, 0x03, 0xFE, 0x00, 0x3F, 0xF8, 0x03, 0xFF, + 0x80, 0x07, 0xF8, 0x40, 0x1F, 0x3C, 0x01, 0xE7, 0x80, 0x3C, 0xFC, 0x1F, + 0x1F, 0xFF, 0xE3, 0xFF, 0xF8, 0x7F, 0xFE, 0x00, 0x7E, 0x00, 0x7F, 0xFF, + 0xEF, 0xFF, 0xFD, 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0x0E, 0x1F, 0xE1, 0xC3, + 0xBC, 0x78, 0x77, 0x0F, 0x1E, 0xE1, 0xC1, 0x80, 0x38, 0x00, 0x0F, 0x00, + 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x3C, 0x00, + 0x07, 0x80, 0x0F, 0xFE, 0x03, 0xFF, 0xE0, 0x7F, 0xFC, 0x0F, 0xFF, 0x00, + 0x7F, 0x8F, 0xF3, 0xFE, 0x7F, 0xDF, 0xF7, 0xFC, 0xFF, 0x1F, 0xE3, 0xC0, + 0x3C, 0x1C, 0x01, 0xE0, 0xE0, 0x0F, 0x0F, 0x00, 0x70, 0x78, 0x03, 0x83, + 0xC0, 0x3C, 0x1C, 0x01, 0xE0, 0xE0, 0x0E, 0x0F, 0x00, 0x70, 0x78, 0x03, + 0x83, 0xC0, 0x3C, 0x1F, 0x01, 0xC0, 0xFC, 0x3E, 0x03, 0xFF, 0xE0, 0x1F, + 0xFE, 0x00, 0x7F, 0xE0, 0x00, 0xFC, 0x00, 0x00, 0x7F, 0x81, 0xFE, 0xFF, + 0x87, 0xFF, 0xFF, 0x0F, 0xFB, 0xFC, 0x1F, 0xE1, 0xC0, 0x0F, 0x03, 0xC0, + 0x1C, 0x07, 0x80, 0x78, 0x0F, 0x01, 0xE0, 0x1E, 0x03, 0x80, 0x1E, 0x0F, + 0x00, 0x3C, 0x3C, 0x00, 0x78, 0x70, 0x00, 0xF1, 0xE0, 0x01, 0xE7, 0x80, + 0x01, 0xEF, 0x00, 0x03, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, + 0x0F, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x7F, 0x87, 0xFF, + 0xFF, 0x1F, 0xFF, 0xF8, 0x7F, 0xFF, 0xE1, 0xFE, 0x78, 0x00, 0xF1, 0xE3, + 0xC3, 0x87, 0x8F, 0x0E, 0x1E, 0x7C, 0x78, 0x79, 0xF9, 0xC1, 0xEF, 0xEF, + 0x07, 0xBF, 0xBC, 0x1D, 0xFE, 0xE0, 0x77, 0x7F, 0x81, 0xFD, 0xFE, 0x07, + 0xE3, 0xF0, 0x3F, 0x8F, 0xC0, 0xFC, 0x3F, 0x03, 0xF0, 0xF8, 0x0F, 0x83, + 0xE0, 0x3E, 0x0F, 0x80, 0xF0, 0x3C, 0x00, 0x07, 0xE0, 0x7E, 0x0F, 0xF0, + 0xFF, 0x0F, 0xF0, 0xFE, 0x0F, 0xE0, 0xFE, 0x03, 0xC0, 0xF8, 0x01, 0xE1, + 0xE0, 0x01, 0xF3, 0xC0, 0x00, 0xF7, 0x80, 0x00, 0x7F, 0x00, 0x00, 0x7E, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xEF, + 0x00, 0x07, 0xCF, 0x80, 0x0F, 0x87, 0xC0, 0x1F, 0x03, 0xC0, 0x7F, 0x07, + 0xF0, 0xFF, 0x8F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xE0, 0x7E, 0x0F, + 0xEF, 0xF0, 0xFF, 0xFF, 0x0F, 0xEF, 0xE0, 0xFE, 0x3C, 0x0F, 0x01, 0xE1, + 0xE0, 0x1E, 0x3E, 0x00, 0xF7, 0xC0, 0x0F, 0xF8, 0x00, 0x7F, 0x00, 0x07, + 0xE0, 0x00, 0x3C, 0x00, 0x03, 0x80, 0x00, 0x78, 0x00, 0x07, 0x80, 0x00, + 0x78, 0x00, 0x07, 0x00, 0x07, 0xFF, 0x00, 0xFF, 0xF8, 0x0F, 0xFF, 0x00, + 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xE0, 0xFF, 0xFC, 0x3F, 0xFF, 0x87, 0xFF, + 0xF0, 0xF0, 0x7C, 0x1C, 0x1F, 0x03, 0x87, 0xC0, 0x61, 0xF0, 0x00, 0x7C, + 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x07, + 0x07, 0xC0, 0xE1, 0xF0, 0x3C, 0x7C, 0x07, 0x9F, 0xFF, 0xF3, 0xFF, 0xFC, + 0x7F, 0xFF, 0x8F, 0xFF, 0xF0, 0x07, 0xF8, 0x3F, 0xC1, 0xFE, 0x0F, 0xE0, + 0x70, 0x07, 0x80, 0x3C, 0x01, 0xC0, 0x0E, 0x00, 0xF0, 0x07, 0x80, 0x3C, + 0x01, 0xC0, 0x0E, 0x00, 0xF0, 0x07, 0x80, 0x38, 0x01, 0xC0, 0x0E, 0x00, + 0xF0, 0x07, 0x80, 0x38, 0x01, 0xC0, 0x1F, 0xE0, 0xFF, 0x07, 0xF8, 0x3F, + 0x80, 0xE0, 0x38, 0x0F, 0x03, 0xC0, 0xF0, 0x1C, 0x07, 0x81, 0xE0, 0x78, + 0x0E, 0x03, 0xC0, 0xF0, 0x3C, 0x07, 0x01, 0xE0, 0x78, 0x1E, 0x03, 0x80, + 0xF0, 0x3C, 0x0F, 0x01, 0xE0, 0x78, 0x1E, 0x03, 0x80, 0xF0, 0x3C, 0x06, + 0x07, 0xF8, 0x3F, 0xC1, 0xFC, 0x0F, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, + 0x1C, 0x00, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0x80, 0x1C, 0x01, 0xE0, 0x0F, + 0x00, 0x78, 0x03, 0x80, 0x1C, 0x01, 0xE0, 0x0F, 0x00, 0x70, 0x03, 0x80, + 0x1C, 0x0F, 0xE0, 0xFF, 0x07, 0xF0, 0x3F, 0x80, 0x00, 0x40, 0x01, 0x80, + 0x07, 0x80, 0x3F, 0x80, 0xFF, 0x03, 0xFF, 0x0F, 0x9F, 0x3E, 0x1E, 0xF8, + 0x3F, 0xE0, 0x3F, 0x00, 0x30, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xF0, 0xC3, 0xC7, 0x0E, 0x3C, 0x30, 0x00, 0xFE, 0x00, + 0x7F, 0xF0, 0x1F, 0xFF, 0x03, 0xFF, 0xE0, 0x00, 0x3C, 0x07, 0xFF, 0x83, + 0xFF, 0xF0, 0xFF, 0xFC, 0x3F, 0xFF, 0x8F, 0x80, 0xF3, 0xE0, 0x1E, 0x78, + 0x1F, 0x8F, 0xFF, 0xFF, 0xFF, 0xFF, 0xDF, 0xFF, 0xF8, 0xFE, 0x7E, 0x07, + 0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFC, 0x00, 0x03, 0xF0, 0x00, 0x01, 0xC0, + 0x00, 0x0F, 0x00, 0x00, 0x3C, 0xFC, 0x00, 0xEF, 0xFC, 0x03, 0xFF, 0xF8, + 0x1F, 0xFF, 0xE0, 0x7E, 0x0F, 0xC1, 0xE0, 0x1F, 0x07, 0x00, 0x3C, 0x1C, + 0x00, 0xF0, 0xE0, 0x03, 0xC3, 0x80, 0x1E, 0x0F, 0x00, 0xF8, 0x3E, 0x07, + 0xC7, 0xFF, 0xFF, 0x3F, 0xFF, 0xF8, 0xFF, 0xFF, 0x81, 0xF1, 0xF8, 0x00, + 0x00, 0xFE, 0x60, 0xFF, 0xFC, 0x3F, 0xFF, 0x8F, 0xFF, 0xF3, 0xF0, 0x3C, + 0xF8, 0x03, 0x9E, 0x00, 0x67, 0x80, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, + 0xC0, 0x00, 0x7E, 0x01, 0xC7, 0xFF, 0xF8, 0xFF, 0xFE, 0x0F, 0xFF, 0x80, + 0x7F, 0x80, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, + 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x70, 0x07, 0xE3, 0x80, 0xFF, 0xDC, 0x0F, + 0xFF, 0xE0, 0xFF, 0xFF, 0x0F, 0xC1, 0xF0, 0xF8, 0x07, 0x87, 0x80, 0x1C, + 0x78, 0x00, 0xE3, 0xC0, 0x0F, 0x1E, 0x00, 0x70, 0xF0, 0x07, 0x87, 0xE0, + 0xFC, 0x1F, 0xFF, 0xF8, 0xFF, 0xFF, 0xC3, 0xFF, 0xFE, 0x07, 0xE3, 0xE0, + 0x00, 0xFC, 0x01, 0xFF, 0xC0, 0xFF, 0xF8, 0x7F, 0xFE, 0x3E, 0x0F, 0xCE, + 0x00, 0xF7, 0x00, 0x3D, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xE0, 0x1E, 0xFF, 0xFF, 0x9F, 0xFF, 0xE3, 0xFF, 0xF0, 0x3F, 0xF0, + 0x00, 0x0F, 0xF0, 0x01, 0xFF, 0xC0, 0x1F, 0xFE, 0x01, 0xFF, 0xE0, 0x0F, + 0x00, 0x00, 0xF0, 0x00, 0x3F, 0xFF, 0x03, 0xFF, 0xF8, 0x1F, 0xFF, 0xC0, + 0xFF, 0xFC, 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x38, 0x00, 0x01, 0xC0, + 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x00, 0x00, 0x38, 0x00, 0x1F, + 0xFF, 0x81, 0xFF, 0xFC, 0x0F, 0xFF, 0xE0, 0x7F, 0xFE, 0x00, 0x01, 0xF9, + 0xF8, 0x3F, 0xFF, 0xC3, 0xFF, 0xFE, 0x7F, 0xFF, 0xE3, 0xE0, 0xFC, 0x3E, + 0x03, 0xE1, 0xE0, 0x0E, 0x1E, 0x00, 0x70, 0xF0, 0x03, 0x87, 0x80, 0x3C, + 0x3E, 0x03, 0xE1, 0xF8, 0x7E, 0x07, 0xFF, 0xF0, 0x3F, 0xFF, 0x80, 0xFF, + 0xFC, 0x01, 0xF9, 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x80, + 0x7F, 0xF8, 0x07, 0xFF, 0x80, 0x3F, 0xF8, 0x00, 0xFF, 0x00, 0x00, 0x0F, + 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x03, 0xC0, 0x00, + 0x38, 0x00, 0x03, 0x9F, 0x00, 0x7F, 0xFC, 0x07, 0xFF, 0xC0, 0x7F, 0xFE, + 0x07, 0xC3, 0xE0, 0x70, 0x1E, 0x0F, 0x01, 0xC0, 0xF0, 0x1C, 0x0E, 0x03, + 0xC0, 0xE0, 0x3C, 0x1E, 0x03, 0x81, 0xE0, 0x38, 0x7F, 0x0F, 0xFF, 0xF8, + 0xFF, 0xFF, 0x8F, 0xF7, 0xF0, 0xFE, 0x00, 0x78, 0x00, 0x78, 0x00, 0x78, + 0x00, 0x78, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xF0, 0x0F, 0xF0, 0x1F, 0xF0, + 0x0F, 0xF0, 0x00, 0xF0, 0x00, 0xE0, 0x00, 0xE0, 0x01, 0xE0, 0x01, 0xE0, + 0x01, 0xE0, 0x01, 0xC0, 0x01, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFE, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0xF8, 0x00, 0x3C, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFC, 0x3F, 0xFE, 0x0F, 0xFF, 0x81, 0xFF, + 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x01, 0xC0, 0x00, 0xF0, + 0x00, 0x3C, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, 0x00, 0x78, 0x00, + 0x1E, 0x00, 0x07, 0x00, 0x01, 0xC0, 0x00, 0xF0, 0x00, 0x7C, 0x1F, 0xFE, + 0x0F, 0xFF, 0x03, 0xFF, 0x80, 0x7F, 0x80, 0x00, 0x07, 0xE0, 0x00, 0xFE, + 0x00, 0x0F, 0xE0, 0x00, 0x7C, 0x00, 0x01, 0xC0, 0x00, 0x3C, 0x00, 0x03, + 0xCF, 0xF0, 0x3C, 0xFF, 0x03, 0x9F, 0xF0, 0x38, 0xFE, 0x07, 0xBF, 0x00, + 0x7F, 0xC0, 0x07, 0xF8, 0x00, 0x7F, 0x00, 0x07, 0xF8, 0x00, 0xFF, 0xC0, + 0x0F, 0x7E, 0x00, 0xE3, 0xF0, 0x7E, 0x1F, 0xE7, 0xE1, 0xFE, 0xFE, 0x3F, + 0xE7, 0xE1, 0xFC, 0x03, 0xFC, 0x07, 0xFC, 0x07, 0xF8, 0x07, 0xF8, 0x00, + 0x78, 0x00, 0x78, 0x00, 0x78, 0x00, 0x70, 0x00, 0x70, 0x00, 0xF0, 0x00, + 0xF0, 0x00, 0xE0, 0x00, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, + 0xC0, 0x01, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x1F, + 0x7C, 0x78, 0x7F, 0xFF, 0xF8, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, 0xF0, 0xF1, + 0xF1, 0xE1, 0xC3, 0x83, 0xC7, 0x87, 0x07, 0x8F, 0x0E, 0x0E, 0x1C, 0x3C, + 0x1C, 0x38, 0x78, 0x78, 0x70, 0xE0, 0xF1, 0xE1, 0xC1, 0xC7, 0xE3, 0xC3, + 0xFF, 0xCF, 0xC7, 0xFF, 0x9F, 0x9F, 0xFF, 0x3E, 0x3E, 0x0F, 0x8F, 0x80, + 0xFD, 0xFF, 0x07, 0xFF, 0xF8, 0x3F, 0xFF, 0xE0, 0x7E, 0x1F, 0x07, 0xC0, + 0x78, 0x3C, 0x03, 0x81, 0xE0, 0x1C, 0x0E, 0x01, 0xE0, 0x70, 0x0F, 0x07, + 0x80, 0x70, 0x3C, 0x03, 0x87, 0xF0, 0x3F, 0x7F, 0xC3, 0xFF, 0xFE, 0x1F, + 0xEF, 0xE0, 0xFE, 0x01, 0xFC, 0x01, 0xFF, 0x80, 0xFF, 0xF8, 0x7F, 0xFE, + 0x3E, 0x0F, 0xDF, 0x01, 0xF7, 0x80, 0x3F, 0xC0, 0x0F, 0xF0, 0x03, 0xFC, + 0x01, 0xEF, 0x80, 0xFB, 0xF0, 0x7C, 0x7F, 0xFF, 0x1F, 0xFF, 0x03, 0xFF, + 0x80, 0x3F, 0x80, 0x07, 0xC7, 0xE0, 0x1F, 0xBF, 0xF0, 0x3F, 0xFF, 0xF0, + 0x7F, 0xFF, 0xE0, 0x3F, 0x07, 0xE0, 0x78, 0x03, 0xC0, 0xE0, 0x07, 0x81, + 0xC0, 0x0F, 0x07, 0x00, 0x1E, 0x0F, 0x00, 0x78, 0x1E, 0x01, 0xF0, 0x3E, + 0x07, 0xC0, 0xFF, 0xFF, 0x81, 0xFF, 0xFE, 0x03, 0xDF, 0xF0, 0x07, 0x1F, + 0x80, 0x0E, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x78, 0x00, 0x03, 0xFE, 0x00, + 0x0F, 0xFE, 0x00, 0x1F, 0xF8, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x01, 0xF8, + 0xF8, 0x1F, 0xFF, 0xF1, 0xFF, 0xFF, 0xCF, 0xFF, 0xFE, 0x3E, 0x07, 0xC1, + 0xF0, 0x0F, 0x07, 0x80, 0x1C, 0x3C, 0x00, 0x70, 0xF0, 0x03, 0x83, 0xC0, + 0x0E, 0x0F, 0x80, 0x78, 0x3F, 0x07, 0xE0, 0x7F, 0xFF, 0x81, 0xFF, 0xFC, + 0x03, 0xFF, 0x70, 0x03, 0xF3, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0xE0, 0x00, 0x3F, 0xE0, 0x01, 0xFF, 0xC0, 0x07, 0xFF, 0x00, 0x1F, + 0xF8, 0x00, 0x0F, 0xC3, 0xC1, 0xFC, 0xFF, 0x1F, 0xFF, 0xF1, 0xFF, 0xFE, + 0x03, 0xFC, 0x00, 0x3F, 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x07, 0x80, + 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0xF0, 0x00, 0xFF, 0xFC, 0x0F, 0xFF, + 0xE0, 0xFF, 0xFC, 0x0F, 0xFF, 0xC0, 0x03, 0xF3, 0x0F, 0xFF, 0x3F, 0xFF, + 0x3F, 0xFF, 0x7C, 0x0E, 0x78, 0x00, 0x7F, 0xE0, 0x3F, 0xFC, 0x1F, 0xFF, + 0x00, 0x3F, 0x70, 0x0F, 0xF8, 0x1F, 0xFF, 0xFE, 0xFF, 0xFC, 0xFF, 0xF8, + 0x0F, 0xE0, 0x06, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0E, 0x00, 0x0E, 0x00, + 0x7F, 0xFE, 0xFF, 0xFE, 0xFF, 0xFE, 0xFF, 0xFC, 0x1C, 0x00, 0x3C, 0x00, + 0x3C, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x78, 0x00, 0x7C, 0x0E, + 0x7F, 0xFF, 0x7F, 0xFE, 0x3F, 0xFC, 0x0F, 0xE0, 0x7C, 0x0F, 0xFF, 0x07, + 0xFF, 0x81, 0xFF, 0xE0, 0x7E, 0x78, 0x03, 0x9E, 0x00, 0xE7, 0x80, 0x79, + 0xE0, 0x1E, 0x78, 0x07, 0x1E, 0x01, 0xC7, 0x80, 0xF1, 0xE0, 0xFC, 0x7F, + 0xFF, 0x9F, 0xFF, 0xE3, 0xFF, 0xF8, 0x3E, 0x7C, 0x7F, 0x87, 0xFF, 0xFC, + 0x7F, 0xFF, 0xE3, 0xFF, 0xFF, 0x1F, 0xE1, 0xE0, 0x3C, 0x0F, 0x03, 0xC0, + 0x78, 0x3C, 0x01, 0xE1, 0xC0, 0x0F, 0x1E, 0x00, 0x79, 0xE0, 0x03, 0xCE, + 0x00, 0x0F, 0xF0, 0x00, 0x7F, 0x00, 0x03, 0xF0, 0x00, 0x0F, 0x80, 0x00, + 0x78, 0x00, 0x7E, 0x03, 0xF7, 0xF0, 0x3F, 0xFF, 0x81, 0xFD, 0xF8, 0x0F, + 0xE7, 0x8E, 0x1C, 0x3C, 0xF9, 0xE1, 0xE7, 0xCE, 0x0F, 0x7E, 0xF0, 0x7B, + 0xF7, 0x03, 0xFF, 0xF8, 0x1F, 0xDF, 0x80, 0xFC, 0xFC, 0x07, 0xE7, 0xE0, + 0x3E, 0x3E, 0x01, 0xF1, 0xF0, 0x0F, 0x07, 0x00, 0x0F, 0xE3, 0xF8, 0xFF, + 0x1F, 0xC7, 0xF9, 0xFE, 0x1F, 0x87, 0xF0, 0x7E, 0x7C, 0x01, 0xFF, 0xC0, + 0x07, 0xFC, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x1F, 0xF0, 0x01, 0xF7, + 0xC0, 0x1F, 0x1F, 0x03, 0xF0, 0x7C, 0x7F, 0xCF, 0xFB, 0xFE, 0x7F, 0xDF, + 0xE3, 0xFC, 0x07, 0xF0, 0x7F, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x07, + 0xE0, 0xFE, 0x03, 0xC0, 0x78, 0x03, 0xC0, 0x78, 0x03, 0xC0, 0xF0, 0x01, + 0xE1, 0xE0, 0x01, 0xE1, 0xC0, 0x01, 0xE3, 0xC0, 0x00, 0xF7, 0x80, 0x00, + 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7C, 0x00, 0x00, + 0x78, 0x00, 0x00, 0x70, 0x00, 0x00, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x7F, + 0xF0, 0x00, 0xFF, 0xF8, 0x00, 0xFF, 0xF0, 0x00, 0x7F, 0xF0, 0x00, 0x1F, + 0xFF, 0xC7, 0xFF, 0xF1, 0xFF, 0xF8, 0xFF, 0xFE, 0x3C, 0x1F, 0x0E, 0x1F, + 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, + 0xF8, 0x3C, 0xFF, 0xFF, 0x3F, 0xFF, 0xCF, 0xFF, 0xE3, 0xFF, 0xF8, 0x00, + 0xF0, 0x1F, 0x03, 0xF0, 0x7E, 0x07, 0x80, 0x70, 0x0F, 0x00, 0xF0, 0x0E, + 0x00, 0xE0, 0x1E, 0x01, 0xC0, 0xFC, 0x0F, 0x80, 0xF8, 0x0F, 0xC0, 0x3C, + 0x03, 0xC0, 0x38, 0x03, 0x80, 0x78, 0x07, 0x80, 0x78, 0x07, 0xE0, 0x7E, + 0x03, 0xE0, 0x1C, 0x00, 0x02, 0x07, 0x07, 0x0F, 0x0F, 0x0E, 0x0E, 0x0E, + 0x1E, 0x1E, 0x1C, 0x1C, 0x1C, 0x3C, 0x3C, 0x38, 0x38, 0x38, 0x78, 0x78, + 0x70, 0x70, 0x70, 0xF0, 0xF0, 0xE0, 0xE0, 0x01, 0xC0, 0x1F, 0x00, 0xFC, + 0x07, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1C, 0x00, 0xE0, 0x0F, 0x00, + 0x78, 0x03, 0xC0, 0x1F, 0x80, 0x7C, 0x03, 0xE0, 0x3F, 0x03, 0xC0, 0x1C, + 0x00, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0x80, 0x3C, 0x0F, 0xE0, 0x7E, 0x07, + 0xE0, 0x1E, 0x00, 0x0F, 0x00, 0x1F, 0xC0, 0x1F, 0xF0, 0xFF, 0xFC, 0xFF, + 0x3F, 0xFF, 0x0F, 0xF8, 0x03, 0xF8, 0x00, 0xF0 }; + +const GFXglyph FreeMonoBoldOblique18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 21, 0, 1 }, // 0x20 ' ' + { 0, 9, 22, 21, 9, -21 }, // 0x21 '!' + { 25, 12, 10, 21, 9, -20 }, // 0x22 '"' + { 40, 18, 25, 21, 4, -22 }, // 0x23 '#' + { 97, 18, 28, 21, 4, -23 }, // 0x24 '$' + { 160, 16, 21, 21, 5, -20 }, // 0x25 '%' + { 202, 16, 20, 21, 4, -19 }, // 0x26 '&' + { 242, 5, 10, 21, 12, -20 }, // 0x27 ''' + { 249, 10, 27, 21, 11, -21 }, // 0x28 '(' + { 283, 10, 27, 21, 4, -21 }, // 0x29 ')' + { 317, 15, 15, 21, 6, -21 }, // 0x2A '*' + { 346, 18, 19, 21, 4, -18 }, // 0x2B '+' + { 389, 9, 10, 21, 4, -3 }, // 0x2C ',' + { 401, 18, 4, 21, 4, -11 }, // 0x2D '-' + { 410, 5, 5, 21, 8, -4 }, // 0x2E '.' + { 414, 21, 28, 21, 2, -23 }, // 0x2F '/' + { 488, 17, 23, 21, 5, -22 }, // 0x30 '0' + { 537, 15, 22, 21, 3, -21 }, // 0x31 '1' + { 579, 20, 23, 21, 2, -22 }, // 0x32 '2' + { 637, 18, 23, 21, 3, -22 }, // 0x33 '3' + { 689, 16, 21, 21, 4, -20 }, // 0x34 '4' + { 731, 18, 22, 21, 4, -21 }, // 0x35 '5' + { 781, 19, 23, 21, 5, -22 }, // 0x36 '6' + { 836, 16, 22, 21, 6, -21 }, // 0x37 '7' + { 880, 19, 23, 21, 3, -22 }, // 0x38 '8' + { 935, 18, 23, 21, 4, -22 }, // 0x39 '9' + { 987, 7, 16, 21, 9, -15 }, // 0x3A ':' + { 1001, 11, 22, 21, 4, -15 }, // 0x3B ';' + { 1032, 18, 16, 21, 4, -17 }, // 0x3C '<' + { 1068, 19, 10, 21, 3, -14 }, // 0x3D '=' + { 1092, 19, 16, 21, 3, -17 }, // 0x3E '>' + { 1130, 14, 21, 21, 8, -20 }, // 0x3F '?' + { 1167, 18, 27, 21, 3, -21 }, // 0x40 '@' + { 1228, 22, 21, 21, 0, -20 }, // 0x41 'A' + { 1286, 21, 21, 21, 1, -20 }, // 0x42 'B' + { 1342, 21, 21, 21, 2, -20 }, // 0x43 'C' + { 1398, 21, 21, 21, 1, -20 }, // 0x44 'D' + { 1454, 22, 21, 21, 0, -20 }, // 0x45 'E' + { 1512, 23, 21, 21, 0, -20 }, // 0x46 'F' + { 1573, 21, 21, 21, 2, -20 }, // 0x47 'G' + { 1629, 23, 21, 21, 0, -20 }, // 0x48 'H' + { 1690, 19, 21, 21, 2, -20 }, // 0x49 'I' + { 1740, 23, 21, 21, 0, -20 }, // 0x4A 'J' + { 1801, 23, 21, 21, 0, -20 }, // 0x4B 'K' + { 1862, 20, 21, 21, 1, -20 }, // 0x4C 'L' + { 1915, 25, 21, 21, 0, -20 }, // 0x4D 'M' + { 1981, 24, 21, 21, 1, -20 }, // 0x4E 'N' + { 2044, 20, 21, 21, 2, -20 }, // 0x4F 'O' + { 2097, 21, 21, 21, 1, -20 }, // 0x50 'P' + { 2153, 20, 26, 21, 2, -20 }, // 0x51 'Q' + { 2218, 22, 21, 21, 0, -20 }, // 0x52 'R' + { 2276, 19, 21, 21, 3, -20 }, // 0x53 'S' + { 2326, 19, 21, 21, 3, -20 }, // 0x54 'T' + { 2376, 21, 21, 21, 3, -20 }, // 0x55 'U' + { 2432, 23, 21, 21, 1, -20 }, // 0x56 'V' + { 2493, 22, 21, 21, 2, -20 }, // 0x57 'W' + { 2551, 24, 21, 21, 0, -20 }, // 0x58 'X' + { 2614, 20, 21, 21, 3, -20 }, // 0x59 'Y' + { 2667, 19, 21, 21, 2, -20 }, // 0x5A 'Z' + { 2717, 13, 27, 21, 8, -21 }, // 0x5B '[' + { 2761, 10, 28, 21, 8, -23 }, // 0x5C '\' + { 2796, 13, 27, 21, 4, -21 }, // 0x5D ']' + { 2840, 15, 11, 21, 6, -21 }, // 0x5E '^' + { 2861, 21, 4, 21, -1, 4 }, // 0x5F '_' + { 2872, 6, 6, 21, 10, -22 }, // 0x60 '`' + { 2877, 19, 16, 21, 2, -15 }, // 0x61 'a' + { 2915, 22, 22, 21, 0, -21 }, // 0x62 'b' + { 2976, 19, 16, 21, 3, -15 }, // 0x63 'c' + { 3014, 21, 22, 21, 3, -21 }, // 0x64 'd' + { 3072, 18, 16, 21, 3, -15 }, // 0x65 'e' + { 3108, 21, 22, 21, 3, -21 }, // 0x66 'f' + { 3166, 21, 23, 21, 2, -15 }, // 0x67 'g' + { 3227, 20, 22, 21, 1, -21 }, // 0x68 'h' + { 3282, 16, 22, 21, 3, -21 }, // 0x69 'i' + { 3326, 18, 29, 21, 2, -21 }, // 0x6A 'j' + { 3392, 20, 22, 21, 1, -21 }, // 0x6B 'k' + { 3447, 16, 22, 21, 3, -21 }, // 0x6C 'l' + { 3491, 23, 16, 21, 0, -15 }, // 0x6D 'm' + { 3537, 21, 16, 21, 1, -15 }, // 0x6E 'n' + { 3579, 18, 16, 21, 3, -15 }, // 0x6F 'o' + { 3615, 23, 23, 21, -1, -15 }, // 0x70 'p' + { 3682, 22, 23, 21, 2, -15 }, // 0x71 'q' + { 3746, 20, 16, 21, 2, -15 }, // 0x72 'r' + { 3786, 16, 16, 21, 4, -15 }, // 0x73 's' + { 3818, 16, 21, 21, 4, -20 }, // 0x74 't' + { 3860, 18, 16, 21, 3, -15 }, // 0x75 'u' + { 3896, 21, 16, 21, 2, -15 }, // 0x76 'v' + { 3938, 21, 16, 21, 3, -15 }, // 0x77 'w' + { 3980, 21, 16, 21, 1, -15 }, // 0x78 'x' + { 4022, 24, 23, 21, -1, -15 }, // 0x79 'y' + { 4091, 18, 16, 21, 3, -15 }, // 0x7A 'z' + { 4127, 12, 27, 21, 8, -21 }, // 0x7B '{' + { 4168, 8, 27, 21, 8, -21 }, // 0x7C '|' + { 4195, 13, 27, 21, 4, -21 }, // 0x7D '}' + { 4239, 17, 8, 21, 4, -13 } }; // 0x7E '~' + +const GFXfont FreeMonoBoldOblique18pt7b PROGMEM = { + (uint8_t *)FreeMonoBoldOblique18pt7bBitmaps, + (GFXglyph *)FreeMonoBoldOblique18pt7bGlyphs, + 0x20, 0x7E, 35 }; + +// Approx. 4928 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique24pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique24pt7b.h new file mode 100644 index 0000000..a2bbbdf --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique24pt7b.h @@ -0,0 +1,742 @@ +const uint8_t FreeMonoBoldOblique24pt7bBitmaps[] PROGMEM = { + 0x01, 0xE0, 0x3F, 0x07, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xE0, 0xFE, + 0x0F, 0xE0, 0xFE, 0x0F, 0xC0, 0xFC, 0x1F, 0xC1, 0xF8, 0x1F, 0x81, 0xF8, + 0x1F, 0x81, 0xF0, 0x1F, 0x01, 0xF0, 0x1E, 0x00, 0x80, 0x00, 0x00, 0x00, + 0x00, 0x03, 0xC0, 0x7E, 0x0F, 0xE0, 0xFE, 0x0F, 0xC0, 0x78, 0x00, 0x7E, + 0x1F, 0xBF, 0x0F, 0xDF, 0x87, 0xCF, 0x83, 0xE7, 0xC1, 0xF3, 0xE0, 0xF1, + 0xE0, 0xF8, 0xF0, 0x7C, 0x78, 0x3C, 0x38, 0x1E, 0x1C, 0x0F, 0x0E, 0x07, + 0x0E, 0x03, 0x83, 0x01, 0x80, 0x00, 0x1C, 0x1C, 0x00, 0x3E, 0x3E, 0x00, + 0x3E, 0x3E, 0x00, 0x3C, 0x3C, 0x00, 0x7C, 0x7C, 0x00, 0x7C, 0x7C, 0x00, + 0x7C, 0x7C, 0x00, 0xF8, 0xF8, 0x00, 0xF8, 0xF8, 0x00, 0xF8, 0xF8, 0x0F, + 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0x1F, + 0xFF, 0xFE, 0x03, 0xE3, 0xE0, 0x03, 0xE3, 0xE0, 0x03, 0xC3, 0xC0, 0x07, + 0xC7, 0xC0, 0x7F, 0xFF, 0xF8, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFC, 0xFF, + 0xFF, 0xF8, 0xFF, 0xFF, 0xF0, 0x0F, 0x0F, 0x00, 0x1F, 0x1F, 0x00, 0x1F, + 0x1F, 0x00, 0x1F, 0x1F, 0x00, 0x3E, 0x1E, 0x00, 0x3E, 0x3E, 0x00, 0x3E, + 0x3E, 0x00, 0x3C, 0x3C, 0x00, 0x7C, 0x7C, 0x00, 0x38, 0x38, 0x00, 0x00, + 0x00, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0xFF, 0x00, 0x01, 0xFF, 0xFC, 0x03, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, + 0x01, 0xFF, 0xFF, 0x81, 0xFC, 0x1F, 0xC1, 0xF8, 0x03, 0xC0, 0xF8, 0x01, + 0xE0, 0x7C, 0x00, 0x40, 0x3F, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x0F, 0xFF, + 0x80, 0x03, 0xFF, 0xF8, 0x00, 0xFF, 0xFE, 0x00, 0x0F, 0xFF, 0x00, 0x00, + 0x7F, 0xC0, 0x00, 0x07, 0xE0, 0xE0, 0x01, 0xF0, 0xF0, 0x00, 0xF8, 0xF8, + 0x00, 0xFC, 0x7E, 0x00, 0xFC, 0x3F, 0x81, 0xFE, 0x1F, 0xFF, 0xFE, 0x0F, + 0xFF, 0xFE, 0x0F, 0xFF, 0xFE, 0x03, 0xFF, 0xFC, 0x00, 0x07, 0xF0, 0x00, + 0x01, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x00, 0xF8, + 0x00, 0x0F, 0xF8, 0x00, 0x7F, 0xE0, 0x03, 0xC3, 0xC0, 0x0E, 0x07, 0x00, + 0x70, 0x1C, 0x01, 0xC0, 0x70, 0x07, 0x01, 0xC0, 0x1C, 0x0E, 0x00, 0x78, + 0x78, 0x00, 0xFF, 0xC0, 0x03, 0xFE, 0x1F, 0x03, 0xE3, 0xFC, 0x00, 0x7F, + 0xC0, 0x0F, 0xF8, 0x03, 0xFF, 0x00, 0x7F, 0xC0, 0x03, 0xF8, 0x7C, 0x0F, + 0x07, 0xFC, 0x00, 0x3F, 0xF0, 0x01, 0xE1, 0xE0, 0x07, 0x03, 0x80, 0x38, + 0x0E, 0x00, 0xE0, 0x38, 0x03, 0x80, 0xE0, 0x0E, 0x07, 0x00, 0x3C, 0x3C, + 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1F, 0x00, + 0x01, 0xFF, 0x80, 0x3F, 0xFC, 0x03, 0xFF, 0xE0, 0x1F, 0xFE, 0x01, 0xF1, + 0xE0, 0x1F, 0x04, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, + 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x07, 0xF8, 0x00, 0x7F, 0xE3, + 0xE7, 0xFF, 0x3F, 0x7E, 0xFF, 0xFB, 0xE7, 0xFF, 0x9E, 0x1F, 0xF1, 0xF0, + 0xFF, 0x8F, 0x83, 0xF8, 0x7C, 0x1F, 0xC3, 0xF0, 0xFF, 0x9F, 0xFF, 0xFC, + 0x7F, 0xFF, 0xE3, 0xFF, 0xFF, 0x0F, 0xFD, 0xF0, 0x1F, 0x80, 0x00, 0x7E, + 0xFD, 0xF3, 0xE7, 0xCF, 0x3E, 0x7C, 0xF1, 0xE3, 0xC7, 0x0E, 0x18, 0x00, + 0x00, 0x18, 0x00, 0xF0, 0x07, 0xC0, 0x3F, 0x01, 0xF8, 0x07, 0xC0, 0x3E, + 0x01, 0xF8, 0x07, 0xC0, 0x3E, 0x00, 0xF8, 0x07, 0xC0, 0x1F, 0x00, 0xF8, + 0x03, 0xE0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x3E, 0x00, 0xF8, + 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, + 0x00, 0xFC, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x80, 0x7E, 0x00, 0xFC, 0x03, + 0xF0, 0x07, 0xC0, 0x1E, 0x00, 0x00, 0xC0, 0x07, 0x80, 0x3F, 0x00, 0xFC, + 0x03, 0xF0, 0x07, 0xE0, 0x1F, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xF0, 0x07, + 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, + 0xF0, 0x07, 0xC0, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x1F, 0x00, 0x7C, 0x01, + 0xF0, 0x0F, 0x80, 0x3E, 0x01, 0xF0, 0x0F, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, + 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x3E, 0x00, 0xF0, 0x00, 0x00, 0x3C, + 0x00, 0x01, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x08, + 0x3C, 0x09, 0xF9, 0xE7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, + 0x87, 0xFF, 0xE0, 0x07, 0xF8, 0x00, 0x7F, 0xC0, 0x07, 0xFF, 0x00, 0x7F, + 0xF8, 0x07, 0xE7, 0xE0, 0x3E, 0x3F, 0x01, 0xE0, 0xF8, 0x0E, 0x07, 0x80, + 0x00, 0x07, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x0F, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x3E, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x7C, 0x00, + 0x00, 0x78, 0x00, 0x00, 0x78, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xF0, 0x00, + 0x01, 0xF0, 0x00, 0x00, 0xE0, 0x00, 0x03, 0xF0, 0x7E, 0x07, 0xC0, 0xFC, + 0x0F, 0x81, 0xF0, 0x1E, 0x03, 0xE0, 0x3C, 0x07, 0x80, 0x78, 0x0F, 0x00, + 0xE0, 0x0C, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x3C, 0xFF, 0xFF, 0xFF, 0xCF, 0x00, + 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x01, 0xF0, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, + 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1F, + 0x80, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x07, 0xE0, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x01, 0xF0, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x07, 0x00, 0x00, + 0x00, 0x00, 0x0F, 0xC0, 0x00, 0xFF, 0xE0, 0x03, 0xFF, 0xE0, 0x1F, 0xFF, + 0xE0, 0x7F, 0xFF, 0xC0, 0xFC, 0x1F, 0x83, 0xF0, 0x1F, 0x8F, 0xC0, 0x1F, + 0x1F, 0x00, 0x3E, 0x7C, 0x00, 0x7C, 0xF8, 0x00, 0xF9, 0xF0, 0x01, 0xF3, + 0xC0, 0x07, 0xCF, 0x80, 0x0F, 0x9F, 0x00, 0x1E, 0x3E, 0x00, 0x3C, 0x78, + 0x00, 0xF8, 0xF0, 0x01, 0xF3, 0xE0, 0x03, 0xE7, 0xC0, 0x07, 0x8F, 0x80, + 0x1F, 0x1F, 0x00, 0x3E, 0x3E, 0x00, 0xF8, 0x7C, 0x01, 0xF0, 0xFC, 0x07, + 0xC1, 0xFC, 0x3F, 0x81, 0xFF, 0xFE, 0x03, 0xFF, 0xF8, 0x03, 0xFF, 0xE0, + 0x03, 0xFF, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x7E, + 0x00, 0x0F, 0xF0, 0x01, 0xFF, 0x80, 0x1F, 0xFC, 0x03, 0xFB, 0xE0, 0x1F, + 0x9E, 0x00, 0xF1, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xE0, + 0x00, 0x1E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x03, + 0xC0, 0x00, 0x1E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, + 0x03, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, + 0x01, 0xFF, 0xFF, 0x9F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x3F, + 0xFF, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x03, 0xFF, 0x80, 0x03, 0xFF, 0xF0, + 0x01, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0x80, 0x7F, 0x07, 0xF0, 0x1F, 0x00, + 0xFC, 0x0F, 0x80, 0x1F, 0x03, 0xE0, 0x07, 0xC0, 0xF0, 0x01, 0xF0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x03, 0xF8, + 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, + 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, 0x80, 0x70, 0x3F, 0x80, 0x3E, 0x1F, + 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFC, + 0x3F, 0xFF, 0xFF, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x0F, 0xFE, 0x00, 0x1F, + 0xFF, 0x80, 0x1F, 0xFF, 0xE0, 0x1F, 0xFF, 0xF8, 0x0F, 0x81, 0xFC, 0x07, + 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x0F, 0xC0, + 0x00, 0x07, 0xC0, 0x00, 0x0F, 0xC0, 0x01, 0xFF, 0xC0, 0x01, 0xFF, 0xC0, + 0x00, 0xFF, 0x80, 0x00, 0x7F, 0xE0, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0x1F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, + 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFC, 0x3C, 0x01, + 0xFC, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, 0xFC, 0x0F, 0xFF, 0xFC, 0x03, 0xFF, + 0xFC, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0xFC, 0x00, 0x07, 0xF0, 0x00, + 0x3F, 0xC0, 0x01, 0xFE, 0x00, 0x0F, 0xF8, 0x00, 0x7F, 0xE0, 0x03, 0xFF, + 0x80, 0x1F, 0xBE, 0x00, 0x7C, 0xF0, 0x03, 0xE7, 0xC0, 0x1F, 0x1F, 0x00, + 0xF8, 0x7C, 0x07, 0xE1, 0xE0, 0x3F, 0x07, 0x81, 0xF8, 0x3E, 0x07, 0xC0, + 0xF8, 0x3E, 0x03, 0xC1, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0xBF, 0xFF, 0xFE, + 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0x80, 0x00, 0xF8, 0x00, 0x3F, 0xF8, 0x01, + 0xFF, 0xE0, 0x07, 0xFF, 0x80, 0x1F, 0xFE, 0x00, 0x7F, 0xF0, 0x01, 0xFF, + 0xFF, 0x00, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xC0, 0x3F, 0xFF, 0xE0, 0x3F, + 0xFF, 0xE0, 0x1F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, + 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, 0xF7, 0xF0, 0x00, 0xFF, 0xFE, 0x00, + 0x7F, 0xFF, 0x80, 0x3F, 0xFF, 0xE0, 0x1F, 0xFF, 0xF0, 0x0F, 0x01, 0xFC, + 0x00, 0x00, 0x7E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, + 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0xF8, 0x3C, 0x03, 0xFC, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, + 0xFC, 0x0F, 0xFF, 0xFC, 0x03, 0xFF, 0xF8, 0x00, 0x3F, 0xE0, 0x00, 0x00, + 0x01, 0xFC, 0x00, 0x07, 0xFE, 0x00, 0x1F, 0xFF, 0x00, 0x7F, 0xFF, 0x00, + 0xFF, 0xFE, 0x01, 0xFE, 0x1C, 0x03, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x0F, + 0xC0, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x3E, 0x00, 0x3E, + 0xFF, 0x80, 0x7D, 0xFF, 0xC0, 0x7F, 0xFF, 0xE0, 0x7F, 0xFF, 0xE0, 0x7F, + 0x87, 0xF0, 0xFF, 0x03, 0xF0, 0xFC, 0x01, 0xF0, 0xF8, 0x01, 0xF0, 0xF8, + 0x01, 0xF0, 0xF8, 0x01, 0xF0, 0xF8, 0x03, 0xE0, 0xF8, 0x03, 0xE0, 0xFC, + 0x07, 0xC0, 0xFE, 0x0F, 0xC0, 0x7F, 0xFF, 0x80, 0x7F, 0xFF, 0x00, 0x3F, + 0xFE, 0x00, 0x1F, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x7F, 0xFF, 0xFD, 0xFF, + 0xFF, 0xE7, 0xFF, 0xFF, 0xBF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFB, 0xE0, 0x07, + 0xCF, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x00, + 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x01, + 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, + 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x00, + 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, + 0x00, 0x1F, 0x00, 0x00, 0x38, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0xFF, + 0xE0, 0x07, 0xFF, 0xE0, 0x1F, 0xFF, 0xE0, 0x7F, 0xFF, 0xC0, 0xFC, 0x1F, + 0xC3, 0xF0, 0x1F, 0x8F, 0xC0, 0x1F, 0x1F, 0x00, 0x3E, 0x3E, 0x00, 0x7C, + 0x7C, 0x01, 0xF0, 0xFC, 0x07, 0xE0, 0xFC, 0x1F, 0x81, 0xFF, 0xFE, 0x01, + 0xFF, 0xF0, 0x01, 0xFF, 0xE0, 0x0F, 0xFF, 0xE0, 0x3F, 0xFF, 0xE0, 0xFE, + 0x0F, 0xC3, 0xF0, 0x0F, 0xC7, 0xC0, 0x0F, 0x9F, 0x00, 0x1F, 0x3E, 0x00, + 0x3E, 0x7C, 0x00, 0xFC, 0xFC, 0x03, 0xF1, 0xFC, 0x1F, 0xE3, 0xFF, 0xFF, + 0x83, 0xFF, 0xFE, 0x03, 0xFF, 0xF8, 0x03, 0xFF, 0xC0, 0x01, 0xFC, 0x00, + 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x3F, 0xF8, 0x00, 0xFF, 0xFC, 0x01, 0xFF, + 0xFE, 0x03, 0xFF, 0xFE, 0x03, 0xF0, 0x7F, 0x07, 0xE0, 0x3F, 0x07, 0xC0, + 0x1F, 0x0F, 0xC0, 0x1F, 0x0F, 0x80, 0x1F, 0x0F, 0x80, 0x1F, 0x0F, 0x80, + 0x3F, 0x0F, 0xC0, 0x7F, 0x0F, 0xE1, 0xFF, 0x07, 0xFF, 0xFE, 0x07, 0xFF, + 0xFE, 0x03, 0xFF, 0xBE, 0x01, 0xFF, 0x7C, 0x00, 0xFC, 0x7C, 0x00, 0x00, + 0xFC, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x03, 0xF0, 0x00, 0x0F, + 0xE0, 0x00, 0x1F, 0xC0, 0x38, 0x7F, 0x80, 0x7F, 0xFF, 0x00, 0xFF, 0xFE, + 0x00, 0xFF, 0xF8, 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0x80, 0x00, 0x07, 0x83, + 0xF1, 0xFC, 0x7F, 0x1F, 0x83, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3C, 0x1F, 0x8F, 0xE3, 0xF8, 0xFC, + 0x1E, 0x00, 0x00, 0x3C, 0x00, 0xFC, 0x03, 0xF8, 0x07, 0xF0, 0x0F, 0xC0, + 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xF8, 0x03, 0xE0, 0x0F, 0xC0, + 0x1F, 0x00, 0x7C, 0x00, 0xF0, 0x03, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x38, + 0x00, 0xF0, 0x01, 0xC0, 0x07, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, + 0x03, 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xE0, 0x00, + 0x7F, 0xC0, 0x00, 0xFF, 0x80, 0x03, 0xFF, 0x00, 0x07, 0xFE, 0x00, 0x0F, + 0xFC, 0x00, 0x1F, 0xF0, 0x00, 0x1F, 0xFC, 0x00, 0x01, 0xFF, 0x00, 0x00, + 0x3F, 0xE0, 0x00, 0x0F, 0xFC, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x3F, 0xE0, + 0x00, 0x07, 0xFC, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, + 0x80, 0x1F, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xFC, 0xFF, + 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, + 0xF3, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0x80, 0x00, + 0x00, 0x00, 0x07, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, + 0xFF, 0x80, 0x00, 0x1F, 0xF0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0xFF, 0xC0, + 0x00, 0x1F, 0xF0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x7F, + 0xE0, 0x00, 0xFF, 0xC0, 0x01, 0xFF, 0x80, 0x03, 0xFE, 0x00, 0x07, 0xFC, + 0x00, 0x1F, 0xF8, 0x00, 0x3F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0x80, + 0x00, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFC, 0x01, 0xFF, + 0xE1, 0xFF, 0xFE, 0x3F, 0xFF, 0xE7, 0xFF, 0xFF, 0xF8, 0x1F, 0xFE, 0x00, + 0xFF, 0x80, 0x1F, 0xF0, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x0F, + 0xE0, 0x07, 0xF8, 0x07, 0xFE, 0x01, 0xFF, 0x80, 0x7F, 0xC0, 0x0F, 0xE0, + 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x03, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xF0, 0x00, 0x3F, 0x00, 0x0F, 0xE0, 0x01, 0xFC, 0x00, + 0x3F, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x7F, 0xF0, 0x01, + 0xFF, 0xF0, 0x0F, 0xFF, 0xE0, 0x3F, 0x07, 0xE0, 0x7C, 0x07, 0xC1, 0xE0, + 0x07, 0x87, 0xC0, 0x0F, 0x0F, 0x00, 0x1C, 0x3C, 0x00, 0x78, 0x78, 0x07, + 0xF1, 0xE0, 0x3F, 0xE3, 0xC1, 0xFF, 0x87, 0x87, 0xFF, 0x0E, 0x1F, 0x9E, + 0x3C, 0x7C, 0x3C, 0x78, 0xF0, 0x78, 0xF3, 0xC0, 0xE1, 0xC7, 0x83, 0xC3, + 0x8F, 0x07, 0x8F, 0x1E, 0x0F, 0x1E, 0x3E, 0x1C, 0x3C, 0x7F, 0xFC, 0x78, + 0x7F, 0xFC, 0xF0, 0x7F, 0xF1, 0xE0, 0x3F, 0xE3, 0xC0, 0x00, 0x07, 0x80, + 0x00, 0x0F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x3F, 0x01, + 0xC0, 0x7F, 0xFF, 0x80, 0x7F, 0xFE, 0x00, 0x7F, 0xF8, 0x00, 0x3F, 0x80, + 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x01, 0xFF, 0xF8, 0x00, 0x07, 0xFF, 0xE0, + 0x00, 0x1F, 0xFF, 0x80, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x0F, 0xFC, 0x00, + 0x00, 0x7F, 0xF0, 0x00, 0x01, 0xE7, 0xC0, 0x00, 0x0F, 0x9F, 0x00, 0x00, + 0x7C, 0x7C, 0x00, 0x01, 0xE1, 0xF8, 0x00, 0x0F, 0x87, 0xE0, 0x00, 0x7C, + 0x0F, 0x80, 0x01, 0xF0, 0x3E, 0x00, 0x0F, 0x80, 0xF8, 0x00, 0x3F, 0xFF, + 0xF0, 0x01, 0xFF, 0xFF, 0xC0, 0x0F, 0xFF, 0xFF, 0x00, 0x3F, 0xFF, 0xFC, + 0x01, 0xFF, 0xFF, 0xF8, 0x0F, 0xC0, 0x07, 0xE0, 0x3E, 0x00, 0x0F, 0x87, + 0xFF, 0x03, 0xFF, 0xBF, 0xFC, 0x1F, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xFF, + 0xC1, 0xFF, 0xEF, 0xFE, 0x07, 0xFF, 0x00, 0x03, 0xFF, 0xFF, 0x80, 0x3F, + 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0xFC, 0x0F, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, + 0xFF, 0x80, 0x7C, 0x00, 0xFC, 0x03, 0xE0, 0x03, 0xE0, 0x1E, 0x00, 0x1F, + 0x01, 0xF0, 0x00, 0xF8, 0x0F, 0x80, 0x0F, 0x80, 0x7C, 0x01, 0xF8, 0x03, + 0xFF, 0xFF, 0x80, 0x1F, 0xFF, 0xF8, 0x01, 0xFF, 0xFF, 0xC0, 0x0F, 0xFF, + 0xFF, 0x80, 0x7F, 0xFF, 0xFC, 0x03, 0xC0, 0x0F, 0xF0, 0x3E, 0x00, 0x1F, + 0x81, 0xF0, 0x00, 0x7C, 0x0F, 0x80, 0x03, 0xE0, 0x78, 0x00, 0x1F, 0x03, + 0xC0, 0x03, 0xF1, 0xFF, 0xFF, 0xFF, 0x9F, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, + 0xFF, 0x87, 0xFF, 0xFF, 0xF0, 0x1F, 0xFF, 0xFE, 0x00, 0x00, 0x07, 0xF0, + 0x00, 0x03, 0xFF, 0xE6, 0x00, 0x7F, 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0x03, + 0xFF, 0xFF, 0xF0, 0x7F, 0x81, 0xFF, 0x0F, 0xE0, 0x07, 0xE1, 0xF8, 0x00, + 0x3E, 0x1F, 0x00, 0x03, 0xE3, 0xF0, 0x00, 0x3C, 0x3E, 0x00, 0x03, 0xC7, + 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x0F, 0xC0, + 0x00, 0x70, 0x7E, 0x00, 0x1F, 0x07, 0xF8, 0x07, 0xF0, 0x3F, 0xFF, 0xFF, + 0x03, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xF8, 0x00, 0x7F, 0xFE, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x03, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, 0xF0, 0x07, 0xFF, + 0xFF, 0x80, 0x7F, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0xE0, 0x1F, 0x00, 0xFE, + 0x01, 0xF0, 0x07, 0xE0, 0x1E, 0x00, 0x3F, 0x01, 0xE0, 0x01, 0xF0, 0x3E, + 0x00, 0x1F, 0x03, 0xE0, 0x01, 0xF0, 0x3E, 0x00, 0x1F, 0x03, 0xC0, 0x01, + 0xF0, 0x7C, 0x00, 0x1F, 0x07, 0xC0, 0x03, 0xF0, 0x7C, 0x00, 0x3E, 0x07, + 0x80, 0x03, 0xE0, 0x78, 0x00, 0x7E, 0x0F, 0x80, 0x07, 0xC0, 0xF8, 0x00, + 0xFC, 0x0F, 0x80, 0x1F, 0x80, 0xF0, 0x07, 0xF0, 0x7F, 0xFF, 0xFE, 0x07, + 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, + 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xF8, 0x3F, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, + 0xFE, 0x1F, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0xFF, 0x00, 0x78, 0x00, 0xF8, + 0x07, 0xC0, 0x07, 0xC0, 0x3E, 0x00, 0x3E, 0x01, 0xF0, 0xF1, 0xE0, 0x0F, + 0x0F, 0x8E, 0x00, 0x78, 0x7C, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x3F, 0xFE, + 0x00, 0x01, 0xFF, 0xF0, 0x00, 0x0F, 0xFF, 0x80, 0x00, 0xFF, 0xFC, 0x00, + 0x07, 0xC3, 0xC0, 0x00, 0x3E, 0x1E, 0x1E, 0x01, 0xE0, 0xE0, 0xF0, 0x0F, + 0x00, 0x0F, 0x80, 0xF8, 0x00, 0x7C, 0x07, 0xC0, 0x03, 0xE1, 0xFF, 0xFF, + 0xFE, 0x1F, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xFC, + 0x3F, 0xFF, 0xFF, 0xC0, 0x03, 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xF8, + 0x1F, 0xFF, 0xFF, 0xF0, 0x3F, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, 0xFF, 0xC0, + 0x1F, 0x00, 0x0F, 0x80, 0x3E, 0x00, 0x1E, 0x00, 0x78, 0x00, 0x7C, 0x00, + 0xF0, 0x70, 0xF8, 0x03, 0xE1, 0xF0, 0xE0, 0x07, 0xC3, 0xC0, 0x00, 0x0F, + 0xFF, 0x80, 0x00, 0x1F, 0xFF, 0x00, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0xFF, + 0xFC, 0x00, 0x01, 0xFF, 0xF0, 0x00, 0x03, 0xC3, 0xE0, 0x00, 0x07, 0x87, + 0xC0, 0x00, 0x1F, 0x07, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x3F, 0xFF, 0x80, + 0x00, 0xFF, 0xFF, 0x00, 0x01, 0xFF, 0xFE, 0x00, 0x01, 0xFF, 0xF8, 0x00, + 0x00, 0x00, 0x07, 0xF8, 0x60, 0x03, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xF0, + 0x1F, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xE0, 0x7F, 0x80, 0xFE, 0x0F, 0xE0, + 0x03, 0xE0, 0xF8, 0x00, 0x3C, 0x1F, 0x00, 0x03, 0xC3, 0xF0, 0x00, 0x00, + 0x3E, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, 0x7F, 0xFC, 0xF8, 0x0F, 0xFF, + 0xEF, 0x80, 0xFF, 0xFE, 0xF8, 0x0F, 0xFF, 0xCF, 0x80, 0x7F, 0xF8, 0xF8, + 0x00, 0x1F, 0x0F, 0xC0, 0x01, 0xF0, 0xFE, 0x00, 0x1F, 0x07, 0xF8, 0x07, + 0xE0, 0x7F, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFC, 0x00, + 0x7F, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x01, 0xFF, 0x0F, 0xF8, 0x0F, + 0xFC, 0x7F, 0xF0, 0x7F, 0xF1, 0xFF, 0xC1, 0xFF, 0xC7, 0xFE, 0x03, 0xFE, + 0x1F, 0xF0, 0x07, 0xC0, 0x0F, 0x80, 0x1F, 0x00, 0x3C, 0x00, 0x78, 0x00, + 0xF0, 0x01, 0xE0, 0x07, 0xC0, 0x0F, 0x80, 0x1F, 0x00, 0x3E, 0x00, 0x7C, + 0x00, 0xFF, 0xFF, 0xE0, 0x03, 0xFF, 0xFF, 0x80, 0x1F, 0xFF, 0xFE, 0x00, + 0x7F, 0xFF, 0xF8, 0x01, 0xFF, 0xFF, 0xC0, 0x07, 0x80, 0x1F, 0x00, 0x1E, + 0x00, 0x7C, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, 0x07, 0xC0, 0x0F, 0x80, + 0x1E, 0x00, 0x3C, 0x00, 0xF8, 0x07, 0xFE, 0x1F, 0xF8, 0x3F, 0xF8, 0xFF, + 0xF0, 0xFF, 0xE3, 0xFF, 0xC3, 0xFF, 0x8F, 0xFE, 0x0F, 0xFC, 0x3F, 0xF8, + 0x00, 0x03, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, 0xE0, 0xFF, + 0xFF, 0xF0, 0x7F, 0xFF, 0xF0, 0x00, 0x7C, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, + 0x03, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x07, 0x80, 0x00, 0x07, 0xC0, 0x01, 0xFF, 0xFF, + 0xC1, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xF8, 0x1F, 0xFF, + 0xF8, 0x00, 0x00, 0x07, 0xFF, 0xFE, 0x00, 0x1F, 0xFF, 0xFC, 0x00, 0x3F, + 0xFF, 0xF8, 0x00, 0x7F, 0xFF, 0xF0, 0x00, 0x7F, 0xFF, 0xC0, 0x00, 0x01, + 0xF0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x0F, + 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x00, 0xF8, + 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x07, 0xC0, 0x07, 0x00, 0x0F, 0x80, + 0x1F, 0x00, 0x1F, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x78, 0x00, 0x78, 0x01, + 0xF0, 0x01, 0xF0, 0x03, 0xE0, 0x03, 0xE0, 0x07, 0xC0, 0x0F, 0x80, 0x0F, + 0x80, 0x3F, 0x00, 0x1F, 0xC0, 0xFC, 0x00, 0x7F, 0xFF, 0xF8, 0x00, 0xFF, + 0xFF, 0xE0, 0x00, 0x7F, 0xFF, 0x00, 0x00, 0x3F, 0xFC, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x00, 0x03, 0xFF, 0xC3, 0xFE, 0x0F, 0xFF, 0x8F, 0xFC, 0x1F, + 0xFF, 0x3F, 0xF8, 0x3F, 0xFE, 0x7F, 0xF0, 0x7F, 0xF8, 0x7F, 0xC0, 0x1F, + 0x01, 0xFC, 0x00, 0x3E, 0x07, 0xF0, 0x00, 0x78, 0x3F, 0x80, 0x01, 0xF0, + 0xFE, 0x00, 0x03, 0xE3, 0xF0, 0x00, 0x07, 0xDF, 0xC0, 0x00, 0x0F, 0xFE, + 0x00, 0x00, 0x1F, 0xFE, 0x00, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0xFF, 0xFE, + 0x00, 0x01, 0xFC, 0xFC, 0x00, 0x03, 0xE0, 0xFC, 0x00, 0x0F, 0x81, 0xF8, + 0x00, 0x1F, 0x01, 0xF8, 0x00, 0x3E, 0x03, 0xF0, 0x00, 0x78, 0x03, 0xE0, + 0x00, 0xF0, 0x07, 0xE0, 0x1F, 0xFE, 0x0F, 0xF8, 0x7F, 0xFC, 0x1F, 0xF8, + 0xFF, 0xF8, 0x1F, 0xF1, 0xFF, 0xF0, 0x3F, 0xE1, 0xFF, 0xC0, 0x7F, 0x80, + 0x03, 0xFF, 0xF8, 0x00, 0xFF, 0xFF, 0x00, 0x1F, 0xFF, 0xE0, 0x03, 0xFF, + 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x01, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x00, + 0x3E, 0x00, 0x00, 0x07, 0xC0, 0x0E, 0x00, 0xF0, 0x01, 0xE0, 0x3E, 0x00, + 0x7C, 0x07, 0xC0, 0x0F, 0x80, 0xF8, 0x01, 0xF0, 0x1E, 0x00, 0x7C, 0x07, + 0xC0, 0x0F, 0x9F, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, + 0x9F, 0xFF, 0xFF, 0xF1, 0xFF, 0xFF, 0xFE, 0x00, 0x03, 0xFC, 0x00, 0x3F, + 0xC1, 0xFF, 0x00, 0x1F, 0xF0, 0x7F, 0xC0, 0x07, 0xFC, 0x1F, 0xF0, 0x03, + 0xFE, 0x01, 0xFE, 0x01, 0xFE, 0x00, 0xFF, 0x80, 0xFF, 0x80, 0x3F, 0xE0, + 0x3F, 0xE0, 0x0F, 0xF8, 0x1F, 0xF0, 0x03, 0xFF, 0x0F, 0xFC, 0x00, 0xF7, + 0xC3, 0xFF, 0x00, 0x7D, 0xF1, 0xF7, 0xC0, 0x1F, 0x7C, 0xFD, 0xF0, 0x07, + 0xDF, 0xBE, 0x78, 0x01, 0xE3, 0xFF, 0x3E, 0x00, 0x78, 0xFF, 0xCF, 0x80, + 0x3E, 0x3F, 0xE3, 0xE0, 0x0F, 0x87, 0xF0, 0xF8, 0x03, 0xE1, 0xFC, 0x3C, + 0x00, 0xF0, 0x7E, 0x1F, 0x00, 0x7C, 0x1F, 0x07, 0xC0, 0x1F, 0x00, 0x01, + 0xF0, 0x07, 0xC0, 0x00, 0x78, 0x07, 0xFE, 0x01, 0xFF, 0x83, 0xFF, 0xC0, + 0xFF, 0xF0, 0xFF, 0xF0, 0x7F, 0xFC, 0x3F, 0xF8, 0x1F, 0xFE, 0x0F, 0xFC, + 0x03, 0xFF, 0x00, 0x07, 0xF8, 0x07, 0xFF, 0x0F, 0xFC, 0x0F, 0xFF, 0x0F, + 0xFC, 0x0F, 0xFF, 0x0F, 0xFC, 0x0F, 0xFF, 0x0F, 0xFE, 0x0F, 0xFE, 0x01, + 0xFE, 0x00, 0xF8, 0x01, 0xFF, 0x00, 0xF0, 0x01, 0xFF, 0x01, 0xF0, 0x03, + 0xFF, 0x81, 0xF0, 0x03, 0xFF, 0x81, 0xF0, 0x03, 0xEF, 0xC1, 0xF0, 0x03, + 0xCF, 0xC1, 0xE0, 0x07, 0xC7, 0xE3, 0xE0, 0x07, 0xC7, 0xE3, 0xE0, 0x07, + 0xC3, 0xF3, 0xE0, 0x07, 0xC3, 0xF3, 0xC0, 0x07, 0x81, 0xF7, 0xC0, 0x0F, + 0x81, 0xFF, 0xC0, 0x0F, 0x80, 0xFF, 0xC0, 0x0F, 0x80, 0xFF, 0xC0, 0x0F, + 0x00, 0xFF, 0x80, 0x0F, 0x00, 0x7F, 0x80, 0x7F, 0xF0, 0x7F, 0x80, 0xFF, + 0xF0, 0x3F, 0x80, 0xFF, 0xF0, 0x3F, 0x00, 0xFF, 0xF0, 0x1F, 0x00, 0x7F, + 0xE0, 0x1F, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xFF, 0x80, 0x01, 0xFF, + 0xF8, 0x00, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xF8, 0x0F, 0xF0, 0x7F, 0x83, + 0xF8, 0x03, 0xF0, 0xFC, 0x00, 0x7E, 0x1F, 0x00, 0x07, 0xE7, 0xE0, 0x00, + 0x7C, 0xF8, 0x00, 0x0F, 0xBE, 0x00, 0x01, 0xF7, 0xC0, 0x00, 0x3E, 0xF0, + 0x00, 0x07, 0xFE, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x3E, 0xF8, 0x00, 0x07, + 0xDF, 0x00, 0x00, 0xFB, 0xE0, 0x00, 0x3E, 0x7C, 0x00, 0x0F, 0xCF, 0xC0, + 0x01, 0xF0, 0xF8, 0x00, 0x7E, 0x1F, 0x80, 0x3F, 0x83, 0xFC, 0x1F, 0xE0, + 0x3F, 0xFF, 0xF8, 0x03, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0x00, 0x03, 0xFF, + 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xF8, + 0x07, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xF0, 0x0F, + 0x80, 0x7F, 0x00, 0xF8, 0x01, 0xF0, 0x0F, 0x00, 0x1F, 0x01, 0xF0, 0x01, + 0xF0, 0x1F, 0x00, 0x1F, 0x01, 0xF0, 0x03, 0xE0, 0x1E, 0x00, 0x7E, 0x01, + 0xE0, 0x0F, 0xC0, 0x3F, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, + 0xE0, 0x03, 0xFF, 0xFC, 0x00, 0x7F, 0xFE, 0x00, 0x07, 0xC0, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x78, 0x00, 0x00, 0x7F, 0xFF, + 0x00, 0x0F, 0xFF, 0xF0, 0x00, 0xFF, 0xFF, 0x00, 0x0F, 0xFF, 0xF0, 0x00, + 0x7F, 0xFE, 0x00, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xFF, 0x80, 0x03, + 0xFF, 0xF8, 0x00, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xF8, 0x0F, 0xF0, 0x7F, + 0x83, 0xF8, 0x03, 0xF0, 0xFC, 0x00, 0x3F, 0x1F, 0x00, 0x07, 0xE7, 0xC0, + 0x00, 0x7D, 0xF8, 0x00, 0x0F, 0xBE, 0x00, 0x01, 0xF7, 0xC0, 0x00, 0x3F, + 0xF0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x3E, 0xF8, 0x00, + 0x07, 0xDF, 0x00, 0x01, 0xFB, 0xE0, 0x00, 0x3E, 0x7E, 0x00, 0x0F, 0x8F, + 0xC0, 0x03, 0xF0, 0xFC, 0x01, 0xFC, 0x1F, 0xE0, 0xFF, 0x01, 0xFF, 0xFF, + 0xC0, 0x1F, 0xFF, 0xF0, 0x01, 0xFF, 0xFC, 0x00, 0x1F, 0xFE, 0x00, 0x01, + 0xFE, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1F, 0xF8, 0x38, 0x0F, 0xFF, 0xFF, + 0x81, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xFC, 0x0F, 0xFF, 0xFF, 0x00, 0xF0, + 0x1F, 0x80, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0xFC, 0x01, 0xFF, + 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xFF, 0x00, 0x7C, 0x03, + 0xF8, 0x03, 0xE0, 0x07, 0xC0, 0x1E, 0x00, 0x3E, 0x00, 0xF0, 0x01, 0xF0, + 0x0F, 0x80, 0x1F, 0x80, 0x7C, 0x01, 0xF8, 0x03, 0xE0, 0x3F, 0x80, 0x1F, + 0xFF, 0xFC, 0x01, 0xFF, 0xFF, 0x80, 0x0F, 0xFF, 0xF8, 0x00, 0x7F, 0xFF, + 0x00, 0x03, 0xFF, 0xFC, 0x00, 0x1E, 0x07, 0xF0, 0x01, 0xF0, 0x1F, 0xC0, + 0x0F, 0x80, 0x7E, 0x00, 0x7C, 0x03, 0xF8, 0x03, 0xC0, 0x0F, 0xC0, 0xFF, + 0xE0, 0x7F, 0xCF, 0xFF, 0x01, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xC0, + 0x3F, 0xDF, 0xFC, 0x01, 0xFC, 0x00, 0x0F, 0xE1, 0x80, 0x0F, 0xFF, 0xF0, + 0x0F, 0xFF, 0xFC, 0x07, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xC1, 0xFC, 0x0F, + 0xE0, 0x7C, 0x01, 0xF8, 0x3E, 0x00, 0x3E, 0x0F, 0x80, 0x0F, 0x03, 0xE0, + 0x03, 0xC0, 0xFC, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x07, 0xFF, 0x80, 0x01, + 0xFF, 0xFC, 0x00, 0x3F, 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, 0x07, 0xFE, + 0x00, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xE1, 0xE0, 0x00, 0xF8, 0xF8, 0x00, + 0x3E, 0x3E, 0x00, 0x1F, 0x8F, 0xC0, 0x0F, 0xC3, 0xFC, 0x0F, 0xF0, 0xFF, + 0xFF, 0xF8, 0x3F, 0xFF, 0xFC, 0x0F, 0xFF, 0xFE, 0x03, 0x9F, 0xFE, 0x00, + 0x01, 0xFE, 0x00, 0x00, 0x3F, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0xF7, 0xFF, + 0xFF, 0xFD, 0xFF, 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, 0x9F, 0x07, 0x83, 0xE7, + 0x83, 0xE0, 0xFB, 0xE0, 0xF8, 0x3E, 0xF8, 0x3E, 0x0F, 0x3E, 0x0F, 0x07, + 0xCF, 0x07, 0xC1, 0xF3, 0x81, 0xF0, 0x38, 0x00, 0x7C, 0x00, 0x00, 0x1E, + 0x00, 0x00, 0x07, 0x80, 0x00, 0x03, 0xE0, 0x00, 0x00, 0xF8, 0x00, 0x00, + 0x3E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, + 0x00, 0x7C, 0x00, 0x07, 0xFF, 0xF8, 0x01, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, + 0x80, 0x3F, 0xFF, 0xE0, 0x07, 0xFF, 0xF0, 0x00, 0x3F, 0xF0, 0x7F, 0xE7, + 0xFF, 0x8F, 0xFF, 0x7F, 0xF9, 0xFF, 0xF7, 0xFF, 0x1F, 0xFE, 0x7F, 0xF0, + 0xFF, 0xC1, 0xE0, 0x01, 0xF0, 0x1E, 0x00, 0x1F, 0x03, 0xE0, 0x01, 0xF0, + 0x3E, 0x00, 0x1F, 0x03, 0xE0, 0x01, 0xE0, 0x3C, 0x00, 0x3E, 0x07, 0xC0, + 0x03, 0xE0, 0x7C, 0x00, 0x3E, 0x07, 0xC0, 0x03, 0xC0, 0x7C, 0x00, 0x3C, + 0x07, 0x80, 0x07, 0xC0, 0xF8, 0x00, 0x7C, 0x0F, 0x80, 0x07, 0xC0, 0xF8, + 0x00, 0x78, 0x0F, 0x80, 0x0F, 0x80, 0xFC, 0x01, 0xF8, 0x0F, 0xC0, 0x3F, + 0x00, 0xFF, 0x07, 0xE0, 0x07, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xC0, 0x03, + 0xFF, 0xF0, 0x00, 0x0F, 0xFE, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x7F, 0xF0, + 0x1F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFC, 0x0F, + 0xFF, 0x7F, 0xE0, 0x3F, 0xF8, 0x7C, 0x00, 0x1F, 0x01, 0xF0, 0x00, 0xF8, + 0x07, 0xC0, 0x03, 0xE0, 0x1F, 0x80, 0x1F, 0x00, 0x3E, 0x00, 0xF8, 0x00, + 0xF8, 0x03, 0xE0, 0x03, 0xE0, 0x1F, 0x00, 0x0F, 0xC0, 0xFC, 0x00, 0x1F, + 0x03, 0xE0, 0x00, 0x7C, 0x1F, 0x00, 0x01, 0xF0, 0xFC, 0x00, 0x07, 0xC3, + 0xE0, 0x00, 0x1F, 0x9F, 0x00, 0x00, 0x3E, 0xFC, 0x00, 0x00, 0xFB, 0xE0, + 0x00, 0x03, 0xFF, 0x00, 0x00, 0x0F, 0xFC, 0x00, 0x00, 0x3F, 0xE0, 0x00, + 0x00, 0x7F, 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x00, 0x7F, 0xF0, 0x3F, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, + 0xFC, 0x1F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFE, 0x07, 0xFF, 0x1E, 0x00, + 0x01, 0xE0, 0xF0, 0x7C, 0x1F, 0x0F, 0x87, 0xE0, 0xF0, 0x7C, 0x3F, 0x0F, + 0x83, 0xE3, 0xF8, 0x7C, 0x1F, 0x1F, 0xE3, 0xC0, 0xF9, 0xFF, 0x3E, 0x07, + 0xCF, 0xF9, 0xF0, 0x3E, 0xFF, 0xCF, 0x01, 0xF7, 0xBE, 0xF8, 0x0F, 0xFD, + 0xF7, 0xC0, 0x7B, 0xCF, 0xFC, 0x03, 0xFE, 0x7F, 0xE0, 0x3F, 0xE3, 0xFF, + 0x01, 0xFF, 0x0F, 0xF0, 0x0F, 0xF0, 0x7F, 0x80, 0x7F, 0x83, 0xFC, 0x03, + 0xF8, 0x1F, 0xC0, 0x1F, 0xC0, 0xFE, 0x00, 0xFC, 0x07, 0xF0, 0x07, 0xE0, + 0x3F, 0x00, 0x3E, 0x01, 0xF8, 0x00, 0x01, 0xFE, 0x03, 0xFE, 0x03, 0xFF, + 0x07, 0xFF, 0x07, 0xFF, 0x07, 0xFF, 0x07, 0xFE, 0x07, 0xFE, 0x03, 0xFC, + 0x03, 0xFC, 0x00, 0xFC, 0x03, 0xF0, 0x00, 0xFE, 0x07, 0xE0, 0x00, 0x7E, + 0x1F, 0xC0, 0x00, 0x3F, 0x3F, 0x00, 0x00, 0x1F, 0xFE, 0x00, 0x00, 0x1F, + 0xFC, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, + 0xE0, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x7F, + 0xF8, 0x00, 0x00, 0xFC, 0xFC, 0x00, 0x01, 0xF8, 0x7E, 0x00, 0x03, 0xF0, + 0x7E, 0x00, 0x07, 0xE0, 0x3F, 0x00, 0x0F, 0xC0, 0x1F, 0x80, 0x7F, 0xE0, + 0x7F, 0xE0, 0xFF, 0xE0, 0xFF, 0xE0, 0xFF, 0xE0, 0xFF, 0xE0, 0xFF, 0xE0, + 0xFF, 0xE0, 0x7F, 0xC0, 0xFF, 0xC0, 0x7F, 0xC0, 0x7F, 0xFF, 0xF0, 0x3F, + 0xFF, 0xFC, 0x0F, 0xFF, 0xFF, 0x03, 0xFF, 0x7F, 0x80, 0xFF, 0x87, 0xC0, + 0x1F, 0x01, 0xF8, 0x0F, 0x80, 0x3E, 0x07, 0xC0, 0x0F, 0xC3, 0xE0, 0x01, + 0xF1, 0xF0, 0x00, 0x7E, 0xF8, 0x00, 0x0F, 0xFC, 0x00, 0x03, 0xFE, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x00, 0xF0, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, + 0xE0, 0x00, 0x00, 0x78, 0x00, 0x07, 0xFF, 0xF0, 0x03, 0xFF, 0xFE, 0x00, + 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xC0, 0x0F, 0xFF, 0xE0, 0x00, 0x01, 0xFF, + 0xFF, 0xC0, 0x3F, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xE0, + 0x3F, 0xFF, 0xFC, 0x07, 0xC0, 0x3F, 0x00, 0xF8, 0x0F, 0xC0, 0x1F, 0x03, + 0xF0, 0x03, 0xC0, 0xFC, 0x00, 0xF8, 0x3F, 0x00, 0x0E, 0x0F, 0xC0, 0x00, + 0x03, 0xF0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x1F, 0x80, + 0x00, 0x07, 0xE0, 0x00, 0x01, 0xF8, 0x0E, 0x00, 0x7E, 0x03, 0xE0, 0x1F, + 0x80, 0x7C, 0x07, 0xE0, 0x0F, 0x01, 0xF8, 0x03, 0xE0, 0x7E, 0x00, 0x7C, + 0x1F, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xFC, 0x0F, 0xFF, + 0xFF, 0x81, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0xFF, 0xC0, 0x3F, 0xF0, 0x0F, + 0xFC, 0x07, 0xFF, 0x01, 0xFF, 0x80, 0x7C, 0x00, 0x1E, 0x00, 0x07, 0x80, + 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x07, 0xC0, 0x01, + 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0x80, 0x03, 0xE0, 0x00, 0xF8, + 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x1F, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, + 0x80, 0x03, 0xC0, 0x01, 0xF0, 0x00, 0x7F, 0xE0, 0x1F, 0xF8, 0x07, 0xFE, + 0x01, 0xFF, 0x80, 0xFF, 0xC0, 0x00, 0x20, 0x03, 0xC0, 0x3E, 0x01, 0xF0, + 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x3E, 0x01, 0xF0, 0x0F, 0x80, + 0x7C, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x0F, 0x80, 0x7C, 0x03, + 0xE0, 0x1F, 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0x7C, 0x03, 0xE0, 0x1F, + 0x00, 0xF8, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x1F, 0x00, 0xF8, + 0x07, 0xC0, 0x3E, 0x00, 0xF0, 0x07, 0x80, 0x38, 0x00, 0xFF, 0xC0, 0x7F, + 0xE0, 0x1F, 0xF8, 0x07, 0xFE, 0x01, 0xFF, 0x80, 0x03, 0xE0, 0x00, 0xF0, + 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xE0, 0x00, 0x78, 0x00, + 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, + 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x78, 0x00, 0x3E, 0x00, 0x0F, 0x80, + 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3C, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, + 0xF0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x0F, 0x80, 0x7F, 0xE0, 0x3F, 0xF8, + 0x0F, 0xFC, 0x03, 0xFF, 0x00, 0xFF, 0xC0, 0x00, 0x00, 0x08, 0x00, 0x01, + 0xC0, 0x00, 0x3C, 0x00, 0x07, 0xE0, 0x00, 0xFE, 0x00, 0x1F, 0xF0, 0x03, + 0xFF, 0x80, 0xFF, 0xF8, 0x1F, 0xCF, 0xC3, 0xF8, 0xFE, 0x7E, 0x07, 0xEF, + 0xC0, 0x3F, 0xF8, 0x03, 0xFF, 0x00, 0x1F, 0xE0, 0x00, 0xE0, 0x7F, 0xFF, + 0xFF, 0xFB, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xEF, 0xFF, 0xFF, 0xFF, 0x00, 0x60, 0xF0, 0xF8, 0x7C, 0x3E, 0x1F, 0x0F, + 0x06, 0x00, 0x3F, 0xE0, 0x03, 0xFF, 0xF8, 0x07, 0xFF, 0xFC, 0x07, 0xFF, + 0xFE, 0x07, 0xFF, 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0x3E, 0x00, 0x7F, 0xFE, 0x03, 0xFF, 0xFC, 0x0F, 0xFF, 0xFC, 0x1F, 0xFF, + 0xFC, 0x3F, 0xFF, 0xFC, 0x7F, 0x00, 0x78, 0x7C, 0x00, 0x78, 0xF8, 0x00, + 0xF8, 0xF8, 0x03, 0xF8, 0xFC, 0x0F, 0xFE, 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, + 0xFF, 0x7F, 0xFF, 0xFF, 0x3F, 0xFD, 0xFE, 0x0F, 0xE0, 0x00, 0x03, 0xFC, + 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x0F, 0xF0, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x00, 0xF0, 0xFE, 0x00, 0x0F, 0xBF, 0xFC, 0x00, 0x7F, + 0xFF, 0xF8, 0x03, 0xFF, 0xFF, 0xC0, 0x1F, 0xFF, 0xFF, 0x00, 0xFF, 0x03, + 0xF8, 0x0F, 0xE0, 0x07, 0xE0, 0x7E, 0x00, 0x3F, 0x03, 0xE0, 0x00, 0xF8, + 0x1F, 0x00, 0x07, 0xC0, 0xF0, 0x00, 0x3E, 0x0F, 0x80, 0x01, 0xF0, 0x7C, + 0x00, 0x1F, 0x03, 0xE0, 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0xC0, 0xFC, 0x00, + 0x7C, 0x0F, 0xE0, 0x07, 0xE3, 0xFF, 0xC0, 0xFE, 0x3F, 0xFF, 0xFF, 0xE1, + 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xE0, 0x7F, 0x9F, 0xFC, 0x00, 0x00, + 0x3F, 0x80, 0x00, 0x00, 0x1F, 0xE3, 0x80, 0x7F, 0xFF, 0xC0, 0x7F, 0xFF, + 0xE0, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xF8, 0xFF, 0x01, 0xFC, 0x7E, 0x00, + 0x7C, 0x7E, 0x00, 0x3E, 0x3E, 0x00, 0x0E, 0x3E, 0x00, 0x00, 0x1F, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, + 0x00, 0x01, 0xF0, 0x00, 0x00, 0xFC, 0x00, 0x0C, 0x7F, 0x80, 0x3F, 0x1F, + 0xFF, 0xFF, 0x8F, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0x00, + 0x0F, 0xFC, 0x00, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x01, 0xFE, 0x00, 0x00, + 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x7C, 0x00, 0x3F, 0x87, 0xC0, 0x0F, + 0xFF, 0x7C, 0x03, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, + 0x81, 0xFC, 0x0F, 0xF8, 0x3F, 0x00, 0x3F, 0x83, 0xE0, 0x01, 0xF0, 0x7C, + 0x00, 0x1F, 0x07, 0xC0, 0x01, 0xF0, 0xF8, 0x00, 0x1F, 0x0F, 0x80, 0x01, + 0xF0, 0xF8, 0x00, 0x1E, 0x0F, 0x80, 0x03, 0xE0, 0xF8, 0x00, 0x3E, 0x0F, + 0xC0, 0x07, 0xE0, 0xFC, 0x00, 0xFE, 0x07, 0xF0, 0x3F, 0xF8, 0x7F, 0xFF, + 0xFF, 0xC3, 0xFF, 0xFF, 0xFC, 0x3F, 0xFF, 0xFF, 0xC0, 0xFF, 0xE7, 0xF8, + 0x03, 0xF8, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0xF0, 0x03, 0xFF, + 0xF8, 0x07, 0xFF, 0xFC, 0x0F, 0xFF, 0xFE, 0x1F, 0xE0, 0x7E, 0x3F, 0x80, + 0x1F, 0x3F, 0x00, 0x0F, 0x7E, 0x00, 0x0F, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x00, + 0x00, 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x1C, 0x7F, 0x01, 0xFE, 0x7F, 0xFF, + 0xFE, 0x3F, 0xFF, 0xFE, 0x1F, 0xFF, 0xFC, 0x0F, 0xFF, 0xF0, 0x03, 0xFF, + 0x00, 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFF, 0xF0, + 0x00, 0xFF, 0xFF, 0x00, 0x1F, 0xFF, 0xE0, 0x01, 0xF0, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x7F, 0xFF, 0xF0, + 0x0F, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0x00, 0xFF, + 0xFF, 0xE0, 0x00, 0x78, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, + 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0x03, 0xE0, 0x00, 0x07, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xF0, 0x0F, + 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xF0, 0x07, 0xFF, 0xFE, 0x00, 0x00, 0x3F, + 0x80, 0x00, 0x0F, 0xFE, 0xFF, 0x03, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xFF, + 0x0F, 0xFF, 0xFF, 0xF1, 0xFC, 0x1F, 0xFE, 0x3F, 0x80, 0x7F, 0x03, 0xE0, + 0x03, 0xF0, 0x7E, 0x00, 0x3E, 0x07, 0xC0, 0x03, 0xE0, 0xF8, 0x00, 0x3E, + 0x0F, 0x80, 0x03, 0xE0, 0xF8, 0x00, 0x3E, 0x0F, 0x80, 0x03, 0xC0, 0xF8, + 0x00, 0x7C, 0x0F, 0xC0, 0x0F, 0xC0, 0xFC, 0x01, 0xFC, 0x07, 0xF0, 0x7F, + 0x80, 0x7F, 0xFF, 0xF8, 0x03, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xF8, 0x00, + 0xFF, 0xEF, 0x80, 0x03, 0xF0, 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, + 0xF0, 0x00, 0x00, 0x7E, 0x00, 0x1F, 0xFF, 0xE0, 0x03, 0xFF, 0xFC, 0x00, + 0x3F, 0xFF, 0x80, 0x03, 0xFF, 0xE0, 0x00, 0x3F, 0xF8, 0x00, 0x00, 0x03, + 0xF8, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x3F, 0xE0, 0x00, + 0x07, 0xF0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, + 0x00, 0x01, 0xF1, 0xF8, 0x00, 0x79, 0xFF, 0x80, 0x1E, 0xFF, 0xF0, 0x0F, + 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x80, 0xFF, 0x07, 0xE0, 0x3F, 0x00, 0xF8, + 0x1F, 0x80, 0x3E, 0x07, 0xC0, 0x0F, 0x81, 0xF0, 0x03, 0xC0, 0x7C, 0x00, + 0xF0, 0x1E, 0x00, 0x7C, 0x0F, 0x80, 0x1F, 0x03, 0xE0, 0x07, 0xC0, 0xF8, + 0x01, 0xE0, 0x3C, 0x00, 0xF8, 0x0F, 0x00, 0x3E, 0x1F, 0xF8, 0x3F, 0xEF, + 0xFE, 0x1F, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xF0, 0x3F, + 0xE0, 0x00, 0x07, 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x1F, 0x80, 0x00, 0x3E, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0xFF, 0xC0, 0x07, 0xFF, 0x80, 0x0F, 0xFE, 0x00, 0x1F, 0xFC, 0x00, + 0x3F, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x80, 0x00, + 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF0, 0x00, 0x01, + 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x3F, 0xFF, + 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, + 0x80, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xF0, 0x00, 0x07, + 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0xFF, 0xFE, 0x07, 0xFF, 0xFC, 0x0F, 0xFF, 0xF8, 0x1F, 0xFF, 0xF0, + 0x3F, 0xFF, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x07, 0xC0, 0x00, + 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF8, 0x00, 0x01, + 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0xC0, + 0xFF, 0xFF, 0x03, 0xFF, 0xFC, 0x07, 0xFF, 0xF0, 0x0F, 0xFF, 0xC0, 0x0F, + 0xFC, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, 0xC0, + 0x00, 0x1F, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x0F, + 0x80, 0x00, 0x03, 0xE0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x3C, 0x3F, 0xF0, + 0x1F, 0x1F, 0xFC, 0x07, 0xC7, 0xFF, 0x01, 0xF1, 0xFF, 0xC0, 0x78, 0x7F, + 0xE0, 0x1E, 0x7F, 0x80, 0x0F, 0xBF, 0x80, 0x03, 0xFF, 0xC0, 0x00, 0xFF, + 0xC0, 0x00, 0x3F, 0xE0, 0x00, 0x0F, 0xFC, 0x00, 0x07, 0xFF, 0x80, 0x01, + 0xF7, 0xF0, 0x00, 0x7C, 0xFE, 0x00, 0x1E, 0x1F, 0xC0, 0x0F, 0x83, 0xF8, + 0x1F, 0xE0, 0xFF, 0xEF, 0xF8, 0x3F, 0xFB, 0xFE, 0x1F, 0xFE, 0xFF, 0x07, + 0xFF, 0x9F, 0xC0, 0xFF, 0xC0, 0x00, 0x7F, 0xF0, 0x01, 0xFF, 0xC0, 0x03, + 0xFF, 0x80, 0x07, 0xFF, 0x00, 0x0F, 0xFE, 0x00, 0x00, 0x7C, 0x00, 0x00, + 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, + 0x00, 0x07, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0xF8, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x80, 0x00, + 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x7F, 0xFF, 0xF9, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0x00, 0x00, 0x07, 0x81, 0xE0, + 0x3F, 0xBF, 0x9F, 0xE1, 0xFF, 0xFE, 0xFF, 0x87, 0xFF, 0xFF, 0xFF, 0x1F, + 0xFF, 0xFF, 0xFC, 0x7F, 0xC7, 0xF1, 0xF0, 0x7E, 0x1F, 0x87, 0xC1, 0xF0, + 0x7C, 0x1F, 0x07, 0x81, 0xE0, 0x7C, 0x1E, 0x0F, 0x81, 0xE0, 0xF8, 0x3E, + 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3C, 0x0F, 0x03, + 0xC1, 0xF0, 0x7C, 0x0F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF1, + 0xFE, 0x1F, 0x87, 0xEF, 0xFC, 0x7F, 0x1F, 0xFF, 0xF3, 0xFC, 0x7F, 0xFF, + 0xCF, 0xF3, 0xFF, 0xFE, 0x3F, 0x8F, 0xE0, 0x00, 0x01, 0xF8, 0x01, 0xF9, + 0xFF, 0x80, 0xFE, 0xFF, 0xF0, 0x7F, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0x83, + 0xFF, 0x07, 0xE0, 0x3F, 0x00, 0xF8, 0x1F, 0x80, 0x3E, 0x07, 0xC0, 0x0F, + 0x81, 0xF0, 0x03, 0xC0, 0x7C, 0x00, 0xF0, 0x1E, 0x00, 0x7C, 0x0F, 0x80, + 0x1F, 0x03, 0xE0, 0x07, 0xC0, 0xF8, 0x01, 0xE0, 0x3C, 0x00, 0xF8, 0x0F, + 0x00, 0x3E, 0x1F, 0xF8, 0x3F, 0xEF, 0xFE, 0x1F, 0xFF, 0xFF, 0x87, 0xFF, + 0xFF, 0xE1, 0xFF, 0xFF, 0xF0, 0x3F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x7F, + 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xF0, 0xFF, + 0x03, 0xF8, 0xFE, 0x00, 0xFE, 0x7C, 0x00, 0x3F, 0x7C, 0x00, 0x0F, 0xBE, + 0x00, 0x07, 0xFE, 0x00, 0x03, 0xFF, 0x00, 0x01, 0xFF, 0x80, 0x00, 0xFF, + 0xC0, 0x00, 0xFB, 0xE0, 0x00, 0xFD, 0xF8, 0x00, 0x7C, 0xFE, 0x00, 0xFE, + 0x3F, 0x81, 0xFE, 0x1F, 0xFF, 0xFE, 0x07, 0xFF, 0xFE, 0x01, 0xFF, 0xFC, + 0x00, 0x7F, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x00, 0x3F, 0x80, 0x07, + 0xF9, 0xFF, 0xC0, 0x1F, 0xF7, 0xFF, 0xC0, 0x3F, 0xFF, 0xFF, 0xC0, 0x7F, + 0xFF, 0xFF, 0xC0, 0x7F, 0xF0, 0x3F, 0x80, 0x3F, 0x80, 0x1F, 0x80, 0x7E, + 0x00, 0x3F, 0x00, 0xF8, 0x00, 0x3E, 0x01, 0xF0, 0x00, 0x7C, 0x03, 0xC0, + 0x00, 0xF8, 0x0F, 0x80, 0x01, 0xF0, 0x1F, 0x00, 0x07, 0xE0, 0x3E, 0x00, + 0x0F, 0x80, 0x7C, 0x00, 0x3F, 0x01, 0xFC, 0x00, 0xFC, 0x03, 0xFE, 0x07, + 0xF8, 0x07, 0xFF, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0x80, 0x1E, 0xFF, 0xFC, + 0x00, 0x7C, 0xFF, 0xF0, 0x00, 0xF8, 0x7F, 0x00, 0x01, 0xF0, 0x00, 0x00, + 0x03, 0xE0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, + 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x1F, + 0xFF, 0x80, 0x00, 0x3F, 0xFE, 0x00, 0x00, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x07, 0xFF, 0x3F, 0xC0, 0xFF, 0xFD, 0xFE, 0x0F, 0xFF, 0xFF, 0xF0, 0xFF, + 0xFF, 0xFF, 0x8F, 0xE0, 0x7F, 0xF8, 0xFC, 0x00, 0xFE, 0x07, 0xC0, 0x03, + 0xE0, 0x7C, 0x00, 0x1F, 0x03, 0xE0, 0x00, 0xF8, 0x1E, 0x00, 0x07, 0xC1, + 0xF0, 0x00, 0x3E, 0x0F, 0x80, 0x01, 0xE0, 0x7C, 0x00, 0x1F, 0x03, 0xF0, + 0x01, 0xF8, 0x1F, 0x80, 0x1F, 0xC0, 0xFF, 0x03, 0xFC, 0x03, 0xFF, 0xFF, + 0xE0, 0x1F, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xF8, 0x00, 0xFF, 0xE7, 0xC0, + 0x01, 0xFC, 0x3C, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x07, 0xFF, 0x80, 0x00, 0x7F, + 0xFE, 0x00, 0x07, 0xFF, 0xF0, 0x00, 0x3F, 0xFF, 0x00, 0x00, 0xFF, 0xF0, + 0x00, 0x00, 0x00, 0x0F, 0x80, 0x3F, 0xC3, 0xFE, 0x07, 0xFC, 0xFF, 0xE0, + 0x7F, 0xDF, 0xFF, 0x07, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0x1C, 0x00, 0x7F, + 0xC0, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x0F, 0xC0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x01, 0xE0, 0x00, + 0x07, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0x00, 0xFF, + 0xFF, 0xF0, 0x07, 0xFF, 0xFE, 0x00, 0x00, 0x3F, 0xCE, 0x03, 0xFF, 0xFC, + 0x0F, 0xFF, 0xF8, 0x3F, 0xFF, 0xF0, 0xFF, 0xFF, 0xC3, 0xF8, 0x0F, 0x87, + 0xC0, 0x0E, 0x0F, 0x80, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xFF, 0x80, 0x3F, + 0xFF, 0xC0, 0x3F, 0xFF, 0xC0, 0x1F, 0xFF, 0xC0, 0x01, 0xFF, 0x80, 0x00, + 0x3F, 0x1C, 0x00, 0x3E, 0x7C, 0x00, 0x7C, 0xFC, 0x03, 0xF3, 0xFF, 0xFF, + 0xE7, 0xFF, 0xFF, 0x8F, 0xFF, 0xFE, 0x1F, 0xFF, 0xF0, 0x00, 0xFF, 0x00, + 0x00, 0x03, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, + 0x80, 0x00, 0x78, 0x00, 0x7F, 0xFF, 0xEF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xE1, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xE0, 0x00, + 0x1E, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x3C, 0x00, + 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7E, 0x00, 0xF7, 0xFF, + 0xFF, 0x7F, 0xFF, 0xF3, 0xFF, 0xFE, 0x1F, 0xFF, 0x80, 0x7F, 0x80, 0x7F, + 0x01, 0xFF, 0xFE, 0x07, 0xFF, 0xF8, 0x1F, 0xFF, 0xF0, 0x3F, 0xFF, 0xE0, + 0x3F, 0xC7, 0xC0, 0x07, 0x8F, 0x80, 0x1F, 0x3E, 0x00, 0x3E, 0x7C, 0x00, + 0x7C, 0xF8, 0x00, 0xF1, 0xF0, 0x03, 0xE3, 0xE0, 0x07, 0xC7, 0xC0, 0x0F, + 0x8F, 0x80, 0x1F, 0x1F, 0x00, 0x7C, 0x3E, 0x01, 0xF8, 0x7E, 0x0F, 0xFC, + 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xF1, 0xFF, 0xEF, 0xE1, 0xFF, 0xBF, 0x80, + 0xFC, 0x00, 0x00, 0x7F, 0xF0, 0x7F, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xF0, + 0xFF, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xE0, 0xFF, 0xE1, 0xF8, 0x03, 0xE0, + 0x0F, 0x80, 0x3E, 0x00, 0xF8, 0x07, 0xC0, 0x0F, 0x80, 0xF8, 0x00, 0xFC, + 0x1F, 0x80, 0x07, 0xC1, 0xF0, 0x00, 0x7C, 0x3E, 0x00, 0x07, 0xE7, 0xE0, + 0x00, 0x3E, 0x7C, 0x00, 0x03, 0xEF, 0x80, 0x00, 0x3F, 0xF0, 0x00, 0x03, + 0xFF, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0x7F, 0xC0, 0x1F, 0xEF, 0xFC, 0x03, 0xFF, + 0xFF, 0xC0, 0x7F, 0xFF, 0xFC, 0x07, 0xFE, 0x7F, 0x80, 0x3F, 0xC3, 0xE1, + 0xF0, 0xF8, 0x3E, 0x3F, 0x0F, 0x03, 0xE3, 0xF1, 0xF0, 0x3E, 0x7F, 0x1E, + 0x03, 0xE7, 0xF3, 0xE0, 0x3E, 0xFF, 0xBC, 0x03, 0xFF, 0xFF, 0xC0, 0x3F, + 0xFF, 0xFC, 0x03, 0xFE, 0xFF, 0x80, 0x3F, 0xEF, 0xF8, 0x03, 0xFC, 0xFF, + 0x00, 0x3F, 0x8F, 0xF0, 0x03, 0xF8, 0x7E, 0x00, 0x3F, 0x07, 0xE0, 0x01, + 0xF0, 0x7C, 0x00, 0x1E, 0x07, 0xC0, 0x00, 0x03, 0xFE, 0x0F, 0xF8, 0x3F, + 0xF0, 0xFF, 0xC1, 0xFF, 0x8F, 0xFE, 0x0F, 0xFC, 0x7F, 0xF0, 0x7F, 0xC1, + 0xFF, 0x00, 0xFE, 0x1F, 0xC0, 0x03, 0xF9, 0xFC, 0x00, 0x0F, 0xFF, 0xC0, + 0x00, 0x3F, 0xF8, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, + 0x7F, 0xE0, 0x00, 0x0F, 0xFF, 0x80, 0x00, 0xFE, 0xFE, 0x00, 0x0F, 0xE3, + 0xF8, 0x00, 0xFE, 0x0F, 0xE0, 0x3F, 0xE0, 0x7F, 0xC3, 0xFF, 0x87, 0xFF, + 0x3F, 0xFC, 0x7F, 0xF9, 0xFF, 0xE3, 0xFF, 0x87, 0xFE, 0x0F, 0xF8, 0x00, + 0x01, 0xFE, 0x03, 0xFE, 0x03, 0xFF, 0x07, 0xFF, 0x07, 0xFF, 0x07, 0xFF, + 0x07, 0xFF, 0x07, 0xFE, 0x03, 0xFC, 0x03, 0xFC, 0x01, 0xF8, 0x01, 0xF0, + 0x00, 0xF8, 0x03, 0xF0, 0x00, 0xF8, 0x03, 0xE0, 0x00, 0xFC, 0x07, 0xC0, + 0x00, 0x7C, 0x0F, 0x80, 0x00, 0x7C, 0x0F, 0x80, 0x00, 0x7E, 0x1F, 0x00, + 0x00, 0x7E, 0x3E, 0x00, 0x00, 0x3E, 0x7C, 0x00, 0x00, 0x3E, 0x7C, 0x00, + 0x00, 0x3F, 0xF8, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0x1F, 0xE0, 0x00, + 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x7F, 0xFF, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, + 0xFF, 0xFF, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x7F, 0xFE, 0x00, 0x00, + 0x07, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, + 0xE0, 0xFF, 0xFF, 0xE0, 0x7C, 0x0F, 0xE0, 0x3C, 0x0F, 0xE0, 0x1E, 0x0F, + 0xC0, 0x00, 0x1F, 0xC0, 0x00, 0x1F, 0xC0, 0x00, 0x1F, 0xC0, 0x00, 0x1F, + 0x80, 0x00, 0x3F, 0x80, 0x00, 0x3F, 0x80, 0x00, 0x3F, 0x80, 0xF0, 0x3F, + 0x00, 0xF8, 0x3F, 0xFF, 0xFC, 0x3F, 0xFF, 0xFE, 0x1F, 0xFF, 0xFE, 0x0F, + 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0x80, 0x00, 0x0F, 0x00, 0x1F, 0xC0, 0x1F, + 0xE0, 0x1F, 0xF0, 0x0F, 0xE0, 0x0F, 0xC0, 0x07, 0xC0, 0x07, 0xC0, 0x03, + 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x78, 0x00, 0x7C, 0x00, 0x3E, 0x00, + 0x1F, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x3F, 0x80, 0x3F, 0xC0, 0x1F, 0xC0, + 0x0F, 0xE0, 0x07, 0xF8, 0x00, 0xFC, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, + 0x80, 0x07, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, + 0x7E, 0x00, 0x3F, 0x80, 0x1F, 0xE0, 0x07, 0xF0, 0x03, 0xF8, 0x00, 0x78, + 0x00, 0x01, 0xE0, 0x3C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, 0x80, 0xF0, 0x3E, + 0x07, 0xC0, 0xF0, 0x1E, 0x03, 0xC0, 0xF8, 0x1F, 0x03, 0xC0, 0x78, 0x0F, + 0x03, 0xE0, 0x7C, 0x0F, 0x01, 0xE0, 0x3C, 0x0F, 0x81, 0xF0, 0x3C, 0x07, + 0x80, 0xF0, 0x3E, 0x07, 0xC0, 0xF0, 0x1E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, + 0xC0, 0x70, 0x00, 0x00, 0xF0, 0x00, 0xFC, 0x00, 0x7F, 0x00, 0x3F, 0xC0, + 0x0F, 0xE0, 0x03, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, + 0x00, 0x0F, 0x80, 0x07, 0x80, 0x03, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, + 0xF8, 0x00, 0x7E, 0x00, 0x3F, 0xC0, 0x0F, 0xE0, 0x07, 0xF0, 0x07, 0xF8, + 0x07, 0xF8, 0x03, 0xE0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF0, 0x00, 0x78, + 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x00, 0x1F, 0x80, 0x7F, + 0xC0, 0x7F, 0xC0, 0x3F, 0xC0, 0x1F, 0xC0, 0x07, 0x80, 0x00, 0x03, 0xE0, + 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0xE0, 0x39, 0xFF, 0xE0, 0xF7, 0xFF, 0xE7, + 0xFF, 0xCF, 0xFF, 0xFE, 0x0F, 0xFF, 0x38, 0x0F, 0xFC, 0x00, 0x0F, 0xE0, + 0x00, 0x0F, 0x80 }; + +const GFXglyph FreeMonoBoldOblique24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 28, 0, 1 }, // 0x20 ' ' + { 0, 12, 31, 28, 12, -29 }, // 0x21 '!' + { 47, 17, 14, 28, 11, -28 }, // 0x22 '"' + { 77, 24, 34, 28, 5, -30 }, // 0x23 '#' + { 179, 25, 38, 28, 4, -31 }, // 0x24 '$' + { 298, 22, 30, 28, 6, -28 }, // 0x25 '%' + { 381, 21, 28, 28, 5, -26 }, // 0x26 '&' + { 455, 7, 14, 28, 16, -28 }, // 0x27 ''' + { 468, 14, 37, 28, 14, -29 }, // 0x28 '(' + { 533, 14, 37, 28, 5, -29 }, // 0x29 ')' + { 598, 21, 19, 28, 8, -28 }, // 0x2A '*' + { 648, 24, 26, 28, 5, -25 }, // 0x2B '+' + { 726, 12, 14, 28, 6, -6 }, // 0x2C ',' + { 747, 24, 5, 28, 5, -15 }, // 0x2D '-' + { 762, 7, 6, 28, 11, -4 }, // 0x2E '.' + { 768, 28, 38, 28, 3, -32 }, // 0x2F '/' + { 901, 23, 31, 28, 6, -29 }, // 0x30 '0' + { 991, 21, 30, 28, 4, -29 }, // 0x31 '1' + { 1070, 26, 30, 28, 3, -29 }, // 0x32 '2' + { 1168, 25, 31, 28, 4, -29 }, // 0x33 '3' + { 1265, 22, 28, 28, 5, -27 }, // 0x34 '4' + { 1342, 25, 31, 28, 4, -29 }, // 0x35 '5' + { 1439, 24, 31, 28, 7, -29 }, // 0x36 '6' + { 1532, 22, 30, 28, 9, -29 }, // 0x37 '7' + { 1615, 23, 31, 28, 6, -29 }, // 0x38 '8' + { 1705, 24, 31, 28, 5, -29 }, // 0x39 '9' + { 1798, 10, 22, 28, 11, -20 }, // 0x3A ':' + { 1826, 15, 28, 28, 5, -20 }, // 0x3B ';' + { 1879, 25, 21, 28, 5, -23 }, // 0x3C '<' + { 1945, 26, 14, 28, 4, -19 }, // 0x3D '=' + { 1991, 25, 22, 28, 4, -23 }, // 0x3E '>' + { 2060, 19, 29, 28, 10, -27 }, // 0x3F '?' + { 2129, 23, 36, 28, 5, -28 }, // 0x40 '@' + { 2233, 30, 27, 28, 0, -26 }, // 0x41 'A' + { 2335, 29, 27, 28, 1, -26 }, // 0x42 'B' + { 2433, 28, 29, 28, 3, -27 }, // 0x43 'C' + { 2535, 28, 27, 28, 1, -26 }, // 0x44 'D' + { 2630, 29, 27, 28, 1, -26 }, // 0x45 'E' + { 2728, 31, 27, 28, 0, -26 }, // 0x46 'F' + { 2833, 28, 29, 28, 3, -27 }, // 0x47 'G' + { 2935, 30, 27, 28, 1, -26 }, // 0x48 'H' + { 3037, 25, 27, 28, 3, -26 }, // 0x49 'I' + { 3122, 31, 28, 28, 0, -26 }, // 0x4A 'J' + { 3231, 31, 27, 28, 0, -26 }, // 0x4B 'K' + { 3336, 27, 27, 28, 1, -26 }, // 0x4C 'L' + { 3428, 34, 27, 28, 0, -26 }, // 0x4D 'M' + { 3543, 32, 27, 28, 1, -26 }, // 0x4E 'N' + { 3651, 27, 29, 28, 3, -27 }, // 0x4F 'O' + { 3749, 28, 27, 28, 1, -26 }, // 0x50 'P' + { 3844, 27, 35, 28, 3, -27 }, // 0x51 'Q' + { 3963, 29, 27, 28, 0, -26 }, // 0x52 'R' + { 4061, 26, 29, 28, 3, -27 }, // 0x53 'S' + { 4156, 26, 27, 28, 4, -26 }, // 0x54 'T' + { 4244, 28, 28, 28, 4, -26 }, // 0x55 'U' + { 4342, 30, 27, 28, 2, -26 }, // 0x56 'V' + { 4444, 29, 27, 28, 3, -26 }, // 0x57 'W' + { 4542, 32, 27, 28, 0, -26 }, // 0x58 'X' + { 4650, 26, 27, 28, 4, -26 }, // 0x59 'Y' + { 4738, 27, 27, 28, 2, -26 }, // 0x5A 'Z' + { 4830, 18, 37, 28, 10, -29 }, // 0x5B '[' + { 4914, 13, 38, 28, 10, -32 }, // 0x5C '\' + { 4976, 18, 37, 28, 5, -29 }, // 0x5D ']' + { 5060, 20, 15, 28, 8, -29 }, // 0x5E '^' + { 5098, 29, 5, 28, -2, 5 }, // 0x5F '_' + { 5117, 8, 8, 28, 13, -30 }, // 0x60 '`' + { 5125, 24, 23, 28, 3, -21 }, // 0x61 'a' + { 5194, 29, 31, 28, 0, -29 }, // 0x62 'b' + { 5307, 25, 23, 28, 3, -21 }, // 0x63 'c' + { 5379, 28, 31, 28, 3, -29 }, // 0x64 'd' + { 5488, 24, 23, 28, 3, -21 }, // 0x65 'e' + { 5557, 28, 30, 28, 4, -29 }, // 0x66 'f' + { 5662, 28, 31, 28, 3, -21 }, // 0x67 'g' + { 5771, 26, 30, 28, 2, -29 }, // 0x68 'h' + { 5869, 23, 29, 28, 3, -28 }, // 0x69 'i' + { 5953, 23, 38, 28, 3, -28 }, // 0x6A 'j' + { 6063, 26, 30, 28, 2, -29 }, // 0x6B 'k' + { 6161, 23, 30, 28, 3, -29 }, // 0x6C 'l' + { 6248, 30, 22, 28, 0, -21 }, // 0x6D 'm' + { 6331, 26, 22, 28, 2, -21 }, // 0x6E 'n' + { 6403, 25, 23, 28, 3, -21 }, // 0x6F 'o' + { 6475, 31, 31, 28, -1, -21 }, // 0x70 'p' + { 6596, 29, 31, 28, 2, -21 }, // 0x71 'q' + { 6709, 28, 22, 28, 2, -21 }, // 0x72 'r' + { 6786, 23, 23, 28, 4, -21 }, // 0x73 's' + { 6853, 20, 28, 28, 5, -26 }, // 0x74 't' + { 6923, 23, 22, 28, 5, -20 }, // 0x75 'u' + { 6987, 28, 21, 28, 3, -20 }, // 0x76 'v' + { 7061, 28, 21, 28, 3, -20 }, // 0x77 'w' + { 7135, 29, 21, 28, 1, -20 }, // 0x78 'x' + { 7212, 32, 30, 28, -1, -20 }, // 0x79 'y' + { 7332, 25, 21, 28, 4, -20 }, // 0x7A 'z' + { 7398, 17, 37, 28, 10, -29 }, // 0x7B '{' + { 7477, 11, 36, 28, 11, -28 }, // 0x7C '|' + { 7527, 17, 37, 28, 6, -29 }, // 0x7D '}' + { 7606, 23, 10, 28, 5, -17 } }; // 0x7E '~' + +const GFXfont FreeMonoBoldOblique24pt7b PROGMEM = { + (uint8_t *)FreeMonoBoldOblique24pt7bBitmaps, + (GFXglyph *)FreeMonoBoldOblique24pt7bGlyphs, + 0x20, 0x7E, 47 }; + +// Approx. 8307 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique9pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique9pt7b.h new file mode 100644 index 0000000..b530723 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoBoldOblique9pt7b.h @@ -0,0 +1,203 @@ +const uint8_t FreeMonoBoldOblique9pt7bBitmaps[] PROGMEM = { + 0x39, 0xCC, 0x67, 0x31, 0x8C, 0x07, 0x38, 0x6C, 0xD9, 0x36, 0x48, 0x80, + 0x09, 0x0D, 0x86, 0xCF, 0xF7, 0xF9, 0xB3, 0xFD, 0xFE, 0x6C, 0x36, 0x1B, + 0x00, 0x00, 0x06, 0x07, 0x07, 0xE6, 0x33, 0x01, 0xE0, 0x7C, 0x06, 0x43, + 0x33, 0xBF, 0x83, 0x03, 0x00, 0x80, 0x1C, 0x11, 0x10, 0x88, 0x83, 0xB8, + 0xF3, 0xB8, 0x22, 0x21, 0x11, 0x07, 0x00, 0x0F, 0x1F, 0x30, 0x30, 0x38, + 0x7B, 0xDF, 0xCE, 0xFF, 0x7E, 0xFA, 0x80, 0x19, 0x8C, 0xC6, 0x63, 0x18, + 0xC6, 0x31, 0xC6, 0x30, 0x31, 0xC6, 0x31, 0x8C, 0x63, 0x31, 0x98, 0xCC, + 0x40, 0x08, 0x08, 0xFF, 0xFF, 0x38, 0x6C, 0x6C, 0x0C, 0x06, 0x03, 0x1F, + 0xFF, 0xF8, 0xC0, 0x60, 0x30, 0x10, 0x00, 0x36, 0x4C, 0x80, 0xFF, 0xFF, + 0xC0, 0xFC, 0x00, 0x00, 0x0C, 0x03, 0x00, 0xC0, 0x18, 0x06, 0x01, 0x80, + 0x30, 0x0C, 0x03, 0x00, 0x60, 0x18, 0x06, 0x00, 0xC0, 0x30, 0x00, 0x0F, + 0x0F, 0xCC, 0x6C, 0x36, 0x1B, 0x0D, 0x05, 0x86, 0xC3, 0x63, 0x3F, 0x8F, + 0x00, 0x06, 0x1C, 0x3C, 0x6C, 0x0C, 0x0C, 0x08, 0x18, 0x18, 0x18, 0xFE, + 0xFE, 0x07, 0x83, 0xF1, 0x8C, 0x43, 0x00, 0xC0, 0xE0, 0x70, 0x38, 0x38, + 0x1C, 0x6F, 0xF3, 0xFC, 0x1F, 0x1F, 0xC0, 0x60, 0x30, 0x30, 0x70, 0x38, + 0x06, 0x03, 0x03, 0xBF, 0x9F, 0x80, 0x03, 0x07, 0x0B, 0x1B, 0x32, 0x66, + 0xFF, 0xFF, 0x1E, 0x1E, 0x3F, 0x9F, 0x98, 0x0F, 0xC7, 0xF3, 0x18, 0x0C, + 0x06, 0x06, 0x7F, 0x1E, 0x00, 0x07, 0x87, 0xCE, 0x06, 0x06, 0x03, 0xF3, + 0xFD, 0xC6, 0xC3, 0x63, 0xBF, 0x8F, 0x80, 0xFF, 0xFF, 0xC3, 0x06, 0x06, + 0x0C, 0x18, 0x18, 0x30, 0x30, 0x60, 0x1F, 0x1F, 0xDC, 0x6C, 0x36, 0x31, + 0xF1, 0xF8, 0xC6, 0xC3, 0x63, 0xBF, 0x8F, 0x80, 0x1E, 0x3F, 0x33, 0x63, + 0x63, 0x67, 0x7F, 0x3E, 0x06, 0x1C, 0xF8, 0xF0, 0x77, 0x00, 0x00, 0xEE, + 0x1C, 0x70, 0x00, 0x00, 0x03, 0x0C, 0x61, 0x08, 0x00, 0x00, 0xC1, 0xE1, + 0xE1, 0xE0, 0xF0, 0x07, 0x00, 0xF0, 0x0C, 0x7F, 0xDF, 0xF0, 0x00, 0x00, + 0x7F, 0xFF, 0xF0, 0x30, 0x0F, 0x00, 0xE0, 0x1E, 0x07, 0xC7, 0x87, 0x83, + 0x00, 0x7D, 0xFF, 0x18, 0x30, 0xE3, 0x9C, 0x30, 0x01, 0xC3, 0x80, 0x0F, + 0x0F, 0xCC, 0x6C, 0x36, 0x72, 0x79, 0x7D, 0xB6, 0xDA, 0x6F, 0xB3, 0xD8, + 0x0C, 0x07, 0xE1, 0xE0, 0x0F, 0x83, 0xF0, 0x1E, 0x03, 0xC0, 0xD8, 0x31, + 0x87, 0xF1, 0xFE, 0x30, 0xDF, 0x3F, 0xC7, 0x80, 0x3F, 0xC7, 0xFC, 0x61, + 0x8C, 0x31, 0xFC, 0x3F, 0x84, 0x19, 0x83, 0x30, 0x6F, 0xFB, 0xFE, 0x00, + 0x0F, 0xF1, 0xFF, 0x30, 0x66, 0x06, 0x60, 0x0C, 0x00, 0xC0, 0x0C, 0x00, + 0xE0, 0xC7, 0xF8, 0x3F, 0x00, 0x3F, 0x87, 0xF8, 0x63, 0x8C, 0x31, 0x06, + 0x60, 0xCC, 0x19, 0x86, 0x31, 0xCF, 0xF3, 0xF8, 0x00, 0x3F, 0xE3, 0xFE, + 0x18, 0x61, 0xB6, 0x1F, 0x01, 0xF0, 0x32, 0x03, 0x00, 0x30, 0x4F, 0xFC, + 0xFF, 0xC0, 0x3F, 0xF3, 0xFE, 0x18, 0x61, 0xB6, 0x1F, 0x03, 0xF0, 0x32, + 0x03, 0x00, 0x30, 0x0F, 0xC0, 0xFC, 0x00, 0x0F, 0xE3, 0xFC, 0xC1, 0x30, + 0x06, 0x01, 0x80, 0x31, 0xF6, 0x3E, 0xE1, 0x9F, 0xF0, 0xF8, 0x00, 0x1E, + 0xF3, 0xCF, 0x18, 0x61, 0x84, 0x10, 0xC3, 0xFC, 0x3F, 0xC3, 0x08, 0x31, + 0x8F, 0xBC, 0xFB, 0xC0, 0x3F, 0xCF, 0xF0, 0x60, 0x10, 0x0C, 0x03, 0x00, + 0xC0, 0x20, 0x18, 0x3F, 0xCF, 0xF0, 0x07, 0xF0, 0x7F, 0x00, 0x80, 0x18, + 0x01, 0x80, 0x18, 0x61, 0x84, 0x10, 0xC3, 0x0F, 0xE0, 0x7C, 0x00, 0x3E, + 0xE7, 0xFC, 0x66, 0x0D, 0x81, 0x60, 0x7C, 0x0E, 0xC1, 0x98, 0x31, 0x1F, + 0x3B, 0xE7, 0x00, 0x3F, 0x07, 0xE0, 0x30, 0x06, 0x00, 0xC0, 0x10, 0x06, + 0x00, 0xC3, 0x18, 0x6F, 0xFB, 0xFF, 0x00, 0x38, 0x39, 0xC3, 0xC7, 0x3C, + 0x79, 0xE3, 0xDA, 0x1F, 0xF0, 0x9D, 0x8C, 0xCC, 0x60, 0x67, 0xCF, 0x3C, + 0x78, 0x3C, 0xF9, 0xE7, 0x87, 0x18, 0x3C, 0xC1, 0x66, 0x1B, 0xB0, 0xCD, + 0x06, 0x78, 0x31, 0xC3, 0xCE, 0x3E, 0x30, 0x0F, 0x0F, 0xE7, 0x1D, 0x83, + 0xC0, 0xF0, 0x3C, 0x0F, 0x06, 0xE3, 0x9F, 0xC3, 0xC0, 0x3F, 0xC7, 0xFC, + 0x61, 0x8C, 0x31, 0x8E, 0x3F, 0x87, 0xE1, 0x80, 0x30, 0x0F, 0xC3, 0xF0, + 0x00, 0x0F, 0x0F, 0xE7, 0x1D, 0x83, 0xC0, 0xF0, 0x3C, 0x0F, 0x06, 0xE3, + 0x1F, 0xC3, 0xC0, 0x80, 0x7F, 0x3F, 0xC0, 0x3F, 0xC3, 0xFE, 0x18, 0x61, + 0x86, 0x10, 0xE3, 0xFC, 0x3F, 0x83, 0x18, 0x31, 0xCF, 0x8F, 0xF8, 0x70, + 0x1E, 0xCF, 0xF7, 0x19, 0x80, 0x70, 0x1F, 0x81, 0xF3, 0x0C, 0xC3, 0x3F, + 0x8B, 0xC0, 0x7F, 0xCF, 0xF9, 0x93, 0x66, 0x60, 0xC0, 0x18, 0x02, 0x00, + 0xC0, 0x18, 0x0F, 0xC1, 0xF8, 0x00, 0xF9, 0xFF, 0x7D, 0x83, 0x30, 0x64, + 0x09, 0x83, 0x30, 0x66, 0x0C, 0xE3, 0x0F, 0xC0, 0xF0, 0x00, 0xF9, 0xFE, + 0x3D, 0x83, 0x30, 0xC6, 0x30, 0xE6, 0x0D, 0x81, 0xB0, 0x3C, 0x07, 0x00, + 0x60, 0x00, 0xF9, 0xFF, 0x3D, 0x83, 0x36, 0x64, 0xC8, 0xBF, 0x35, 0xE7, + 0xB8, 0xE7, 0x1C, 0xE3, 0x18, 0x00, 0x3C, 0xF3, 0xCF, 0x1C, 0xC0, 0xD8, + 0x0F, 0x00, 0x60, 0x0F, 0x01, 0xB8, 0x31, 0x8F, 0x3C, 0xF3, 0xC0, 0x79, + 0xEE, 0x38, 0xC6, 0x19, 0x81, 0xE0, 0x38, 0x06, 0x00, 0xC0, 0x18, 0x0F, + 0xC3, 0xF8, 0x00, 0x3F, 0xCF, 0xF3, 0x18, 0xCC, 0x06, 0x03, 0x01, 0x80, + 0xC6, 0x61, 0xBF, 0xCF, 0xF0, 0x1E, 0x3C, 0xC1, 0x83, 0x06, 0x08, 0x30, + 0x60, 0xC1, 0x06, 0x0F, 0x1E, 0x00, 0x06, 0x31, 0x86, 0x31, 0x8C, 0x31, + 0x8C, 0x61, 0x8C, 0x60, 0x1E, 0x78, 0x30, 0x60, 0xC1, 0x86, 0x0C, 0x18, + 0x30, 0x41, 0x8F, 0x1E, 0x00, 0x08, 0x1C, 0x3C, 0x76, 0xE7, 0xC3, 0x7F, + 0xFF, 0xFC, 0x88, 0x80, 0x0F, 0x07, 0xE1, 0xF9, 0xFE, 0xE3, 0x30, 0xCF, + 0xFD, 0xFF, 0x38, 0x07, 0x00, 0x60, 0x0F, 0xC1, 0xFC, 0x71, 0xCC, 0x19, + 0x83, 0x30, 0xDF, 0xFB, 0xBC, 0x00, 0x1F, 0xCF, 0xF6, 0x1B, 0x00, 0xC0, + 0x30, 0x0F, 0xF1, 0xF8, 0x01, 0xE0, 0x38, 0x03, 0x0F, 0x63, 0xFC, 0xC3, + 0x30, 0x66, 0x0C, 0xC3, 0x9F, 0xF9, 0xF7, 0x00, 0x1F, 0x1F, 0xD8, 0x3F, + 0xFF, 0xFE, 0x1B, 0xFC, 0xF8, 0x07, 0xC3, 0xF1, 0x81, 0xFE, 0x7F, 0x84, + 0x03, 0x00, 0xC0, 0x30, 0x3F, 0x8F, 0xE0, 0x1E, 0xE7, 0xFD, 0x86, 0x60, + 0xCC, 0x19, 0xC6, 0x3F, 0xC1, 0xD8, 0x03, 0x00, 0xE1, 0xF8, 0x3E, 0x00, + 0x38, 0x1E, 0x01, 0x00, 0xDC, 0x3F, 0x8C, 0x62, 0x19, 0x84, 0x63, 0x3D, + 0xFF, 0x7C, 0x06, 0x03, 0x00, 0x03, 0xC3, 0xE0, 0x20, 0x30, 0x18, 0x0C, + 0x3F, 0xFF, 0xE0, 0x01, 0x81, 0x80, 0x07, 0xF3, 0xF8, 0x0C, 0x04, 0x06, + 0x03, 0x01, 0x80, 0xC0, 0x40, 0x67, 0xE3, 0xE0, 0x38, 0x0E, 0x01, 0x80, + 0x4F, 0x37, 0xCF, 0x83, 0xC0, 0xF0, 0x26, 0x39, 0xEE, 0x78, 0x1F, 0x0F, + 0x01, 0x80, 0xC0, 0x60, 0x20, 0x30, 0x18, 0x0C, 0x3F, 0xFF, 0xE0, 0x7E, + 0xE7, 0xFF, 0x33, 0x32, 0x63, 0x66, 0x36, 0x62, 0xF7, 0x7F, 0x67, 0x77, + 0x8F, 0xF8, 0xC3, 0x10, 0x66, 0x08, 0xC3, 0x3C, 0x7F, 0x8F, 0x1F, 0x0F, + 0xE6, 0x1F, 0x03, 0xC0, 0xF8, 0x67, 0xF0, 0xF8, 0x3F, 0xE3, 0xFF, 0x1C, + 0x31, 0x83, 0x18, 0x31, 0x86, 0x3F, 0xE3, 0x78, 0x30, 0x03, 0x00, 0xFC, + 0x0F, 0x80, 0x1E, 0xEF, 0xFD, 0x86, 0x60, 0xCC, 0x19, 0xC7, 0x3F, 0xE1, + 0xE8, 0x03, 0x00, 0x60, 0x3E, 0x07, 0xC0, 0x39, 0xDF, 0xF1, 0xC0, 0x60, + 0x10, 0x0C, 0x0F, 0xF3, 0xF8, 0x1F, 0x7F, 0x63, 0x7E, 0x1F, 0xC3, 0xFE, + 0xFC, 0x10, 0x08, 0x0C, 0x1F, 0xEF, 0xF1, 0x80, 0x80, 0xC0, 0x60, 0x3F, + 0x8F, 0x80, 0xF3, 0xFC, 0xF6, 0x09, 0x86, 0x61, 0x98, 0xE7, 0xF8, 0xFE, + 0xFB, 0xFF, 0x7C, 0xC6, 0x19, 0x83, 0x60, 0x6C, 0x07, 0x00, 0xC0, 0xF1, + 0xFE, 0x3D, 0xB3, 0x37, 0xC7, 0xF8, 0xEE, 0x1D, 0xC3, 0x30, 0x79, 0xEF, + 0x38, 0xEE, 0x0F, 0x01, 0xE0, 0x6E, 0x3C, 0xE7, 0xBC, 0x3C, 0xF3, 0x8F, + 0x18, 0xC1, 0x9C, 0x19, 0x81, 0xF0, 0x0E, 0x00, 0xE0, 0x0C, 0x01, 0x80, + 0xFC, 0x0F, 0xC0, 0x7F, 0xBF, 0xD9, 0xC1, 0x83, 0x83, 0x1B, 0xFD, 0xFE, + 0x06, 0x1C, 0x60, 0xC1, 0x86, 0x3C, 0x70, 0x30, 0x41, 0x83, 0x07, 0x06, + 0x00, 0x33, 0x32, 0x26, 0x66, 0x44, 0xCC, 0xC8, 0x0C, 0x0E, 0x04, 0x0C, + 0x0C, 0x0C, 0x0F, 0x0F, 0x18, 0x18, 0x10, 0x30, 0xF0, 0xE0, 0x38, 0x7C, + 0xF7, 0xC1, 0xC0 }; + +const GFXglyph FreeMonoBoldOblique9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 11, 0, 1 }, // 0x20 ' ' + { 0, 5, 11, 11, 4, -10 }, // 0x21 '!' + { 7, 7, 5, 11, 4, -10 }, // 0x22 '"' + { 12, 9, 12, 11, 2, -10 }, // 0x23 '#' + { 26, 9, 14, 11, 2, -11 }, // 0x24 '$' + { 42, 9, 11, 11, 2, -10 }, // 0x25 '%' + { 55, 8, 10, 11, 2, -9 }, // 0x26 '&' + { 65, 2, 5, 11, 6, -10 }, // 0x27 ''' + { 67, 5, 14, 11, 5, -10 }, // 0x28 '(' + { 76, 5, 14, 11, 2, -10 }, // 0x29 ')' + { 85, 8, 7, 11, 3, -10 }, // 0x2A '*' + { 92, 9, 9, 11, 2, -8 }, // 0x2B '+' + { 103, 4, 5, 11, 2, -1 }, // 0x2C ',' + { 106, 9, 2, 11, 2, -5 }, // 0x2D '-' + { 109, 3, 2, 11, 4, -1 }, // 0x2E '.' + { 110, 11, 15, 11, 1, -12 }, // 0x2F '/' + { 131, 9, 12, 11, 2, -11 }, // 0x30 '0' + { 145, 8, 12, 11, 2, -11 }, // 0x31 '1' + { 157, 10, 12, 11, 1, -11 }, // 0x32 '2' + { 172, 9, 12, 11, 2, -11 }, // 0x33 '3' + { 186, 8, 10, 11, 2, -9 }, // 0x34 '4' + { 196, 9, 11, 11, 3, -10 }, // 0x35 '5' + { 209, 9, 12, 11, 3, -11 }, // 0x36 '6' + { 223, 8, 11, 11, 3, -10 }, // 0x37 '7' + { 234, 9, 12, 11, 2, -11 }, // 0x38 '8' + { 248, 8, 12, 11, 3, -11 }, // 0x39 '9' + { 260, 4, 8, 11, 4, -7 }, // 0x3A ':' + { 264, 6, 11, 11, 2, -7 }, // 0x3B ';' + { 273, 10, 8, 11, 2, -8 }, // 0x3C '<' + { 283, 10, 6, 11, 1, -7 }, // 0x3D '=' + { 291, 10, 8, 11, 1, -8 }, // 0x3E '>' + { 301, 7, 11, 11, 4, -10 }, // 0x3F '?' + { 311, 9, 15, 11, 2, -11 }, // 0x40 '@' + { 328, 11, 11, 11, 0, -10 }, // 0x41 'A' + { 344, 11, 11, 11, 0, -10 }, // 0x42 'B' + { 360, 12, 11, 11, 1, -10 }, // 0x43 'C' + { 377, 11, 11, 11, 0, -10 }, // 0x44 'D' + { 393, 12, 11, 11, 0, -10 }, // 0x45 'E' + { 410, 12, 11, 11, 0, -10 }, // 0x46 'F' + { 427, 11, 11, 11, 1, -10 }, // 0x47 'G' + { 443, 12, 11, 11, 0, -10 }, // 0x48 'H' + { 460, 10, 11, 11, 1, -10 }, // 0x49 'I' + { 474, 12, 11, 11, 0, -10 }, // 0x4A 'J' + { 491, 11, 11, 11, 0, -10 }, // 0x4B 'K' + { 507, 11, 11, 11, 0, -10 }, // 0x4C 'L' + { 523, 13, 11, 11, 0, -10 }, // 0x4D 'M' + { 541, 13, 11, 11, 0, -10 }, // 0x4E 'N' + { 559, 10, 11, 11, 1, -10 }, // 0x4F 'O' + { 573, 11, 11, 11, 0, -10 }, // 0x50 'P' + { 589, 10, 14, 11, 1, -10 }, // 0x51 'Q' + { 607, 12, 11, 11, 0, -10 }, // 0x52 'R' + { 624, 10, 11, 11, 2, -10 }, // 0x53 'S' + { 638, 11, 11, 11, 1, -10 }, // 0x54 'T' + { 654, 11, 11, 11, 1, -10 }, // 0x55 'U' + { 670, 11, 11, 11, 1, -10 }, // 0x56 'V' + { 686, 11, 11, 11, 1, -10 }, // 0x57 'W' + { 702, 12, 11, 11, 0, -10 }, // 0x58 'X' + { 719, 11, 11, 11, 1, -10 }, // 0x59 'Y' + { 735, 10, 11, 11, 1, -10 }, // 0x5A 'Z' + { 749, 7, 14, 11, 4, -10 }, // 0x5B '[' + { 762, 5, 15, 11, 4, -12 }, // 0x5C '\' + { 772, 7, 14, 11, 2, -10 }, // 0x5D ']' + { 785, 8, 6, 11, 3, -11 }, // 0x5E '^' + { 791, 11, 2, 11, -1, 3 }, // 0x5F '_' + { 794, 3, 3, 11, 5, -11 }, // 0x60 '`' + { 796, 10, 8, 11, 1, -7 }, // 0x61 'a' + { 806, 11, 11, 11, 0, -10 }, // 0x62 'b' + { 822, 10, 8, 11, 1, -7 }, // 0x63 'c' + { 832, 11, 11, 11, 1, -10 }, // 0x64 'd' + { 848, 9, 8, 11, 1, -7 }, // 0x65 'e' + { 857, 10, 11, 11, 2, -10 }, // 0x66 'f' + { 871, 11, 12, 11, 1, -7 }, // 0x67 'g' + { 888, 10, 11, 11, 1, -10 }, // 0x68 'h' + { 902, 9, 11, 11, 1, -10 }, // 0x69 'i' + { 915, 9, 15, 11, 1, -10 }, // 0x6A 'j' + { 932, 10, 11, 11, 1, -10 }, // 0x6B 'k' + { 946, 9, 11, 11, 1, -10 }, // 0x6C 'l' + { 959, 12, 8, 11, 0, -7 }, // 0x6D 'm' + { 971, 11, 8, 11, 1, -7 }, // 0x6E 'n' + { 982, 10, 8, 11, 1, -7 }, // 0x6F 'o' + { 992, 12, 12, 11, -1, -7 }, // 0x70 'p' + { 1010, 11, 12, 11, 1, -7 }, // 0x71 'q' + { 1027, 10, 8, 11, 1, -7 }, // 0x72 'r' + { 1037, 8, 8, 11, 2, -7 }, // 0x73 's' + { 1045, 9, 11, 11, 1, -10 }, // 0x74 't' + { 1058, 10, 8, 11, 1, -7 }, // 0x75 'u' + { 1068, 11, 8, 11, 1, -7 }, // 0x76 'v' + { 1079, 11, 8, 11, 1, -7 }, // 0x77 'w' + { 1090, 11, 8, 11, 1, -7 }, // 0x78 'x' + { 1101, 12, 12, 11, 0, -7 }, // 0x79 'y' + { 1119, 9, 8, 11, 2, -7 }, // 0x7A 'z' + { 1128, 7, 14, 11, 3, -10 }, // 0x7B '{' + { 1141, 4, 14, 11, 4, -10 }, // 0x7C '|' + { 1148, 8, 14, 11, 2, -10 }, // 0x7D '}' + { 1162, 9, 4, 11, 2, -6 } }; // 0x7E '~' + +const GFXfont FreeMonoBoldOblique9pt7b PROGMEM = { + (uint8_t *)FreeMonoBoldOblique9pt7bBitmaps, + (GFXglyph *)FreeMonoBoldOblique9pt7bGlyphs, + 0x20, 0x7E, 18 }; + +// Approx. 1839 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique12pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique12pt7b.h new file mode 100644 index 0000000..83a9a77 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique12pt7b.h @@ -0,0 +1,248 @@ +const uint8_t FreeMonoOblique12pt7bBitmaps[] PROGMEM = { + 0x11, 0x11, 0x12, 0x22, 0x22, 0x00, 0x0E, 0xE0, 0xE7, 0xE7, 0xC6, 0xC6, + 0xC6, 0x84, 0x84, 0x02, 0x40, 0x88, 0x12, 0x02, 0x40, 0x48, 0x7F, 0xC2, + 0x40, 0x48, 0x11, 0x1F, 0xF8, 0x48, 0x09, 0x02, 0x40, 0x48, 0x09, 0x02, + 0x20, 0x02, 0x01, 0x00, 0xF4, 0xC3, 0x60, 0x50, 0x04, 0x00, 0xC0, 0x0F, + 0x00, 0x60, 0x0A, 0x02, 0x81, 0x30, 0xC7, 0xC0, 0x80, 0x20, 0x08, 0x00, + 0x0E, 0x02, 0x20, 0x84, 0x10, 0x82, 0x20, 0x38, 0x00, 0x38, 0x38, 0x38, + 0x08, 0xE0, 0x22, 0x08, 0x41, 0x08, 0x22, 0x03, 0x80, 0x07, 0x84, 0x04, + 0x02, 0x01, 0x00, 0xC1, 0xA2, 0x8A, 0x85, 0x43, 0x31, 0x8F, 0x60, 0xFF, + 0x6D, 0x20, 0x00, 0x44, 0x42, 0x21, 0x08, 0x84, 0x21, 0x08, 0x42, 0x10, + 0x42, 0x00, 0x00, 0x84, 0x10, 0x84, 0x21, 0x08, 0x46, 0x21, 0x10, 0x88, + 0x44, 0x00, 0x04, 0x02, 0x02, 0x1D, 0x13, 0xF0, 0x40, 0x50, 0x48, 0x44, + 0x00, 0x02, 0x00, 0x40, 0x08, 0x02, 0x00, 0x41, 0xFF, 0xC1, 0x00, 0x20, + 0x08, 0x01, 0x00, 0x20, 0x00, 0x1C, 0xE3, 0x18, 0x63, 0x08, 0x00, 0xFF, + 0xE0, 0x7F, 0x00, 0x00, 0x08, 0x00, 0x80, 0x04, 0x00, 0x40, 0x04, 0x00, + 0x60, 0x02, 0x00, 0x20, 0x03, 0x00, 0x10, 0x01, 0x00, 0x18, 0x00, 0x80, + 0x08, 0x00, 0x80, 0x04, 0x00, 0x40, 0x04, 0x00, 0x00, 0x07, 0x06, 0x23, + 0x04, 0x81, 0x40, 0x50, 0x14, 0x06, 0x02, 0x80, 0xA0, 0x28, 0x0A, 0x04, + 0x83, 0x11, 0x83, 0x80, 0x03, 0x03, 0x83, 0x83, 0x43, 0x20, 0x10, 0x08, + 0x08, 0x04, 0x02, 0x01, 0x01, 0x00, 0x80, 0x43, 0xFE, 0x01, 0xC0, 0x62, + 0x0C, 0x10, 0x81, 0x00, 0x10, 0x02, 0x00, 0x60, 0x0C, 0x01, 0x00, 0x20, + 0x0C, 0x01, 0x80, 0x20, 0x04, 0x04, 0xFF, 0xC0, 0x07, 0xC3, 0x0C, 0x00, + 0x80, 0x10, 0x06, 0x01, 0x81, 0xC0, 0x0C, 0x00, 0x40, 0x08, 0x01, 0x00, + 0x20, 0x09, 0x86, 0x0F, 0x00, 0x00, 0xC0, 0x50, 0x24, 0x12, 0x04, 0x82, + 0x21, 0x08, 0x82, 0x21, 0x10, 0x4F, 0xF8, 0x04, 0x01, 0x00, 0x80, 0xF8, + 0x0F, 0xE2, 0x00, 0x40, 0x08, 0x01, 0x00, 0x4E, 0x0E, 0x20, 0x02, 0x00, + 0x40, 0x08, 0x01, 0x00, 0x40, 0x19, 0x06, 0x1F, 0x00, 0x01, 0xE0, 0xC0, + 0x60, 0x18, 0x02, 0x00, 0x80, 0x13, 0xC5, 0x88, 0xE0, 0x98, 0x12, 0x02, + 0x40, 0x48, 0x10, 0x84, 0x0F, 0x00, 0xFF, 0xA0, 0x20, 0x08, 0x04, 0x01, + 0x00, 0x80, 0x20, 0x10, 0x04, 0x02, 0x00, 0x80, 0x40, 0x10, 0x08, 0x02, + 0x00, 0x07, 0x81, 0x08, 0x40, 0x90, 0x12, 0x02, 0x40, 0x84, 0x20, 0x78, + 0x30, 0x88, 0x0A, 0x01, 0x40, 0x28, 0x08, 0x82, 0x0F, 0x80, 0x07, 0x81, + 0x08, 0x40, 0x90, 0x12, 0x02, 0x40, 0xC8, 0x39, 0x8D, 0x1E, 0x40, 0x08, + 0x02, 0x00, 0xC0, 0x30, 0x18, 0x3E, 0x00, 0x19, 0xCC, 0x00, 0x00, 0x0C, + 0xE6, 0x00, 0x06, 0x1C, 0x30, 0x00, 0x00, 0x00, 0x1C, 0x30, 0xE1, 0x86, + 0x08, 0x00, 0x00, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x06, 0x00, 0x30, + 0x00, 0xC0, 0x06, 0x00, 0x18, 0x00, 0xC0, 0x7F, 0xF8, 0x00, 0x00, 0x01, + 0xFF, 0xE0, 0x18, 0x00, 0xC0, 0x03, 0x00, 0x18, 0x00, 0x60, 0x03, 0x00, + 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x00, 0x3E, 0xC3, 0x81, 0x01, 0x03, + 0x06, 0x18, 0x20, 0x20, 0x00, 0x00, 0x00, 0xE0, 0xE0, 0x07, 0x82, 0x31, + 0x04, 0x81, 0x20, 0x48, 0x74, 0x65, 0x21, 0x48, 0x92, 0x28, 0x7A, 0x00, + 0x80, 0x20, 0x04, 0x00, 0xF8, 0x07, 0xE0, 0x02, 0x80, 0x0A, 0x00, 0x48, + 0x01, 0x20, 0x08, 0x40, 0x41, 0x01, 0x04, 0x0F, 0xF0, 0x20, 0x41, 0x01, + 0x04, 0x02, 0x20, 0x0B, 0xE1, 0xF0, 0x1F, 0xF0, 0x40, 0xC2, 0x02, 0x10, + 0x10, 0x81, 0x84, 0x18, 0x7F, 0x82, 0x02, 0x10, 0x08, 0x80, 0x44, 0x02, + 0x60, 0x22, 0x03, 0x7F, 0xE0, 0x07, 0x91, 0x87, 0x20, 0x34, 0x02, 0x40, + 0x08, 0x00, 0x80, 0x08, 0x00, 0x80, 0x08, 0x00, 0x80, 0x04, 0x04, 0x61, + 0x81, 0xE0, 0x1F, 0xE0, 0x41, 0x82, 0x06, 0x10, 0x11, 0x00, 0x88, 0x04, + 0x40, 0x22, 0x01, 0x10, 0x11, 0x00, 0x88, 0x08, 0x40, 0xC2, 0x0C, 0x7F, + 0x80, 0x1F, 0xFC, 0x20, 0x10, 0x80, 0x82, 0x00, 0x08, 0x00, 0x22, 0x01, + 0xF8, 0x04, 0x20, 0x10, 0x00, 0x40, 0x01, 0x01, 0x0C, 0x04, 0x20, 0x13, + 0xFF, 0xC0, 0x1F, 0xFC, 0x20, 0x10, 0x80, 0x42, 0x01, 0x08, 0x00, 0x22, + 0x01, 0xF8, 0x04, 0x20, 0x10, 0x00, 0x40, 0x01, 0x00, 0x0C, 0x00, 0x20, + 0x03, 0xF8, 0x00, 0x07, 0xD0, 0x83, 0x30, 0x12, 0x00, 0x40, 0x04, 0x00, + 0x80, 0x08, 0x00, 0x83, 0xE8, 0x04, 0x80, 0x4C, 0x04, 0x60, 0x41, 0xF8, + 0x0F, 0x3C, 0x08, 0x10, 0x20, 0x20, 0x40, 0x40, 0x81, 0x01, 0x02, 0x03, + 0xFC, 0x08, 0x08, 0x10, 0x10, 0x20, 0x40, 0x40, 0x80, 0x81, 0x02, 0x02, + 0x1F, 0x1E, 0x00, 0x3F, 0xE0, 0x40, 0x08, 0x01, 0x00, 0x20, 0x08, 0x01, + 0x00, 0x20, 0x04, 0x00, 0x80, 0x20, 0x04, 0x00, 0x81, 0xFF, 0x00, 0x03, + 0xFE, 0x00, 0x20, 0x00, 0x80, 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x08, + 0x00, 0x20, 0x40, 0x40, 0x80, 0x81, 0x01, 0x02, 0x04, 0x06, 0x10, 0x07, + 0xC0, 0x00, 0x1F, 0x1E, 0x10, 0x10, 0x20, 0xC0, 0x43, 0x00, 0x88, 0x01, + 0x20, 0x07, 0xC0, 0x0C, 0x40, 0x10, 0x40, 0x20, 0x80, 0x41, 0x01, 0x81, + 0x02, 0x02, 0x1F, 0x87, 0x00, 0x3F, 0x80, 0x40, 0x04, 0x00, 0x40, 0x08, + 0x00, 0x80, 0x08, 0x00, 0x80, 0x08, 0x01, 0x01, 0x10, 0x11, 0x02, 0x10, + 0x2F, 0xFE, 0x1C, 0x03, 0x85, 0x03, 0x02, 0x82, 0x81, 0x41, 0x40, 0xA1, + 0x20, 0x89, 0x30, 0x44, 0x90, 0x22, 0x88, 0x11, 0x44, 0x08, 0x42, 0x08, + 0x03, 0x04, 0x01, 0x02, 0x00, 0x87, 0xC3, 0xE0, 0x3C, 0x3E, 0x18, 0x08, + 0x38, 0x20, 0x50, 0x41, 0x20, 0x82, 0x61, 0x04, 0x42, 0x08, 0x88, 0x10, + 0x90, 0x41, 0x20, 0x83, 0x41, 0x02, 0x82, 0x06, 0x1F, 0x04, 0x00, 0x03, + 0xC0, 0x61, 0x84, 0x04, 0x40, 0x14, 0x00, 0xA0, 0x06, 0x00, 0x30, 0x01, + 0x80, 0x14, 0x00, 0xA0, 0x08, 0x80, 0x86, 0x18, 0x0F, 0x00, 0x1F, 0xE0, + 0x40, 0x82, 0x02, 0x10, 0x10, 0x80, 0x84, 0x08, 0x40, 0x83, 0xF8, 0x10, + 0x00, 0x80, 0x04, 0x00, 0x60, 0x02, 0x00, 0x7F, 0x00, 0x03, 0xC0, 0x61, + 0x84, 0x04, 0x40, 0x14, 0x00, 0xA0, 0x06, 0x00, 0x30, 0x01, 0x80, 0x14, + 0x00, 0xA0, 0x08, 0x80, 0x86, 0x18, 0x1F, 0x00, 0x40, 0x0F, 0xC4, 0x41, + 0xC0, 0x1F, 0xE0, 0x40, 0x82, 0x02, 0x10, 0x10, 0x80, 0x84, 0x08, 0x60, + 0x83, 0xF8, 0x10, 0xC0, 0x82, 0x04, 0x08, 0x40, 0x42, 0x03, 0x7E, 0x0C, + 0x07, 0xA3, 0x0C, 0x40, 0x90, 0x12, 0x00, 0x40, 0x06, 0x00, 0x3C, 0x00, + 0x40, 0x0A, 0x01, 0x40, 0x4C, 0x11, 0x7C, 0x00, 0xFF, 0xE8, 0x42, 0x84, + 0x20, 0x40, 0x04, 0x00, 0x80, 0x08, 0x00, 0x80, 0x08, 0x00, 0x80, 0x10, + 0x01, 0x00, 0x10, 0x0F, 0xE0, 0xF8, 0xF9, 0x00, 0x88, 0x08, 0x80, 0x44, + 0x02, 0x20, 0x11, 0x01, 0x08, 0x08, 0x80, 0x44, 0x02, 0x20, 0x31, 0x01, + 0x04, 0x30, 0x1E, 0x00, 0xF8, 0x7D, 0x00, 0x42, 0x01, 0x08, 0x08, 0x20, + 0x40, 0x81, 0x02, 0x08, 0x08, 0x20, 0x11, 0x00, 0x48, 0x01, 0x20, 0x05, + 0x00, 0x14, 0x00, 0x60, 0x00, 0xF8, 0x7D, 0x00, 0x44, 0x01, 0x11, 0x84, + 0x46, 0x21, 0x18, 0x84, 0xA2, 0x12, 0x90, 0x91, 0x42, 0x45, 0x0A, 0x14, + 0x28, 0x60, 0xC1, 0x83, 0x06, 0x00, 0x1E, 0x1E, 0x10, 0x10, 0x10, 0x40, + 0x21, 0x00, 0x24, 0x00, 0x78, 0x00, 0x60, 0x01, 0xC0, 0x06, 0x80, 0x09, + 0x80, 0x21, 0x00, 0x81, 0x02, 0x02, 0x1E, 0x1F, 0x00, 0xF0, 0xF4, 0x04, + 0x20, 0x82, 0x18, 0x11, 0x01, 0x20, 0x1C, 0x00, 0x80, 0x08, 0x00, 0x80, + 0x10, 0x01, 0x00, 0x10, 0x0F, 0xE0, 0x0F, 0xF1, 0x01, 0x10, 0x21, 0x04, + 0x00, 0x80, 0x10, 0x02, 0x00, 0x40, 0x0C, 0x01, 0x82, 0x10, 0x22, 0x04, + 0x40, 0x47, 0xFC, 0x0E, 0x20, 0x40, 0x81, 0x02, 0x08, 0x10, 0x20, 0x40, + 0x82, 0x04, 0x08, 0x10, 0x20, 0x81, 0xE0, 0x84, 0x20, 0x84, 0x20, 0x84, + 0x21, 0x04, 0x21, 0x08, 0x21, 0x08, 0x40, 0x1E, 0x04, 0x08, 0x20, 0x40, + 0x81, 0x02, 0x04, 0x10, 0x20, 0x40, 0x81, 0x02, 0x08, 0x11, 0xE0, 0x04, + 0x06, 0x04, 0x84, 0x44, 0x14, 0x0C, 0xFF, 0xFE, 0x99, 0x90, 0x1F, 0xC0, + 0x06, 0x00, 0x20, 0x02, 0x1F, 0xE6, 0x04, 0xC0, 0x48, 0x04, 0x81, 0xC7, + 0xEF, 0x18, 0x00, 0x40, 0x02, 0x00, 0x10, 0x00, 0x80, 0x09, 0xF0, 0x50, + 0xC3, 0x03, 0x10, 0x08, 0x80, 0x48, 0x02, 0x40, 0x23, 0x03, 0x1C, 0x33, + 0xBE, 0x00, 0x0F, 0xD3, 0x07, 0x60, 0x24, 0x02, 0x80, 0x08, 0x00, 0x80, + 0x08, 0x06, 0x41, 0xC3, 0xF0, 0x00, 0x38, 0x00, 0x40, 0x02, 0x00, 0x20, + 0x01, 0x07, 0xC8, 0x43, 0x44, 0x0E, 0x40, 0x24, 0x01, 0x20, 0x09, 0x00, + 0xC8, 0x0E, 0x20, 0xE0, 0xF9, 0xC0, 0x0F, 0x86, 0x09, 0x00, 0xA0, 0x1F, + 0xFF, 0x00, 0x20, 0x06, 0x00, 0x60, 0xC7, 0xE0, 0x01, 0xF8, 0x10, 0x01, + 0x00, 0x08, 0x00, 0x40, 0x1F, 0xF0, 0x20, 0x01, 0x00, 0x08, 0x00, 0x40, + 0x04, 0x00, 0x20, 0x01, 0x00, 0x08, 0x03, 0xFE, 0x00, 0x0F, 0x31, 0x86, + 0x10, 0x10, 0x80, 0x88, 0x04, 0x40, 0x22, 0x02, 0x10, 0x10, 0x43, 0x81, + 0xE4, 0x00, 0x40, 0x02, 0x00, 0x20, 0x3E, 0x00, 0x1C, 0x00, 0x20, 0x03, + 0x00, 0x10, 0x00, 0x80, 0x05, 0xF0, 0x30, 0xC3, 0x02, 0x10, 0x10, 0x80, + 0x84, 0x0C, 0x20, 0x63, 0x02, 0x10, 0x13, 0xE3, 0xE0, 0x01, 0x80, 0x40, + 0x10, 0x00, 0x00, 0x07, 0xC0, 0x20, 0x08, 0x02, 0x00, 0x80, 0x20, 0x10, + 0x04, 0x01, 0x0F, 0xFC, 0x00, 0x40, 0x10, 0x0C, 0x00, 0x00, 0x07, 0xF0, + 0x04, 0x01, 0x00, 0x40, 0x20, 0x08, 0x02, 0x00, 0x80, 0x20, 0x10, 0x04, + 0x01, 0x00, 0x8F, 0xC0, 0x18, 0x00, 0x80, 0x08, 0x00, 0x80, 0x08, 0x01, + 0x1F, 0x10, 0x81, 0x30, 0x14, 0x01, 0xC0, 0x26, 0x02, 0x20, 0x21, 0x02, + 0x08, 0xE1, 0xE0, 0x0F, 0x80, 0x40, 0x10, 0x04, 0x01, 0x00, 0x40, 0x20, + 0x08, 0x02, 0x00, 0x80, 0x20, 0x10, 0x04, 0x01, 0x0F, 0xFC, 0x3B, 0xB8, + 0x33, 0x91, 0x08, 0x44, 0x21, 0x10, 0x84, 0x42, 0x12, 0x10, 0x48, 0x42, + 0x21, 0x0B, 0xC6, 0x30, 0x19, 0xE0, 0xE3, 0x08, 0x11, 0x01, 0x10, 0x11, + 0x02, 0x10, 0x21, 0x02, 0x20, 0x2F, 0x87, 0x0F, 0x86, 0x19, 0x80, 0xA0, + 0x18, 0x03, 0x00, 0x60, 0x14, 0x06, 0x61, 0x87, 0xC0, 0x19, 0xF0, 0x28, + 0x20, 0xC0, 0x42, 0x01, 0x10, 0x04, 0x40, 0x11, 0x00, 0x86, 0x06, 0x14, + 0x30, 0xCF, 0x02, 0x00, 0x08, 0x00, 0x20, 0x03, 0xF0, 0x00, 0x0F, 0x39, + 0x85, 0x18, 0x18, 0x80, 0x88, 0x04, 0x40, 0x22, 0x01, 0x18, 0x18, 0x63, + 0x81, 0xE4, 0x00, 0x20, 0x01, 0x00, 0x10, 0x07, 0xE0, 0x1C, 0x78, 0x2C, + 0x01, 0x80, 0x18, 0x00, 0x80, 0x04, 0x00, 0x20, 0x02, 0x00, 0x10, 0x07, + 0xFC, 0x00, 0x0F, 0x44, 0x32, 0x04, 0x80, 0x1E, 0x00, 0x60, 0x0A, 0x02, + 0xC1, 0x2F, 0x80, 0x10, 0x08, 0x04, 0x02, 0x0F, 0xF9, 0x00, 0x80, 0x40, + 0x20, 0x20, 0x10, 0x08, 0x04, 0x19, 0xF0, 0xE0, 0xF2, 0x02, 0x40, 0x24, + 0x02, 0x40, 0x24, 0x06, 0x40, 0x44, 0x04, 0x41, 0xC3, 0xE6, 0xF8, 0xFA, + 0x01, 0x08, 0x10, 0x41, 0x02, 0x08, 0x10, 0x80, 0x48, 0x02, 0x40, 0x14, + 0x00, 0xC0, 0x00, 0xE0, 0x7A, 0x01, 0x10, 0x08, 0x8C, 0x84, 0xA4, 0x25, + 0x21, 0x4A, 0x0A, 0x50, 0x63, 0x02, 0x18, 0x00, 0x1E, 0x3C, 0x20, 0x40, + 0x46, 0x00, 0xB0, 0x03, 0x00, 0x0E, 0x00, 0xC8, 0x06, 0x10, 0x20, 0x23, + 0xE3, 0xC0, 0x3C, 0x3C, 0x40, 0x20, 0x81, 0x02, 0x08, 0x08, 0x20, 0x31, + 0x00, 0x48, 0x01, 0x40, 0x05, 0x00, 0x08, 0x00, 0x40, 0x02, 0x00, 0x08, + 0x03, 0xF0, 0x00, 0x3F, 0xC4, 0x18, 0x06, 0x01, 0x80, 0x60, 0x10, 0x04, + 0x01, 0x00, 0x40, 0x9F, 0xF0, 0x06, 0x10, 0x20, 0x41, 0x02, 0x04, 0x08, + 0x21, 0x80, 0x81, 0x02, 0x08, 0x10, 0x20, 0x40, 0xC0, 0x01, 0x11, 0x12, + 0x22, 0x24, 0x44, 0x44, 0x88, 0x80, 0x0C, 0x08, 0x10, 0x20, 0x40, 0x82, + 0x04, 0x08, 0x0C, 0x20, 0x81, 0x02, 0x04, 0x08, 0x21, 0x80, 0x38, 0x28, + 0x88, 0x0E, 0x00 }; + +const GFXglyph FreeMonoOblique12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 14, 0, 1 }, // 0x20 ' ' + { 0, 4, 15, 14, 6, -14 }, // 0x21 '!' + { 8, 8, 7, 14, 5, -14 }, // 0x22 '"' + { 15, 11, 16, 14, 3, -14 }, // 0x23 '#' + { 37, 10, 18, 14, 4, -15 }, // 0x24 '$' + { 60, 11, 15, 14, 3, -14 }, // 0x25 '%' + { 81, 9, 12, 14, 3, -11 }, // 0x26 '&' + { 95, 3, 7, 14, 8, -14 }, // 0x27 ''' + { 98, 5, 18, 14, 8, -14 }, // 0x28 '(' + { 110, 5, 18, 14, 4, -14 }, // 0x29 ')' + { 122, 9, 9, 14, 5, -14 }, // 0x2A '*' + { 133, 11, 11, 14, 3, -11 }, // 0x2B '+' + { 149, 6, 7, 14, 3, -3 }, // 0x2C ',' + { 155, 11, 1, 14, 3, -6 }, // 0x2D '-' + { 157, 3, 3, 14, 6, -2 }, // 0x2E '.' + { 159, 13, 18, 14, 2, -15 }, // 0x2F '/' + { 189, 10, 15, 14, 4, -14 }, // 0x30 '0' + { 208, 9, 15, 14, 3, -14 }, // 0x31 '1' + { 225, 12, 15, 14, 2, -14 }, // 0x32 '2' + { 248, 11, 15, 14, 3, -14 }, // 0x33 '3' + { 269, 10, 15, 14, 3, -14 }, // 0x34 '4' + { 288, 11, 15, 14, 3, -14 }, // 0x35 '5' + { 309, 11, 15, 14, 4, -14 }, // 0x36 '6' + { 330, 10, 15, 14, 5, -14 }, // 0x37 '7' + { 349, 11, 15, 14, 3, -14 }, // 0x38 '8' + { 370, 11, 15, 14, 3, -14 }, // 0x39 '9' + { 391, 5, 10, 14, 5, -9 }, // 0x3A ':' + { 398, 7, 13, 14, 3, -9 }, // 0x3B ';' + { 410, 12, 11, 14, 3, -11 }, // 0x3C '<' + { 427, 13, 4, 14, 2, -8 }, // 0x3D '=' + { 434, 12, 11, 14, 2, -11 }, // 0x3E '>' + { 451, 8, 14, 14, 6, -13 }, // 0x3F '?' + { 465, 10, 16, 14, 3, -14 }, // 0x40 '@' + { 485, 14, 14, 14, 0, -13 }, // 0x41 'A' + { 510, 13, 14, 14, 1, -13 }, // 0x42 'B' + { 533, 12, 14, 14, 3, -13 }, // 0x43 'C' + { 554, 13, 14, 14, 1, -13 }, // 0x44 'D' + { 577, 14, 14, 14, 1, -13 }, // 0x45 'E' + { 602, 14, 14, 14, 1, -13 }, // 0x46 'F' + { 627, 12, 14, 14, 3, -13 }, // 0x47 'G' + { 648, 15, 14, 14, 1, -13 }, // 0x48 'H' + { 675, 11, 14, 14, 3, -13 }, // 0x49 'I' + { 695, 15, 14, 14, 2, -13 }, // 0x4A 'J' + { 722, 15, 14, 14, 1, -13 }, // 0x4B 'K' + { 749, 12, 14, 14, 2, -13 }, // 0x4C 'L' + { 770, 17, 14, 14, 0, -13 }, // 0x4D 'M' + { 800, 15, 14, 14, 1, -13 }, // 0x4E 'N' + { 827, 13, 14, 14, 2, -13 }, // 0x4F 'O' + { 850, 13, 14, 14, 1, -13 }, // 0x50 'P' + { 873, 13, 17, 14, 2, -13 }, // 0x51 'Q' + { 901, 13, 14, 14, 1, -13 }, // 0x52 'R' + { 924, 11, 14, 14, 3, -13 }, // 0x53 'S' + { 944, 12, 14, 14, 4, -13 }, // 0x54 'T' + { 965, 13, 14, 14, 3, -13 }, // 0x55 'U' + { 988, 14, 14, 14, 3, -13 }, // 0x56 'V' + { 1013, 14, 14, 14, 3, -13 }, // 0x57 'W' + { 1038, 15, 14, 14, 1, -13 }, // 0x58 'X' + { 1065, 12, 14, 14, 4, -13 }, // 0x59 'Y' + { 1086, 12, 14, 14, 2, -13 }, // 0x5A 'Z' + { 1107, 7, 18, 14, 6, -14 }, // 0x5B '[' + { 1123, 5, 18, 14, 6, -15 }, // 0x5C '\' + { 1135, 7, 18, 14, 3, -14 }, // 0x5D ']' + { 1151, 9, 6, 14, 5, -14 }, // 0x5E '^' + { 1158, 15, 1, 14, -1, 3 }, // 0x5F '_' + { 1160, 3, 4, 14, 6, -15 }, // 0x60 '`' + { 1162, 12, 10, 14, 2, -9 }, // 0x61 'a' + { 1177, 13, 15, 14, 1, -14 }, // 0x62 'b' + { 1202, 12, 10, 14, 3, -9 }, // 0x63 'c' + { 1217, 13, 15, 14, 2, -14 }, // 0x64 'd' + { 1242, 11, 10, 14, 3, -9 }, // 0x65 'e' + { 1256, 13, 15, 14, 3, -14 }, // 0x66 'f' + { 1281, 13, 14, 14, 3, -9 }, // 0x67 'g' + { 1304, 13, 15, 14, 1, -14 }, // 0x68 'h' + { 1329, 10, 15, 14, 2, -14 }, // 0x69 'i' + { 1348, 10, 19, 14, 2, -14 }, // 0x6A 'j' + { 1372, 12, 15, 14, 2, -14 }, // 0x6B 'k' + { 1395, 10, 15, 14, 2, -14 }, // 0x6C 'l' + { 1414, 14, 10, 14, 0, -9 }, // 0x6D 'm' + { 1432, 12, 10, 14, 1, -9 }, // 0x6E 'n' + { 1447, 11, 10, 14, 3, -9 }, // 0x6F 'o' + { 1461, 14, 14, 14, 0, -9 }, // 0x70 'p' + { 1486, 13, 14, 14, 3, -9 }, // 0x71 'q' + { 1509, 13, 10, 14, 2, -9 }, // 0x72 'r' + { 1526, 10, 10, 14, 3, -9 }, // 0x73 's' + { 1539, 9, 14, 14, 3, -13 }, // 0x74 't' + { 1555, 12, 10, 14, 2, -9 }, // 0x75 'u' + { 1570, 13, 10, 14, 3, -9 }, // 0x76 'v' + { 1587, 13, 10, 14, 3, -9 }, // 0x77 'w' + { 1604, 14, 10, 14, 1, -9 }, // 0x78 'x' + { 1622, 14, 14, 14, 1, -9 }, // 0x79 'y' + { 1647, 11, 10, 14, 3, -9 }, // 0x7A 'z' + { 1661, 7, 18, 14, 5, -14 }, // 0x7B '{' + { 1677, 4, 17, 14, 6, -13 }, // 0x7C '|' + { 1686, 7, 18, 14, 4, -14 }, // 0x7D '}' + { 1702, 11, 3, 14, 3, -7 } }; // 0x7E '~' + +const GFXfont FreeMonoOblique12pt7b PROGMEM = { + (uint8_t *)FreeMonoOblique12pt7bBitmaps, + (GFXglyph *)FreeMonoOblique12pt7bGlyphs, + 0x20, 0x7E, 24 }; + +// Approx. 2379 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique18pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique18pt7b.h new file mode 100644 index 0000000..1979e72 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique18pt7b.h @@ -0,0 +1,398 @@ +const uint8_t FreeMonoOblique18pt7bBitmaps[] PROGMEM = { + 0x00, 0x1C, 0x38, 0x70, 0xC1, 0x83, 0x06, 0x18, 0x30, 0x60, 0xC1, 0x02, + 0x04, 0x00, 0x00, 0x01, 0xC7, 0x8F, 0x1C, 0x00, 0x78, 0x7B, 0xC3, 0xFC, + 0x3D, 0xE1, 0xEF, 0x0F, 0x70, 0x73, 0x83, 0x98, 0x18, 0xC0, 0xC6, 0x06, + 0x00, 0x00, 0x8C, 0x01, 0x18, 0x06, 0x20, 0x08, 0x40, 0x11, 0x80, 0x62, + 0x00, 0xC4, 0x01, 0x18, 0x02, 0x30, 0x7F, 0xFC, 0x10, 0x80, 0x23, 0x00, + 0xC4, 0x01, 0x88, 0x3F, 0xFF, 0x04, 0x60, 0x18, 0x80, 0x21, 0x00, 0x46, + 0x01, 0x88, 0x03, 0x10, 0x04, 0x60, 0x08, 0xC0, 0x31, 0x00, 0x00, 0x30, + 0x00, 0x20, 0x00, 0x20, 0x00, 0xF9, 0x03, 0x0F, 0x06, 0x03, 0x04, 0x03, + 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x03, 0xC0, 0x00, 0x78, + 0x00, 0x0C, 0x00, 0x04, 0x00, 0x04, 0x40, 0x04, 0x40, 0x08, 0x40, 0x18, + 0xF0, 0x60, 0x9F, 0x80, 0x02, 0x00, 0x06, 0x00, 0x04, 0x00, 0x04, 0x00, + 0x04, 0x00, 0x03, 0xC0, 0x0C, 0x60, 0x08, 0x20, 0x10, 0x20, 0x10, 0x20, + 0x10, 0x40, 0x18, 0x80, 0x0F, 0x00, 0x00, 0x0F, 0x00, 0x78, 0x07, 0xC0, + 0x3C, 0x00, 0xE0, 0x00, 0x01, 0xE0, 0x02, 0x18, 0x04, 0x08, 0x08, 0x08, + 0x08, 0x08, 0x08, 0x10, 0x0C, 0x20, 0x07, 0xC0, 0x01, 0xF0, 0x11, 0x81, + 0x00, 0x10, 0x00, 0x80, 0x04, 0x00, 0x20, 0x01, 0x80, 0x04, 0x00, 0xF0, + 0x09, 0x86, 0x84, 0x48, 0x32, 0x40, 0xA2, 0x07, 0x10, 0x30, 0x43, 0x81, + 0xE7, 0x80, 0x7B, 0xFD, 0xEF, 0x73, 0x98, 0xC6, 0x00, 0x01, 0x02, 0x06, + 0x0C, 0x0C, 0x18, 0x10, 0x30, 0x30, 0x60, 0x60, 0x60, 0xC0, 0xC0, 0xC0, + 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0x40, 0x60, 0x60, 0x20, 0x04, 0x06, + 0x06, 0x02, 0x02, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, 0x06, + 0x06, 0x06, 0x0C, 0x0C, 0x0C, 0x18, 0x10, 0x30, 0x60, 0x40, 0xC0, 0x01, + 0x00, 0x04, 0x00, 0x10, 0x00, 0xC6, 0xE3, 0xF8, 0x7E, 0x00, 0x70, 0x03, + 0x40, 0x19, 0x80, 0xC2, 0x06, 0x0C, 0x00, 0x00, 0xC0, 0x01, 0x00, 0x02, + 0x00, 0x04, 0x00, 0x08, 0x00, 0x20, 0x00, 0x40, 0x00, 0x80, 0xFF, 0xFE, + 0x02, 0x00, 0x08, 0x00, 0x10, 0x00, 0x20, 0x00, 0x40, 0x00, 0x80, 0x02, + 0x00, 0x04, 0x00, 0x0F, 0x87, 0x87, 0x83, 0x83, 0xC1, 0xC1, 0xC0, 0xC0, + 0xE0, 0x60, 0x00, 0xFF, 0xFF, 0x77, 0xFF, 0xF7, 0x00, 0x00, 0x00, 0x60, + 0x00, 0x08, 0x00, 0x02, 0x00, 0x00, 0xC0, 0x00, 0x30, 0x00, 0x04, 0x00, + 0x01, 0x80, 0x00, 0x60, 0x00, 0x08, 0x00, 0x03, 0x00, 0x00, 0xC0, 0x00, + 0x10, 0x00, 0x06, 0x00, 0x01, 0x80, 0x00, 0x20, 0x00, 0x0C, 0x00, 0x03, + 0x00, 0x00, 0x40, 0x00, 0x18, 0x00, 0x06, 0x00, 0x00, 0x80, 0x00, 0x20, + 0x00, 0x0C, 0x00, 0x03, 0x00, 0x00, 0x40, 0x00, 0x08, 0x00, 0x00, 0x01, + 0xF0, 0x18, 0x60, 0x80, 0x86, 0x01, 0x10, 0x04, 0x80, 0x12, 0x00, 0x50, + 0x01, 0x40, 0x0D, 0x00, 0x24, 0x00, 0xA0, 0x02, 0x80, 0x1A, 0x00, 0x48, + 0x01, 0x20, 0x0C, 0x80, 0x22, 0x01, 0x84, 0x0C, 0x18, 0x60, 0x3E, 0x00, + 0x00, 0x60, 0x07, 0x00, 0x68, 0x06, 0x40, 0xE4, 0x04, 0x20, 0x01, 0x00, + 0x08, 0x00, 0x40, 0x04, 0x00, 0x20, 0x01, 0x00, 0x08, 0x00, 0x80, 0x04, + 0x00, 0x20, 0x01, 0x00, 0x08, 0x00, 0x80, 0x04, 0x0F, 0xFF, 0x80, 0x00, + 0x3C, 0x00, 0x61, 0x80, 0x40, 0x40, 0x40, 0x10, 0x60, 0x08, 0x00, 0x04, + 0x00, 0x02, 0x00, 0x02, 0x00, 0x03, 0x00, 0x03, 0x00, 0x07, 0x00, 0x07, + 0x00, 0x06, 0x00, 0x06, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0C, 0x00, 0x0C, + 0x00, 0x1C, 0x01, 0x1C, 0x00, 0x8F, 0xFF, 0xC0, 0x00, 0xFC, 0x03, 0x06, + 0x06, 0x03, 0x00, 0x01, 0x00, 0x01, 0x00, 0x01, 0x00, 0x02, 0x00, 0x02, + 0x00, 0x0C, 0x00, 0xF0, 0x00, 0x18, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, + 0x00, 0x02, 0x00, 0x02, 0x00, 0x04, 0x00, 0x04, 0x40, 0x18, 0x70, 0x30, + 0x0F, 0xC0, 0x00, 0x1C, 0x00, 0xD0, 0x06, 0x80, 0x32, 0x00, 0x88, 0x04, + 0x20, 0x30, 0x81, 0x84, 0x04, 0x10, 0x20, 0x41, 0x81, 0x0C, 0x08, 0x60, + 0x21, 0x00, 0x8F, 0xFF, 0x80, 0x18, 0x00, 0x40, 0x01, 0x00, 0x04, 0x00, + 0x10, 0x07, 0xE0, 0x03, 0xFF, 0x03, 0x00, 0x01, 0x80, 0x00, 0x80, 0x00, + 0x40, 0x00, 0x20, 0x00, 0x30, 0x00, 0x1B, 0xE0, 0x0E, 0x0C, 0x00, 0x02, + 0x00, 0x00, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0x10, 0x00, 0x08, 0x00, + 0x08, 0x00, 0x04, 0x60, 0x04, 0x18, 0x04, 0x06, 0x0C, 0x00, 0xF8, 0x00, + 0x00, 0x3F, 0x00, 0xC0, 0x03, 0x00, 0x04, 0x00, 0x08, 0x00, 0x10, 0x00, + 0x30, 0x00, 0x20, 0x00, 0x40, 0x00, 0x43, 0xE0, 0x4C, 0x30, 0xB0, 0x18, + 0xE0, 0x08, 0xC0, 0x08, 0x80, 0x08, 0x80, 0x08, 0x80, 0x10, 0xC0, 0x10, + 0x40, 0x20, 0x20, 0xC0, 0x1F, 0x00, 0xFF, 0xFC, 0x00, 0xE0, 0x04, 0x00, + 0x60, 0x02, 0x00, 0x30, 0x01, 0x00, 0x18, 0x00, 0x80, 0x0C, 0x00, 0x40, + 0x06, 0x00, 0x20, 0x03, 0x00, 0x10, 0x01, 0x80, 0x08, 0x00, 0xC0, 0x04, + 0x00, 0x60, 0x02, 0x00, 0x00, 0x00, 0xF0, 0x06, 0x18, 0x10, 0x18, 0x40, + 0x11, 0x00, 0x22, 0x00, 0x44, 0x00, 0x88, 0x02, 0x18, 0x08, 0x18, 0x60, + 0x1F, 0x80, 0xC1, 0x82, 0x01, 0x88, 0x01, 0x20, 0x02, 0x40, 0x04, 0x80, + 0x09, 0x00, 0x23, 0x00, 0x83, 0x06, 0x01, 0xF0, 0x00, 0x00, 0xF0, 0x06, + 0x18, 0x10, 0x10, 0x40, 0x30, 0x80, 0x22, 0x00, 0x44, 0x00, 0x88, 0x03, + 0x10, 0x0E, 0x30, 0x34, 0x30, 0xD0, 0x3E, 0x20, 0x00, 0x40, 0x01, 0x00, + 0x02, 0x00, 0x08, 0x00, 0x20, 0x00, 0xC0, 0x02, 0x00, 0x18, 0x0F, 0xC0, + 0x00, 0x1C, 0x7C, 0xF9, 0xF1, 0xC0, 0x00, 0x00, 0x00, 0x01, 0xC7, 0xCF, + 0x9F, 0x1C, 0x00, 0x01, 0xC0, 0x7C, 0x0F, 0x81, 0xF0, 0x1C, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x3E, 0x07, 0x81, 0xE0, 0x3C, 0x0F, 0x01, + 0xC0, 0x70, 0x0E, 0x03, 0x80, 0x60, 0x00, 0x00, 0x01, 0x80, 0x03, 0x80, + 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x00, + 0xE0, 0x00, 0x1C, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x07, + 0x00, 0x00, 0xE0, 0x00, 0x38, 0x7F, 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x18, 0x00, 0x03, 0x80, + 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x00, 0xE0, + 0x00, 0x0E, 0x00, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0x03, + 0x80, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0x00, 0x1F, 0xCE, 0x06, 0x80, + 0x38, 0x01, 0x80, 0x10, 0x01, 0x00, 0x20, 0x04, 0x01, 0x80, 0xF0, 0x18, + 0x01, 0x00, 0x10, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78, 0x0F, 0x80, 0xF8, + 0x07, 0x00, 0x01, 0xF0, 0x0C, 0x30, 0x30, 0x30, 0x40, 0x21, 0x00, 0x44, + 0x00, 0x88, 0x01, 0x10, 0x1E, 0x40, 0xC4, 0x86, 0x11, 0x08, 0x22, 0x20, + 0x48, 0x40, 0x90, 0x82, 0x21, 0x84, 0x40, 0xFC, 0x80, 0x01, 0x00, 0x02, + 0x00, 0x04, 0x00, 0x04, 0x00, 0x0C, 0x18, 0x07, 0xC0, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x68, 0x00, 0x06, 0x40, 0x00, 0x32, 0x00, 0x03, 0x10, 0x00, + 0x10, 0x80, 0x01, 0x84, 0x00, 0x18, 0x10, 0x00, 0xC0, 0x80, 0x0C, 0x04, + 0x00, 0x60, 0x20, 0x06, 0x01, 0x00, 0x3F, 0xFC, 0x02, 0x00, 0x20, 0x10, + 0x01, 0x01, 0x00, 0x08, 0x08, 0x00, 0x40, 0x80, 0x02, 0x0C, 0x00, 0x09, + 0xFC, 0x07, 0xF0, 0x0F, 0xFF, 0x00, 0x40, 0x60, 0x20, 0x0C, 0x08, 0x01, + 0x02, 0x00, 0x40, 0x80, 0x10, 0x40, 0x08, 0x10, 0x06, 0x04, 0x03, 0x01, + 0xFF, 0x80, 0x40, 0x38, 0x20, 0x02, 0x08, 0x00, 0x42, 0x00, 0x10, 0x80, + 0x04, 0x40, 0x01, 0x10, 0x00, 0x84, 0x00, 0x41, 0x00, 0x23, 0xFF, 0xF0, + 0x00, 0xFC, 0x40, 0xC1, 0xF0, 0xC0, 0x1C, 0x60, 0x06, 0x10, 0x00, 0x88, + 0x00, 0x24, 0x00, 0x01, 0x00, 0x00, 0x40, 0x00, 0x30, 0x00, 0x08, 0x00, + 0x02, 0x00, 0x00, 0x80, 0x00, 0x20, 0x00, 0x08, 0x00, 0x03, 0x00, 0x00, + 0x40, 0x06, 0x08, 0x03, 0x01, 0x83, 0x80, 0x3F, 0x00, 0x0F, 0xFE, 0x00, + 0x80, 0xC0, 0x20, 0x18, 0x10, 0x02, 0x04, 0x00, 0x41, 0x00, 0x10, 0x40, + 0x04, 0x20, 0x01, 0x08, 0x00, 0x42, 0x00, 0x10, 0x80, 0x08, 0x20, 0x02, + 0x10, 0x00, 0x84, 0x00, 0x21, 0x00, 0x10, 0x40, 0x08, 0x20, 0x06, 0x08, + 0x03, 0x02, 0x01, 0x83, 0xFF, 0x80, 0x0F, 0xFF, 0xE0, 0x10, 0x02, 0x02, + 0x00, 0x60, 0x20, 0x06, 0x02, 0x00, 0x60, 0x20, 0x00, 0x04, 0x00, 0x00, + 0x40, 0x80, 0x04, 0x10, 0x00, 0x7F, 0x00, 0x04, 0x10, 0x00, 0x81, 0x00, + 0x08, 0x00, 0x00, 0x80, 0x00, 0x08, 0x00, 0x81, 0x00, 0x08, 0x10, 0x00, + 0x81, 0x00, 0x18, 0x10, 0x01, 0x8F, 0xFF, 0xF0, 0x0F, 0xFF, 0xF0, 0x10, + 0x03, 0x02, 0x00, 0x30, 0x20, 0x03, 0x02, 0x00, 0x20, 0x20, 0x00, 0x04, + 0x00, 0x00, 0x40, 0x80, 0x04, 0x10, 0x00, 0x7F, 0x00, 0x04, 0x10, 0x00, + 0x81, 0x00, 0x08, 0x00, 0x00, 0x80, 0x00, 0x08, 0x00, 0x01, 0x00, 0x00, + 0x10, 0x00, 0x01, 0x00, 0x00, 0x10, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0xFE, + 0x40, 0xC0, 0xF0, 0x40, 0x1C, 0x20, 0x03, 0x10, 0x00, 0x88, 0x00, 0x02, + 0x00, 0x01, 0x00, 0x00, 0x40, 0x00, 0x10, 0x00, 0x08, 0x00, 0x02, 0x01, + 0xFE, 0x80, 0x02, 0x20, 0x00, 0x88, 0x00, 0x22, 0x00, 0x08, 0x40, 0x04, + 0x18, 0x01, 0x03, 0x81, 0xC0, 0x3F, 0x80, 0x07, 0xE1, 0xF8, 0x08, 0x02, + 0x00, 0x80, 0x10, 0x04, 0x00, 0x80, 0x20, 0x04, 0x01, 0x00, 0x20, 0x18, + 0x02, 0x00, 0x80, 0x10, 0x04, 0x00, 0x80, 0x3F, 0xFC, 0x01, 0x00, 0x60, + 0x10, 0x02, 0x00, 0x80, 0x10, 0x04, 0x00, 0x80, 0x20, 0x04, 0x02, 0x00, + 0x40, 0x10, 0x02, 0x00, 0x80, 0x10, 0x04, 0x00, 0x81, 0xF8, 0x3F, 0x00, + 0x0F, 0xFF, 0x80, 0x10, 0x00, 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x02, + 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, + 0x10, 0x00, 0x08, 0x00, 0x08, 0x00, 0x04, 0x00, 0x02, 0x00, 0x01, 0x00, + 0x01, 0x00, 0x00, 0x80, 0x1F, 0xFF, 0x00, 0x00, 0xFF, 0xF0, 0x00, 0x20, + 0x00, 0x02, 0x00, 0x00, 0x20, 0x00, 0x02, 0x00, 0x00, 0x20, 0x00, 0x04, + 0x00, 0x00, 0x40, 0x00, 0x04, 0x00, 0x00, 0x40, 0x00, 0x0C, 0x04, 0x00, + 0x80, 0x40, 0x08, 0x08, 0x00, 0x80, 0x80, 0x08, 0x08, 0x01, 0x00, 0x80, + 0x10, 0x0C, 0x02, 0x00, 0x60, 0xC0, 0x01, 0xF0, 0x00, 0x0F, 0xE1, 0xF8, + 0x08, 0x03, 0x00, 0x80, 0x60, 0x04, 0x06, 0x00, 0x20, 0x60, 0x01, 0x06, + 0x00, 0x10, 0xC0, 0x00, 0x8C, 0x00, 0x04, 0xC0, 0x00, 0x2F, 0x80, 0x01, + 0x8E, 0x00, 0x18, 0x30, 0x00, 0x80, 0xC0, 0x04, 0x06, 0x00, 0x20, 0x10, + 0x02, 0x00, 0xC0, 0x10, 0x06, 0x00, 0x80, 0x30, 0x04, 0x00, 0x81, 0xFC, + 0x07, 0x80, 0x07, 0xFC, 0x00, 0x10, 0x00, 0x08, 0x00, 0x02, 0x00, 0x00, + 0x80, 0x00, 0x20, 0x00, 0x08, 0x00, 0x04, 0x00, 0x01, 0x00, 0x00, 0x40, + 0x00, 0x10, 0x00, 0x08, 0x00, 0x02, 0x00, 0x00, 0x80, 0x10, 0x20, 0x04, + 0x08, 0x01, 0x04, 0x00, 0x81, 0x00, 0x20, 0x40, 0x0B, 0xFF, 0xFE, 0x0F, + 0x00, 0x1E, 0x03, 0x00, 0x38, 0x05, 0x00, 0x68, 0x04, 0x80, 0x68, 0x04, + 0x80, 0xC8, 0x04, 0x80, 0x90, 0x04, 0x81, 0x90, 0x08, 0x43, 0x10, 0x08, + 0x42, 0x10, 0x08, 0x46, 0x10, 0x08, 0x4C, 0x20, 0x10, 0x2C, 0x20, 0x10, + 0x38, 0x20, 0x10, 0x30, 0x20, 0x10, 0x00, 0x40, 0x10, 0x00, 0x40, 0x20, + 0x00, 0x40, 0x20, 0x00, 0x40, 0x20, 0x00, 0x40, 0xFC, 0x07, 0xE0, 0x1F, + 0x01, 0xFC, 0x0C, 0x00, 0x80, 0x78, 0x02, 0x01, 0xE0, 0x18, 0x04, 0x80, + 0x60, 0x13, 0x01, 0x00, 0x4C, 0x04, 0x03, 0x18, 0x10, 0x0C, 0x60, 0xC0, + 0x20, 0x83, 0x00, 0x83, 0x08, 0x06, 0x0C, 0x20, 0x18, 0x18, 0x80, 0x40, + 0x66, 0x01, 0x00, 0x98, 0x04, 0x03, 0x40, 0x30, 0x0D, 0x00, 0xC0, 0x14, + 0x02, 0x00, 0x70, 0x3F, 0x80, 0xC0, 0x00, 0xF8, 0x01, 0x83, 0x01, 0x00, + 0xC1, 0x00, 0x21, 0x00, 0x19, 0x00, 0x04, 0x80, 0x02, 0x80, 0x01, 0x40, + 0x00, 0xC0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x28, 0x00, 0x14, 0x00, 0x12, + 0x00, 0x09, 0x80, 0x08, 0x40, 0x08, 0x30, 0x08, 0x0C, 0x18, 0x01, 0xF0, + 0x00, 0x0F, 0xFE, 0x00, 0x40, 0x60, 0x20, 0x0C, 0x08, 0x01, 0x02, 0x00, + 0x40, 0x80, 0x10, 0x40, 0x04, 0x10, 0x02, 0x04, 0x01, 0x01, 0x01, 0x80, + 0x7F, 0x80, 0x20, 0x00, 0x08, 0x00, 0x02, 0x00, 0x00, 0x80, 0x00, 0x40, + 0x00, 0x10, 0x00, 0x04, 0x00, 0x01, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xF8, + 0x01, 0x83, 0x01, 0x00, 0xC1, 0x00, 0x21, 0x00, 0x19, 0x00, 0x05, 0x00, + 0x02, 0x80, 0x01, 0x40, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x28, + 0x00, 0x14, 0x00, 0x12, 0x00, 0x09, 0x80, 0x08, 0x40, 0x08, 0x30, 0x08, + 0x0C, 0x18, 0x03, 0xF0, 0x00, 0xC0, 0x01, 0xC0, 0x01, 0xFE, 0x18, 0xC0, + 0xF0, 0x0F, 0xFE, 0x00, 0x40, 0x60, 0x20, 0x0C, 0x08, 0x01, 0x02, 0x00, + 0x40, 0x80, 0x10, 0x40, 0x04, 0x10, 0x02, 0x04, 0x01, 0x01, 0x01, 0x80, + 0x7F, 0x80, 0x20, 0x60, 0x08, 0x0C, 0x02, 0x03, 0x80, 0x80, 0x60, 0x40, + 0x18, 0x10, 0x03, 0x04, 0x00, 0xC1, 0x00, 0x1B, 0xF8, 0x07, 0x00, 0x7E, + 0x40, 0x60, 0xF0, 0x20, 0x1C, 0x10, 0x02, 0x08, 0x00, 0x82, 0x00, 0x00, + 0x80, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xC0, 0x00, + 0x18, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x11, 0x00, 0x04, 0x40, 0x02, + 0x38, 0x01, 0x0B, 0x81, 0x82, 0x3F, 0x80, 0x3F, 0xFF, 0xA0, 0x20, 0x50, + 0x10, 0x28, 0x08, 0x24, 0x08, 0x10, 0x04, 0x00, 0x02, 0x00, 0x01, 0x00, + 0x01, 0x00, 0x00, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0x10, 0x00, 0x10, + 0x00, 0x08, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x00, 0x01, 0x00, 0x1F, + 0xFC, 0x00, 0x7E, 0x0F, 0xC4, 0x00, 0x42, 0x00, 0x10, 0x80, 0x08, 0x20, + 0x02, 0x08, 0x00, 0x82, 0x00, 0x21, 0x00, 0x08, 0x40, 0x04, 0x10, 0x01, + 0x04, 0x00, 0x41, 0x00, 0x10, 0x80, 0x0C, 0x20, 0x02, 0x08, 0x00, 0x82, + 0x00, 0x60, 0x80, 0x10, 0x10, 0x08, 0x06, 0x0C, 0x00, 0x7C, 0x00, 0xFE, + 0x03, 0xF9, 0x80, 0x02, 0x0C, 0x00, 0x30, 0x20, 0x01, 0x01, 0x00, 0x10, + 0x08, 0x01, 0x80, 0x60, 0x08, 0x03, 0x00, 0xC0, 0x18, 0x04, 0x00, 0x40, + 0x60, 0x02, 0x06, 0x00, 0x10, 0x20, 0x00, 0xC3, 0x00, 0x06, 0x10, 0x00, + 0x31, 0x80, 0x00, 0x88, 0x00, 0x04, 0x80, 0x00, 0x2C, 0x00, 0x01, 0xC0, + 0x00, 0x0E, 0x00, 0x00, 0x7F, 0x07, 0xF2, 0x00, 0x04, 0x20, 0x00, 0xC2, + 0x00, 0x08, 0x20, 0xC0, 0x82, 0x0C, 0x18, 0x21, 0xA1, 0x02, 0x1A, 0x10, + 0x23, 0x23, 0x04, 0x32, 0x30, 0x46, 0x22, 0x04, 0x62, 0x60, 0x4C, 0x26, + 0x04, 0xC2, 0x40, 0x58, 0x24, 0x05, 0x82, 0xC0, 0x70, 0x28, 0x07, 0x02, + 0x80, 0xE0, 0x38, 0x0E, 0x03, 0x00, 0x0F, 0xC1, 0xF8, 0x30, 0x03, 0x00, + 0xC0, 0x30, 0x06, 0x03, 0x00, 0x18, 0x10, 0x00, 0xC1, 0x00, 0x03, 0x18, + 0x00, 0x09, 0x80, 0x00, 0x78, 0x00, 0x01, 0x80, 0x00, 0x1C, 0x00, 0x01, + 0xA0, 0x00, 0x19, 0x80, 0x01, 0x84, 0x00, 0x18, 0x30, 0x01, 0x80, 0xC0, + 0x08, 0x06, 0x00, 0x80, 0x18, 0x08, 0x00, 0xC1, 0xF8, 0x3F, 0x80, 0x7E, + 0x0F, 0xC4, 0x00, 0xC1, 0x80, 0x60, 0x20, 0x30, 0x0C, 0x08, 0x03, 0x04, + 0x00, 0x43, 0x00, 0x19, 0x80, 0x02, 0xC0, 0x00, 0xE0, 0x00, 0x10, 0x00, + 0x04, 0x00, 0x01, 0x00, 0x00, 0x80, 0x00, 0x20, 0x00, 0x08, 0x00, 0x02, + 0x00, 0x01, 0x00, 0x00, 0x40, 0x03, 0xFF, 0x80, 0x0F, 0xFF, 0x86, 0x00, + 0x82, 0x00, 0x81, 0x00, 0xC1, 0x80, 0xC0, 0xC0, 0xC0, 0x00, 0xC0, 0x00, + 0xC0, 0x00, 0x40, 0x00, 0x40, 0x00, 0x60, 0x00, 0x60, 0x00, 0x60, 0x00, + 0x60, 0x10, 0x60, 0x18, 0x20, 0x08, 0x20, 0x04, 0x20, 0x02, 0x30, 0x03, + 0x1F, 0xFF, 0x80, 0x07, 0xE0, 0x80, 0x10, 0x02, 0x00, 0xC0, 0x18, 0x02, + 0x00, 0x40, 0x18, 0x03, 0x00, 0x40, 0x08, 0x01, 0x00, 0x60, 0x0C, 0x01, + 0x00, 0x20, 0x04, 0x01, 0x80, 0x30, 0x04, 0x00, 0x80, 0x10, 0x06, 0x00, + 0xFC, 0x00, 0x80, 0x80, 0x80, 0x40, 0x40, 0x40, 0x20, 0x20, 0x20, 0x20, + 0x10, 0x10, 0x10, 0x10, 0x08, 0x08, 0x08, 0x08, 0x04, 0x04, 0x04, 0x04, + 0x02, 0x02, 0x02, 0x02, 0x00, 0x07, 0xE0, 0x0C, 0x01, 0x00, 0x20, 0x04, + 0x01, 0x80, 0x30, 0x04, 0x00, 0x80, 0x30, 0x06, 0x00, 0x80, 0x10, 0x02, + 0x00, 0xC0, 0x18, 0x02, 0x00, 0x40, 0x18, 0x03, 0x00, 0x40, 0x08, 0x03, + 0x00, 0x60, 0xF8, 0x00, 0x01, 0x00, 0x1C, 0x01, 0xB0, 0x19, 0x81, 0x86, + 0x18, 0x11, 0x80, 0xD8, 0x03, 0x80, 0x18, 0xFF, 0xFF, 0xF8, 0xC7, 0x1C, + 0x71, 0x80, 0x03, 0xF8, 0x0C, 0x0C, 0x00, 0x02, 0x00, 0x02, 0x00, 0x02, + 0x00, 0x02, 0x07, 0xFC, 0x18, 0x0C, 0x20, 0x04, 0x40, 0x04, 0x80, 0x04, + 0x80, 0x08, 0x80, 0x38, 0xC0, 0xE8, 0x3F, 0x0F, 0x0F, 0x00, 0x00, 0x20, + 0x00, 0x04, 0x00, 0x01, 0x80, 0x00, 0x30, 0x00, 0x04, 0x00, 0x00, 0x87, + 0xC0, 0x13, 0x0C, 0x06, 0x80, 0x40, 0xE0, 0x0C, 0x18, 0x00, 0x82, 0x00, + 0x10, 0xC0, 0x02, 0x10, 0x00, 0x42, 0x00, 0x08, 0x40, 0x02, 0x08, 0x00, + 0x43, 0x80, 0x10, 0x70, 0x04, 0x09, 0x83, 0x0F, 0x1F, 0x80, 0x01, 0xFC, + 0x83, 0x03, 0xC6, 0x00, 0xE4, 0x00, 0x22, 0x00, 0x12, 0x00, 0x01, 0x00, + 0x01, 0x00, 0x00, 0x80, 0x00, 0x40, 0x00, 0x20, 0x00, 0x18, 0x00, 0x64, + 0x00, 0x61, 0x81, 0xC0, 0x7F, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x30, 0x00, + 0x0C, 0x00, 0x02, 0x00, 0x00, 0x80, 0x00, 0x60, 0x3F, 0x18, 0x10, 0x64, + 0x18, 0x0D, 0x08, 0x01, 0xC2, 0x00, 0x71, 0x00, 0x0C, 0x80, 0x02, 0x20, + 0x00, 0x88, 0x00, 0x62, 0x00, 0x18, 0x80, 0x0E, 0x20, 0x03, 0x04, 0x03, + 0x40, 0xC1, 0xB0, 0x1F, 0x8F, 0x00, 0x01, 0xF0, 0x0E, 0x0C, 0x18, 0x06, + 0x30, 0x02, 0x60, 0x01, 0x40, 0x01, 0xC0, 0x01, 0xFF, 0xFF, 0x80, 0x00, + 0x80, 0x00, 0x80, 0x00, 0x40, 0x00, 0x60, 0x06, 0x30, 0x1C, 0x0F, 0xE0, + 0x00, 0x1F, 0xE0, 0x0C, 0x00, 0x03, 0x00, 0x00, 0x40, 0x00, 0x08, 0x00, + 0x02, 0x00, 0x07, 0xFF, 0xC0, 0x08, 0x00, 0x01, 0x00, 0x00, 0x20, 0x00, + 0x08, 0x00, 0x01, 0x00, 0x00, 0x20, 0x00, 0x04, 0x00, 0x00, 0x80, 0x00, + 0x20, 0x00, 0x04, 0x00, 0x00, 0x80, 0x00, 0x10, 0x00, 0x04, 0x00, 0x0F, + 0xFF, 0x00, 0x03, 0xE3, 0xE1, 0x83, 0x60, 0x40, 0x38, 0x10, 0x03, 0x04, + 0x00, 0x60, 0x80, 0x0C, 0x20, 0x01, 0x84, 0x00, 0x20, 0x80, 0x04, 0x10, + 0x01, 0x82, 0x00, 0x30, 0x60, 0x0C, 0x04, 0x02, 0x80, 0x61, 0x90, 0x07, + 0xC6, 0x00, 0x00, 0xC0, 0x00, 0x10, 0x00, 0x02, 0x00, 0x00, 0x80, 0x00, + 0x30, 0x00, 0x0C, 0x00, 0xFE, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x40, 0x00, + 0x10, 0x00, 0x08, 0x00, 0x02, 0x00, 0x00, 0x80, 0x00, 0x23, 0xE0, 0x0B, + 0x0C, 0x05, 0x00, 0x81, 0x80, 0x20, 0x40, 0x08, 0x10, 0x02, 0x08, 0x00, + 0x82, 0x00, 0x60, 0x80, 0x18, 0x20, 0x06, 0x10, 0x01, 0x84, 0x00, 0x61, + 0x00, 0x30, 0x40, 0x0C, 0xFC, 0x1F, 0xC0, 0x00, 0x30, 0x00, 0x60, 0x00, + 0xC0, 0x01, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x20, + 0x00, 0x40, 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x08, 0x00, 0x10, 0x00, + 0x40, 0x00, 0x80, 0x01, 0x00, 0x02, 0x00, 0x08, 0x00, 0x10, 0x1F, 0xFF, + 0x80, 0x00, 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x07, 0xFE, 0x00, 0x04, 0x00, 0x08, 0x00, 0x10, 0x00, 0x20, + 0x00, 0x80, 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x08, 0x00, 0x20, 0x00, + 0x40, 0x00, 0x80, 0x01, 0x00, 0x06, 0x00, 0x08, 0x00, 0x10, 0x00, 0x20, + 0x00, 0x80, 0x03, 0x00, 0x0C, 0x0F, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x60, + 0x00, 0x10, 0x00, 0x04, 0x00, 0x01, 0x00, 0x00, 0xC0, 0x00, 0x30, 0xFC, + 0x08, 0x18, 0x02, 0x0C, 0x00, 0x8C, 0x00, 0x66, 0x00, 0x1B, 0x00, 0x05, + 0x80, 0x01, 0xB0, 0x00, 0x46, 0x00, 0x31, 0xC0, 0x0C, 0x30, 0x02, 0x06, + 0x00, 0x80, 0xC0, 0x60, 0x30, 0xF8, 0x1F, 0x80, 0x01, 0xF8, 0x00, 0x20, + 0x00, 0x40, 0x00, 0x80, 0x01, 0x00, 0x04, 0x00, 0x08, 0x00, 0x10, 0x00, + 0x20, 0x00, 0x80, 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x08, 0x00, 0x20, + 0x00, 0x40, 0x00, 0x80, 0x01, 0x00, 0x04, 0x00, 0x08, 0x0F, 0xFF, 0xC0, + 0x1C, 0xF1, 0xE0, 0xF1, 0xE3, 0x0E, 0x1C, 0x10, 0xC1, 0x81, 0x08, 0x10, + 0x30, 0x81, 0x03, 0x18, 0x10, 0x21, 0x83, 0x02, 0x10, 0x30, 0x21, 0x02, + 0x06, 0x10, 0x20, 0x63, 0x02, 0x04, 0x30, 0x60, 0x42, 0x06, 0x04, 0xF8, + 0x70, 0xF0, 0x0E, 0x3E, 0x01, 0x60, 0x81, 0xC0, 0x20, 0xC0, 0x10, 0x40, + 0x08, 0x20, 0x04, 0x30, 0x02, 0x10, 0x02, 0x08, 0x01, 0x04, 0x00, 0x82, + 0x00, 0x42, 0x00, 0x21, 0x00, 0x20, 0x80, 0x13, 0xF0, 0x3E, 0x01, 0xF0, + 0x06, 0x0C, 0x18, 0x06, 0x20, 0x03, 0x60, 0x01, 0x40, 0x01, 0x80, 0x01, + 0x80, 0x01, 0x80, 0x01, 0x80, 0x02, 0x80, 0x06, 0xC0, 0x04, 0x40, 0x18, + 0x30, 0x60, 0x1F, 0x80, 0x0F, 0x1F, 0x80, 0x16, 0x0C, 0x01, 0xC0, 0x20, + 0x30, 0x03, 0x03, 0x00, 0x10, 0x20, 0x01, 0x02, 0x00, 0x10, 0x40, 0x01, + 0x04, 0x00, 0x10, 0x40, 0x02, 0x06, 0x00, 0x60, 0x60, 0x04, 0x0B, 0x00, + 0x80, 0x98, 0x30, 0x08, 0xFC, 0x00, 0x80, 0x00, 0x08, 0x00, 0x01, 0x00, + 0x00, 0x10, 0x00, 0x01, 0x00, 0x00, 0x10, 0x00, 0x0F, 0xF0, 0x00, 0x03, + 0xF1, 0xE1, 0x83, 0x20, 0x40, 0x34, 0x10, 0x03, 0x84, 0x00, 0x30, 0x80, + 0x04, 0x20, 0x00, 0x84, 0x00, 0x10, 0x80, 0x06, 0x10, 0x00, 0xC2, 0x00, + 0x30, 0x60, 0x0E, 0x04, 0x03, 0x40, 0x60, 0xC8, 0x07, 0xE2, 0x00, 0x00, + 0x40, 0x00, 0x08, 0x00, 0x01, 0x00, 0x00, 0x20, 0x00, 0x08, 0x00, 0x01, + 0x00, 0x03, 0xFC, 0x00, 0x0F, 0x87, 0xC0, 0x23, 0x08, 0x04, 0xC0, 0x00, + 0xE0, 0x00, 0x18, 0x00, 0x02, 0x00, 0x00, 0x80, 0x00, 0x10, 0x00, 0x02, + 0x00, 0x00, 0x40, 0x00, 0x10, 0x00, 0x02, 0x00, 0x00, 0x40, 0x00, 0x08, + 0x00, 0x3F, 0xFE, 0x00, 0x01, 0xFA, 0x0C, 0x1C, 0x20, 0x08, 0x80, 0x11, + 0x00, 0x03, 0x00, 0x03, 0xF8, 0x00, 0x7C, 0x00, 0x0C, 0x00, 0x09, 0x00, + 0x16, 0x00, 0x2C, 0x00, 0x9E, 0x06, 0x27, 0xF0, 0x00, 0x08, 0x00, 0x40, + 0x02, 0x00, 0x10, 0x00, 0x80, 0x7F, 0xFC, 0x40, 0x02, 0x00, 0x10, 0x00, + 0x80, 0x08, 0x00, 0x40, 0x02, 0x00, 0x10, 0x01, 0x00, 0x08, 0x00, 0x40, + 0x02, 0x00, 0xD8, 0x1C, 0x3F, 0x00, 0xF0, 0x1E, 0x20, 0x04, 0x80, 0x09, + 0x00, 0x12, 0x00, 0x24, 0x00, 0xC8, 0x01, 0x20, 0x02, 0x40, 0x04, 0x80, + 0x09, 0x00, 0x12, 0x00, 0x64, 0x03, 0x8C, 0x1D, 0x0F, 0xC3, 0x80, 0xFE, + 0x0F, 0xE6, 0x00, 0x20, 0x40, 0x08, 0x08, 0x03, 0x01, 0x80, 0x40, 0x30, + 0x18, 0x06, 0x02, 0x00, 0x40, 0x80, 0x08, 0x30, 0x01, 0x84, 0x00, 0x31, + 0x80, 0x02, 0x20, 0x00, 0x48, 0x00, 0x09, 0x00, 0x01, 0xC0, 0x00, 0xF8, + 0x0F, 0xA0, 0x01, 0x90, 0x00, 0x88, 0x40, 0xC4, 0x30, 0x42, 0x18, 0x61, + 0x1A, 0x20, 0x8D, 0x10, 0x4C, 0x98, 0x26, 0x48, 0x16, 0x2C, 0x0B, 0x14, + 0x07, 0x0A, 0x03, 0x07, 0x01, 0x81, 0x00, 0x0F, 0x83, 0xE0, 0xC0, 0x18, + 0x0C, 0x0C, 0x01, 0x83, 0x00, 0x18, 0xC0, 0x01, 0xB0, 0x00, 0x1C, 0x00, + 0x03, 0x00, 0x00, 0xF0, 0x00, 0x63, 0x00, 0x18, 0x30, 0x06, 0x06, 0x01, + 0x80, 0x60, 0x60, 0x06, 0x3F, 0x07, 0xE0, 0x0F, 0xC0, 0xF8, 0x30, 0x01, + 0x00, 0x80, 0x18, 0x04, 0x00, 0x80, 0x30, 0x0C, 0x01, 0x80, 0xC0, 0x04, + 0x04, 0x00, 0x30, 0x60, 0x01, 0x86, 0x00, 0x04, 0x20, 0x00, 0x23, 0x00, + 0x01, 0xB0, 0x00, 0x0D, 0x00, 0x00, 0x38, 0x00, 0x01, 0x80, 0x00, 0x08, + 0x00, 0x00, 0xC0, 0x00, 0x04, 0x00, 0x00, 0x60, 0x00, 0x06, 0x00, 0x00, + 0x20, 0x00, 0x7F, 0xE0, 0x00, 0x1F, 0xFF, 0x10, 0x06, 0x10, 0x0C, 0x10, + 0x18, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x06, + 0x00, 0x0C, 0x00, 0x18, 0x04, 0x30, 0x0C, 0x60, 0x0C, 0xFF, 0xF8, 0x00, + 0xE0, 0x20, 0x08, 0x01, 0x00, 0x20, 0x04, 0x01, 0x00, 0x20, 0x04, 0x00, + 0x80, 0x20, 0x08, 0x0E, 0x00, 0x60, 0x04, 0x00, 0x80, 0x10, 0x02, 0x00, + 0x40, 0x08, 0x02, 0x00, 0x40, 0x08, 0x01, 0x00, 0x18, 0x00, 0x00, 0x10, + 0xC3, 0x08, 0x20, 0x86, 0x18, 0x41, 0x04, 0x30, 0xC2, 0x08, 0x21, 0x86, + 0x10, 0x43, 0x0C, 0x20, 0x06, 0x00, 0x40, 0x10, 0x04, 0x01, 0x00, 0x40, + 0x10, 0x04, 0x02, 0x00, 0x80, 0x20, 0x0C, 0x01, 0xC0, 0xC0, 0x40, 0x10, + 0x04, 0x03, 0x00, 0x80, 0x20, 0x08, 0x02, 0x01, 0x00, 0xC0, 0xE0, 0x00, + 0x1E, 0x02, 0x66, 0x0D, 0x86, 0x16, 0x06, 0x48, 0x07, 0x00 }; + +const GFXglyph FreeMonoOblique18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 21, 0, 1 }, // 0x20 ' ' + { 0, 7, 22, 21, 9, -21 }, // 0x21 '!' + { 20, 13, 10, 21, 7, -20 }, // 0x22 '"' + { 37, 15, 24, 21, 5, -21 }, // 0x23 '#' + { 82, 16, 26, 21, 4, -22 }, // 0x24 '$' + { 134, 16, 21, 21, 5, -20 }, // 0x25 '%' + { 176, 13, 18, 21, 5, -17 }, // 0x26 '&' + { 206, 5, 10, 21, 12, -20 }, // 0x27 ''' + { 213, 8, 25, 21, 12, -20 }, // 0x28 '(' + { 238, 8, 25, 21, 5, -20 }, // 0x29 ')' + { 263, 14, 11, 21, 7, -19 }, // 0x2A '*' + { 283, 15, 17, 21, 5, -17 }, // 0x2B '+' + { 315, 9, 10, 21, 4, -4 }, // 0x2C ',' + { 327, 16, 1, 21, 5, -9 }, // 0x2D '-' + { 329, 5, 5, 21, 8, -4 }, // 0x2E '.' + { 333, 19, 26, 21, 3, -22 }, // 0x2F '/' + { 395, 14, 21, 21, 5, -20 }, // 0x30 '0' + { 432, 13, 21, 21, 4, -20 }, // 0x31 '1' + { 467, 17, 21, 21, 3, -20 }, // 0x32 '2' + { 512, 16, 21, 21, 3, -20 }, // 0x33 '3' + { 554, 14, 21, 21, 5, -20 }, // 0x34 '4' + { 591, 17, 21, 21, 4, -20 }, // 0x35 '5' + { 636, 16, 21, 21, 6, -20 }, // 0x36 '6' + { 678, 13, 21, 21, 8, -20 }, // 0x37 '7' + { 713, 15, 21, 21, 5, -20 }, // 0x38 '8' + { 753, 15, 21, 21, 5, -20 }, // 0x39 '9' + { 793, 7, 15, 21, 8, -14 }, // 0x3A ':' + { 807, 11, 20, 21, 4, -14 }, // 0x3B ';' + { 835, 17, 16, 21, 5, -17 }, // 0x3C '<' + { 869, 19, 6, 21, 3, -12 }, // 0x3D '=' + { 884, 18, 16, 21, 3, -17 }, // 0x3E '>' + { 920, 12, 20, 21, 8, -19 }, // 0x3F '?' + { 950, 15, 23, 21, 5, -20 }, // 0x40 '@' + { 994, 21, 20, 21, 0, -19 }, // 0x41 'A' + { 1047, 18, 20, 21, 2, -19 }, // 0x42 'B' + { 1092, 18, 20, 21, 4, -19 }, // 0x43 'C' + { 1137, 18, 20, 21, 2, -19 }, // 0x44 'D' + { 1182, 20, 20, 21, 2, -19 }, // 0x45 'E' + { 1232, 20, 20, 21, 2, -19 }, // 0x46 'F' + { 1282, 18, 20, 21, 4, -19 }, // 0x47 'G' + { 1327, 21, 20, 21, 2, -19 }, // 0x48 'H' + { 1380, 17, 20, 21, 4, -19 }, // 0x49 'I' + { 1423, 20, 20, 21, 4, -19 }, // 0x4A 'J' + { 1473, 21, 20, 21, 2, -19 }, // 0x4B 'K' + { 1526, 18, 20, 21, 2, -19 }, // 0x4C 'L' + { 1571, 24, 20, 21, 1, -19 }, // 0x4D 'M' + { 1631, 22, 20, 21, 2, -19 }, // 0x4E 'N' + { 1686, 17, 20, 21, 4, -19 }, // 0x4F 'O' + { 1729, 18, 20, 21, 2, -19 }, // 0x50 'P' + { 1774, 17, 24, 21, 4, -19 }, // 0x51 'Q' + { 1825, 18, 20, 21, 2, -19 }, // 0x52 'R' + { 1870, 18, 20, 21, 3, -19 }, // 0x53 'S' + { 1915, 17, 20, 21, 5, -19 }, // 0x54 'T' + { 1958, 18, 20, 21, 5, -19 }, // 0x55 'U' + { 2003, 21, 20, 21, 4, -19 }, // 0x56 'V' + { 2056, 20, 20, 21, 4, -19 }, // 0x57 'W' + { 2106, 21, 20, 21, 2, -19 }, // 0x58 'X' + { 2159, 18, 20, 21, 5, -19 }, // 0x59 'Y' + { 2204, 17, 20, 21, 4, -19 }, // 0x5A 'Z' + { 2247, 11, 25, 21, 9, -20 }, // 0x5B '[' + { 2282, 8, 27, 21, 9, -22 }, // 0x5C '\' + { 2309, 11, 25, 21, 5, -20 }, // 0x5D ']' + { 2344, 13, 9, 21, 7, -20 }, // 0x5E '^' + { 2359, 21, 1, 21, -1, 4 }, // 0x5F '_' + { 2362, 5, 5, 21, 9, -21 }, // 0x60 '`' + { 2366, 16, 15, 21, 3, -14 }, // 0x61 'a' + { 2396, 19, 21, 21, 1, -20 }, // 0x62 'b' + { 2446, 17, 15, 21, 4, -14 }, // 0x63 'c' + { 2478, 18, 21, 21, 4, -20 }, // 0x64 'd' + { 2526, 16, 15, 21, 4, -14 }, // 0x65 'e' + { 2556, 19, 21, 21, 4, -20 }, // 0x66 'f' + { 2606, 19, 22, 21, 4, -14 }, // 0x67 'g' + { 2659, 18, 21, 21, 2, -20 }, // 0x68 'h' + { 2707, 15, 22, 21, 3, -21 }, // 0x69 'i' + { 2749, 15, 29, 21, 3, -21 }, // 0x6A 'j' + { 2804, 18, 21, 21, 2, -20 }, // 0x6B 'k' + { 2852, 15, 21, 21, 3, -20 }, // 0x6C 'l' + { 2892, 20, 15, 21, 1, -14 }, // 0x6D 'm' + { 2930, 17, 15, 21, 2, -14 }, // 0x6E 'n' + { 2962, 16, 15, 21, 4, -14 }, // 0x6F 'o' + { 2992, 20, 22, 21, 0, -14 }, // 0x70 'p' + { 3047, 19, 22, 21, 4, -14 }, // 0x71 'q' + { 3100, 19, 15, 21, 3, -14 }, // 0x72 'r' + { 3136, 15, 15, 21, 4, -14 }, // 0x73 's' + { 3165, 13, 20, 21, 5, -19 }, // 0x74 't' + { 3198, 15, 15, 21, 4, -14 }, // 0x75 'u' + { 3227, 19, 15, 21, 4, -14 }, // 0x76 'v' + { 3263, 17, 15, 21, 5, -14 }, // 0x77 'w' + { 3295, 19, 15, 21, 2, -14 }, // 0x78 'x' + { 3331, 21, 22, 21, 1, -14 }, // 0x79 'y' + { 3389, 16, 15, 21, 4, -14 }, // 0x7A 'z' + { 3419, 11, 25, 21, 8, -20 }, // 0x7B '{' + { 3454, 6, 24, 21, 9, -19 }, // 0x7C '|' + { 3472, 10, 25, 21, 6, -20 }, // 0x7D '}' + { 3504, 15, 5, 21, 5, -11 } }; // 0x7E '~' + +const GFXfont FreeMonoOblique18pt7b PROGMEM = { + (uint8_t *)FreeMonoOblique18pt7bBitmaps, + (GFXglyph *)FreeMonoOblique18pt7bGlyphs, + 0x20, 0x7E, 35 }; + +// Approx. 4186 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique24pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique24pt7b.h new file mode 100644 index 0000000..8a5592c --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique24pt7b.h @@ -0,0 +1,643 @@ +const uint8_t FreeMonoOblique24pt7bBitmaps[] PROGMEM = { + 0x01, 0xC0, 0xF0, 0x3C, 0x0E, 0x03, 0x81, 0xE0, 0x78, 0x1C, 0x07, 0x01, + 0xC0, 0xE0, 0x38, 0x0E, 0x03, 0x00, 0xC0, 0x70, 0x1C, 0x06, 0x01, 0x80, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1C, 0x0F, 0x83, 0xE0, 0xF8, + 0x1C, 0x00, 0x7E, 0x3F, 0x7E, 0x3F, 0x7C, 0x3E, 0x7C, 0x3E, 0x7C, 0x3E, + 0x78, 0x3C, 0xF8, 0x7C, 0xF0, 0x78, 0xF0, 0x78, 0xF0, 0x78, 0xE0, 0x70, + 0xE0, 0x70, 0xE0, 0x70, 0xC0, 0x60, 0x00, 0x18, 0x30, 0x00, 0x61, 0x80, + 0x01, 0x86, 0x00, 0x04, 0x18, 0x00, 0x30, 0xC0, 0x00, 0xC3, 0x00, 0x03, + 0x0C, 0x00, 0x18, 0x30, 0x00, 0x61, 0x80, 0x01, 0x86, 0x00, 0x06, 0x18, + 0x07, 0xFF, 0xFF, 0x1F, 0xFF, 0xFC, 0x03, 0x0C, 0x00, 0x18, 0x30, 0x00, + 0x61, 0x80, 0x01, 0x86, 0x00, 0x06, 0x18, 0x00, 0x30, 0xC0, 0x1F, 0xFF, + 0xF8, 0x7F, 0xFF, 0xE0, 0x18, 0x30, 0x00, 0x61, 0x80, 0x01, 0x86, 0x00, + 0x06, 0x18, 0x00, 0x30, 0x40, 0x00, 0xC3, 0x00, 0x03, 0x0C, 0x00, 0x18, + 0x30, 0x00, 0x61, 0x80, 0x01, 0x86, 0x00, 0x06, 0x18, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x18, 0x00, 0x00, 0x80, 0x00, 0x3F, 0x00, 0x07, 0xFD, 0x80, + 0x70, 0x7C, 0x06, 0x00, 0xE0, 0x60, 0x02, 0x07, 0x00, 0x10, 0x30, 0x00, + 0x01, 0x80, 0x00, 0x0C, 0x00, 0x00, 0x70, 0x00, 0x01, 0xF0, 0x00, 0x07, + 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x18, + 0x00, 0x00, 0xC2, 0x00, 0x06, 0x30, 0x00, 0x61, 0x80, 0x03, 0x1E, 0x00, + 0x30, 0xFC, 0x07, 0x06, 0x7F, 0xF0, 0x00, 0xFE, 0x00, 0x01, 0x80, 0x00, + 0x0C, 0x00, 0x00, 0x60, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0x80, + 0x00, 0x00, 0x78, 0x00, 0x07, 0xF8, 0x00, 0x38, 0x60, 0x01, 0xC0, 0xC0, + 0x06, 0x03, 0x00, 0x30, 0x0C, 0x00, 0xC0, 0x30, 0x03, 0x01, 0x80, 0x0C, + 0x0E, 0x00, 0x38, 0x70, 0x00, 0x7F, 0x81, 0xC0, 0xF8, 0x3F, 0x00, 0x07, + 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xC0, 0x00, 0x78, 0x00, 0x01, + 0x00, 0x78, 0x00, 0x07, 0xF8, 0x00, 0x38, 0x60, 0x01, 0x80, 0xC0, 0x06, + 0x03, 0x00, 0x30, 0x0C, 0x00, 0xC0, 0x30, 0x03, 0x01, 0x80, 0x0C, 0x0E, + 0x00, 0x18, 0x70, 0x00, 0x7F, 0x80, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, + 0x0F, 0xF8, 0x03, 0x8E, 0x00, 0xC0, 0x00, 0x38, 0x00, 0x06, 0x00, 0x00, + 0xC0, 0x00, 0x18, 0x00, 0x01, 0x00, 0x00, 0x30, 0x00, 0x06, 0x00, 0x03, + 0xE0, 0x01, 0xCC, 0x0E, 0x60, 0xC3, 0xD8, 0x18, 0x63, 0x03, 0x18, 0xC0, + 0x33, 0x18, 0x06, 0xC3, 0x00, 0x70, 0x60, 0x0E, 0x0C, 0x01, 0xC0, 0xC0, + 0x78, 0x1C, 0x3B, 0xE1, 0xFE, 0x3C, 0x1F, 0x00, 0x00, 0x7E, 0xFD, 0xF3, + 0xE7, 0xCF, 0x3E, 0x78, 0xF1, 0xE3, 0x87, 0x0E, 0x18, 0x00, 0x00, 0x60, + 0x18, 0x07, 0x00, 0xC0, 0x30, 0x0E, 0x01, 0x80, 0x70, 0x0C, 0x03, 0x80, + 0x60, 0x1C, 0x03, 0x80, 0xE0, 0x1C, 0x03, 0x80, 0xF0, 0x1C, 0x03, 0x80, + 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x30, + 0x06, 0x00, 0xC0, 0x1C, 0x01, 0x80, 0x30, 0x02, 0x00, 0x01, 0x80, 0x30, + 0x06, 0x00, 0xE0, 0x0C, 0x01, 0x80, 0x30, 0x07, 0x00, 0xE0, 0x1C, 0x03, + 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x38, 0x07, 0x00, + 0xE0, 0x3C, 0x07, 0x00, 0xE0, 0x38, 0x07, 0x01, 0xC0, 0x38, 0x0E, 0x01, + 0x80, 0x70, 0x0C, 0x03, 0x00, 0xC0, 0x10, 0x00, 0x00, 0x20, 0x00, 0x18, + 0x00, 0x06, 0x00, 0x01, 0x80, 0x00, 0xC0, 0x00, 0x30, 0x0E, 0x0C, 0x0B, + 0xF3, 0x3E, 0x3F, 0xFE, 0x01, 0xFC, 0x00, 0x3C, 0x00, 0x1F, 0x00, 0x0E, + 0x60, 0x07, 0x18, 0x01, 0x83, 0x00, 0xC0, 0xC0, 0x60, 0x30, 0x00, 0x00, + 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x18, + 0x00, 0x00, 0x60, 0x00, 0x01, 0x80, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, + 0x00, 0xC0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x30, 0x00, 0x01, + 0x80, 0x00, 0x06, 0x00, 0x00, 0x18, 0x00, 0x00, 0x60, 0x00, 0x01, 0x80, + 0x00, 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, + 0x03, 0xF0, 0x7E, 0x07, 0xC0, 0xF8, 0x0F, 0x81, 0xF0, 0x1E, 0x03, 0xE0, + 0x3C, 0x07, 0x80, 0x70, 0x0F, 0x00, 0xE0, 0x0C, 0x00, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xE0, 0x3C, 0xFF, 0xFF, 0xFF, 0xCF, 0x00, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x03, 0x00, 0x00, 0x06, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x0C, + 0x00, 0x00, 0x18, 0x00, 0x00, 0x30, 0x00, 0x00, 0x30, 0x00, 0x00, 0x60, + 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x01, 0x80, 0x00, 0x03, 0x00, + 0x00, 0x07, 0x00, 0x00, 0x06, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x1C, 0x00, + 0x00, 0x18, 0x00, 0x00, 0x30, 0x00, 0x00, 0x70, 0x00, 0x00, 0x60, 0x00, + 0x00, 0xC0, 0x00, 0x01, 0x80, 0x00, 0x01, 0x80, 0x00, 0x03, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x06, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x18, 0x00, 0x00, + 0x18, 0x00, 0x00, 0x30, 0x00, 0x00, 0x60, 0x00, 0x00, 0xE0, 0x00, 0x00, + 0xC0, 0x00, 0x00, 0x80, 0x00, 0x00, 0x00, 0x3F, 0x00, 0x0F, 0xF8, 0x01, + 0xC1, 0xC0, 0x38, 0x0E, 0x07, 0x00, 0x60, 0xE0, 0x03, 0x0C, 0x00, 0x31, + 0x80, 0x03, 0x18, 0x00, 0x33, 0x00, 0x03, 0x30, 0x00, 0x33, 0x00, 0x03, + 0x20, 0x00, 0x26, 0x00, 0x06, 0x60, 0x00, 0x66, 0x00, 0x06, 0x40, 0x00, + 0x4C, 0x00, 0x0C, 0xC0, 0x00, 0xCC, 0x00, 0x0C, 0xC0, 0x01, 0x8C, 0x00, + 0x18, 0xC0, 0x01, 0x8C, 0x00, 0x30, 0xC0, 0x07, 0x06, 0x00, 0xE0, 0x60, + 0x1C, 0x03, 0x87, 0x80, 0x3F, 0xF0, 0x00, 0xFC, 0x00, 0x00, 0x0E, 0x00, + 0x0F, 0x00, 0x0F, 0x80, 0x0E, 0xC0, 0x1C, 0xC0, 0x1C, 0x60, 0x1C, 0x30, + 0x08, 0x18, 0x00, 0x1C, 0x00, 0x0C, 0x00, 0x06, 0x00, 0x03, 0x00, 0x01, + 0x80, 0x01, 0xC0, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x18, 0x00, + 0x18, 0x00, 0x0C, 0x00, 0x06, 0x00, 0x03, 0x00, 0x01, 0x80, 0x01, 0x80, + 0x00, 0xC0, 0x00, 0x60, 0x00, 0x30, 0x1F, 0xFF, 0xFF, 0xFF, 0xF8, 0x00, + 0x07, 0xE0, 0x00, 0x3F, 0xE0, 0x01, 0xE0, 0xE0, 0x07, 0x00, 0xE0, 0x1C, + 0x00, 0xE0, 0x30, 0x00, 0xC0, 0xC0, 0x01, 0x81, 0x00, 0x03, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x18, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x03, + 0x00, 0x00, 0x1C, 0x00, 0x00, 0x70, 0x00, 0x01, 0xC0, 0x00, 0x07, 0x00, + 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x03, 0x80, 0x00, 0x0E, 0x00, 0x00, + 0x70, 0x00, 0x01, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xE0, + 0x00, 0xC3, 0x80, 0x01, 0x87, 0xFF, 0xFF, 0x0F, 0xFF, 0xFC, 0x00, 0x00, + 0x0F, 0xC0, 0x01, 0xFF, 0xC0, 0x1E, 0x07, 0x80, 0xE0, 0x06, 0x03, 0x00, + 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, 0x0C, + 0x00, 0x00, 0x60, 0x00, 0x03, 0x80, 0x00, 0x1C, 0x00, 0x00, 0xE0, 0x00, + 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xE0, 0x00, 0x01, + 0x80, 0x00, 0x03, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, + 0x00, 0x03, 0x00, 0x00, 0x18, 0x00, 0x00, 0xE3, 0x00, 0x07, 0x0E, 0x00, + 0x38, 0x1E, 0x03, 0xC0, 0x3F, 0xFC, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x03, + 0xE0, 0x00, 0xF8, 0x00, 0x1B, 0x00, 0x06, 0x60, 0x01, 0x8C, 0x00, 0x63, + 0x00, 0x18, 0x60, 0x07, 0x0C, 0x00, 0xC1, 0x80, 0x30, 0x30, 0x0C, 0x0C, + 0x03, 0x01, 0x80, 0xC0, 0x30, 0x18, 0x06, 0x06, 0x00, 0xC1, 0x80, 0x30, + 0x60, 0x06, 0x18, 0x00, 0xC3, 0xFF, 0xFE, 0x7F, 0xFF, 0xC0, 0x00, 0xC0, + 0x00, 0x18, 0x00, 0x03, 0x00, 0x00, 0x60, 0x00, 0x18, 0x00, 0x03, 0x00, + 0x0F, 0xFC, 0x01, 0xFF, 0x80, 0x01, 0xFF, 0xF8, 0x0F, 0xFF, 0xC0, 0x40, + 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0x80, 0x00, 0x0C, 0x00, 0x00, + 0xC0, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0xBF, 0xC0, 0x0F, 0xFF, + 0x80, 0xF8, 0x1E, 0x02, 0x00, 0x30, 0x00, 0x01, 0xC0, 0x00, 0x06, 0x00, + 0x00, 0x30, 0x00, 0x01, 0x80, 0x00, 0x0C, 0x00, 0x00, 0x60, 0x00, 0x06, + 0x00, 0x00, 0x30, 0x00, 0x03, 0x80, 0x00, 0x18, 0xC0, 0x01, 0x87, 0x00, + 0x38, 0x1E, 0x07, 0x80, 0x7F, 0xF8, 0x00, 0x7E, 0x00, 0x00, 0x00, 0x03, + 0xF0, 0x00, 0xFF, 0xC0, 0x1F, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x01, + 0x80, 0x00, 0x18, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x00, 0xC0, 0x00, + 0x0E, 0x00, 0x00, 0x60, 0x00, 0x07, 0x0F, 0x80, 0x31, 0xFF, 0x01, 0x9C, + 0x3C, 0x0D, 0x80, 0x60, 0xD8, 0x03, 0x87, 0x80, 0x0C, 0x38, 0x00, 0x61, + 0xC0, 0x03, 0x0C, 0x00, 0x18, 0x60, 0x00, 0xC3, 0x00, 0x0C, 0x18, 0x00, + 0x60, 0xE0, 0x06, 0x03, 0x00, 0x30, 0x1C, 0x07, 0x00, 0x70, 0x70, 0x01, + 0xFF, 0x00, 0x07, 0xE0, 0x00, 0x7F, 0xFF, 0xDF, 0xFF, 0xFC, 0x00, 0x0F, + 0x00, 0x03, 0x00, 0x01, 0x80, 0x00, 0x60, 0x00, 0x30, 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, 0x60, 0x00, 0x18, 0x00, 0x0C, + 0x00, 0x03, 0x00, 0x01, 0x80, 0x00, 0x60, 0x00, 0x00, 0x3F, 0x00, 0x0F, + 0xFC, 0x01, 0xC1, 0xE0, 0x70, 0x06, 0x06, 0x00, 0x30, 0xC0, 0x03, 0x1C, + 0x00, 0x31, 0x80, 0x03, 0x18, 0x00, 0x31, 0x80, 0x06, 0x18, 0x00, 0xE0, + 0xC0, 0x1C, 0x0F, 0x07, 0x80, 0x3F, 0xE0, 0x03, 0xFE, 0x00, 0xE0, 0x70, + 0x18, 0x03, 0x83, 0x00, 0x1C, 0x60, 0x00, 0xC6, 0x00, 0x0C, 0xC0, 0x00, + 0xCC, 0x00, 0x0C, 0xC0, 0x00, 0xCC, 0x00, 0x18, 0xC0, 0x03, 0x8E, 0x00, + 0x70, 0x60, 0x0E, 0x07, 0x83, 0xC0, 0x3F, 0xF0, 0x00, 0xFC, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0xFF, 0x80, 0x0F, 0x07, 0x00, 0x70, 0x0E, 0x03, 0x80, + 0x18, 0x0C, 0x00, 0x70, 0x60, 0x00, 0xC1, 0x80, 0x03, 0x0C, 0x00, 0x0C, + 0x30, 0x00, 0x30, 0xC0, 0x01, 0xC3, 0x00, 0x0F, 0x0C, 0x00, 0x6C, 0x38, + 0x03, 0xF0, 0x60, 0x1D, 0x81, 0xE1, 0xE6, 0x03, 0xFE, 0x18, 0x03, 0xE0, + 0xC0, 0x00, 0x03, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x60, 0x00, 0x03, 0x00, + 0x00, 0x1C, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00, 0x38, 0x00, 0x03, + 0xC0, 0x00, 0x7C, 0x00, 0xFF, 0xC0, 0x01, 0xF8, 0x00, 0x00, 0x07, 0x83, + 0xF1, 0xFC, 0x7F, 0x1F, 0x83, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0xF0, 0x7E, 0x3F, 0x8F, 0xE3, 0xF0, 0x78, + 0x00, 0x00, 0x3C, 0x00, 0xFC, 0x03, 0xF8, 0x07, 0xF0, 0x0F, 0xC0, 0x0F, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x7E, 0x00, 0xFC, 0x03, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x3E, + 0x00, 0xF8, 0x01, 0xE0, 0x07, 0x80, 0x0F, 0x00, 0x3C, 0x00, 0x70, 0x01, + 0xC0, 0x01, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x3C, 0x00, 0x01, + 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, + 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x03, + 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, + 0x70, 0x00, 0x00, 0x78, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x0C, 0x00, 0x3F, 0xFF, 0xFF, 0x9F, + 0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, + 0x00, 0x06, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, 0xF0, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, + 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0x70, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x07, 0xF0, 0x3F, 0xFC, 0x78, + 0x1E, 0xC0, 0x07, 0xC0, 0x03, 0xC0, 0x03, 0x00, 0x03, 0x00, 0x03, 0x00, + 0x06, 0x00, 0x06, 0x00, 0x1C, 0x00, 0x38, 0x00, 0xE0, 0x07, 0xC0, 0x07, + 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x3C, 0x00, 0x7E, 0x00, 0xFE, 0x00, 0xFE, + 0x00, 0x7C, 0x00, 0x00, 0x3F, 0x00, 0x1F, 0xF0, 0x07, 0x07, 0x01, 0xC0, + 0x70, 0x60, 0x06, 0x1C, 0x00, 0xC3, 0x00, 0x18, 0xC0, 0x03, 0x18, 0x00, + 0x66, 0x00, 0xFC, 0xC0, 0x7F, 0x98, 0x1C, 0x66, 0x06, 0x0C, 0xC1, 0x81, + 0x98, 0x30, 0x33, 0x0C, 0x0E, 0x61, 0x81, 0x98, 0x30, 0x33, 0x06, 0x06, + 0x60, 0xF0, 0xCC, 0x0F, 0xF9, 0x80, 0x7F, 0x30, 0x00, 0x06, 0x00, 0x00, + 0xC0, 0x00, 0x18, 0x00, 0x03, 0x80, 0x00, 0x30, 0x00, 0x07, 0x00, 0x00, + 0x70, 0x18, 0x0F, 0xFE, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0xF0, 0x00, 0x0F, + 0xFE, 0x00, 0x00, 0x06, 0xC0, 0x00, 0x00, 0xCC, 0x00, 0x00, 0x31, 0x80, + 0x00, 0x06, 0x30, 0x00, 0x01, 0x86, 0x00, 0x00, 0x60, 0xC0, 0x00, 0x0C, + 0x1C, 0x00, 0x03, 0x01, 0x80, 0x00, 0x40, 0x30, 0x00, 0x18, 0x06, 0x00, + 0x06, 0x00, 0xC0, 0x00, 0xC0, 0x18, 0x00, 0x30, 0x01, 0x80, 0x07, 0xFF, + 0xF0, 0x01, 0xFF, 0xFE, 0x00, 0x60, 0x00, 0xC0, 0x0C, 0x00, 0x18, 0x03, + 0x00, 0x03, 0x00, 0x40, 0x00, 0x30, 0x18, 0x00, 0x06, 0x06, 0x00, 0x00, + 0xC0, 0xC0, 0x00, 0x18, 0xFF, 0x80, 0x7F, 0xFF, 0xF0, 0x0F, 0xFC, 0x03, + 0xFF, 0xFC, 0x01, 0xFF, 0xFF, 0xC0, 0x06, 0x00, 0x38, 0x01, 0x80, 0x07, + 0x00, 0xC0, 0x00, 0xC0, 0x30, 0x00, 0x30, 0x0C, 0x00, 0x0C, 0x03, 0x00, + 0x03, 0x00, 0xC0, 0x01, 0x80, 0x60, 0x00, 0xC0, 0x18, 0x01, 0xE0, 0x07, + 0xFF, 0xE0, 0x01, 0xFF, 0xFC, 0x00, 0xE0, 0x03, 0x80, 0x30, 0x00, 0x70, + 0x0C, 0x00, 0x0E, 0x03, 0x00, 0x01, 0x80, 0xC0, 0x00, 0x60, 0x60, 0x00, + 0x18, 0x18, 0x00, 0x06, 0x06, 0x00, 0x03, 0x01, 0x80, 0x01, 0xC0, 0x60, + 0x00, 0xE0, 0x30, 0x00, 0x70, 0xFF, 0xFF, 0xF8, 0x3F, 0xFF, 0xF8, 0x00, + 0x00, 0x0F, 0xE0, 0x00, 0x3F, 0xFC, 0xC0, 0x3C, 0x0F, 0x60, 0x78, 0x01, + 0xF0, 0x70, 0x00, 0x70, 0x70, 0x00, 0x18, 0x30, 0x00, 0x0C, 0x30, 0x00, + 0x06, 0x38, 0x00, 0x02, 0x18, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x0C, 0x00, + 0x00, 0x06, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, 0x80, 0x00, 0x01, 0x80, + 0x00, 0x00, 0xC0, 0x00, 0x00, 0x60, 0x00, 0x00, 0x30, 0x00, 0x00, 0x18, + 0x00, 0x00, 0x0C, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, 0x80, 0x00, 0x60, + 0x60, 0x00, 0x60, 0x38, 0x00, 0xE0, 0x0F, 0x01, 0xE0, 0x03, 0xFF, 0xC0, + 0x00, 0x3F, 0x00, 0x00, 0x03, 0xFF, 0xF0, 0x01, 0xFF, 0xFF, 0x00, 0x0C, + 0x00, 0xF0, 0x03, 0x00, 0x1C, 0x01, 0xC0, 0x03, 0x80, 0x60, 0x00, 0x60, + 0x18, 0x00, 0x1C, 0x06, 0x00, 0x03, 0x01, 0x80, 0x00, 0xC0, 0xC0, 0x00, + 0x30, 0x30, 0x00, 0x0C, 0x0C, 0x00, 0x03, 0x03, 0x00, 0x00, 0xC0, 0xC0, + 0x00, 0x60, 0x60, 0x00, 0x18, 0x18, 0x00, 0x06, 0x06, 0x00, 0x03, 0x01, + 0x80, 0x00, 0xC0, 0xE0, 0x00, 0x70, 0x30, 0x00, 0x18, 0x0C, 0x00, 0x0C, + 0x03, 0x00, 0x06, 0x00, 0xC0, 0x07, 0x00, 0x60, 0x07, 0x80, 0xFF, 0xFF, + 0xC0, 0x3F, 0xFF, 0x80, 0x00, 0x03, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFC, + 0x01, 0x80, 0x01, 0x80, 0x30, 0x00, 0x60, 0x0C, 0x00, 0x0C, 0x01, 0x80, + 0x01, 0x80, 0x30, 0x00, 0x30, 0x06, 0x00, 0x00, 0x00, 0xC0, 0xC0, 0x00, + 0x30, 0x18, 0x00, 0x06, 0x03, 0x00, 0x00, 0xFF, 0xE0, 0x00, 0x1F, 0xF8, + 0x00, 0x07, 0x03, 0x00, 0x00, 0xC0, 0x60, 0x00, 0x18, 0x0C, 0x00, 0x03, + 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x18, 0x00, 0x0C, 0x03, 0x00, 0x01, + 0x80, 0x60, 0x00, 0x30, 0x0C, 0x00, 0x0C, 0x01, 0x80, 0x01, 0x80, 0x60, + 0x00, 0x30, 0xFF, 0xFF, 0xFE, 0x1F, 0xFF, 0xFF, 0xC0, 0x03, 0xFF, 0xFF, + 0xF0, 0x7F, 0xFF, 0xFF, 0x00, 0x60, 0x00, 0x30, 0x06, 0x00, 0x06, 0x00, + 0xC0, 0x00, 0x60, 0x0C, 0x00, 0x06, 0x00, 0xC0, 0x00, 0x60, 0x0C, 0x00, + 0x00, 0x00, 0xC0, 0xC0, 0x00, 0x18, 0x0C, 0x00, 0x01, 0x80, 0xC0, 0x00, + 0x1F, 0xFC, 0x00, 0x01, 0xFF, 0x80, 0x00, 0x38, 0x18, 0x00, 0x03, 0x01, + 0x80, 0x00, 0x30, 0x18, 0x00, 0x03, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x60, + 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xFF, 0xFC, 0x00, + 0x0F, 0xFF, 0xC0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x3F, 0xFC, 0xC0, 0x3C, + 0x0F, 0xE0, 0x78, 0x01, 0xF0, 0x70, 0x00, 0x30, 0x70, 0x00, 0x18, 0x70, + 0x00, 0x0C, 0x30, 0x00, 0x00, 0x30, 0x00, 0x00, 0x18, 0x00, 0x00, 0x18, + 0x00, 0x00, 0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, + 0x80, 0x00, 0x01, 0x80, 0x1F, 0xFE, 0xC0, 0x0F, 0xFF, 0x60, 0x00, 0x06, + 0x30, 0x00, 0x06, 0x18, 0x00, 0x03, 0x0C, 0x00, 0x01, 0x87, 0x00, 0x00, + 0xC1, 0x80, 0x00, 0xE0, 0xE0, 0x00, 0x60, 0x38, 0x00, 0x70, 0x0F, 0x00, + 0xF8, 0x03, 0xFF, 0xF0, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xFC, 0x1F, 0xE0, + 0x7F, 0x83, 0xFC, 0x03, 0x00, 0x06, 0x00, 0x60, 0x01, 0x80, 0x1C, 0x00, + 0x30, 0x03, 0x00, 0x06, 0x00, 0x60, 0x00, 0xC0, 0x0C, 0x00, 0x38, 0x01, + 0x80, 0x06, 0x00, 0x60, 0x00, 0xC0, 0x0C, 0x00, 0x18, 0x01, 0xFF, 0xFF, + 0x00, 0x3F, 0xFF, 0xC0, 0x06, 0x00, 0x18, 0x01, 0x80, 0x03, 0x00, 0x30, + 0x00, 0x60, 0x06, 0x00, 0x0C, 0x00, 0xC0, 0x03, 0x00, 0x38, 0x00, 0x60, + 0x06, 0x00, 0x0C, 0x00, 0xC0, 0x01, 0x80, 0x18, 0x00, 0x70, 0x03, 0x00, + 0x0C, 0x00, 0xE0, 0x01, 0x80, 0xFF, 0x83, 0xFE, 0x1F, 0xF0, 0x7F, 0xC0, + 0x07, 0xFF, 0xFC, 0x1F, 0xFF, 0xF0, 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, + 0x0C, 0x00, 0x00, 0x70, 0x00, 0x01, 0x80, 0x00, 0x06, 0x00, 0x00, 0x18, + 0x00, 0x00, 0x60, 0x00, 0x03, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x30, 0x00, + 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, 0x18, 0x00, 0x00, 0x60, 0x00, 0x01, + 0x80, 0x00, 0x06, 0x00, 0x00, 0x38, 0x00, 0x00, 0xC0, 0x00, 0x03, 0x00, + 0x00, 0x0C, 0x00, 0x00, 0x30, 0x00, 0xFF, 0xFF, 0x83, 0xFF, 0xFE, 0x00, + 0x00, 0x0F, 0xFF, 0xF0, 0x01, 0xFF, 0xFF, 0x00, 0x00, 0x0C, 0x00, 0x00, + 0x00, 0xC0, 0x00, 0x00, 0x18, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x18, + 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x38, 0x00, 0x00, 0x03, 0x00, 0x00, + 0x00, 0x30, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x07, + 0x00, 0x20, 0x00, 0x60, 0x06, 0x00, 0x06, 0x00, 0x60, 0x00, 0x60, 0x06, + 0x00, 0x06, 0x00, 0x60, 0x00, 0xC0, 0x0C, 0x00, 0x0C, 0x00, 0xC0, 0x00, + 0xC0, 0x0C, 0x00, 0x18, 0x00, 0xE0, 0x03, 0x00, 0x07, 0x00, 0x70, 0x00, + 0x3C, 0x1C, 0x00, 0x01, 0xFF, 0x80, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x03, + 0xFF, 0x07, 0xF8, 0x3F, 0xF8, 0x3F, 0xC0, 0x18, 0x00, 0x70, 0x00, 0xC0, + 0x07, 0x00, 0x0C, 0x00, 0x60, 0x00, 0x60, 0x0E, 0x00, 0x03, 0x00, 0xE0, + 0x00, 0x18, 0x0C, 0x00, 0x00, 0xC1, 0xC0, 0x00, 0x0C, 0x1C, 0x00, 0x00, + 0x61, 0x80, 0x00, 0x03, 0x3C, 0x00, 0x00, 0x1B, 0x78, 0x00, 0x01, 0xF0, + 0xE0, 0x00, 0x0F, 0x03, 0x80, 0x00, 0x60, 0x0C, 0x00, 0x03, 0x00, 0x70, + 0x00, 0x18, 0x01, 0x80, 0x01, 0x80, 0x0C, 0x00, 0x0C, 0x00, 0x60, 0x00, + 0x60, 0x01, 0x80, 0x03, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x60, 0x01, 0x80, + 0x03, 0x00, 0xFF, 0xE0, 0x1F, 0x87, 0xFF, 0x00, 0x7C, 0x00, 0x07, 0xFF, + 0xE0, 0x03, 0xFF, 0xF0, 0x00, 0x06, 0x00, 0x00, 0x03, 0x00, 0x00, 0x03, + 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x60, 0x00, 0x00, + 0x70, 0x00, 0x00, 0x30, 0x00, 0x00, 0x18, 0x00, 0x00, 0x0C, 0x00, 0x00, + 0x06, 0x00, 0x00, 0x06, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, 0x80, 0x00, + 0x00, 0xC0, 0x03, 0x00, 0x60, 0x01, 0x80, 0x60, 0x00, 0xC0, 0x30, 0x00, + 0x60, 0x18, 0x00, 0x30, 0x0C, 0x00, 0x30, 0x0E, 0x00, 0x18, 0x06, 0x00, + 0x0C, 0xFF, 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, 0x00, 0x07, 0xF0, 0x00, 0x3F, + 0x07, 0xF0, 0x00, 0x7F, 0x01, 0xB0, 0x00, 0xD8, 0x01, 0xB0, 0x00, 0xD8, + 0x01, 0x98, 0x01, 0x98, 0x01, 0x98, 0x03, 0x30, 0x01, 0x98, 0x03, 0x30, + 0x03, 0x18, 0x06, 0x30, 0x03, 0x1C, 0x0C, 0x30, 0x03, 0x0C, 0x0C, 0x30, + 0x03, 0x0C, 0x18, 0x60, 0x07, 0x0C, 0x30, 0x60, 0x06, 0x0C, 0x30, 0x60, + 0x06, 0x06, 0x60, 0x60, 0x06, 0x06, 0xC0, 0x60, 0x06, 0x06, 0xC0, 0xC0, + 0x0C, 0x07, 0x80, 0xC0, 0x0C, 0x03, 0x00, 0xC0, 0x0C, 0x00, 0x00, 0xC0, + 0x0C, 0x00, 0x01, 0xC0, 0x0C, 0x00, 0x01, 0x80, 0x18, 0x00, 0x01, 0x80, + 0x18, 0x00, 0x01, 0x80, 0x18, 0x00, 0x01, 0x80, 0xFF, 0x80, 0x3F, 0xE0, + 0xFF, 0x80, 0x3F, 0xE0, 0x07, 0xE0, 0x0F, 0xFC, 0x3F, 0x80, 0x3F, 0xF0, + 0x0F, 0x00, 0x06, 0x00, 0x3C, 0x00, 0x10, 0x01, 0x98, 0x00, 0xC0, 0x06, + 0x60, 0x03, 0x00, 0x19, 0xC0, 0x0C, 0x00, 0x63, 0x00, 0x30, 0x01, 0x0C, + 0x01, 0x80, 0x0C, 0x18, 0x06, 0x00, 0x30, 0x60, 0x18, 0x00, 0xC1, 0xC0, + 0x60, 0x03, 0x03, 0x01, 0x00, 0x08, 0x0C, 0x0C, 0x00, 0x60, 0x18, 0x30, + 0x01, 0x80, 0x60, 0xC0, 0x06, 0x01, 0xC3, 0x00, 0x18, 0x03, 0x18, 0x00, + 0xC0, 0x0C, 0x60, 0x03, 0x00, 0x19, 0x80, 0x0C, 0x00, 0x66, 0x00, 0x30, + 0x01, 0xD8, 0x00, 0x80, 0x03, 0xC0, 0x06, 0x00, 0x0F, 0x00, 0xFF, 0xC0, + 0x1C, 0x03, 0xFE, 0x00, 0x70, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x7F, 0xF0, + 0x00, 0xF0, 0x78, 0x03, 0x80, 0x1C, 0x07, 0x00, 0x0E, 0x0E, 0x00, 0x06, + 0x0C, 0x00, 0x06, 0x18, 0x00, 0x07, 0x38, 0x00, 0x03, 0x30, 0x00, 0x03, + 0x60, 0x00, 0x03, 0x60, 0x00, 0x03, 0x60, 0x00, 0x03, 0xC0, 0x00, 0x03, + 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x06, 0xC0, 0x00, 0x06, 0xC0, 0x00, 0x06, + 0xC0, 0x00, 0x0C, 0xC0, 0x00, 0x1C, 0xC0, 0x00, 0x18, 0x60, 0x00, 0x30, + 0x60, 0x00, 0x70, 0x70, 0x00, 0xE0, 0x38, 0x01, 0xC0, 0x1E, 0x0F, 0x00, + 0x0F, 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xFF, 0xFC, 0x01, 0xFF, 0xFF, + 0xC0, 0x06, 0x00, 0x78, 0x01, 0x80, 0x06, 0x00, 0xC0, 0x01, 0xC0, 0x30, + 0x00, 0x30, 0x0C, 0x00, 0x0C, 0x03, 0x00, 0x03, 0x00, 0xC0, 0x01, 0xC0, + 0x60, 0x00, 0x60, 0x18, 0x00, 0x30, 0x06, 0x00, 0x18, 0x01, 0x80, 0x3C, + 0x00, 0xFF, 0xFE, 0x00, 0x3F, 0xFC, 0x00, 0x0C, 0x00, 0x00, 0x03, 0x00, + 0x00, 0x00, 0xC0, 0x00, 0x00, 0x60, 0x00, 0x00, 0x18, 0x00, 0x00, 0x06, + 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x60, 0x00, 0x00, 0x30, 0x00, 0x00, + 0xFF, 0xFC, 0x00, 0x3F, 0xFF, 0x00, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x7F, + 0xF0, 0x00, 0xF0, 0x78, 0x03, 0x80, 0x1C, 0x07, 0x00, 0x0E, 0x0E, 0x00, + 0x06, 0x0C, 0x00, 0x06, 0x18, 0x00, 0x03, 0x38, 0x00, 0x03, 0x30, 0x00, + 0x03, 0x60, 0x00, 0x03, 0x60, 0x00, 0x03, 0x60, 0x00, 0x03, 0xC0, 0x00, + 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x06, 0xC0, 0x00, 0x06, 0xC0, 0x00, + 0x06, 0xC0, 0x00, 0x0C, 0xC0, 0x00, 0x1C, 0xC0, 0x00, 0x18, 0x60, 0x00, + 0x30, 0x60, 0x00, 0x70, 0x30, 0x00, 0xE0, 0x38, 0x01, 0xC0, 0x0E, 0x0F, + 0x00, 0x07, 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0x1F, 0xF8, + 0x30, 0x3F, 0xFF, 0xF0, 0x78, 0x0F, 0x80, 0x07, 0xFF, 0xFC, 0x01, 0xFF, + 0xFF, 0xC0, 0x06, 0x00, 0x78, 0x01, 0x80, 0x0E, 0x00, 0xC0, 0x01, 0xC0, + 0x30, 0x00, 0x30, 0x0C, 0x00, 0x0C, 0x03, 0x00, 0x03, 0x00, 0xC0, 0x00, + 0xC0, 0x60, 0x00, 0x60, 0x18, 0x00, 0x30, 0x06, 0x00, 0x38, 0x01, 0x80, + 0x3C, 0x00, 0xFF, 0xFC, 0x00, 0x3F, 0xFC, 0x00, 0x0C, 0x07, 0x80, 0x03, + 0x00, 0x70, 0x00, 0xC0, 0x0E, 0x00, 0x60, 0x01, 0x80, 0x18, 0x00, 0x70, + 0x06, 0x00, 0x0C, 0x01, 0x80, 0x03, 0x80, 0x60, 0x00, 0x60, 0x30, 0x00, + 0x1C, 0xFF, 0xE0, 0x07, 0xFF, 0xF8, 0x00, 0xF0, 0x00, 0x1F, 0xC0, 0x00, + 0x7F, 0xF3, 0x00, 0xE0, 0x3B, 0x03, 0x80, 0x0F, 0x07, 0x00, 0x0E, 0x06, + 0x00, 0x06, 0x0C, 0x00, 0x06, 0x0C, 0x00, 0x06, 0x0C, 0x00, 0x00, 0x0C, + 0x00, 0x00, 0x0E, 0x00, 0x00, 0x07, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, + 0x7F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x70, 0x00, 0x00, 0x38, 0x00, + 0x00, 0x18, 0x00, 0x00, 0x18, 0x20, 0x00, 0x18, 0x60, 0x00, 0x18, 0x60, + 0x00, 0x30, 0x60, 0x00, 0x70, 0xF0, 0x00, 0xE0, 0xF8, 0x01, 0xC0, 0xDC, + 0x07, 0x80, 0x8F, 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0xFF, 0xFE, 0x3F, + 0xFF, 0xFE, 0x30, 0x18, 0x06, 0x60, 0x18, 0x06, 0x60, 0x18, 0x06, 0x60, + 0x38, 0x0C, 0x60, 0x30, 0x04, 0x00, 0x30, 0x00, 0x00, 0x30, 0x00, 0x00, + 0x30, 0x00, 0x00, 0x70, 0x00, 0x00, 0x60, 0x00, 0x00, 0x60, 0x00, 0x00, + 0x60, 0x00, 0x00, 0x60, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, + 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x01, 0x80, 0x00, 0x01, + 0x80, 0x00, 0x01, 0x80, 0x00, 0x01, 0x80, 0x00, 0xFF, 0xFE, 0x00, 0xFF, + 0xFC, 0x00, 0x7F, 0xC0, 0xFF, 0xDF, 0xF0, 0x3F, 0xF1, 0x80, 0x00, 0x60, + 0x60, 0x00, 0x30, 0x18, 0x00, 0x0C, 0x06, 0x00, 0x03, 0x03, 0x80, 0x00, + 0xC0, 0xC0, 0x00, 0x30, 0x30, 0x00, 0x18, 0x0C, 0x00, 0x06, 0x03, 0x00, + 0x01, 0x81, 0xC0, 0x00, 0x60, 0x60, 0x00, 0x18, 0x18, 0x00, 0x0C, 0x06, + 0x00, 0x03, 0x01, 0x80, 0x00, 0xC0, 0xC0, 0x00, 0x30, 0x30, 0x00, 0x1C, + 0x0C, 0x00, 0x06, 0x03, 0x00, 0x01, 0x80, 0xC0, 0x00, 0xC0, 0x30, 0x00, + 0x70, 0x0E, 0x00, 0x38, 0x01, 0xC0, 0x1C, 0x00, 0x38, 0x1E, 0x00, 0x07, + 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFF, 0x80, 0x3F, 0xFF, 0xF0, 0x07, + 0xFC, 0xE0, 0x00, 0x0C, 0x0C, 0x00, 0x03, 0x01, 0x80, 0x00, 0x60, 0x30, + 0x00, 0x18, 0x06, 0x00, 0x02, 0x00, 0xC0, 0x00, 0xC0, 0x0C, 0x00, 0x30, + 0x01, 0x80, 0x06, 0x00, 0x30, 0x01, 0x80, 0x06, 0x00, 0x60, 0x00, 0xC0, + 0x0C, 0x00, 0x18, 0x03, 0x00, 0x01, 0x80, 0xC0, 0x00, 0x30, 0x18, 0x00, + 0x06, 0x06, 0x00, 0x00, 0xC0, 0xC0, 0x00, 0x18, 0x30, 0x00, 0x03, 0x8C, + 0x00, 0x00, 0x31, 0x80, 0x00, 0x06, 0x60, 0x00, 0x00, 0xD8, 0x00, 0x00, + 0x1B, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x38, 0x00, 0x00, 0xFF, 0xC0, + 0x7F, 0xFF, 0xF8, 0x0F, 0xF8, 0xC0, 0x00, 0x0C, 0x18, 0x00, 0x01, 0x83, + 0x00, 0x00, 0x30, 0x60, 0x08, 0x0C, 0x0C, 0x07, 0x01, 0x81, 0x81, 0xE0, + 0x30, 0x60, 0x2C, 0x0C, 0x0C, 0x0D, 0x81, 0x81, 0x81, 0x30, 0x30, 0x30, + 0x66, 0x0C, 0x06, 0x08, 0xC1, 0x80, 0xC3, 0x0C, 0x30, 0x18, 0x41, 0x8C, + 0x03, 0x18, 0x31, 0x80, 0x62, 0x06, 0x30, 0x0C, 0xC0, 0xCC, 0x03, 0x10, + 0x19, 0x80, 0x66, 0x03, 0x30, 0x0C, 0x80, 0x6C, 0x01, 0xB0, 0x0D, 0x80, + 0x34, 0x01, 0xB0, 0x07, 0x80, 0x3C, 0x00, 0xE0, 0x07, 0x80, 0x1C, 0x00, + 0xF0, 0x00, 0x03, 0xF8, 0x03, 0xF8, 0x1F, 0xC0, 0x3F, 0xC0, 0x30, 0x00, + 0x30, 0x01, 0xC0, 0x03, 0x00, 0x06, 0x00, 0x30, 0x00, 0x18, 0x03, 0x00, + 0x00, 0xE0, 0x30, 0x00, 0x03, 0x03, 0x00, 0x00, 0x1C, 0x30, 0x00, 0x00, + 0x63, 0x00, 0x00, 0x03, 0xB0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x30, + 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x36, 0x00, 0x00, 0x03, 0x38, 0x00, + 0x00, 0x30, 0xC0, 0x00, 0x03, 0x07, 0x00, 0x00, 0x30, 0x18, 0x00, 0x03, + 0x00, 0x60, 0x00, 0x30, 0x03, 0x80, 0x03, 0x00, 0x0C, 0x00, 0x30, 0x00, + 0x70, 0x03, 0x00, 0x01, 0x80, 0xFF, 0x80, 0xFF, 0x07, 0xFC, 0x07, 0xF8, + 0x00, 0x7F, 0x80, 0x7F, 0x7F, 0x00, 0x7F, 0x1C, 0x00, 0x18, 0x0C, 0x00, + 0x30, 0x0C, 0x00, 0x70, 0x06, 0x00, 0xE0, 0x06, 0x00, 0xC0, 0x03, 0x01, + 0x80, 0x03, 0x03, 0x00, 0x01, 0x86, 0x00, 0x01, 0x8C, 0x00, 0x00, 0xD8, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x60, 0x00, 0x00, 0xC0, + 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, + 0x00, 0x01, 0x80, 0x00, 0x01, 0x80, 0x00, 0x01, 0x80, 0x00, 0x01, 0x80, + 0x00, 0xFF, 0xFE, 0x00, 0xFF, 0xFC, 0x00, 0x03, 0xFF, 0xFE, 0x07, 0xFF, + 0xF8, 0x0C, 0x00, 0x30, 0x10, 0x00, 0xC0, 0x60, 0x03, 0x80, 0xC0, 0x0E, + 0x01, 0x80, 0x38, 0x03, 0x00, 0xE0, 0x00, 0x03, 0x80, 0x00, 0x0E, 0x00, + 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x01, 0x80, 0x00, 0x06, 0x00, 0x00, + 0x18, 0x00, 0x00, 0x60, 0x00, 0x01, 0x80, 0x00, 0x06, 0x00, 0x60, 0x18, + 0x00, 0xC0, 0x60, 0x01, 0x81, 0x80, 0x02, 0x06, 0x00, 0x0C, 0x18, 0x00, + 0x18, 0x60, 0x00, 0x30, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0x80, 0x01, 0xFE, + 0x03, 0xFC, 0x06, 0x00, 0x08, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x01, + 0x80, 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0x40, 0x01, 0x80, + 0x03, 0x00, 0x06, 0x00, 0x0C, 0x00, 0x10, 0x00, 0x60, 0x00, 0xC0, 0x01, + 0x80, 0x03, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, 0x00, 0x80, + 0x03, 0x00, 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x20, 0x00, 0xFF, 0x01, + 0xFE, 0x00, 0xC0, 0x30, 0x0E, 0x01, 0x80, 0x60, 0x18, 0x07, 0x00, 0xC0, + 0x30, 0x0C, 0x03, 0x80, 0x60, 0x18, 0x06, 0x00, 0xC0, 0x30, 0x0C, 0x03, + 0x00, 0x60, 0x18, 0x06, 0x01, 0x80, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x18, + 0x06, 0x01, 0x80, 0x60, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x04, 0x01, 0xFE, + 0x03, 0xFC, 0x00, 0x10, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, + 0x04, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x03, 0x00, 0x06, + 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, + 0x06, 0x00, 0x08, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x06, + 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, 0x01, 0x80, 0xFF, 0x01, + 0xFE, 0x00, 0x00, 0x10, 0x00, 0x0C, 0x00, 0x07, 0x80, 0x03, 0x60, 0x01, + 0x8C, 0x00, 0xC3, 0x80, 0xE0, 0x60, 0x70, 0x1C, 0x38, 0x03, 0x1C, 0x00, + 0x6E, 0x00, 0x1F, 0x00, 0x02, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xC3, 0x86, 0x0C, 0x18, 0x70, 0xC0, 0x00, 0x3F, 0x80, 0x0F, 0xFF, 0x80, + 0x78, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x18, 0x00, 0x00, 0x60, 0x00, + 0x01, 0x80, 0x00, 0x06, 0x00, 0x00, 0x38, 0x03, 0xFC, 0xC0, 0x7F, 0xFF, + 0x07, 0xC0, 0x0C, 0x38, 0x00, 0x31, 0xC0, 0x01, 0xCE, 0x00, 0x06, 0x30, + 0x00, 0x18, 0xC0, 0x00, 0xE3, 0x00, 0x07, 0x8E, 0x00, 0x7C, 0x1C, 0x0F, + 0x3F, 0x3F, 0xF0, 0xFC, 0x7F, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x30, 0x00, 0x00, 0x06, 0x00, 0x00, + 0x00, 0xC0, 0x00, 0x00, 0x10, 0x00, 0x00, 0x06, 0x07, 0xE0, 0x00, 0xC3, + 0xFF, 0x00, 0x19, 0xC0, 0xF0, 0x03, 0x60, 0x07, 0x00, 0xD8, 0x00, 0x60, + 0x1E, 0x00, 0x0E, 0x03, 0x80, 0x00, 0xC0, 0x60, 0x00, 0x18, 0x0C, 0x00, + 0x03, 0x03, 0x00, 0x00, 0x60, 0x60, 0x00, 0x0C, 0x0C, 0x00, 0x01, 0x81, + 0x80, 0x00, 0x60, 0x70, 0x00, 0x0C, 0x0E, 0x00, 0x03, 0x01, 0xC0, 0x00, + 0x60, 0x3C, 0x00, 0x18, 0x05, 0x80, 0x06, 0x01, 0xB8, 0x01, 0x83, 0xF3, + 0xC1, 0xE0, 0x7E, 0x3F, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x3F, 0x00, + 0x07, 0xFF, 0x30, 0x38, 0x0F, 0xC1, 0x80, 0x1F, 0x0C, 0x00, 0x18, 0x60, + 0x00, 0x63, 0x00, 0x01, 0x9C, 0x00, 0x06, 0x60, 0x00, 0x01, 0x80, 0x00, + 0x0C, 0x00, 0x00, 0x30, 0x00, 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, 0x0C, + 0x00, 0x00, 0x30, 0x00, 0x00, 0xE0, 0x00, 0x01, 0x80, 0x00, 0xC7, 0x00, + 0x0E, 0x0F, 0x01, 0xF0, 0x1F, 0xFF, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x00, + 0x1F, 0x80, 0x00, 0x0F, 0x80, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x60, 0x00, + 0x00, 0x30, 0x00, 0x00, 0x10, 0x00, 0x00, 0x18, 0x00, 0xFC, 0x0C, 0x01, + 0xFF, 0x86, 0x01, 0xC0, 0xE3, 0x03, 0x80, 0x1B, 0x03, 0x80, 0x05, 0x81, + 0x80, 0x03, 0xC1, 0x80, 0x00, 0xE1, 0x80, 0x00, 0x60, 0xC0, 0x00, 0x30, + 0x60, 0x00, 0x18, 0x60, 0x00, 0x0C, 0x30, 0x00, 0x06, 0x18, 0x00, 0x02, + 0x0C, 0x00, 0x03, 0x06, 0x00, 0x01, 0x83, 0x00, 0x01, 0xC1, 0xC0, 0x01, + 0xE0, 0x60, 0x01, 0xE0, 0x38, 0x01, 0xB0, 0x0F, 0x03, 0x9F, 0x03, 0xFF, + 0x0F, 0x80, 0x7E, 0x00, 0x00, 0x00, 0x3F, 0x00, 0x07, 0xFF, 0x80, 0x78, + 0x0F, 0x03, 0x80, 0x0E, 0x1C, 0x00, 0x18, 0xE0, 0x00, 0x73, 0x00, 0x00, + 0xD8, 0x00, 0x03, 0x60, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, + 0x00, 0x00, 0xC0, 0x00, 0x03, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x38, 0x00, + 0x00, 0x60, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x03, 0x07, 0x80, 0xF8, + 0x0F, 0xFF, 0x80, 0x0F, 0xF0, 0x00, 0x00, 0x00, 0xFF, 0x80, 0x00, 0xFF, + 0xF0, 0x00, 0xF0, 0x00, 0x00, 0x70, 0x00, 0x00, 0x18, 0x00, 0x00, 0x06, + 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0xC0, 0x00, 0x07, 0xFF, 0xFC, 0x03, + 0xFF, 0xFF, 0x00, 0x03, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x60, 0x00, + 0x00, 0x18, 0x00, 0x00, 0x06, 0x00, 0x00, 0x03, 0x80, 0x00, 0x00, 0xC0, + 0x00, 0x00, 0x30, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, + 0x80, 0x00, 0x00, 0x60, 0x00, 0x00, 0x18, 0x00, 0x00, 0x06, 0x00, 0x00, + 0x01, 0x80, 0x00, 0x00, 0xC0, 0x00, 0x0F, 0xFF, 0xFC, 0x03, 0xFF, 0xFE, + 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFF, 0x87, 0xC1, 0xE0, 0xF3, 0xE1, 0xC0, + 0x1B, 0x01, 0xC0, 0x07, 0x81, 0xC0, 0x03, 0xC0, 0xC0, 0x00, 0xE0, 0xC0, + 0x00, 0x60, 0x60, 0x00, 0x30, 0x60, 0x00, 0x18, 0x30, 0x00, 0x0C, 0x18, + 0x00, 0x06, 0x0C, 0x00, 0x06, 0x06, 0x00, 0x03, 0x03, 0x00, 0x03, 0x81, + 0xC0, 0x01, 0xC0, 0x60, 0x01, 0xC0, 0x38, 0x03, 0x60, 0x0F, 0x07, 0x30, + 0x03, 0xFF, 0x18, 0x00, 0x7E, 0x0C, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x06, + 0x00, 0x00, 0x03, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, 0x80, 0x00, 0x01, + 0x80, 0x00, 0x03, 0x80, 0x03, 0xFF, 0x80, 0x01, 0xFF, 0x00, 0x00, 0x07, + 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, + 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x01, 0x80, 0x00, 0x01, 0x83, 0xF0, 0x01, + 0x8F, 0xF8, 0x01, 0x98, 0x1C, 0x03, 0xB0, 0x0E, 0x03, 0x40, 0x06, 0x03, + 0x80, 0x06, 0x03, 0x00, 0x06, 0x03, 0x00, 0x06, 0x07, 0x00, 0x06, 0x06, + 0x00, 0x0E, 0x06, 0x00, 0x0E, 0x06, 0x00, 0x0E, 0x06, 0x00, 0x0C, 0x0C, + 0x00, 0x0C, 0x0C, 0x00, 0x1C, 0x0C, 0x00, 0x1C, 0x0C, 0x00, 0x18, 0x0C, + 0x00, 0x18, 0x18, 0x00, 0x18, 0xFF, 0x01, 0xFF, 0xFF, 0x01, 0xFF, 0x00, + 0x07, 0x00, 0x00, 0xC0, 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0x80, 0x1F, + 0xF0, 0x00, 0x06, 0x00, 0x01, 0xC0, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, + 0xC0, 0x00, 0x18, 0x00, 0x07, 0x00, 0x00, 0xC0, 0x00, 0x18, 0x00, 0x03, + 0x00, 0x00, 0x60, 0x00, 0x1C, 0x00, 0x03, 0x00, 0x00, 0x60, 0x00, 0x0C, + 0x00, 0x01, 0x80, 0x7F, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x00, 0x70, 0x00, + 0x07, 0x00, 0x00, 0x70, 0x00, 0x06, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xFF, 0x03, 0xFF, 0xF0, + 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, 0x60, 0x00, 0x06, + 0x00, 0x00, 0x60, 0x00, 0x06, 0x00, 0x00, 0xC0, 0x00, 0x0C, 0x00, 0x00, + 0xC0, 0x00, 0x0C, 0x00, 0x01, 0xC0, 0x00, 0x18, 0x00, 0x01, 0x80, 0x00, + 0x18, 0x00, 0x01, 0x80, 0x00, 0x38, 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, + 0x03, 0x00, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, + 0x03, 0x80, 0xFF, 0xF0, 0x0F, 0xFC, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0x60, 0x00, 0x00, 0x60, 0x00, 0x00, 0x60, 0x00, 0x00, 0x60, + 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0xFF, 0x00, 0xC1, + 0xFF, 0x00, 0x80, 0x70, 0x01, 0x80, 0xC0, 0x01, 0x83, 0x80, 0x01, 0x87, + 0x00, 0x01, 0x8C, 0x00, 0x03, 0x38, 0x00, 0x03, 0x70, 0x00, 0x03, 0xF8, + 0x00, 0x03, 0x9C, 0x00, 0x03, 0x0C, 0x00, 0x06, 0x0E, 0x00, 0x06, 0x07, + 0x00, 0x06, 0x03, 0x80, 0x06, 0x01, 0x80, 0x04, 0x00, 0xC0, 0x0C, 0x00, + 0xE0, 0xFC, 0x03, 0xFE, 0xFC, 0x03, 0xFC, 0x01, 0xFF, 0x00, 0x3F, 0xE0, + 0x00, 0x0C, 0x00, 0x03, 0x00, 0x00, 0x60, 0x00, 0x0C, 0x00, 0x01, 0x80, + 0x00, 0x70, 0x00, 0x0C, 0x00, 0x01, 0x80, 0x00, 0x30, 0x00, 0x06, 0x00, + 0x01, 0x80, 0x00, 0x30, 0x00, 0x06, 0x00, 0x00, 0xC0, 0x00, 0x18, 0x00, + 0x06, 0x00, 0x00, 0xC0, 0x00, 0x18, 0x00, 0x03, 0x00, 0x00, 0xE0, 0x00, + 0x18, 0x00, 0x03, 0x00, 0x00, 0x60, 0x00, 0x0C, 0x03, 0xFF, 0xFF, 0xFF, + 0xFF, 0xF0, 0x00, 0x1E, 0x07, 0x81, 0xE7, 0xE1, 0xF8, 0x3D, 0x8E, 0xE3, + 0x81, 0xE0, 0xF8, 0x30, 0x38, 0x1E, 0x06, 0x06, 0x03, 0x80, 0xC1, 0x80, + 0x60, 0x18, 0x30, 0x0C, 0x03, 0x06, 0x01, 0x80, 0x60, 0xC0, 0x30, 0x08, + 0x18, 0x0C, 0x03, 0x06, 0x01, 0x80, 0x60, 0xC0, 0x30, 0x0C, 0x18, 0x06, + 0x01, 0x83, 0x00, 0x80, 0x60, 0x40, 0x30, 0x0C, 0x18, 0x06, 0x01, 0x83, + 0x00, 0xC0, 0x30, 0x60, 0x18, 0x06, 0x7F, 0x03, 0xC1, 0xFF, 0xE0, 0xF8, + 0x3E, 0x00, 0x03, 0xE0, 0x1F, 0x1F, 0xF0, 0x3E, 0x60, 0x70, 0x0F, 0x80, + 0x70, 0x3C, 0x00, 0x60, 0x70, 0x00, 0xC0, 0xC0, 0x01, 0x81, 0x80, 0x03, + 0x07, 0x00, 0x06, 0x0C, 0x00, 0x1C, 0x18, 0x00, 0x30, 0x30, 0x00, 0x60, + 0x60, 0x00, 0xC1, 0xC0, 0x01, 0x83, 0x00, 0x06, 0x06, 0x00, 0x0C, 0x0C, + 0x00, 0x18, 0x18, 0x00, 0x30, 0x70, 0x00, 0x67, 0xFC, 0x07, 0xFF, 0xF0, + 0x0F, 0xE0, 0x00, 0x3F, 0x00, 0x07, 0xFF, 0x00, 0x3C, 0x0F, 0x01, 0xC0, + 0x1C, 0x0C, 0x00, 0x38, 0x60, 0x00, 0x63, 0x00, 0x00, 0xDC, 0x00, 0x03, + 0x60, 0x00, 0x0D, 0x80, 0x00, 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, + 0x00, 0x1B, 0x00, 0x00, 0x6C, 0x00, 0x03, 0xB0, 0x00, 0x0C, 0x60, 0x00, + 0x61, 0xC0, 0x03, 0x03, 0x80, 0x38, 0x0F, 0x03, 0xC0, 0x0F, 0xFE, 0x00, + 0x0F, 0xC0, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x1F, 0x8F, 0xFE, 0x00, 0xFC, + 0xE0, 0x78, 0x00, 0xCC, 0x00, 0xE0, 0x06, 0xC0, 0x03, 0x00, 0x3C, 0x00, + 0x1C, 0x01, 0xC0, 0x00, 0x60, 0x0C, 0x00, 0x03, 0x00, 0xE0, 0x00, 0x18, + 0x06, 0x00, 0x00, 0xC0, 0x30, 0x00, 0x06, 0x01, 0x80, 0x00, 0x30, 0x0C, + 0x00, 0x03, 0x00, 0xE0, 0x00, 0x18, 0x07, 0x00, 0x01, 0x80, 0x3C, 0x00, + 0x1C, 0x01, 0xE0, 0x01, 0xC0, 0x0D, 0x80, 0x1C, 0x00, 0xCF, 0x03, 0xC0, + 0x06, 0x3F, 0xF8, 0x00, 0x30, 0x7F, 0x00, 0x01, 0x80, 0x00, 0x00, 0x0C, + 0x00, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x30, 0x00, + 0x00, 0x01, 0x80, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x07, 0xFF, 0x00, 0x00, + 0x7F, 0xF8, 0x00, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7F, 0xE1, 0xF0, 0x78, + 0x1C, 0xFC, 0x38, 0x01, 0xB0, 0x1C, 0x00, 0x2C, 0x0E, 0x00, 0x0F, 0x03, + 0x00, 0x01, 0xC1, 0x80, 0x00, 0x60, 0x60, 0x00, 0x18, 0x30, 0x00, 0x06, + 0x0C, 0x00, 0x01, 0x83, 0x00, 0x00, 0x60, 0xC0, 0x00, 0x30, 0x30, 0x00, + 0x0C, 0x0C, 0x00, 0x07, 0x03, 0x80, 0x03, 0xC0, 0x60, 0x01, 0xB0, 0x1C, + 0x00, 0xD8, 0x03, 0xC0, 0xE6, 0x00, 0x7F, 0xF1, 0x80, 0x07, 0xE0, 0x60, + 0x00, 0x00, 0x18, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, + 0xC0, 0x00, 0x00, 0x30, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x06, 0x00, 0x00, + 0x7F, 0xF8, 0x00, 0x1F, 0xFE, 0x00, 0x07, 0xF0, 0x3E, 0x03, 0xF8, 0x7F, + 0xC0, 0x18, 0xF0, 0x60, 0x0C, 0xE0, 0x00, 0x07, 0xE0, 0x00, 0x03, 0xC0, + 0x00, 0x03, 0xC0, 0x00, 0x01, 0x80, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x60, + 0x00, 0x00, 0x30, 0x00, 0x00, 0x38, 0x00, 0x00, 0x18, 0x00, 0x00, 0x0C, + 0x00, 0x00, 0x06, 0x00, 0x00, 0x03, 0x00, 0x00, 0x03, 0x80, 0x00, 0x01, + 0x80, 0x00, 0x3F, 0xFF, 0xF0, 0x1F, 0xFF, 0xF0, 0x00, 0x00, 0x3F, 0x00, + 0x0F, 0xFE, 0xC0, 0xF0, 0x3E, 0x0E, 0x00, 0x70, 0xE0, 0x01, 0x06, 0x00, + 0x08, 0x30, 0x00, 0x41, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x3F, 0xF0, 0x00, + 0x3F, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x18, 0x00, 0x00, + 0xCC, 0x00, 0x06, 0x60, 0x00, 0x33, 0x00, 0x03, 0x3C, 0x00, 0x71, 0xF8, + 0x0F, 0x0D, 0xFF, 0xF0, 0x01, 0xFC, 0x00, 0x03, 0x00, 0x03, 0x00, 0x01, + 0x80, 0x00, 0xC0, 0x00, 0x60, 0x00, 0x70, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, + 0x0C, 0x00, 0x06, 0x00, 0x06, 0x00, 0x03, 0x00, 0x01, 0x80, 0x00, 0xC0, + 0x00, 0xE0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x18, 0x00, 0x0C, 0x00, 0x0E, + 0x00, 0x06, 0x00, 0x03, 0x00, 0x01, 0x80, 0x00, 0xC0, 0x03, 0x38, 0x0F, + 0x9F, 0xFF, 0x03, 0xF8, 0x00, 0xFC, 0x03, 0xFF, 0xE0, 0x1F, 0xC6, 0x00, + 0x0C, 0x30, 0x00, 0x61, 0x80, 0x03, 0x0C, 0x00, 0x18, 0x60, 0x01, 0x86, + 0x00, 0x0C, 0x30, 0x00, 0x61, 0x80, 0x03, 0x0C, 0x00, 0x18, 0x60, 0x01, + 0x86, 0x00, 0x0C, 0x30, 0x00, 0x61, 0x80, 0x03, 0x0C, 0x00, 0x38, 0x60, + 0x07, 0x83, 0x80, 0x6C, 0x1E, 0x1E, 0x7C, 0x7F, 0xE3, 0xE0, 0xF8, 0x00, + 0x00, 0x7F, 0xC0, 0xFF, 0xFF, 0xF0, 0x3F, 0xF1, 0xC0, 0x00, 0xC0, 0x30, + 0x00, 0x60, 0x0C, 0x00, 0x18, 0x03, 0x00, 0x0C, 0x00, 0xE0, 0x06, 0x00, + 0x18, 0x01, 0x80, 0x06, 0x00, 0xC0, 0x01, 0x80, 0x30, 0x00, 0x60, 0x18, + 0x00, 0x0C, 0x0C, 0x00, 0x03, 0x03, 0x00, 0x00, 0xC1, 0x80, 0x00, 0x30, + 0xC0, 0x00, 0x06, 0x30, 0x00, 0x01, 0x98, 0x00, 0x00, 0x6C, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x07, 0x80, 0x00, 0xFE, 0x00, 0x7F, 0xFF, 0x00, 0x3F, + 0xCC, 0x00, 0x03, 0x06, 0x00, 0x01, 0x83, 0x00, 0x01, 0x81, 0x81, 0x80, + 0xC0, 0xC1, 0xE0, 0x60, 0x60, 0xF0, 0x60, 0x30, 0xD8, 0x30, 0x18, 0x6C, + 0x30, 0x0C, 0x66, 0x18, 0x06, 0x33, 0x18, 0x03, 0x31, 0x8C, 0x01, 0x98, + 0x66, 0x00, 0xD8, 0x36, 0x00, 0x6C, 0x1B, 0x00, 0x3C, 0x0F, 0x00, 0x1E, + 0x07, 0x80, 0x0E, 0x03, 0x80, 0x07, 0x01, 0xC0, 0x00, 0x07, 0xF0, 0x3F, + 0xC3, 0xFC, 0x0F, 0xF0, 0x38, 0x00, 0x60, 0x07, 0x00, 0x70, 0x00, 0xE0, + 0x38, 0x00, 0x18, 0x1C, 0x00, 0x03, 0x0C, 0x00, 0x00, 0xEE, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x03, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xDC, 0x00, + 0x00, 0xE3, 0x80, 0x00, 0x70, 0x70, 0x00, 0x38, 0x0E, 0x00, 0x18, 0x01, + 0x80, 0x1C, 0x00, 0x30, 0x0E, 0x00, 0x0E, 0x0F, 0xF0, 0x3F, 0xE3, 0xFC, + 0x0F, 0xF8, 0x03, 0xF8, 0x07, 0xF8, 0x3F, 0xC0, 0x3F, 0xC0, 0x60, 0x00, + 0x30, 0x01, 0x80, 0x01, 0x80, 0x0C, 0x00, 0x18, 0x00, 0x60, 0x01, 0x80, + 0x03, 0x80, 0x0C, 0x00, 0x0C, 0x00, 0xC0, 0x00, 0x60, 0x0C, 0x00, 0x03, + 0x00, 0x60, 0x00, 0x0C, 0x06, 0x00, 0x00, 0x60, 0x60, 0x00, 0x03, 0x06, + 0x00, 0x00, 0x1C, 0x30, 0x00, 0x00, 0x63, 0x00, 0x00, 0x03, 0x30, 0x00, + 0x00, 0x19, 0x80, 0x00, 0x00, 0x78, 0x00, 0x00, 0x03, 0x80, 0x00, 0x00, + 0x1C, 0x00, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x60, + 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x03, 0x00, 0x00, + 0x00, 0x30, 0x00, 0x01, 0xFF, 0xF8, 0x00, 0x0F, 0xFF, 0x80, 0x00, 0x00, + 0x07, 0xFF, 0xF8, 0x3F, 0xFF, 0xC3, 0x00, 0x0C, 0x18, 0x00, 0xC0, 0xC0, + 0x0C, 0x00, 0x00, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, + 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x18, 0x00, 0x01, 0x80, + 0x00, 0x18, 0x00, 0x01, 0x80, 0x0C, 0x18, 0x00, 0x61, 0x80, 0x02, 0x1F, + 0xFF, 0xF0, 0xFF, 0xFF, 0x80, 0x00, 0x0E, 0x00, 0x7C, 0x01, 0xC0, 0x03, + 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, 0x01, 0xC0, 0x03, 0x00, + 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x60, 0x01, 0xC0, 0x0F, 0x00, 0xF8, + 0x01, 0xF0, 0x00, 0x30, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x03, 0x80, + 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0xE0, 0x01, 0x80, 0x03, + 0x00, 0x06, 0x00, 0x0E, 0x00, 0x0F, 0x00, 0x0E, 0x00, 0x01, 0x80, 0xC0, + 0x60, 0x60, 0x30, 0x18, 0x0C, 0x06, 0x06, 0x03, 0x01, 0x80, 0xC0, 0x40, + 0x60, 0x30, 0x18, 0x0C, 0x0C, 0x06, 0x03, 0x01, 0x80, 0xC0, 0xC0, 0x60, + 0x30, 0x18, 0x08, 0x0C, 0x06, 0x03, 0x01, 0x80, 0x80, 0xC0, 0x60, 0x30, + 0x00, 0x01, 0xC0, 0x03, 0xC0, 0x01, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x06, + 0x00, 0x0C, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, + 0x0C, 0x00, 0x18, 0x00, 0x38, 0x00, 0x38, 0x00, 0x3E, 0x00, 0x7C, 0x03, + 0xC0, 0x0E, 0x00, 0x18, 0x00, 0x70, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, + 0x06, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x03, 0x00, 0x0E, + 0x00, 0xF8, 0x01, 0xC0, 0x00, 0x0F, 0x00, 0x01, 0xFC, 0x03, 0x70, 0xE0, + 0x7E, 0x07, 0x1E, 0xC0, 0x3F, 0x80, 0x01, 0xE0 }; + +const GFXglyph FreeMonoOblique24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 28, 0, 1 }, // 0x20 ' ' + { 0, 10, 30, 28, 12, -28 }, // 0x21 '!' + { 38, 16, 14, 28, 10, -28 }, // 0x22 '"' + { 66, 22, 32, 28, 6, -29 }, // 0x23 '#' + { 154, 21, 33, 28, 6, -29 }, // 0x24 '$' + { 241, 22, 29, 28, 6, -27 }, // 0x25 '%' + { 321, 19, 25, 28, 6, -23 }, // 0x26 '&' + { 381, 7, 14, 28, 16, -28 }, // 0x27 ''' + { 394, 11, 34, 28, 16, -27 }, // 0x28 '(' + { 441, 11, 34, 28, 7, -27 }, // 0x29 ')' + { 488, 18, 17, 28, 10, -28 }, // 0x2A '*' + { 527, 22, 22, 28, 6, -23 }, // 0x2B '+' + { 588, 12, 14, 28, 5, -6 }, // 0x2C ',' + { 609, 22, 2, 28, 6, -13 }, // 0x2D '-' + { 615, 7, 6, 28, 11, -4 }, // 0x2E '.' + { 621, 24, 35, 28, 5, -30 }, // 0x2F '/' + { 726, 20, 30, 28, 7, -28 }, // 0x30 '0' + { 801, 17, 29, 28, 6, -28 }, // 0x31 '1' + { 863, 23, 29, 28, 4, -28 }, // 0x32 '2' + { 947, 22, 30, 28, 5, -28 }, // 0x33 '3' + { 1030, 19, 28, 28, 7, -27 }, // 0x34 '4' + { 1097, 21, 29, 28, 6, -27 }, // 0x35 '5' + { 1174, 21, 30, 28, 9, -28 }, // 0x36 '6' + { 1253, 18, 28, 28, 10, -27 }, // 0x37 '7' + { 1316, 20, 30, 28, 7, -28 }, // 0x38 '8' + { 1391, 22, 30, 28, 6, -28 }, // 0x39 '9' + { 1474, 10, 21, 28, 11, -19 }, // 0x3A ':' + { 1501, 15, 27, 28, 5, -19 }, // 0x3B ';' + { 1552, 23, 22, 28, 6, -23 }, // 0x3C '<' + { 1616, 25, 9, 28, 4, -17 }, // 0x3D '=' + { 1645, 24, 22, 28, 4, -23 }, // 0x3E '>' + { 1711, 16, 28, 28, 11, -26 }, // 0x3F '?' + { 1767, 19, 32, 28, 7, -28 }, // 0x40 '@' + { 1843, 27, 26, 28, 1, -25 }, // 0x41 'A' + { 1931, 26, 26, 28, 2, -25 }, // 0x42 'B' + { 2016, 25, 28, 28, 5, -26 }, // 0x43 'C' + { 2104, 26, 26, 28, 2, -25 }, // 0x44 'D' + { 2189, 27, 26, 28, 2, -25 }, // 0x45 'E' + { 2277, 28, 26, 28, 2, -25 }, // 0x46 'F' + { 2368, 25, 28, 28, 5, -26 }, // 0x47 'G' + { 2456, 27, 26, 28, 3, -25 }, // 0x48 'H' + { 2544, 22, 26, 28, 6, -25 }, // 0x49 'I' + { 2616, 28, 27, 28, 5, -25 }, // 0x4A 'J' + { 2711, 29, 26, 28, 2, -25 }, // 0x4B 'K' + { 2806, 25, 26, 28, 3, -25 }, // 0x4C 'L' + { 2888, 32, 26, 28, 1, -25 }, // 0x4D 'M' + { 2992, 30, 26, 28, 2, -25 }, // 0x4E 'N' + { 3090, 24, 28, 28, 5, -26 }, // 0x4F 'O' + { 3174, 26, 26, 28, 2, -25 }, // 0x50 'P' + { 3259, 24, 32, 28, 5, -26 }, // 0x51 'Q' + { 3355, 26, 26, 28, 2, -25 }, // 0x52 'R' + { 3440, 24, 28, 28, 5, -26 }, // 0x53 'S' + { 3524, 24, 26, 28, 7, -25 }, // 0x54 'T' + { 3602, 26, 27, 28, 6, -25 }, // 0x55 'U' + { 3690, 27, 26, 28, 6, -25 }, // 0x56 'V' + { 3778, 27, 26, 28, 6, -25 }, // 0x57 'W' + { 3866, 29, 26, 28, 2, -25 }, // 0x58 'X' + { 3961, 24, 26, 28, 7, -25 }, // 0x59 'Y' + { 4039, 23, 26, 28, 5, -25 }, // 0x5A 'Z' + { 4114, 15, 34, 28, 12, -27 }, // 0x5B '[' + { 4178, 10, 35, 28, 12, -30 }, // 0x5C '\' + { 4222, 15, 34, 28, 6, -27 }, // 0x5D ']' + { 4286, 18, 12, 28, 9, -28 }, // 0x5E '^' + { 4313, 28, 2, 28, -1, 5 }, // 0x5F '_' + { 4320, 6, 7, 28, 13, -29 }, // 0x60 '`' + { 4326, 22, 22, 28, 4, -20 }, // 0x61 'a' + { 4387, 27, 29, 28, 1, -27 }, // 0x62 'b' + { 4485, 22, 22, 28, 6, -20 }, // 0x63 'c' + { 4546, 25, 29, 28, 5, -27 }, // 0x64 'd' + { 4637, 22, 22, 28, 5, -20 }, // 0x65 'e' + { 4698, 26, 28, 28, 5, -27 }, // 0x66 'f' + { 4789, 25, 30, 28, 5, -20 }, // 0x67 'g' + { 4883, 24, 28, 28, 3, -27 }, // 0x68 'h' + { 4967, 19, 29, 28, 5, -28 }, // 0x69 'i' + { 5036, 20, 38, 28, 4, -28 }, // 0x6A 'j' + { 5131, 24, 28, 28, 3, -27 }, // 0x6B 'k' + { 5215, 19, 28, 28, 5, -27 }, // 0x6C 'l' + { 5282, 27, 21, 28, 1, -20 }, // 0x6D 'm' + { 5353, 23, 21, 28, 3, -20 }, // 0x6E 'n' + { 5414, 22, 22, 28, 5, -20 }, // 0x6F 'o' + { 5475, 29, 30, 28, -1, -20 }, // 0x70 'p' + { 5584, 26, 30, 28, 5, -20 }, // 0x71 'q' + { 5682, 25, 20, 28, 4, -19 }, // 0x72 'r' + { 5745, 21, 22, 28, 5, -20 }, // 0x73 's' + { 5803, 17, 27, 28, 7, -25 }, // 0x74 't' + { 5861, 21, 21, 28, 6, -19 }, // 0x75 'u' + { 5917, 26, 20, 28, 5, -19 }, // 0x76 'v' + { 5982, 25, 20, 28, 6, -19 }, // 0x77 'w' + { 6045, 26, 20, 28, 3, -19 }, // 0x78 'x' + { 6110, 29, 29, 28, 1, -19 }, // 0x79 'y' + { 6216, 21, 20, 28, 5, -19 }, // 0x7A 'z' + { 6269, 15, 34, 28, 10, -27 }, // 0x7B '{' + { 6333, 9, 35, 28, 12, -28 }, // 0x7C '|' + { 6373, 15, 34, 28, 8, -27 }, // 0x7D '}' + { 6437, 20, 6, 28, 7, -15 } }; // 0x7E '~' + +const GFXfont FreeMonoOblique24pt7b PROGMEM = { + (uint8_t *)FreeMonoOblique24pt7bBitmaps, + (GFXglyph *)FreeMonoOblique24pt7bGlyphs, + 0x20, 0x7E, 47 }; + +// Approx. 7124 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique9pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique9pt7b.h new file mode 100644 index 0000000..a00ca82 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeMonoOblique9pt7b.h @@ -0,0 +1,187 @@ +const uint8_t FreeMonoOblique9pt7bBitmaps[] PROGMEM = { + 0x11, 0x22, 0x24, 0x40, 0x00, 0xC0, 0xDE, 0xE5, 0x29, 0x00, 0x09, 0x05, + 0x02, 0x82, 0x47, 0xF8, 0xA0, 0x51, 0xFE, 0x28, 0x14, 0x0A, 0x09, 0x00, + 0x08, 0x1D, 0x23, 0x40, 0x70, 0x1C, 0x02, 0x82, 0x84, 0x78, 0x20, 0x20, + 0x1C, 0x11, 0x08, 0x83, 0x80, 0x18, 0x71, 0xC0, 0x1C, 0x11, 0x08, 0x83, + 0x80, 0x1E, 0x60, 0x81, 0x03, 0x0A, 0x65, 0x46, 0x88, 0xE8, 0xFA, 0x80, + 0x12, 0x24, 0x48, 0x88, 0x88, 0x88, 0x80, 0x01, 0x11, 0x11, 0x11, 0x22, + 0x44, 0x80, 0x10, 0x22, 0x5B, 0xC3, 0x0A, 0x22, 0x00, 0x04, 0x02, 0x02, + 0x1F, 0xF0, 0x80, 0x40, 0x20, 0x00, 0x36, 0x4C, 0x80, 0xFF, 0x80, 0xF0, + 0x00, 0x80, 0x80, 0x40, 0x40, 0x40, 0x20, 0x20, 0x20, 0x10, 0x10, 0x10, + 0x08, 0x08, 0x00, 0x1C, 0x45, 0x0A, 0x18, 0x30, 0x61, 0x42, 0x85, 0x11, + 0xC0, 0x04, 0x38, 0x90, 0x20, 0x81, 0x02, 0x04, 0x08, 0x23, 0xF8, 0x07, + 0x04, 0xC4, 0x20, 0x10, 0x10, 0x30, 0x20, 0x20, 0x60, 0x40, 0x3F, 0x80, + 0x0F, 0x00, 0x40, 0x20, 0x20, 0x60, 0x18, 0x04, 0x02, 0x01, 0x43, 0x1E, + 0x00, 0x03, 0x05, 0x0A, 0x12, 0x22, 0x22, 0x42, 0x7F, 0x04, 0x04, 0x1E, + 0x1F, 0x88, 0x08, 0x05, 0xC3, 0x30, 0x08, 0x04, 0x02, 0x02, 0x42, 0x1E, + 0x00, 0x07, 0x18, 0x20, 0x40, 0x5C, 0xA6, 0xC2, 0x82, 0x82, 0xC4, 0x78, + 0xFF, 0x04, 0x10, 0x20, 0x82, 0x04, 0x10, 0x20, 0x81, 0x00, 0x1E, 0x23, + 0x41, 0x41, 0x62, 0x1C, 0x66, 0x82, 0x82, 0x84, 0x78, 0x1E, 0x23, 0x41, + 0x41, 0x43, 0x65, 0x3A, 0x02, 0x04, 0x18, 0xE0, 0x6C, 0x00, 0x36, 0x18, + 0xC0, 0x00, 0x19, 0x8C, 0xC4, 0x00, 0x01, 0x83, 0x06, 0x0C, 0x06, 0x00, + 0x80, 0x30, 0x04, 0xFF, 0x80, 0x00, 0x1F, 0xF0, 0x20, 0x0C, 0x01, 0x00, + 0x60, 0x20, 0x60, 0xC1, 0x80, 0x3D, 0x8E, 0x08, 0x10, 0xC6, 0x08, 0x00, + 0x01, 0x80, 0x1C, 0x45, 0x0A, 0x79, 0x34, 0x69, 0x4E, 0x81, 0x03, 0x03, + 0xC0, 0x0F, 0x00, 0x60, 0x12, 0x02, 0x40, 0x88, 0x21, 0x07, 0xE1, 0x04, + 0x20, 0x5E, 0x3C, 0x3F, 0x84, 0x11, 0x04, 0x82, 0x3F, 0x88, 0x32, 0x04, + 0x81, 0x60, 0xBF, 0xC0, 0x1E, 0x98, 0xD0, 0x28, 0x08, 0x04, 0x02, 0x01, + 0x00, 0x41, 0x1F, 0x00, 0x3F, 0x0C, 0x22, 0x04, 0x81, 0x20, 0x48, 0x12, + 0x09, 0x02, 0x43, 0x3F, 0x00, 0x3F, 0xC4, 0x11, 0x00, 0x88, 0x3E, 0x08, + 0x82, 0x00, 0x82, 0x60, 0xBF, 0xE0, 0x3F, 0xE2, 0x08, 0x40, 0x11, 0x03, + 0xE0, 0x44, 0x08, 0x01, 0x00, 0x60, 0x1F, 0x00, 0x1E, 0x98, 0xD0, 0x08, + 0x08, 0x04, 0x7A, 0x05, 0x02, 0x41, 0x1F, 0x00, 0x3D, 0xE2, 0x18, 0x42, + 0x08, 0x43, 0xF8, 0x41, 0x08, 0x21, 0x08, 0x21, 0x1E, 0xF0, 0x3F, 0x82, + 0x02, 0x01, 0x00, 0x80, 0x40, 0x20, 0x20, 0x10, 0x7F, 0x00, 0x0F, 0xE0, + 0x20, 0x04, 0x00, 0x80, 0x10, 0x02, 0x20, 0x84, 0x10, 0x84, 0x0F, 0x00, + 0x3C, 0xE2, 0x10, 0x44, 0x11, 0x02, 0xC0, 0x64, 0x08, 0x81, 0x08, 0x61, + 0x1E, 0x38, 0x3E, 0x02, 0x00, 0x80, 0x20, 0x10, 0x04, 0x01, 0x04, 0x42, + 0x10, 0xBF, 0xE0, 0x38, 0x38, 0xC3, 0x05, 0x28, 0x29, 0x42, 0x52, 0x13, + 0x10, 0x99, 0x84, 0x08, 0x20, 0x47, 0x8F, 0x00, 0x70, 0xE6, 0x08, 0xA1, + 0x14, 0x22, 0x48, 0x49, 0x11, 0x22, 0x14, 0x43, 0x1E, 0x20, 0x1E, 0x18, + 0x90, 0x28, 0x18, 0x0C, 0x06, 0x05, 0x02, 0x46, 0x1E, 0x00, 0x3F, 0x84, + 0x31, 0x04, 0x81, 0x20, 0x8F, 0xC2, 0x00, 0x80, 0x60, 0x3E, 0x00, 0x1E, + 0x18, 0x90, 0x28, 0x18, 0x0C, 0x06, 0x05, 0x02, 0x46, 0x1E, 0x08, 0x0F, + 0x44, 0x60, 0x3F, 0x84, 0x31, 0x04, 0x81, 0x20, 0x8F, 0xC2, 0x10, 0x84, + 0x60, 0xBC, 0x10, 0x0F, 0x88, 0xC8, 0x24, 0x01, 0x80, 0x38, 0x05, 0x02, + 0xC2, 0x5E, 0x00, 0xFF, 0xC4, 0x44, 0x02, 0x01, 0x00, 0x80, 0x40, 0x60, + 0x20, 0x7E, 0x00, 0xF1, 0xD0, 0x24, 0x09, 0x02, 0x41, 0xA0, 0x48, 0x12, + 0x04, 0xC6, 0x1F, 0x00, 0xF1, 0xE8, 0x11, 0x02, 0x20, 0x82, 0x20, 0x44, + 0x09, 0x01, 0x40, 0x28, 0x02, 0x00, 0xF1, 0xE8, 0x09, 0x12, 0x26, 0x45, + 0x48, 0xAA, 0x29, 0x45, 0x28, 0xC6, 0x18, 0xC0, 0x38, 0xE2, 0x08, 0x26, + 0x05, 0x00, 0x40, 0x18, 0x04, 0x81, 0x08, 0x41, 0x1C, 0x70, 0xE3, 0xA0, + 0x90, 0x84, 0x81, 0x80, 0x80, 0x40, 0x20, 0x20, 0x7E, 0x00, 0x3F, 0x90, + 0x88, 0x80, 0x80, 0x80, 0x80, 0x80, 0x82, 0x82, 0x7F, 0x00, 0x39, 0x08, + 0x44, 0x21, 0x08, 0x42, 0x21, 0x0E, 0x00, 0x88, 0x44, 0x44, 0x22, 0x22, + 0x11, 0x11, 0x38, 0x42, 0x11, 0x08, 0x42, 0x10, 0x84, 0x2E, 0x00, 0x08, + 0x28, 0x92, 0x18, 0x20, 0xFF, 0xC0, 0xA4, 0x3E, 0x00, 0x80, 0x47, 0xA4, + 0x34, 0x12, 0x18, 0xF7, 0x38, 0x01, 0x00, 0x40, 0x09, 0xE1, 0xC6, 0x20, + 0x44, 0x09, 0x01, 0x30, 0x46, 0x13, 0xBC, 0x00, 0x1F, 0x48, 0x74, 0x0A, + 0x00, 0x80, 0x20, 0x0C, 0x18, 0xF8, 0x01, 0x80, 0x40, 0x23, 0x96, 0x32, + 0x0A, 0x05, 0x02, 0x81, 0x61, 0x1F, 0xE0, 0x1F, 0x30, 0xD0, 0x3F, 0xF8, + 0x04, 0x01, 0x00, 0x7C, 0x07, 0xC3, 0x00, 0x80, 0xFE, 0x10, 0x04, 0x01, + 0x00, 0x40, 0x10, 0x08, 0x0F, 0xE0, 0x1D, 0xD8, 0xC4, 0x12, 0x04, 0x82, + 0x20, 0x8C, 0x61, 0xE8, 0x02, 0x01, 0x07, 0x80, 0x30, 0x04, 0x01, 0x00, + 0x5C, 0x38, 0x88, 0x22, 0x08, 0x82, 0x21, 0x18, 0x4F, 0x3C, 0x04, 0x04, + 0x00, 0x38, 0x08, 0x08, 0x08, 0x08, 0x10, 0x10, 0xFF, 0x01, 0x00, 0x80, + 0x03, 0xF0, 0x10, 0x08, 0x04, 0x02, 0x02, 0x01, 0x00, 0x80, 0x40, 0x47, + 0xC0, 0x38, 0x08, 0x04, 0x02, 0x71, 0x20, 0xA0, 0xA0, 0x68, 0x24, 0x11, + 0x38, 0xE0, 0x3C, 0x04, 0x04, 0x08, 0x08, 0x08, 0x08, 0x08, 0x10, 0x10, + 0xFF, 0x3E, 0xE2, 0x64, 0x88, 0x91, 0x12, 0x24, 0x48, 0x91, 0x17, 0x33, + 0x37, 0x14, 0x4C, 0x24, 0x12, 0x09, 0x08, 0x85, 0xE3, 0x1E, 0x10, 0x90, + 0x30, 0x18, 0x0C, 0x0B, 0x08, 0x78, 0x33, 0xC3, 0x8C, 0x40, 0x88, 0x12, + 0x02, 0x60, 0x8C, 0x31, 0x78, 0x20, 0x08, 0x03, 0xE0, 0x00, 0x1C, 0xD8, + 0xC4, 0x12, 0x04, 0x81, 0x20, 0x4C, 0x21, 0xF8, 0x02, 0x00, 0x81, 0xF0, + 0x73, 0x8E, 0x04, 0x04, 0x02, 0x01, 0x00, 0x81, 0xFC, 0x1F, 0x61, 0x40, + 0x3C, 0x03, 0x81, 0x82, 0xFC, 0x10, 0x63, 0xF9, 0x02, 0x04, 0x10, 0x20, + 0x40, 0x7C, 0xE3, 0x10, 0x90, 0x48, 0x24, 0x22, 0x11, 0x18, 0xF6, 0xF3, + 0xD0, 0x44, 0x10, 0x88, 0x24, 0x09, 0x02, 0x80, 0x40, 0xE1, 0xD0, 0x24, + 0x91, 0x24, 0x55, 0x19, 0x86, 0x61, 0x10, 0x39, 0xC4, 0x20, 0xB0, 0x30, + 0x0C, 0x04, 0x86, 0x13, 0x8E, 0x3C, 0x71, 0x04, 0x10, 0x40, 0x88, 0x09, + 0x00, 0xA0, 0x06, 0x00, 0x40, 0x08, 0x01, 0x00, 0xFC, 0x00, 0x7F, 0x42, + 0x04, 0x08, 0x10, 0x20, 0x42, 0xFE, 0x0C, 0x41, 0x04, 0x30, 0x8C, 0x08, + 0x21, 0x04, 0x10, 0x60, 0x24, 0x94, 0x92, 0x52, 0x40, 0x18, 0x20, 0x82, + 0x10, 0x40, 0xC4, 0x10, 0x82, 0x08, 0xC0, 0x61, 0x24, 0x30 }; + +const GFXglyph FreeMonoOblique9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 11, 0, 1 }, // 0x20 ' ' + { 0, 4, 11, 11, 4, -10 }, // 0x21 '!' + { 6, 5, 5, 11, 4, -10 }, // 0x22 '"' + { 10, 9, 12, 11, 2, -10 }, // 0x23 '#' + { 24, 8, 12, 11, 3, -10 }, // 0x24 '$' + { 36, 9, 11, 11, 2, -10 }, // 0x25 '%' + { 49, 7, 10, 11, 2, -9 }, // 0x26 '&' + { 58, 2, 5, 11, 6, -10 }, // 0x27 ''' + { 60, 4, 13, 11, 6, -10 }, // 0x28 '(' + { 67, 4, 13, 11, 3, -10 }, // 0x29 ')' + { 74, 7, 7, 11, 4, -10 }, // 0x2A '*' + { 81, 9, 8, 11, 2, -8 }, // 0x2B '+' + { 90, 4, 5, 11, 2, -1 }, // 0x2C ',' + { 93, 9, 1, 11, 2, -5 }, // 0x2D '-' + { 95, 2, 2, 11, 4, -1 }, // 0x2E '.' + { 96, 9, 13, 11, 2, -11 }, // 0x2F '/' + { 111, 7, 11, 11, 3, -10 }, // 0x30 '0' + { 121, 7, 11, 11, 2, -10 }, // 0x31 '1' + { 131, 9, 11, 11, 2, -10 }, // 0x32 '2' + { 144, 9, 11, 11, 2, -10 }, // 0x33 '3' + { 157, 8, 11, 11, 2, -10 }, // 0x34 '4' + { 168, 9, 11, 11, 2, -10 }, // 0x35 '5' + { 181, 8, 11, 11, 3, -10 }, // 0x36 '6' + { 192, 7, 11, 11, 4, -10 }, // 0x37 '7' + { 202, 8, 11, 11, 3, -10 }, // 0x38 '8' + { 213, 8, 11, 11, 3, -10 }, // 0x39 '9' + { 224, 3, 8, 11, 4, -7 }, // 0x3A ':' + { 227, 5, 11, 11, 2, -7 }, // 0x3B ';' + { 234, 9, 8, 11, 2, -8 }, // 0x3C '<' + { 243, 9, 4, 11, 2, -6 }, // 0x3D '=' + { 248, 9, 8, 11, 2, -8 }, // 0x3E '>' + { 257, 7, 10, 11, 4, -9 }, // 0x3F '?' + { 266, 7, 12, 11, 3, -10 }, // 0x40 '@' + { 277, 11, 10, 11, 0, -9 }, // 0x41 'A' + { 291, 10, 10, 11, 1, -9 }, // 0x42 'B' + { 304, 9, 10, 11, 2, -9 }, // 0x43 'C' + { 316, 10, 10, 11, 1, -9 }, // 0x44 'D' + { 329, 10, 10, 11, 1, -9 }, // 0x45 'E' + { 342, 11, 10, 11, 1, -9 }, // 0x46 'F' + { 356, 9, 10, 11, 2, -9 }, // 0x47 'G' + { 368, 11, 10, 11, 1, -9 }, // 0x48 'H' + { 382, 9, 10, 11, 2, -9 }, // 0x49 'I' + { 394, 11, 10, 11, 2, -9 }, // 0x4A 'J' + { 408, 11, 10, 11, 1, -9 }, // 0x4B 'K' + { 422, 10, 10, 11, 1, -9 }, // 0x4C 'L' + { 435, 13, 10, 11, 0, -9 }, // 0x4D 'M' + { 452, 11, 10, 11, 1, -9 }, // 0x4E 'N' + { 466, 9, 10, 11, 2, -9 }, // 0x4F 'O' + { 478, 10, 10, 11, 1, -9 }, // 0x50 'P' + { 491, 9, 13, 11, 2, -9 }, // 0x51 'Q' + { 506, 10, 10, 11, 1, -9 }, // 0x52 'R' + { 519, 9, 10, 11, 2, -9 }, // 0x53 'S' + { 531, 9, 10, 11, 3, -9 }, // 0x54 'T' + { 543, 10, 10, 11, 2, -9 }, // 0x55 'U' + { 556, 11, 10, 11, 2, -9 }, // 0x56 'V' + { 570, 11, 10, 11, 2, -9 }, // 0x57 'W' + { 584, 11, 10, 11, 1, -9 }, // 0x58 'X' + { 598, 9, 10, 11, 3, -9 }, // 0x59 'Y' + { 610, 9, 10, 11, 2, -9 }, // 0x5A 'Z' + { 622, 5, 13, 11, 5, -10 }, // 0x5B '[' + { 631, 4, 14, 11, 4, -11 }, // 0x5C '\' + { 638, 5, 13, 11, 2, -10 }, // 0x5D ']' + { 647, 7, 5, 11, 3, -10 }, // 0x5E '^' + { 652, 11, 1, 11, 0, 2 }, // 0x5F '_' + { 654, 2, 3, 11, 5, -11 }, // 0x60 '`' + { 655, 9, 8, 11, 2, -7 }, // 0x61 'a' + { 664, 11, 11, 11, 0, -10 }, // 0x62 'b' + { 680, 10, 8, 11, 2, -7 }, // 0x63 'c' + { 690, 9, 11, 11, 2, -10 }, // 0x64 'd' + { 703, 9, 8, 11, 2, -7 }, // 0x65 'e' + { 712, 10, 11, 11, 2, -10 }, // 0x66 'f' + { 726, 10, 11, 11, 2, -7 }, // 0x67 'g' + { 740, 10, 11, 11, 1, -10 }, // 0x68 'h' + { 754, 8, 11, 11, 2, -10 }, // 0x69 'i' + { 765, 9, 14, 11, 1, -10 }, // 0x6A 'j' + { 781, 9, 11, 11, 1, -10 }, // 0x6B 'k' + { 794, 8, 11, 11, 2, -10 }, // 0x6C 'l' + { 805, 11, 8, 11, 0, -7 }, // 0x6D 'm' + { 816, 9, 8, 11, 1, -7 }, // 0x6E 'n' + { 825, 9, 8, 11, 2, -7 }, // 0x6F 'o' + { 834, 11, 11, 11, 0, -7 }, // 0x70 'p' + { 850, 10, 11, 11, 2, -7 }, // 0x71 'q' + { 864, 9, 8, 11, 2, -7 }, // 0x72 'r' + { 873, 8, 8, 11, 2, -7 }, // 0x73 's' + { 881, 7, 10, 11, 2, -9 }, // 0x74 't' + { 890, 9, 8, 11, 2, -7 }, // 0x75 'u' + { 899, 10, 8, 11, 2, -7 }, // 0x76 'v' + { 909, 10, 8, 11, 2, -7 }, // 0x77 'w' + { 919, 10, 8, 11, 1, -7 }, // 0x78 'x' + { 929, 12, 11, 11, 0, -7 }, // 0x79 'y' + { 946, 8, 8, 11, 2, -7 }, // 0x7A 'z' + { 954, 6, 13, 11, 4, -10 }, // 0x7B '{' + { 964, 3, 12, 11, 5, -9 }, // 0x7C '|' + { 969, 6, 13, 11, 3, -10 }, // 0x7D '}' + { 979, 7, 3, 11, 3, -6 } }; // 0x7E '~' + +const GFXfont FreeMonoOblique9pt7b PROGMEM = { + (uint8_t *)FreeMonoOblique9pt7bBitmaps, + (GFXglyph *)FreeMonoOblique9pt7bGlyphs, + 0x20, 0x7E, 18 }; + +// Approx. 1654 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSans12pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSans12pt7b.h new file mode 100644 index 0000000..9ecbb8f --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSans12pt7b.h @@ -0,0 +1,270 @@ +const uint8_t FreeSans12pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xF0, 0xF0, 0xCF, 0x3C, 0xF3, 0x8A, 0x20, 0x06, 0x30, + 0x31, 0x03, 0x18, 0x18, 0xC7, 0xFF, 0xBF, 0xFC, 0x31, 0x03, 0x18, 0x18, + 0xC7, 0xFF, 0xBF, 0xFC, 0x31, 0x01, 0x18, 0x18, 0xC0, 0xC6, 0x06, 0x30, + 0x04, 0x03, 0xE1, 0xFF, 0x72, 0x6C, 0x47, 0x88, 0xF1, 0x07, 0x20, 0x7E, + 0x03, 0xF0, 0x17, 0x02, 0x3C, 0x47, 0x88, 0xF1, 0x1B, 0x26, 0x7F, 0xC3, + 0xE0, 0x10, 0x02, 0x00, 0x00, 0x06, 0x03, 0xC0, 0x40, 0x7E, 0x0C, 0x0E, + 0x70, 0x80, 0xC3, 0x18, 0x0C, 0x31, 0x00, 0xE7, 0x30, 0x07, 0xE6, 0x00, + 0x3C, 0x40, 0x00, 0x0C, 0x7C, 0x00, 0x8F, 0xE0, 0x19, 0xC7, 0x01, 0x18, + 0x30, 0x31, 0x83, 0x02, 0x1C, 0x70, 0x40, 0xFE, 0x04, 0x07, 0xC0, 0x0F, + 0x00, 0x7E, 0x03, 0x9C, 0x0C, 0x30, 0x30, 0xC0, 0xE7, 0x01, 0xF8, 0x03, + 0x80, 0x3E, 0x01, 0xCC, 0x6E, 0x19, 0xB0, 0x7C, 0xC0, 0xF3, 0x03, 0xCE, + 0x1F, 0x9F, 0xE6, 0x1E, 0x1C, 0xFF, 0xA0, 0x08, 0x8C, 0x66, 0x31, 0x98, + 0xC6, 0x31, 0x8C, 0x63, 0x08, 0x63, 0x08, 0x61, 0x0C, 0x20, 0x82, 0x18, + 0xC3, 0x18, 0xC3, 0x18, 0xC6, 0x31, 0x8C, 0x62, 0x31, 0x88, 0xC4, 0x62, + 0x00, 0x10, 0x23, 0x5B, 0xE3, 0x8D, 0x91, 0x00, 0x0C, 0x03, 0x00, 0xC0, + 0x30, 0xFF, 0xFF, 0xF0, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0xF5, 0x60, + 0xFF, 0xF0, 0xF0, 0x02, 0x0C, 0x10, 0x20, 0xC1, 0x02, 0x0C, 0x10, 0x20, + 0xC1, 0x02, 0x0C, 0x10, 0x20, 0xC1, 0x00, 0x1F, 0x07, 0xF1, 0xC7, 0x30, + 0x6E, 0x0F, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, + 0x0E, 0xC1, 0x9C, 0x71, 0xFC, 0x1F, 0x00, 0x08, 0xCF, 0xFF, 0x8C, 0x63, + 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0x1F, 0x0F, 0xF9, 0x87, 0x60, 0x7C, + 0x06, 0x00, 0xC0, 0x18, 0x07, 0x01, 0xC0, 0xF0, 0x78, 0x1C, 0x06, 0x00, + 0x80, 0x30, 0x07, 0xFF, 0xFF, 0xE0, 0x3F, 0x0F, 0xF3, 0x87, 0x60, 0x6C, + 0x0C, 0x01, 0x80, 0x70, 0x7C, 0x0F, 0x80, 0x18, 0x01, 0x80, 0x3C, 0x07, + 0x80, 0xD8, 0x73, 0xFC, 0x1F, 0x00, 0x01, 0x80, 0x70, 0x0E, 0x03, 0xC0, + 0xD8, 0x1B, 0x06, 0x61, 0x8C, 0x21, 0x8C, 0x33, 0x06, 0x7F, 0xFF, 0xFE, + 0x03, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x3F, 0xCF, 0xF9, 0x80, 0x30, 0x06, + 0x00, 0xDE, 0x1F, 0xE7, 0x0E, 0x00, 0xE0, 0x0C, 0x01, 0x80, 0x30, 0x07, + 0x81, 0xF8, 0x73, 0xFC, 0x1F, 0x00, 0x0F, 0x07, 0xF9, 0xC3, 0x30, 0x74, + 0x01, 0x80, 0x33, 0xC7, 0xFE, 0xF0, 0xDC, 0x1F, 0x01, 0xE0, 0x3C, 0x06, + 0xC1, 0xDC, 0x71, 0xFC, 0x1F, 0x00, 0xFF, 0xFF, 0xFC, 0x01, 0x00, 0x60, + 0x18, 0x02, 0x00, 0xC0, 0x30, 0x06, 0x01, 0x80, 0x30, 0x04, 0x01, 0x80, + 0x30, 0x06, 0x01, 0x80, 0x30, 0x00, 0x1F, 0x07, 0xF1, 0xC7, 0x30, 0x66, + 0x0C, 0xC1, 0x8C, 0x61, 0xFC, 0x3F, 0x8E, 0x3B, 0x01, 0xE0, 0x3C, 0x07, + 0x80, 0xD8, 0x31, 0xFC, 0x1F, 0x00, 0x1F, 0x07, 0xF1, 0xC7, 0x70, 0x6C, + 0x07, 0x80, 0xF0, 0x1E, 0x07, 0x61, 0xEF, 0xFC, 0x79, 0x80, 0x30, 0x05, + 0x81, 0x98, 0x73, 0xFC, 0x1E, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0xF0, 0x00, + 0x0F, 0x56, 0x00, 0x00, 0x07, 0x01, 0xE0, 0xF8, 0x3C, 0x0F, 0x00, 0xE0, + 0x07, 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xF0, 0x01, 0xFF, 0xFF, 0xFF, 0x00, + 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0x00, 0x0E, 0x00, 0x78, 0x01, 0xF0, 0x07, + 0xC0, 0x0F, 0x00, 0x70, 0x1E, 0x0F, 0x03, 0xC0, 0xF0, 0x08, 0x00, 0x1F, + 0x1F, 0xEE, 0x1B, 0x03, 0xC0, 0xC0, 0x30, 0x0C, 0x06, 0x03, 0x81, 0xC0, + 0xE0, 0x30, 0x0C, 0x03, 0x00, 0x00, 0x00, 0x0C, 0x03, 0x00, 0x00, 0xFE, + 0x00, 0x0F, 0xFE, 0x00, 0xF0, 0x3E, 0x07, 0x00, 0x3C, 0x38, 0x00, 0x30, + 0xC1, 0xE0, 0x66, 0x0F, 0xD9, 0xD8, 0x61, 0xC3, 0xC3, 0x07, 0x0F, 0x1C, + 0x1C, 0x3C, 0x60, 0x60, 0xF1, 0x81, 0x83, 0xC6, 0x06, 0x1B, 0x18, 0x38, + 0xEE, 0x71, 0xE7, 0x18, 0xFD, 0xF8, 0x71, 0xE7, 0xC0, 0xE0, 0x00, 0x01, + 0xE0, 0x00, 0x01, 0xFF, 0xC0, 0x01, 0xFC, 0x00, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x07, 0xE0, 0x06, 0x60, 0x06, 0x60, 0x0E, 0x70, 0x0C, 0x30, + 0x0C, 0x30, 0x1C, 0x38, 0x18, 0x18, 0x1F, 0xF8, 0x3F, 0xFC, 0x30, 0x1C, + 0x30, 0x0C, 0x70, 0x0E, 0x60, 0x06, 0x60, 0x06, 0xFF, 0xC7, 0xFF, 0x30, + 0x19, 0x80, 0x6C, 0x03, 0x60, 0x1B, 0x00, 0xD8, 0x0C, 0xFF, 0xC7, 0xFF, + 0x30, 0x0D, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x06, 0xFF, 0xF7, + 0xFE, 0x00, 0x07, 0xE0, 0x3F, 0xF0, 0xE0, 0x73, 0x80, 0x66, 0x00, 0x6C, + 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x06, 0x00, + 0x06, 0x00, 0x6C, 0x00, 0xDC, 0x03, 0x1E, 0x0E, 0x1F, 0xF8, 0x0F, 0xC0, + 0xFF, 0x83, 0xFF, 0x8C, 0x07, 0x30, 0x0E, 0xC0, 0x1B, 0x00, 0x7C, 0x00, + 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x1F, 0x00, + 0x6C, 0x03, 0xB0, 0x1C, 0xFF, 0xE3, 0xFF, 0x00, 0xFF, 0xFF, 0xFF, 0xC0, + 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0xFF, 0xEF, 0xFE, 0xC0, + 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xFF, 0xDF, + 0xFB, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, 0x18, 0x00, + 0x07, 0xF0, 0x1F, 0xFC, 0x3C, 0x1E, 0x70, 0x06, 0x60, 0x03, 0xE0, 0x00, + 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x7F, 0xC0, 0x7F, 0xC0, 0x03, 0xC0, 0x03, + 0x60, 0x03, 0x60, 0x07, 0x30, 0x0F, 0x3C, 0x1F, 0x1F, 0xFB, 0x07, 0xE1, + 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, + 0x03, 0xFF, 0xFF, 0xFF, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, + 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x01, + 0x80, 0xC0, 0x60, 0x30, 0x18, 0x0C, 0x06, 0x03, 0x01, 0x80, 0xC0, 0x60, + 0x3C, 0x1E, 0x0F, 0x07, 0xC7, 0x7F, 0x1F, 0x00, 0xC0, 0x3B, 0x01, 0xCC, + 0x0E, 0x30, 0x70, 0xC3, 0x83, 0x1C, 0x0C, 0xE0, 0x33, 0x80, 0xDE, 0x03, + 0xDC, 0x0E, 0x38, 0x30, 0x60, 0xC1, 0xC3, 0x03, 0x8C, 0x06, 0x30, 0x1C, + 0xC0, 0x3B, 0x00, 0x60, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x0C, + 0x03, 0x00, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x0C, 0x03, 0x00, + 0xFF, 0xFF, 0xF0, 0xE0, 0x07, 0xE0, 0x07, 0xF0, 0x0F, 0xF0, 0x0F, 0xD0, + 0x0F, 0xD8, 0x1B, 0xD8, 0x1B, 0xD8, 0x1B, 0xCC, 0x33, 0xCC, 0x33, 0xCC, + 0x33, 0xC6, 0x63, 0xC6, 0x63, 0xC6, 0x63, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, + 0xC3, 0xC1, 0x83, 0xE0, 0x1F, 0x00, 0xFC, 0x07, 0xE0, 0x3D, 0x81, 0xEE, + 0x0F, 0x30, 0x79, 0xC3, 0xC6, 0x1E, 0x18, 0xF0, 0xE7, 0x83, 0x3C, 0x1D, + 0xE0, 0x6F, 0x01, 0xF8, 0x0F, 0xC0, 0x3E, 0x01, 0xC0, 0x03, 0xE0, 0x0F, + 0xFC, 0x0F, 0x07, 0x86, 0x00, 0xC6, 0x00, 0x33, 0x00, 0x1B, 0x00, 0x07, + 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x36, 0x00, + 0x33, 0x00, 0x18, 0xC0, 0x18, 0x78, 0x3C, 0x1F, 0xFC, 0x03, 0xF8, 0x00, + 0xFF, 0x8F, 0xFE, 0xC0, 0x6C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x07, + 0xFF, 0xEF, 0xFC, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, + 0xC0, 0x0C, 0x00, 0x03, 0xE0, 0x0F, 0xFC, 0x0F, 0x07, 0x86, 0x00, 0xC6, + 0x00, 0x33, 0x00, 0x1B, 0x00, 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x00, + 0xF0, 0x00, 0x78, 0x00, 0x36, 0x00, 0x33, 0x01, 0x98, 0xC0, 0xFC, 0x78, + 0x3C, 0x1F, 0xFF, 0x03, 0xF9, 0x80, 0x00, 0x40, 0xFF, 0xC3, 0xFF, 0xCC, + 0x03, 0xB0, 0x06, 0xC0, 0x1B, 0x00, 0x6C, 0x01, 0xB0, 0x0C, 0xFF, 0xE3, + 0xFF, 0xCC, 0x03, 0xB0, 0x06, 0xC0, 0x1B, 0x00, 0x6C, 0x01, 0xB0, 0x06, + 0xC0, 0x1B, 0x00, 0x70, 0x0F, 0xE0, 0x7F, 0xC3, 0x83, 0x9C, 0x07, 0x60, + 0x0D, 0x80, 0x06, 0x00, 0x1E, 0x00, 0x3F, 0x80, 0x3F, 0xC0, 0x0F, 0x80, + 0x07, 0xC0, 0x0F, 0x00, 0x3E, 0x00, 0xDE, 0x0E, 0x3F, 0xF0, 0x3F, 0x80, + 0xFF, 0xFF, 0xFF, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x06, 0x00, 0x60, 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xE0, + 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, + 0xE0, 0x0F, 0x80, 0xEE, 0x0E, 0x3F, 0xE0, 0x7C, 0x00, 0x60, 0x06, 0xC0, + 0x1D, 0xC0, 0x31, 0x80, 0x63, 0x01, 0xC7, 0x03, 0x06, 0x06, 0x0C, 0x1C, + 0x1C, 0x30, 0x18, 0x60, 0x31, 0xC0, 0x73, 0x00, 0x66, 0x00, 0xDC, 0x01, + 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0xE0, 0x30, 0x1D, 0x80, 0xE0, + 0x76, 0x07, 0x81, 0xD8, 0x1E, 0x06, 0x70, 0x7C, 0x18, 0xC1, 0xB0, 0xE3, + 0x0C, 0xC3, 0x8C, 0x33, 0x0C, 0x38, 0xC6, 0x30, 0x67, 0x18, 0xC1, 0x98, + 0x67, 0x06, 0x61, 0xD8, 0x1D, 0x83, 0x60, 0x3C, 0x0D, 0x80, 0xF0, 0x3E, + 0x03, 0xC0, 0x70, 0x0F, 0x01, 0xC0, 0x18, 0x07, 0x00, 0x70, 0x0E, 0x60, + 0x38, 0xE0, 0x60, 0xE1, 0xC0, 0xC3, 0x01, 0xCC, 0x01, 0xF8, 0x01, 0xE0, + 0x03, 0x80, 0x07, 0x80, 0x1F, 0x00, 0x33, 0x00, 0xE7, 0x03, 0x86, 0x06, + 0x0E, 0x1C, 0x0E, 0x70, 0x0C, 0xC0, 0x1C, 0x60, 0x06, 0x70, 0x0E, 0x30, + 0x1C, 0x38, 0x18, 0x1C, 0x38, 0x0C, 0x30, 0x0E, 0x70, 0x06, 0x60, 0x03, + 0xC0, 0x03, 0xC0, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, + 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xC0, 0x0E, + 0x00, 0xE0, 0x0E, 0x00, 0x60, 0x07, 0x00, 0x70, 0x07, 0x00, 0x30, 0x03, + 0x80, 0x38, 0x03, 0x80, 0x18, 0x01, 0xC0, 0x1C, 0x00, 0xFF, 0xFF, 0xFF, + 0xC0, 0xFF, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCF, + 0xF0, 0x81, 0x81, 0x02, 0x06, 0x04, 0x08, 0x18, 0x10, 0x20, 0x60, 0x40, + 0x81, 0x81, 0x02, 0x06, 0x04, 0xFF, 0x33, 0x33, 0x33, 0x33, 0x33, 0x33, + 0x33, 0x33, 0x33, 0x3F, 0xF0, 0x0C, 0x0E, 0x05, 0x86, 0xC3, 0x21, 0x19, + 0x8C, 0x83, 0xC1, 0x80, 0xFF, 0xFE, 0xE3, 0x8C, 0x30, 0x3F, 0x07, 0xF8, + 0xE1, 0xCC, 0x0C, 0x00, 0xC0, 0x1C, 0x3F, 0xCF, 0x8C, 0xC0, 0xCC, 0x0C, + 0xE3, 0xC7, 0xEF, 0x3C, 0x70, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0xC0, + 0x0C, 0xF8, 0xDF, 0xCF, 0x0E, 0xE0, 0x7C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, + 0x3C, 0x03, 0xE0, 0x6F, 0x0E, 0xDF, 0xCC, 0xF8, 0x1F, 0x0F, 0xE7, 0x1B, + 0x83, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x38, 0x37, 0x1C, 0xFE, 0x1F, + 0x00, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x3C, 0xCF, 0xFB, 0x8F, + 0xE0, 0xF8, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF8, 0x3B, 0x8F, 0x3F, + 0x63, 0xCC, 0x1F, 0x07, 0xF1, 0xC7, 0x70, 0x3C, 0x07, 0xFF, 0xFF, 0xFE, + 0x00, 0xC0, 0x1C, 0x0D, 0xC3, 0x1F, 0xE1, 0xF0, 0x3B, 0xD8, 0xC6, 0x7F, + 0xEC, 0x63, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x00, 0x1E, 0x67, 0xFD, 0xC7, + 0xF0, 0x7C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x7C, 0x1D, 0xC7, 0x9F, + 0xB1, 0xE6, 0x00, 0xC0, 0x3E, 0x0E, 0x7F, 0xC7, 0xE0, 0xC0, 0x30, 0x0C, + 0x03, 0x00, 0xC0, 0x33, 0xCD, 0xFB, 0xC7, 0xE0, 0xF0, 0x3C, 0x0F, 0x03, + 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x30, 0xF0, 0x3F, 0xFF, 0xFF, + 0xF0, 0x33, 0x00, 0x03, 0x33, 0x33, 0x33, 0x33, 0x33, 0x33, 0x33, 0x3F, + 0xE0, 0xC0, 0x18, 0x03, 0x00, 0x60, 0x0C, 0x01, 0x83, 0x30, 0xC6, 0x30, + 0xCC, 0x1B, 0x83, 0xF0, 0x77, 0x0C, 0x61, 0x8E, 0x30, 0xE6, 0x0C, 0xC1, + 0xD8, 0x18, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xCF, 0x1F, 0x6F, 0xDF, 0xFC, + 0x78, 0xFC, 0x18, 0x3C, 0x0C, 0x1E, 0x06, 0x0F, 0x03, 0x07, 0x81, 0x83, + 0xC0, 0xC1, 0xE0, 0x60, 0xF0, 0x30, 0x78, 0x18, 0x3C, 0x0C, 0x18, 0xCF, + 0x37, 0xEF, 0x1F, 0x83, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3C, + 0x0F, 0x03, 0xC0, 0xC0, 0x1F, 0x07, 0xF1, 0xC7, 0x70, 0x7C, 0x07, 0x80, + 0xF0, 0x1E, 0x03, 0xC0, 0x7C, 0x1D, 0xC7, 0x1F, 0xC1, 0xF0, 0xCF, 0x8D, + 0xFC, 0xF0, 0xEE, 0x06, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3E, + 0x07, 0xF0, 0xEF, 0xFC, 0xCF, 0x8C, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x00, + 0x1E, 0x67, 0xFD, 0xC7, 0xF0, 0x7C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, + 0x7C, 0x1D, 0xC7, 0x9F, 0xF1, 0xE6, 0x00, 0xC0, 0x18, 0x03, 0x00, 0x60, + 0xCF, 0x7F, 0x38, 0xC3, 0x0C, 0x30, 0xC3, 0x0C, 0x30, 0xC0, 0x3E, 0x1F, + 0xEE, 0x1B, 0x00, 0xC0, 0x3C, 0x07, 0xF0, 0x3E, 0x01, 0xF0, 0x3E, 0x1D, + 0xFE, 0x3E, 0x00, 0x63, 0x19, 0xFF, 0xB1, 0x8C, 0x63, 0x18, 0xC6, 0x31, + 0xE7, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, + 0xF0, 0x7E, 0x3D, 0xFB, 0x3C, 0xC0, 0xE0, 0x66, 0x06, 0x60, 0x67, 0x0C, + 0x30, 0xC3, 0x0C, 0x39, 0x81, 0x98, 0x19, 0x81, 0xF0, 0x0F, 0x00, 0xE0, + 0x0E, 0x00, 0xC1, 0xC1, 0xB0, 0xE1, 0xD8, 0x70, 0xCC, 0x2C, 0x66, 0x36, + 0x31, 0x9B, 0x18, 0xCD, 0x98, 0x64, 0x6C, 0x16, 0x36, 0x0F, 0x1A, 0x07, + 0x8F, 0x03, 0x83, 0x80, 0xC1, 0xC0, 0x60, 0xEE, 0x18, 0xC6, 0x0C, 0xC1, + 0xF0, 0x1C, 0x01, 0x80, 0x78, 0x1B, 0x03, 0x30, 0xC7, 0x30, 0x66, 0x06, + 0xE0, 0x6C, 0x0D, 0x83, 0x38, 0x63, 0x0C, 0x63, 0x0E, 0x60, 0xCC, 0x1B, + 0x03, 0x60, 0x3C, 0x07, 0x00, 0xE0, 0x18, 0x03, 0x00, 0xE0, 0x78, 0x0E, + 0x00, 0xFF, 0xFF, 0xF0, 0x18, 0x0C, 0x07, 0x03, 0x81, 0xC0, 0x60, 0x30, + 0x18, 0x0E, 0x03, 0xFF, 0xFF, 0xC0, 0x19, 0xCC, 0x63, 0x18, 0xC6, 0x31, + 0x99, 0x86, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x1C, 0x60, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFC, 0xC7, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x0C, 0x33, 0x31, + 0x8C, 0x63, 0x18, 0xC6, 0x73, 0x00, 0x70, 0x3E, 0x09, 0xE4, 0x1F, 0x03, + 0x80 }; + +const GFXglyph FreeSans12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 6, 0, 1 }, // 0x20 ' ' + { 0, 2, 18, 8, 3, -17 }, // 0x21 '!' + { 5, 6, 6, 8, 1, -16 }, // 0x22 '"' + { 10, 13, 16, 13, 0, -15 }, // 0x23 '#' + { 36, 11, 20, 13, 1, -17 }, // 0x24 '$' + { 64, 20, 17, 21, 1, -16 }, // 0x25 '%' + { 107, 14, 17, 16, 1, -16 }, // 0x26 '&' + { 137, 2, 6, 5, 1, -16 }, // 0x27 ''' + { 139, 5, 23, 8, 2, -17 }, // 0x28 '(' + { 154, 5, 23, 8, 1, -17 }, // 0x29 ')' + { 169, 7, 7, 9, 1, -17 }, // 0x2A '*' + { 176, 10, 11, 14, 2, -10 }, // 0x2B '+' + { 190, 2, 6, 7, 2, -1 }, // 0x2C ',' + { 192, 6, 2, 8, 1, -7 }, // 0x2D '-' + { 194, 2, 2, 6, 2, -1 }, // 0x2E '.' + { 195, 7, 18, 7, 0, -17 }, // 0x2F '/' + { 211, 11, 17, 13, 1, -16 }, // 0x30 '0' + { 235, 5, 17, 13, 3, -16 }, // 0x31 '1' + { 246, 11, 17, 13, 1, -16 }, // 0x32 '2' + { 270, 11, 17, 13, 1, -16 }, // 0x33 '3' + { 294, 11, 17, 13, 1, -16 }, // 0x34 '4' + { 318, 11, 17, 13, 1, -16 }, // 0x35 '5' + { 342, 11, 17, 13, 1, -16 }, // 0x36 '6' + { 366, 11, 17, 13, 1, -16 }, // 0x37 '7' + { 390, 11, 17, 13, 1, -16 }, // 0x38 '8' + { 414, 11, 17, 13, 1, -16 }, // 0x39 '9' + { 438, 2, 13, 6, 2, -12 }, // 0x3A ':' + { 442, 2, 16, 6, 2, -11 }, // 0x3B ';' + { 446, 12, 12, 14, 1, -11 }, // 0x3C '<' + { 464, 12, 6, 14, 1, -8 }, // 0x3D '=' + { 473, 12, 12, 14, 1, -11 }, // 0x3E '>' + { 491, 10, 18, 13, 2, -17 }, // 0x3F '?' + { 514, 22, 21, 24, 1, -17 }, // 0x40 '@' + { 572, 16, 18, 16, 0, -17 }, // 0x41 'A' + { 608, 13, 18, 16, 2, -17 }, // 0x42 'B' + { 638, 15, 18, 17, 1, -17 }, // 0x43 'C' + { 672, 14, 18, 17, 2, -17 }, // 0x44 'D' + { 704, 12, 18, 15, 2, -17 }, // 0x45 'E' + { 731, 11, 18, 14, 2, -17 }, // 0x46 'F' + { 756, 16, 18, 18, 1, -17 }, // 0x47 'G' + { 792, 13, 18, 17, 2, -17 }, // 0x48 'H' + { 822, 2, 18, 7, 2, -17 }, // 0x49 'I' + { 827, 9, 18, 13, 1, -17 }, // 0x4A 'J' + { 848, 14, 18, 16, 2, -17 }, // 0x4B 'K' + { 880, 10, 18, 14, 2, -17 }, // 0x4C 'L' + { 903, 16, 18, 20, 2, -17 }, // 0x4D 'M' + { 939, 13, 18, 18, 2, -17 }, // 0x4E 'N' + { 969, 17, 18, 19, 1, -17 }, // 0x4F 'O' + { 1008, 12, 18, 16, 2, -17 }, // 0x50 'P' + { 1035, 17, 19, 19, 1, -17 }, // 0x51 'Q' + { 1076, 14, 18, 17, 2, -17 }, // 0x52 'R' + { 1108, 14, 18, 16, 1, -17 }, // 0x53 'S' + { 1140, 12, 18, 15, 1, -17 }, // 0x54 'T' + { 1167, 13, 18, 17, 2, -17 }, // 0x55 'U' + { 1197, 15, 18, 15, 0, -17 }, // 0x56 'V' + { 1231, 22, 18, 22, 0, -17 }, // 0x57 'W' + { 1281, 15, 18, 16, 0, -17 }, // 0x58 'X' + { 1315, 16, 18, 16, 0, -17 }, // 0x59 'Y' + { 1351, 13, 18, 15, 1, -17 }, // 0x5A 'Z' + { 1381, 4, 23, 7, 2, -17 }, // 0x5B '[' + { 1393, 7, 18, 7, 0, -17 }, // 0x5C '\' + { 1409, 4, 23, 7, 1, -17 }, // 0x5D ']' + { 1421, 9, 9, 11, 1, -16 }, // 0x5E '^' + { 1432, 15, 1, 13, -1, 4 }, // 0x5F '_' + { 1434, 5, 4, 6, 1, -17 }, // 0x60 '`' + { 1437, 12, 13, 13, 1, -12 }, // 0x61 'a' + { 1457, 12, 18, 13, 1, -17 }, // 0x62 'b' + { 1484, 10, 13, 12, 1, -12 }, // 0x63 'c' + { 1501, 11, 18, 13, 1, -17 }, // 0x64 'd' + { 1526, 11, 13, 13, 1, -12 }, // 0x65 'e' + { 1544, 5, 18, 7, 1, -17 }, // 0x66 'f' + { 1556, 11, 18, 13, 1, -12 }, // 0x67 'g' + { 1581, 10, 18, 13, 1, -17 }, // 0x68 'h' + { 1604, 2, 18, 5, 2, -17 }, // 0x69 'i' + { 1609, 4, 23, 6, 0, -17 }, // 0x6A 'j' + { 1621, 11, 18, 12, 1, -17 }, // 0x6B 'k' + { 1646, 2, 18, 5, 1, -17 }, // 0x6C 'l' + { 1651, 17, 13, 19, 1, -12 }, // 0x6D 'm' + { 1679, 10, 13, 13, 1, -12 }, // 0x6E 'n' + { 1696, 11, 13, 13, 1, -12 }, // 0x6F 'o' + { 1714, 12, 17, 13, 1, -12 }, // 0x70 'p' + { 1740, 11, 17, 13, 1, -12 }, // 0x71 'q' + { 1764, 6, 13, 8, 1, -12 }, // 0x72 'r' + { 1774, 10, 13, 12, 1, -12 }, // 0x73 's' + { 1791, 5, 16, 7, 1, -15 }, // 0x74 't' + { 1801, 10, 13, 13, 1, -12 }, // 0x75 'u' + { 1818, 12, 13, 12, 0, -12 }, // 0x76 'v' + { 1838, 17, 13, 17, 0, -12 }, // 0x77 'w' + { 1866, 11, 13, 11, 0, -12 }, // 0x78 'x' + { 1884, 11, 18, 11, 0, -12 }, // 0x79 'y' + { 1909, 10, 13, 12, 1, -12 }, // 0x7A 'z' + { 1926, 5, 23, 8, 1, -17 }, // 0x7B '{' + { 1941, 2, 23, 6, 2, -17 }, // 0x7C '|' + { 1947, 5, 23, 8, 2, -17 }, // 0x7D '}' + { 1962, 10, 5, 12, 1, -10 } }; // 0x7E '~' + +const GFXfont FreeSans12pt7b PROGMEM = { + (uint8_t *)FreeSans12pt7bBitmaps, + (GFXglyph *)FreeSans12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 2641 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSans18pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSans18pt7b.h new file mode 100644 index 0000000..3fdc591 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSans18pt7b.h @@ -0,0 +1,452 @@ +const uint8_t FreeSans18pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE9, 0x20, 0x3F, 0xFC, 0xE3, 0xF1, + 0xF8, 0xFC, 0x7E, 0x3F, 0x1F, 0x8E, 0x82, 0x41, 0x00, 0x01, 0xC3, 0x80, + 0x38, 0x70, 0x06, 0x0E, 0x00, 0xC1, 0x80, 0x38, 0x70, 0x07, 0x0E, 0x0F, + 0xFF, 0xF9, 0xFF, 0xFF, 0x3F, 0xFF, 0xE0, 0xE1, 0xC0, 0x1C, 0x38, 0x03, + 0x87, 0x00, 0x70, 0xE0, 0x0C, 0x18, 0x3F, 0xFF, 0xF7, 0xFF, 0xFE, 0xFF, + 0xFF, 0xC1, 0xC3, 0x80, 0x30, 0x60, 0x06, 0x0C, 0x01, 0xC3, 0x80, 0x38, + 0x70, 0x07, 0x0E, 0x00, 0xC1, 0x80, 0x03, 0x00, 0x0F, 0xC0, 0x3F, 0xF0, + 0x3F, 0xF8, 0x7B, 0x3C, 0xF3, 0x1C, 0xE3, 0x0E, 0xE3, 0x0E, 0xE3, 0x0E, + 0xE3, 0x00, 0xE3, 0x00, 0xF3, 0x00, 0x7B, 0x00, 0x7F, 0x80, 0x1F, 0xF0, + 0x07, 0xFC, 0x03, 0x7E, 0x03, 0x0F, 0x03, 0x07, 0xE3, 0x07, 0xE3, 0x07, + 0xE3, 0x07, 0xE3, 0x0F, 0x73, 0x3E, 0x7F, 0xFC, 0x3F, 0xF8, 0x0F, 0xE0, + 0x03, 0x00, 0x03, 0x00, 0x03, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x78, 0x00, + 0xE0, 0x0F, 0xF0, 0x06, 0x00, 0xFF, 0xC0, 0x70, 0x07, 0x0E, 0x07, 0x00, + 0x70, 0x38, 0x38, 0x03, 0x00, 0xC3, 0x80, 0x18, 0x06, 0x1C, 0x00, 0xE0, + 0x71, 0xC0, 0x03, 0x87, 0x8C, 0x00, 0x1F, 0xF8, 0xE0, 0x00, 0x7F, 0x86, + 0x00, 0x01, 0xF8, 0x70, 0x00, 0x00, 0x03, 0x03, 0xC0, 0x00, 0x38, 0x7F, + 0x80, 0x01, 0x87, 0xFE, 0x00, 0x1C, 0x38, 0x70, 0x00, 0xC3, 0x81, 0xC0, + 0x0E, 0x18, 0x06, 0x00, 0xE0, 0xC0, 0x30, 0x07, 0x07, 0x03, 0x80, 0x70, + 0x1C, 0x38, 0x03, 0x80, 0xFF, 0xC0, 0x38, 0x03, 0xFC, 0x01, 0x80, 0x07, + 0x80, 0x01, 0xF0, 0x00, 0x7F, 0x80, 0x0F, 0xFC, 0x01, 0xE1, 0xE0, 0x1C, + 0x0E, 0x01, 0xC0, 0xE0, 0x1C, 0x0E, 0x01, 0xE1, 0xE0, 0x0E, 0x3C, 0x00, + 0x77, 0x80, 0x07, 0xF0, 0x00, 0x7C, 0x00, 0x0F, 0xE0, 0x03, 0xCF, 0x1C, + 0x78, 0x79, 0xC7, 0x03, 0xDC, 0xE0, 0x1F, 0x8E, 0x00, 0xF8, 0xE0, 0x0F, + 0x0E, 0x00, 0x70, 0xF0, 0x0F, 0x87, 0xC3, 0xFC, 0x7F, 0xFD, 0xC3, 0xFF, + 0x0E, 0x0F, 0xC0, 0xF0, 0xFF, 0xFF, 0xFA, 0x40, 0x06, 0x06, 0x0C, 0x0C, + 0x18, 0x18, 0x38, 0x30, 0x70, 0x70, 0x70, 0x60, 0xE0, 0xE0, 0xE0, 0xE0, + 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0x60, 0x70, 0x70, 0x70, 0x30, 0x38, 0x18, + 0x18, 0x0C, 0x0C, 0x06, 0x03, 0xC0, 0x60, 0x30, 0x30, 0x38, 0x18, 0x1C, + 0x0C, 0x0E, 0x0E, 0x0E, 0x06, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, + 0x07, 0x07, 0x06, 0x0E, 0x0E, 0x0E, 0x0C, 0x1C, 0x18, 0x38, 0x30, 0x30, + 0x60, 0xC0, 0x0C, 0x03, 0x00, 0xC3, 0xB7, 0xFF, 0xC7, 0x81, 0xE0, 0xEC, + 0x73, 0x88, 0x40, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, + 0x80, 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x01, 0x80, 0x01, + 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0xFF, + 0xF6, 0xDA, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0xC0, 0x30, 0x18, + 0x06, 0x01, 0x80, 0xC0, 0x30, 0x0C, 0x06, 0x01, 0x80, 0x60, 0x30, 0x0C, + 0x03, 0x00, 0xC0, 0x60, 0x18, 0x06, 0x03, 0x00, 0xC0, 0x30, 0x18, 0x06, + 0x01, 0x80, 0xC0, 0x30, 0x00, 0x07, 0xE0, 0x0F, 0xF8, 0x1F, 0xFC, 0x3C, + 0x3C, 0x78, 0x1E, 0x70, 0x0E, 0x70, 0x0E, 0xE0, 0x07, 0xE0, 0x07, 0xE0, + 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, + 0x07, 0xE0, 0x07, 0xE0, 0x0F, 0x70, 0x0E, 0x70, 0x0E, 0x78, 0x1E, 0x3C, + 0x3C, 0x1F, 0xF8, 0x1F, 0xF0, 0x07, 0xE0, 0x03, 0x03, 0x07, 0x0F, 0x3F, + 0xFF, 0xFF, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, + 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0xE0, 0x1F, 0xF8, + 0x3F, 0xFC, 0x7C, 0x3E, 0x70, 0x0F, 0xF0, 0x0F, 0xE0, 0x07, 0xE0, 0x07, + 0x00, 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0xF8, + 0x03, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x3C, 0x00, 0x38, 0x00, 0x70, 0x00, + 0x60, 0x00, 0xE0, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x07, 0xF0, + 0x07, 0xFE, 0x07, 0xFF, 0x87, 0x83, 0xC3, 0x80, 0xF3, 0x80, 0x39, 0xC0, + 0x1C, 0xE0, 0x0E, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x7F, 0x00, 0x3F, 0x00, + 0x1F, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x03, 0xF0, 0x01, + 0xF8, 0x00, 0xFE, 0x00, 0x77, 0x00, 0x73, 0xE0, 0xF8, 0xFF, 0xF8, 0x3F, + 0xF8, 0x07, 0xF0, 0x00, 0x00, 0x38, 0x00, 0x38, 0x00, 0x78, 0x00, 0xF8, + 0x00, 0xF8, 0x01, 0xF8, 0x03, 0xB8, 0x03, 0x38, 0x07, 0x38, 0x0E, 0x38, + 0x1C, 0x38, 0x18, 0x38, 0x38, 0x38, 0x70, 0x38, 0x60, 0x38, 0xE0, 0x38, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, + 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x1F, 0xFF, 0x0F, 0xFF, 0x8F, 0xFF, + 0xC7, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x39, + 0xF0, 0x3F, 0xFE, 0x1F, 0xFF, 0x8F, 0x83, 0xE7, 0x00, 0xF0, 0x00, 0x3C, + 0x00, 0x0E, 0x00, 0x07, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xFC, 0x00, + 0xEF, 0x00, 0x73, 0xC0, 0xF0, 0xFF, 0xF8, 0x3F, 0xF8, 0x07, 0xE0, 0x00, + 0x03, 0xE0, 0x0F, 0xF8, 0x1F, 0xFC, 0x3C, 0x1E, 0x38, 0x0E, 0x70, 0x0E, + 0x70, 0x00, 0x60, 0x00, 0xE0, 0x00, 0xE3, 0xE0, 0xEF, 0xF8, 0xFF, 0xFC, + 0xFC, 0x3E, 0xF0, 0x0E, 0xF0, 0x0F, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, + 0x60, 0x07, 0x70, 0x0F, 0x70, 0x0E, 0x3C, 0x3E, 0x3F, 0xFC, 0x1F, 0xF8, + 0x07, 0xE0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x06, 0x00, 0x0E, + 0x00, 0x1C, 0x00, 0x18, 0x00, 0x38, 0x00, 0x70, 0x00, 0x60, 0x00, 0xE0, + 0x00, 0xC0, 0x01, 0xC0, 0x01, 0x80, 0x03, 0x80, 0x03, 0x80, 0x07, 0x00, + 0x07, 0x00, 0x07, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0C, 0x00, + 0x1C, 0x00, 0x1C, 0x00, 0x07, 0xF0, 0x0F, 0xFE, 0x0F, 0xFF, 0x87, 0x83, + 0xC7, 0x80, 0xF3, 0x80, 0x39, 0xC0, 0x1C, 0xE0, 0x0E, 0x78, 0x0F, 0x1E, + 0x0F, 0x07, 0xFF, 0x01, 0xFF, 0x03, 0xFF, 0xE3, 0xE0, 0xF9, 0xC0, 0x1D, + 0xC0, 0x0F, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0xF7, 0x00, + 0x73, 0xE0, 0xF8, 0xFF, 0xF8, 0x3F, 0xF8, 0x07, 0xF0, 0x00, 0x07, 0xE0, + 0x1F, 0xF8, 0x3F, 0xFC, 0x7C, 0x3C, 0x70, 0x0E, 0xF0, 0x0E, 0xE0, 0x06, + 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x0F, 0x70, 0x0F, 0x78, 0x3F, + 0x3F, 0xFF, 0x1F, 0xF7, 0x07, 0xC7, 0x00, 0x07, 0x00, 0x06, 0x00, 0x0E, + 0x70, 0x0E, 0x70, 0x1C, 0x78, 0x3C, 0x3F, 0xF8, 0x1F, 0xF0, 0x07, 0xC0, + 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x07, 0xFF, 0x80, 0xFF, 0xF0, 0x00, 0x00, + 0x00, 0x07, 0xFF, 0xB6, 0xD6, 0x00, 0x00, 0x80, 0x03, 0xC0, 0x07, 0xE0, + 0x0F, 0xC0, 0x3F, 0x80, 0x7E, 0x00, 0xFC, 0x01, 0xF0, 0x00, 0xE0, 0x00, + 0x7C, 0x00, 0x1F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x80, 0x07, 0xF0, 0x00, + 0x7E, 0x00, 0x0F, 0x00, 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0x80, 0x80, 0x00, 0x70, 0x00, 0x3E, 0x00, 0x0F, 0xE0, 0x00, 0xFC, + 0x00, 0x1F, 0xC0, 0x03, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0x80, 0x0F, 0xC0, + 0x1F, 0x80, 0x7F, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x01, 0xC0, 0x00, + 0x80, 0x00, 0x00, 0x0F, 0xC0, 0x7F, 0xE1, 0xFF, 0xE3, 0xC3, 0xEF, 0x01, + 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, 0x00, 0x0E, 0x00, 0x38, 0x00, 0xF0, + 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x00, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x0E, + 0x00, 0x1C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xC0, 0x03, 0x80, + 0x07, 0x00, 0x0E, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x3F, 0xFF, 0x00, + 0x00, 0xFF, 0xFF, 0xC0, 0x01, 0xF8, 0x0F, 0xE0, 0x03, 0xE0, 0x01, 0xF0, + 0x07, 0x80, 0x00, 0xF8, 0x0F, 0x00, 0x00, 0x3C, 0x1E, 0x00, 0x00, 0x1E, + 0x3C, 0x03, 0xE0, 0x1E, 0x38, 0x0F, 0xF3, 0x8E, 0x78, 0x1E, 0x3F, 0x0F, + 0x70, 0x38, 0x1F, 0x07, 0x70, 0x78, 0x0F, 0x07, 0xE0, 0x70, 0x0E, 0x07, + 0xE0, 0x70, 0x0E, 0x07, 0xE0, 0xE0, 0x0E, 0x07, 0xE0, 0xE0, 0x1C, 0x07, + 0xE0, 0xE0, 0x1C, 0x0E, 0xE0, 0xE0, 0x1C, 0x0E, 0xE0, 0xE0, 0x38, 0x1C, + 0xF0, 0x70, 0x78, 0x3C, 0x70, 0x78, 0xFC, 0x78, 0x78, 0x3F, 0xDF, 0xF0, + 0x38, 0x1F, 0x0F, 0xC0, 0x3C, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x00, 0x07, 0xF0, 0x0E, 0x00, 0x01, 0xFF, 0xFE, 0x00, + 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x03, + 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xDC, 0x00, 0x07, 0x78, + 0x00, 0x3C, 0xE0, 0x00, 0xE3, 0x80, 0x03, 0x8F, 0x00, 0x1E, 0x1C, 0x00, + 0x70, 0x70, 0x01, 0xC1, 0xE0, 0x0E, 0x03, 0x80, 0x38, 0x0E, 0x00, 0xE0, + 0x3C, 0x07, 0xFF, 0xF0, 0x1F, 0xFF, 0xE0, 0xFF, 0xFF, 0x83, 0xC0, 0x0E, + 0x0E, 0x00, 0x3C, 0x78, 0x00, 0xF1, 0xE0, 0x01, 0xC7, 0x00, 0x07, 0xBC, + 0x00, 0x1E, 0xF0, 0x00, 0x3B, 0x80, 0x00, 0xF0, 0xFF, 0xFC, 0x1F, 0xFF, + 0xE3, 0xFF, 0xFE, 0x70, 0x03, 0xCE, 0x00, 0x3D, 0xC0, 0x03, 0xB8, 0x00, + 0x77, 0x00, 0x0E, 0xE0, 0x01, 0xDC, 0x00, 0x73, 0x80, 0x1E, 0x7F, 0xFF, + 0x8F, 0xFF, 0xF1, 0xFF, 0xFF, 0x38, 0x00, 0xF7, 0x00, 0x0E, 0xE0, 0x00, + 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x03, + 0xF8, 0x00, 0xF7, 0xFF, 0xFC, 0xFF, 0xFF, 0x1F, 0xFF, 0x80, 0x00, 0xFF, + 0x00, 0x0F, 0xFF, 0x00, 0xFF, 0xFE, 0x07, 0xE0, 0x7C, 0x3E, 0x00, 0x78, + 0xF0, 0x00, 0xE7, 0x80, 0x03, 0xDC, 0x00, 0x07, 0x70, 0x00, 0x03, 0x80, + 0x00, 0x0E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x03, 0x80, 0x00, + 0x0E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x1D, 0xC0, 0x00, 0x77, + 0x00, 0x03, 0xDE, 0x00, 0x0E, 0x3C, 0x00, 0x78, 0xF8, 0x03, 0xC1, 0xF8, + 0x1F, 0x03, 0xFF, 0xF8, 0x03, 0xFF, 0xC0, 0x03, 0xF8, 0x00, 0xFF, 0xF8, + 0x0F, 0xFF, 0xE0, 0xFF, 0xFF, 0x0E, 0x00, 0xF8, 0xE0, 0x03, 0xCE, 0x00, + 0x1C, 0xE0, 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xFE, 0x00, 0x07, 0xE0, + 0x00, 0x7E, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x07, 0xE0, 0x00, 0x7E, + 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x0F, 0xE0, 0x00, 0xEE, 0x00, 0x0E, + 0xE0, 0x01, 0xEE, 0x00, 0x3C, 0xE0, 0x0F, 0x8F, 0xFF, 0xF0, 0xFF, 0xFE, + 0x0F, 0xFF, 0x80, 0xFF, 0xFF, 0xBF, 0xFF, 0xEF, 0xFF, 0xFB, 0x80, 0x00, + 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, 0x00, 0x38, + 0x00, 0x0E, 0x00, 0x03, 0xFF, 0xFE, 0xFF, 0xFF, 0xBF, 0xFF, 0xEE, 0x00, + 0x03, 0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, + 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x0E, 0x00, + 0x07, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x38, + 0x00, 0x1F, 0xFF, 0xCF, 0xFF, 0xE7, 0xFF, 0xF3, 0x80, 0x01, 0xC0, 0x00, + 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, 0x00, + 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x00, 0x00, 0x7F, + 0x80, 0x03, 0xFF, 0xE0, 0x07, 0xFF, 0xF8, 0x0F, 0x80, 0xFC, 0x1E, 0x00, + 0x3E, 0x3C, 0x00, 0x0E, 0x78, 0x00, 0x0F, 0x70, 0x00, 0x07, 0x70, 0x00, + 0x00, 0xE0, 0x00, 0x00, 0xE0, 0x00, 0x00, 0xE0, 0x00, 0x00, 0xE0, 0x03, + 0xFF, 0xE0, 0x03, 0xFF, 0xE0, 0x03, 0xFF, 0xE0, 0x00, 0x07, 0xF0, 0x00, + 0x07, 0x70, 0x00, 0x07, 0x70, 0x00, 0x0F, 0x78, 0x00, 0x0F, 0x3C, 0x00, + 0x1F, 0x1E, 0x00, 0x3F, 0x0F, 0xC0, 0xF7, 0x07, 0xFF, 0xE7, 0x03, 0xFF, + 0xC3, 0x00, 0xFF, 0x03, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, + 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0, + 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, + 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00, + 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1C, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, + 0x1C, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xC0, + 0x07, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, 0x1F, 0x80, 0x7E, + 0x01, 0xF8, 0x07, 0xE0, 0x1F, 0xC0, 0xF7, 0x87, 0x9F, 0xFE, 0x3F, 0xF0, + 0x3F, 0x00, 0xE0, 0x01, 0xEE, 0x00, 0x3C, 0xE0, 0x07, 0x8E, 0x00, 0xF0, + 0xE0, 0x1E, 0x0E, 0x03, 0xE0, 0xE0, 0x7C, 0x0E, 0x0F, 0x80, 0xE1, 0xF0, + 0x0E, 0x1E, 0x00, 0xE3, 0xC0, 0x0E, 0x7C, 0x00, 0xEF, 0xE0, 0x0F, 0xCE, + 0x00, 0xF8, 0xF0, 0x0F, 0x07, 0x80, 0xE0, 0x3C, 0x0E, 0x03, 0xC0, 0xE0, + 0x1E, 0x0E, 0x00, 0xF0, 0xE0, 0x0F, 0x0E, 0x00, 0x78, 0xE0, 0x03, 0xCE, + 0x00, 0x3C, 0xE0, 0x01, 0xEE, 0x00, 0x0F, 0xE0, 0x01, 0xC0, 0x03, 0x80, + 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x01, + 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x70, + 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00, + 0x38, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xF8, 0x00, 0x1F, 0xF8, + 0x00, 0x1F, 0xF8, 0x00, 0x1F, 0xFC, 0x00, 0x3F, 0xFC, 0x00, 0x3F, 0xFC, + 0x00, 0x3F, 0xEE, 0x00, 0x77, 0xEE, 0x00, 0x77, 0xEE, 0x00, 0x77, 0xE7, + 0x00, 0xE7, 0xE7, 0x00, 0xE7, 0xE7, 0x00, 0xE7, 0xE3, 0x81, 0xC7, 0xE3, + 0x81, 0xC7, 0xE3, 0x81, 0xC7, 0xE1, 0xC3, 0x87, 0xE1, 0xC3, 0x87, 0xE1, + 0xC3, 0x87, 0xE0, 0xE7, 0x07, 0xE0, 0xE7, 0x07, 0xE0, 0xE7, 0x07, 0xE0, + 0x7E, 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0x3C, 0x07, 0xE0, + 0x3C, 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xF8, 0x00, 0x7F, 0xC0, 0x07, + 0xFC, 0x00, 0x7F, 0xE0, 0x07, 0xEF, 0x00, 0x7E, 0x70, 0x07, 0xE7, 0x80, + 0x7E, 0x3C, 0x07, 0xE1, 0xC0, 0x7E, 0x1E, 0x07, 0xE0, 0xE0, 0x7E, 0x0F, + 0x07, 0xE0, 0x78, 0x7E, 0x03, 0x87, 0xE0, 0x3C, 0x7E, 0x01, 0xE7, 0xE0, + 0x0E, 0x7E, 0x00, 0xF7, 0xE0, 0x07, 0xFE, 0x00, 0x3F, 0xE0, 0x03, 0xFE, + 0x00, 0x1F, 0xE0, 0x01, 0xFE, 0x00, 0x0F, 0x00, 0x7F, 0x00, 0x01, 0xFF, + 0xF0, 0x01, 0xFF, 0xFC, 0x01, 0xF0, 0x1F, 0x01, 0xE0, 0x03, 0xC1, 0xE0, + 0x00, 0xF1, 0xE0, 0x00, 0x3C, 0xE0, 0x00, 0x0E, 0x70, 0x00, 0x07, 0x70, + 0x00, 0x03, 0xF8, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, + 0x00, 0x00, 0x1F, 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03, + 0xB8, 0x00, 0x03, 0x9C, 0x00, 0x01, 0xCF, 0x00, 0x01, 0xE3, 0xC0, 0x01, + 0xE0, 0xF0, 0x01, 0xE0, 0x3E, 0x03, 0xE0, 0x0F, 0xFF, 0xE0, 0x03, 0xFF, + 0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFF, 0xFC, 0x3F, 0xFF, 0x8F, 0xFF, 0xF3, + 0x80, 0x3E, 0xE0, 0x03, 0xF8, 0x00, 0x7E, 0x00, 0x1F, 0x80, 0x07, 0xE0, + 0x01, 0xF8, 0x00, 0x7E, 0x00, 0x3F, 0x80, 0x1E, 0xFF, 0xFF, 0x3F, 0xFF, + 0x8F, 0xFF, 0xC3, 0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, + 0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, + 0x00, 0x38, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x01, 0xFF, 0xF0, 0x01, 0xFF, + 0xFC, 0x01, 0xF0, 0x1F, 0x01, 0xE0, 0x03, 0xC1, 0xE0, 0x00, 0xF1, 0xE0, + 0x00, 0x3C, 0xE0, 0x00, 0x0E, 0x70, 0x00, 0x07, 0x70, 0x00, 0x01, 0xF8, + 0x00, 0x00, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, + 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x07, 0xB8, 0x00, 0x03, + 0x9C, 0x00, 0x01, 0xCF, 0x00, 0x39, 0xE3, 0xC0, 0x1F, 0xE0, 0xF0, 0x07, + 0xE0, 0x3E, 0x03, 0xF0, 0x0F, 0xFF, 0xFC, 0x03, 0xFF, 0xEE, 0x00, 0x3F, + 0x83, 0x80, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x20, 0xFF, 0xFE, 0x0F, 0xFF, + 0xF8, 0xFF, 0xFF, 0xCE, 0x00, 0x3C, 0xE0, 0x01, 0xEE, 0x00, 0x0E, 0xE0, + 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x01, 0xCE, + 0x00, 0x3C, 0xFF, 0xFF, 0x8F, 0xFF, 0xF0, 0xFF, 0xFF, 0x8E, 0x00, 0x3C, + 0xE0, 0x01, 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x00, + 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xEE, 0x00, 0x0E, 0xE0, 0x00, 0xFE, 0x00, + 0x0F, 0x03, 0xFC, 0x00, 0xFF, 0xF0, 0x1F, 0xFF, 0x83, 0xE0, 0x7C, 0x38, + 0x01, 0xE7, 0x00, 0x0E, 0x70, 0x00, 0xE7, 0x00, 0x00, 0x70, 0x00, 0x07, + 0x80, 0x00, 0x3E, 0x00, 0x01, 0xFE, 0x00, 0x0F, 0xFE, 0x00, 0x3F, 0xF8, + 0x00, 0x3F, 0xE0, 0x00, 0x3E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0xE0, 0x00, + 0x7E, 0x00, 0x07, 0xF0, 0x00, 0x77, 0x80, 0x0E, 0x7C, 0x03, 0xE3, 0xFF, + 0xFC, 0x1F, 0xFF, 0x80, 0x3F, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0x80, 0x70, 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x07, + 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x0E, + 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x1C, + 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x38, + 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0xE0, 0x00, 0xFC, 0x00, + 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, + 0x3F, 0x00, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, + 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0, 0x00, + 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7F, 0x00, 0x1E, 0xF0, 0x07, + 0x9F, 0x01, 0xF1, 0xFF, 0xFC, 0x1F, 0xFE, 0x00, 0x7F, 0x00, 0xE0, 0x00, + 0x7F, 0x80, 0x03, 0xFC, 0x00, 0x1C, 0xE0, 0x01, 0xE7, 0x80, 0x0F, 0x3C, + 0x00, 0x70, 0xE0, 0x07, 0x87, 0x80, 0x3C, 0x1C, 0x01, 0xC0, 0xE0, 0x0E, + 0x07, 0x80, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x38, 0x07, 0x83, 0x80, 0x1C, + 0x1C, 0x00, 0xE0, 0xE0, 0x07, 0x8E, 0x00, 0x1C, 0x70, 0x00, 0xE3, 0x80, + 0x07, 0xB8, 0x00, 0x1D, 0xC0, 0x00, 0xEE, 0x00, 0x07, 0xE0, 0x00, 0x1F, + 0x00, 0x00, 0xF8, 0x00, 0x03, 0x80, 0x00, 0x70, 0x03, 0xC0, 0x0F, 0x70, + 0x03, 0xC0, 0x0F, 0x78, 0x03, 0xE0, 0x0F, 0x78, 0x03, 0xE0, 0x0E, 0x38, + 0x07, 0xE0, 0x0E, 0x38, 0x07, 0xF0, 0x1E, 0x3C, 0x07, 0x70, 0x1E, 0x3C, + 0x07, 0x70, 0x1C, 0x1C, 0x0E, 0x70, 0x1C, 0x1C, 0x0E, 0x38, 0x3C, 0x1C, + 0x0E, 0x38, 0x3C, 0x1E, 0x1E, 0x38, 0x38, 0x0E, 0x1C, 0x38, 0x38, 0x0E, + 0x1C, 0x1C, 0x38, 0x0E, 0x1C, 0x1C, 0x78, 0x0F, 0x3C, 0x1C, 0x70, 0x07, + 0x38, 0x0E, 0x70, 0x07, 0x38, 0x0E, 0x70, 0x07, 0x38, 0x0E, 0x70, 0x07, + 0x70, 0x0E, 0xE0, 0x03, 0xF0, 0x07, 0xE0, 0x03, 0xF0, 0x07, 0xE0, 0x03, + 0xF0, 0x07, 0xE0, 0x03, 0xE0, 0x03, 0xC0, 0x01, 0xE0, 0x03, 0xC0, 0x01, + 0xE0, 0x03, 0xC0, 0xF0, 0x00, 0x7B, 0xC0, 0x07, 0x8F, 0x00, 0x38, 0x78, + 0x03, 0xC1, 0xE0, 0x3C, 0x07, 0x81, 0xC0, 0x3C, 0x1E, 0x00, 0xF1, 0xE0, + 0x03, 0x8E, 0x00, 0x1E, 0xF0, 0x00, 0x7F, 0x00, 0x01, 0xF0, 0x00, 0x0F, + 0x80, 0x00, 0x7C, 0x00, 0x07, 0xF0, 0x00, 0x3B, 0x80, 0x03, 0xDE, 0x00, + 0x3C, 0x78, 0x01, 0xC1, 0xC0, 0x1E, 0x0F, 0x01, 0xE0, 0x3C, 0x0E, 0x00, + 0xE0, 0xF0, 0x07, 0x8F, 0x00, 0x1E, 0x70, 0x00, 0xF7, 0x80, 0x03, 0xC0, + 0xF0, 0x00, 0x3C, 0xF0, 0x00, 0x78, 0xF0, 0x01, 0xE1, 0xE0, 0x03, 0x81, + 0xE0, 0x0F, 0x01, 0xC0, 0x1C, 0x03, 0xC0, 0x78, 0x03, 0xC1, 0xE0, 0x07, + 0x83, 0x80, 0x07, 0x8F, 0x00, 0x07, 0x1C, 0x00, 0x0F, 0x78, 0x00, 0x0E, + 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, + 0x00, 0x00, 0x70, 0x00, 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, + 0x00, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, + 0x00, 0x70, 0x00, 0x7F, 0xFF, 0xEF, 0xFF, 0xFD, 0xFF, 0xFF, 0x80, 0x00, + 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, + 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, + 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x7C, 0x00, + 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xF8, 0xE3, 0x8E, 0x38, 0xE3, + 0x8E, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x8E, 0x38, 0xE3, + 0x8E, 0x38, 0xE3, 0x8F, 0xFF, 0xFC, 0xC0, 0x30, 0x06, 0x01, 0x80, 0x60, + 0x0C, 0x03, 0x00, 0xC0, 0x18, 0x06, 0x01, 0x80, 0x20, 0x0C, 0x03, 0x00, + 0x40, 0x18, 0x06, 0x01, 0x80, 0x30, 0x0C, 0x03, 0x00, 0x60, 0x18, 0x06, + 0x00, 0xC0, 0x30, 0xFF, 0xFF, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, + 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, + 0x1C, 0x7F, 0xFF, 0xFC, 0x07, 0x00, 0x78, 0x03, 0xC0, 0x3F, 0x01, 0xD8, + 0x0C, 0xE0, 0xE3, 0x06, 0x1C, 0x70, 0xE3, 0x83, 0x18, 0x1D, 0xC0, 0x6C, + 0x03, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xF0, 0xF0, 0xE0, 0xE0, + 0xE0, 0x07, 0xF0, 0x0F, 0xFC, 0x0F, 0xFF, 0x0F, 0x03, 0xC7, 0x00, 0xE0, + 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0xFE, 0x0F, 0xFF, 0x1F, 0xF3, + 0x9F, 0x01, 0xCF, 0x00, 0xE7, 0x00, 0x73, 0x80, 0x79, 0xE0, 0xFC, 0x7F, + 0xEF, 0x9F, 0xE3, 0xC7, 0xE1, 0xE0, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, + 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE3, 0xE0, 0xEF, 0xF8, + 0xFF, 0xFC, 0xFC, 0x3E, 0xF8, 0x1E, 0xF0, 0x0E, 0xE0, 0x0F, 0xE0, 0x07, + 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xF0, 0x0E, + 0xF8, 0x1E, 0xFC, 0x3C, 0xEF, 0xFC, 0xEF, 0xF8, 0xE3, 0xE0, 0x07, 0xF0, + 0x1F, 0xF8, 0x3F, 0xFC, 0x3C, 0x1E, 0x78, 0x0E, 0x70, 0x07, 0xE0, 0x00, + 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x07, + 0x70, 0x07, 0x78, 0x0E, 0x7C, 0x1E, 0x3F, 0xFC, 0x1F, 0xF8, 0x07, 0xE0, + 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, + 0x1C, 0x00, 0x0E, 0x0F, 0xC7, 0x1F, 0xFB, 0x9F, 0xFF, 0xDF, 0x07, 0xEF, + 0x01, 0xF7, 0x00, 0x7F, 0x80, 0x3F, 0x80, 0x0F, 0xC0, 0x07, 0xE0, 0x03, + 0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0x77, 0x00, 0x7B, 0xC0, 0x7D, 0xF0, + 0x7E, 0x7F, 0xFB, 0x1F, 0xF9, 0x83, 0xF0, 0xC0, 0x07, 0xE0, 0x1F, 0xF8, + 0x3F, 0xFC, 0x7C, 0x1E, 0x70, 0x0E, 0x60, 0x06, 0xE0, 0x07, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0x70, 0x07, + 0x78, 0x0E, 0x3C, 0x1E, 0x3F, 0xFC, 0x1F, 0xF8, 0x07, 0xE0, 0x0E, 0x3C, + 0xF9, 0xC3, 0x87, 0x0E, 0x7F, 0xFF, 0xFC, 0xE1, 0xC3, 0x87, 0x0E, 0x1C, + 0x38, 0x70, 0xE1, 0xC3, 0x87, 0x0E, 0x1C, 0x38, 0x70, 0x07, 0xC7, 0x1F, + 0xF7, 0x3F, 0xFF, 0x3C, 0x3F, 0x78, 0x0F, 0x70, 0x0F, 0xE0, 0x07, 0xE0, + 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0x70, + 0x0F, 0x78, 0x0F, 0x7C, 0x3F, 0x3F, 0xF7, 0x1F, 0xE7, 0x07, 0xC7, 0x00, + 0x07, 0x00, 0x07, 0x00, 0x0E, 0x70, 0x0E, 0x78, 0x1E, 0x3F, 0xFC, 0x1F, + 0xF8, 0x07, 0xE0, 0xE0, 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, + 0x1C, 0x00, 0x38, 0x00, 0x71, 0xF8, 0xE7, 0xFD, 0xDF, 0xFB, 0xF0, 0xFF, + 0xC0, 0xFF, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, 0xE0, 0x0F, 0xC0, + 0x1F, 0x80, 0x3F, 0x00, 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, + 0xE0, 0x0F, 0xC0, 0x1C, 0xFF, 0xF0, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFC, 0x1C, 0x71, 0xC7, 0x00, 0x00, 0x07, 0x1C, 0x71, 0xC7, 0x1C, + 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, + 0x73, 0xFF, 0xFB, 0xC0, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, + 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x3C, 0xE0, 0x78, 0xE0, 0xF0, + 0xE1, 0xE0, 0xE3, 0xC0, 0xE7, 0x80, 0xEF, 0x00, 0xEF, 0x80, 0xFF, 0x80, + 0xFB, 0xC0, 0xF1, 0xE0, 0xE0, 0xE0, 0xE0, 0xF0, 0xE0, 0x70, 0xE0, 0x78, + 0xE0, 0x3C, 0xE0, 0x1C, 0xE0, 0x1E, 0xE0, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xE3, 0xE0, 0xF8, 0xE7, 0xF1, 0xFE, + 0xEF, 0xFB, 0xFE, 0xF8, 0x7F, 0x0F, 0xF0, 0x3E, 0x07, 0xF0, 0x1C, 0x07, + 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, + 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, + 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, 0xE0, 0x1C, 0x07, + 0xE0, 0x1C, 0x07, 0xE3, 0xF1, 0xCF, 0xFB, 0xBF, 0xF7, 0xE1, 0xFF, 0x81, + 0xFE, 0x01, 0xF8, 0x03, 0xF0, 0x07, 0xE0, 0x0F, 0xC0, 0x1F, 0x80, 0x3F, + 0x00, 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, 0xE0, 0x0F, 0xC0, + 0x1F, 0x80, 0x38, 0x07, 0xF0, 0x0F, 0xFE, 0x0F, 0xFF, 0x87, 0x83, 0xC7, + 0x80, 0xF3, 0x80, 0x3B, 0x80, 0x1F, 0xC0, 0x07, 0xE0, 0x03, 0xF0, 0x01, + 0xF8, 0x00, 0xFC, 0x00, 0x7E, 0x00, 0x3B, 0x80, 0x39, 0xE0, 0x3C, 0x78, + 0x3C, 0x3F, 0xFE, 0x0F, 0xFE, 0x01, 0xFC, 0x00, 0xE3, 0xE0, 0xE7, 0xF8, + 0xEF, 0xFC, 0xFC, 0x3E, 0xF8, 0x1E, 0xF0, 0x0E, 0xE0, 0x0F, 0xE0, 0x07, + 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xF0, 0x0E, + 0xF8, 0x1E, 0xFC, 0x3E, 0xFF, 0xFC, 0xEF, 0xF8, 0xE3, 0xE0, 0xE0, 0x00, + 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0x07, 0xE1, + 0x8F, 0xFC, 0xCF, 0xFF, 0x67, 0x83, 0xF7, 0x80, 0xFB, 0x80, 0x3F, 0xC0, + 0x1F, 0xC0, 0x07, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0x7E, + 0x00, 0x3B, 0x80, 0x3D, 0xE0, 0x3E, 0xF8, 0x3F, 0x3F, 0xFF, 0x8F, 0xFD, + 0xC1, 0xF8, 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, + 0x07, 0x00, 0x03, 0x80, 0xE3, 0xF7, 0xFB, 0xFF, 0x8F, 0x07, 0x83, 0x81, + 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, + 0x38, 0x00, 0x0F, 0xC0, 0xFF, 0x87, 0xFF, 0x3C, 0x1E, 0xE0, 0x3B, 0x80, + 0x0E, 0x00, 0x3C, 0x00, 0x7F, 0x00, 0xFF, 0x80, 0xFF, 0x80, 0x7F, 0x00, + 0x3F, 0x80, 0x7E, 0x01, 0xFC, 0x1F, 0x7F, 0xF8, 0xFF, 0xC1, 0xFC, 0x00, + 0x38, 0x70, 0xE1, 0xCF, 0xFF, 0xFF, 0x9C, 0x38, 0x70, 0xE1, 0xC3, 0x87, + 0x0E, 0x1C, 0x38, 0x70, 0xE1, 0xC3, 0xE7, 0xC7, 0x80, 0xE0, 0x0F, 0xC0, + 0x1F, 0x80, 0x3F, 0x00, 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, 0x07, + 0xE0, 0x0F, 0xC0, 0x1F, 0x80, 0x3F, 0x00, 0x7E, 0x00, 0xFC, 0x03, 0xFC, + 0x0F, 0xFC, 0x3F, 0x7F, 0xEE, 0xFF, 0x9C, 0x7E, 0x38, 0x70, 0x03, 0xB8, + 0x03, 0x9C, 0x01, 0xC7, 0x00, 0xE3, 0x80, 0xE1, 0xC0, 0x70, 0x70, 0x38, + 0x38, 0x38, 0x1C, 0x1C, 0x07, 0x0E, 0x03, 0x8E, 0x01, 0xC7, 0x00, 0x77, + 0x00, 0x3B, 0x80, 0x1D, 0xC0, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, + 0x70, 0x00, 0xF0, 0x1C, 0x03, 0xB8, 0x1F, 0x03, 0xDC, 0x0F, 0x81, 0xCE, + 0x07, 0xC0, 0xE7, 0x83, 0xE0, 0x71, 0xC3, 0xB8, 0x70, 0xE1, 0xDC, 0x38, + 0x70, 0xEE, 0x1C, 0x1C, 0x63, 0x0E, 0x0E, 0x71, 0xCE, 0x07, 0x38, 0xE7, + 0x03, 0x9C, 0x73, 0x80, 0xEC, 0x19, 0x80, 0x7E, 0x0F, 0xC0, 0x3F, 0x07, + 0xE0, 0x0F, 0x83, 0xF0, 0x07, 0x80, 0xF0, 0x03, 0xC0, 0x78, 0x01, 0xE0, + 0x3C, 0x00, 0x70, 0x07, 0x38, 0x0E, 0x3C, 0x1C, 0x1C, 0x1C, 0x0E, 0x38, + 0x0F, 0x70, 0x07, 0x70, 0x03, 0xE0, 0x03, 0xC0, 0x01, 0xC0, 0x03, 0xE0, + 0x07, 0xE0, 0x07, 0x70, 0x0E, 0x78, 0x1E, 0x38, 0x1C, 0x1C, 0x38, 0x1E, + 0x78, 0x0E, 0x70, 0x07, 0x70, 0x07, 0x38, 0x03, 0x9C, 0x01, 0xC7, 0x01, + 0xC3, 0x80, 0xE1, 0xC0, 0x70, 0x70, 0x70, 0x38, 0x38, 0x1C, 0x3C, 0x07, + 0x1C, 0x03, 0x8E, 0x01, 0xCE, 0x00, 0x77, 0x00, 0x3B, 0x80, 0x1F, 0x80, + 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x38, + 0x00, 0x1C, 0x00, 0x1E, 0x00, 0x0E, 0x00, 0x3F, 0x00, 0x1F, 0x00, 0x0F, + 0x00, 0x00, 0x7F, 0xFC, 0xFF, 0xF9, 0xFF, 0xF0, 0x00, 0xE0, 0x03, 0x80, + 0x0E, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x1C, 0x00, 0x70, + 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xF8, 0x07, 0x0F, 0x1F, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1C, 0x1C, 0x1C, 0x38, 0xF8, 0xE0, 0xF8, 0x38, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1F, 0x0F, 0x07, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xE0, 0xF0, 0xF8, 0x38, + 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x1C, 0x1F, + 0x07, 0x1F, 0x1C, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, 0x38, + 0x38, 0x38, 0xF8, 0xF0, 0xE0, 0x38, 0x00, 0xFC, 0x03, 0xFC, 0x1F, 0x3E, + 0x3C, 0x1F, 0xE0, 0x1F, 0x80, 0x1E, 0x00 }; + +const GFXglyph FreeSans18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 9, 0, 1 }, // 0x20 ' ' + { 0, 3, 26, 12, 4, -25 }, // 0x21 '!' + { 10, 9, 9, 12, 1, -24 }, // 0x22 '"' + { 21, 19, 24, 19, 0, -23 }, // 0x23 '#' + { 78, 16, 30, 19, 2, -26 }, // 0x24 '$' + { 138, 29, 25, 31, 1, -24 }, // 0x25 '%' + { 229, 20, 25, 23, 2, -24 }, // 0x26 '&' + { 292, 3, 9, 7, 2, -24 }, // 0x27 ''' + { 296, 8, 33, 12, 3, -25 }, // 0x28 '(' + { 329, 8, 33, 12, 1, -25 }, // 0x29 ')' + { 362, 10, 10, 14, 2, -25 }, // 0x2A '*' + { 375, 16, 16, 20, 2, -15 }, // 0x2B '+' + { 407, 3, 9, 10, 3, -3 }, // 0x2C ',' + { 411, 8, 3, 12, 2, -10 }, // 0x2D '-' + { 414, 3, 4, 9, 3, -3 }, // 0x2E '.' + { 416, 10, 26, 10, 0, -25 }, // 0x2F '/' + { 449, 16, 25, 19, 2, -24 }, // 0x30 '0' + { 499, 8, 25, 19, 4, -24 }, // 0x31 '1' + { 524, 16, 25, 19, 2, -24 }, // 0x32 '2' + { 574, 17, 25, 19, 1, -24 }, // 0x33 '3' + { 628, 16, 25, 19, 1, -24 }, // 0x34 '4' + { 678, 17, 25, 19, 1, -24 }, // 0x35 '5' + { 732, 16, 25, 19, 2, -24 }, // 0x36 '6' + { 782, 16, 25, 19, 2, -24 }, // 0x37 '7' + { 832, 17, 25, 19, 1, -24 }, // 0x38 '8' + { 886, 16, 25, 19, 1, -24 }, // 0x39 '9' + { 936, 3, 19, 9, 3, -18 }, // 0x3A ':' + { 944, 3, 24, 9, 3, -18 }, // 0x3B ';' + { 953, 17, 17, 20, 2, -16 }, // 0x3C '<' + { 990, 17, 9, 20, 2, -12 }, // 0x3D '=' + { 1010, 17, 17, 20, 2, -16 }, // 0x3E '>' + { 1047, 15, 26, 19, 3, -25 }, // 0x3F '?' + { 1096, 32, 31, 36, 1, -25 }, // 0x40 '@' + { 1220, 22, 26, 23, 1, -25 }, // 0x41 'A' + { 1292, 19, 26, 23, 3, -25 }, // 0x42 'B' + { 1354, 22, 26, 25, 1, -25 }, // 0x43 'C' + { 1426, 20, 26, 24, 3, -25 }, // 0x44 'D' + { 1491, 18, 26, 22, 3, -25 }, // 0x45 'E' + { 1550, 17, 26, 21, 3, -25 }, // 0x46 'F' + { 1606, 24, 26, 27, 1, -25 }, // 0x47 'G' + { 1684, 19, 26, 25, 3, -25 }, // 0x48 'H' + { 1746, 3, 26, 10, 4, -25 }, // 0x49 'I' + { 1756, 14, 26, 18, 1, -25 }, // 0x4A 'J' + { 1802, 20, 26, 24, 3, -25 }, // 0x4B 'K' + { 1867, 15, 26, 20, 3, -25 }, // 0x4C 'L' + { 1916, 24, 26, 30, 3, -25 }, // 0x4D 'M' + { 1994, 20, 26, 26, 3, -25 }, // 0x4E 'N' + { 2059, 25, 26, 27, 1, -25 }, // 0x4F 'O' + { 2141, 18, 26, 23, 3, -25 }, // 0x50 'P' + { 2200, 25, 28, 27, 1, -25 }, // 0x51 'Q' + { 2288, 20, 26, 25, 3, -25 }, // 0x52 'R' + { 2353, 20, 26, 23, 1, -25 }, // 0x53 'S' + { 2418, 19, 26, 22, 1, -25 }, // 0x54 'T' + { 2480, 19, 26, 25, 3, -25 }, // 0x55 'U' + { 2542, 21, 26, 23, 1, -25 }, // 0x56 'V' + { 2611, 32, 26, 33, 0, -25 }, // 0x57 'W' + { 2715, 21, 26, 23, 1, -25 }, // 0x58 'X' + { 2784, 23, 26, 24, 0, -25 }, // 0x59 'Y' + { 2859, 19, 26, 22, 1, -25 }, // 0x5A 'Z' + { 2921, 6, 33, 10, 2, -25 }, // 0x5B '[' + { 2946, 10, 26, 10, 0, -25 }, // 0x5C '\' + { 2979, 6, 33, 10, 1, -25 }, // 0x5D ']' + { 3004, 13, 13, 16, 2, -24 }, // 0x5E '^' + { 3026, 21, 2, 19, -1, 5 }, // 0x5F '_' + { 3032, 7, 5, 9, 1, -25 }, // 0x60 '`' + { 3037, 17, 19, 19, 1, -18 }, // 0x61 'a' + { 3078, 16, 26, 20, 2, -25 }, // 0x62 'b' + { 3130, 16, 19, 18, 1, -18 }, // 0x63 'c' + { 3168, 17, 26, 20, 1, -25 }, // 0x64 'd' + { 3224, 16, 19, 19, 1, -18 }, // 0x65 'e' + { 3262, 7, 26, 10, 1, -25 }, // 0x66 'f' + { 3285, 16, 27, 19, 1, -18 }, // 0x67 'g' + { 3339, 15, 26, 19, 2, -25 }, // 0x68 'h' + { 3388, 3, 26, 8, 2, -25 }, // 0x69 'i' + { 3398, 6, 34, 9, 0, -25 }, // 0x6A 'j' + { 3424, 16, 26, 18, 2, -25 }, // 0x6B 'k' + { 3476, 3, 26, 7, 2, -25 }, // 0x6C 'l' + { 3486, 24, 19, 28, 2, -18 }, // 0x6D 'm' + { 3543, 15, 19, 19, 2, -18 }, // 0x6E 'n' + { 3579, 17, 19, 19, 1, -18 }, // 0x6F 'o' + { 3620, 16, 25, 20, 2, -18 }, // 0x70 'p' + { 3670, 17, 25, 20, 1, -18 }, // 0x71 'q' + { 3724, 9, 19, 12, 2, -18 }, // 0x72 'r' + { 3746, 14, 19, 17, 2, -18 }, // 0x73 's' + { 3780, 7, 23, 10, 1, -22 }, // 0x74 't' + { 3801, 15, 19, 19, 2, -18 }, // 0x75 'u' + { 3837, 17, 19, 17, 0, -18 }, // 0x76 'v' + { 3878, 25, 19, 25, 0, -18 }, // 0x77 'w' + { 3938, 16, 19, 17, 0, -18 }, // 0x78 'x' + { 3976, 17, 27, 17, 0, -18 }, // 0x79 'y' + { 4034, 15, 19, 17, 1, -18 }, // 0x7A 'z' + { 4070, 8, 33, 12, 1, -25 }, // 0x7B '{' + { 4103, 2, 33, 9, 3, -25 }, // 0x7C '|' + { 4112, 8, 33, 12, 3, -25 }, // 0x7D '}' + { 4145, 15, 7, 18, 1, -15 } }; // 0x7E '~' + +const GFXfont FreeSans18pt7b PROGMEM = { + (uint8_t *)FreeSans18pt7bBitmaps, + (GFXglyph *)FreeSans18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 4831 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSans24pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSans24pt7b.h new file mode 100644 index 0000000..ff2d174 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSans24pt7b.h @@ -0,0 +1,727 @@ +const uint8_t FreeSans24pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x76, 0x66, + 0x66, 0x00, 0x0F, 0xFF, 0xFF, 0xF1, 0xFE, 0x3F, 0xC7, 0xF8, 0xFF, 0x1F, + 0xE3, 0xFC, 0x7F, 0x8F, 0xF1, 0xEC, 0x19, 0x83, 0x30, 0x60, 0x00, 0x70, + 0x3C, 0x00, 0x70, 0x3C, 0x00, 0xF0, 0x38, 0x00, 0xF0, 0x38, 0x00, 0xF0, + 0x78, 0x00, 0xE0, 0x78, 0x00, 0xE0, 0x78, 0x01, 0xE0, 0x70, 0x01, 0xE0, + 0x70, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x03, 0xC0, + 0xE0, 0x03, 0xC0, 0xE0, 0x03, 0xC0, 0xE0, 0x03, 0x81, 0xE0, 0x03, 0x81, + 0xE0, 0x03, 0x81, 0xE0, 0x07, 0x81, 0xC0, 0x07, 0x81, 0xC0, 0xFF, 0xFF, + 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0x0F, 0x03, 0x80, 0x0F, 0x03, + 0x80, 0x0F, 0x07, 0x80, 0x0E, 0x07, 0x80, 0x0E, 0x07, 0x80, 0x1E, 0x07, + 0x00, 0x1E, 0x07, 0x00, 0x1E, 0x07, 0x00, 0x1C, 0x0F, 0x00, 0x1C, 0x0F, + 0x00, 0x00, 0x38, 0x00, 0x01, 0xFC, 0x00, 0x1F, 0xFE, 0x00, 0x7F, 0xFE, + 0x01, 0xFF, 0xFE, 0x07, 0xE7, 0x3E, 0x0F, 0x8E, 0x3C, 0x3E, 0x1C, 0x3C, + 0x78, 0x38, 0x38, 0xF0, 0x70, 0x71, 0xE0, 0xE0, 0xE3, 0xC1, 0xC0, 0x07, + 0x83, 0x80, 0x0F, 0x87, 0x00, 0x0F, 0x8E, 0x00, 0x1F, 0xDC, 0x00, 0x1F, + 0xF8, 0x00, 0x1F, 0xFF, 0x00, 0x0F, 0xFF, 0x80, 0x07, 0xFF, 0x80, 0x03, + 0xFF, 0x80, 0x07, 0x1F, 0x80, 0x0E, 0x1F, 0x00, 0x1C, 0x1F, 0x00, 0x38, + 0x1F, 0xC0, 0x70, 0x3F, 0x80, 0xE0, 0x7F, 0x81, 0xC0, 0xFF, 0x03, 0x81, + 0xEF, 0x07, 0x07, 0x9F, 0x0E, 0x0F, 0x3E, 0x1C, 0x3E, 0x3F, 0x39, 0xF8, + 0x3F, 0xFF, 0xE0, 0x3F, 0xFF, 0x00, 0x0F, 0xF8, 0x00, 0x03, 0x80, 0x00, + 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, 0x00, + 0x00, 0x00, 0x1C, 0x00, 0x0F, 0xC0, 0x00, 0x78, 0x00, 0x3F, 0xE0, 0x00, + 0xE0, 0x01, 0xFF, 0xE0, 0x03, 0x80, 0x03, 0xFF, 0xE0, 0x07, 0x00, 0x0F, + 0x87, 0xC0, 0x1C, 0x00, 0x3C, 0x03, 0xC0, 0x38, 0x00, 0x70, 0x03, 0x80, + 0xE0, 0x00, 0xE0, 0x07, 0x03, 0xC0, 0x01, 0xC0, 0x0E, 0x07, 0x00, 0x03, + 0x80, 0x1C, 0x1E, 0x00, 0x07, 0x80, 0x78, 0x38, 0x00, 0x07, 0xC3, 0xE0, + 0xF0, 0x00, 0x07, 0xFF, 0xC1, 0xC0, 0x00, 0x0F, 0xFF, 0x07, 0x80, 0x00, + 0x0F, 0xFC, 0x0E, 0x00, 0x00, 0x07, 0xE0, 0x38, 0x00, 0x00, 0x00, 0x00, + 0x70, 0x00, 0x00, 0x00, 0x01, 0xC0, 0x3F, 0x00, 0x00, 0x03, 0x80, 0xFF, + 0x80, 0x00, 0x0E, 0x07, 0xFF, 0x80, 0x00, 0x3C, 0x0F, 0xFF, 0x80, 0x00, + 0x70, 0x3E, 0x1F, 0x00, 0x01, 0xE0, 0xF0, 0x0F, 0x00, 0x03, 0x81, 0xC0, + 0x0E, 0x00, 0x0F, 0x03, 0x80, 0x1C, 0x00, 0x1C, 0x07, 0x00, 0x38, 0x00, + 0x78, 0x0E, 0x00, 0x70, 0x00, 0xE0, 0x1E, 0x01, 0xE0, 0x03, 0x80, 0x1F, + 0x0F, 0x80, 0x07, 0x00, 0x1F, 0xFF, 0x00, 0x1C, 0x00, 0x3F, 0xFC, 0x00, + 0x38, 0x00, 0x1F, 0xF0, 0x00, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x7E, 0x00, + 0x00, 0x1F, 0xF0, 0x00, 0x03, 0xFF, 0x80, 0x00, 0x7F, 0xFC, 0x00, 0x07, + 0xC3, 0xC0, 0x00, 0xF8, 0x1E, 0x00, 0x0F, 0x00, 0xE0, 0x00, 0xF0, 0x0E, + 0x00, 0x0F, 0x00, 0xE0, 0x00, 0xF0, 0x0E, 0x00, 0x07, 0x81, 0xE0, 0x00, + 0x7C, 0x3C, 0x00, 0x03, 0xEF, 0x80, 0x00, 0x1F, 0xF0, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x1F, 0x80, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0xE0, 0x00, + 0x1F, 0x1E, 0x07, 0x83, 0xE0, 0xF0, 0x78, 0x7C, 0x0F, 0x8F, 0x87, 0x80, + 0x7C, 0xF0, 0xF0, 0x03, 0xFF, 0x0F, 0x00, 0x1F, 0xE0, 0xF0, 0x00, 0xFE, + 0x0F, 0x00, 0x0F, 0xC0, 0xF0, 0x00, 0x7E, 0x0F, 0x80, 0x0F, 0xF0, 0x7C, + 0x01, 0xFF, 0x07, 0xF0, 0x7D, 0xF8, 0x3F, 0xFF, 0x8F, 0xC1, 0xFF, 0xF0, + 0x7E, 0x0F, 0xFE, 0x03, 0xE0, 0x3F, 0x80, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF6, 0x66, 0x01, 0xC0, 0x70, 0x38, 0x1C, 0x07, 0x03, 0xC0, 0xE0, 0x78, + 0x1C, 0x07, 0x03, 0xC0, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x70, 0x3C, + 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, + 0xC0, 0x70, 0x1E, 0x07, 0x81, 0xE0, 0x38, 0x0F, 0x03, 0xC0, 0x70, 0x1E, + 0x03, 0x80, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x18, 0x07, 0xE0, 0x38, 0x07, + 0x01, 0xC0, 0x38, 0x0F, 0x01, 0xC0, 0x78, 0x0E, 0x03, 0x80, 0xF0, 0x1C, + 0x07, 0x01, 0xE0, 0x78, 0x1E, 0x03, 0x80, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, + 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x07, 0x81, 0xE0, 0x78, + 0x1E, 0x07, 0x03, 0xC0, 0xF0, 0x38, 0x1E, 0x07, 0x01, 0xC0, 0xE0, 0x38, + 0x1C, 0x06, 0x03, 0x80, 0x03, 0x00, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x63, + 0x1B, 0xFF, 0xFF, 0xFF, 0xC3, 0xF0, 0x07, 0x80, 0x3F, 0x01, 0xCE, 0x07, + 0x3C, 0x38, 0x70, 0x21, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, 0x00, + 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, 0x0E, + 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x07, 0x00, 0x00, 0x0E, 0x00, + 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, 0x00, 0xE0, 0x00, + 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, 0xFF, 0xFF, 0xF3, + 0x33, 0x36, 0xEC, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xF0, + 0x00, 0x38, 0x01, 0xC0, 0x0C, 0x00, 0xE0, 0x07, 0x00, 0x30, 0x03, 0x80, + 0x1C, 0x00, 0xC0, 0x06, 0x00, 0x70, 0x03, 0x80, 0x18, 0x01, 0xC0, 0x0E, + 0x00, 0x60, 0x03, 0x00, 0x38, 0x01, 0x80, 0x0C, 0x00, 0xE0, 0x07, 0x00, + 0x30, 0x03, 0x80, 0x1C, 0x00, 0xC0, 0x06, 0x00, 0x70, 0x03, 0x80, 0x18, + 0x01, 0xC0, 0x0E, 0x00, 0x60, 0x07, 0x00, 0x38, 0x00, 0x00, 0xFC, 0x00, + 0x0F, 0xFC, 0x00, 0xFF, 0xFC, 0x07, 0xFF, 0xF8, 0x1F, 0x87, 0xE0, 0xF8, + 0x07, 0xC3, 0xC0, 0x0F, 0x1F, 0x00, 0x3E, 0x78, 0x00, 0x79, 0xE0, 0x01, + 0xE7, 0x80, 0x07, 0xBC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, + 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x00, + 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x00, 0x03, + 0xDE, 0x00, 0x1E, 0x78, 0x00, 0x79, 0xE0, 0x01, 0xE7, 0xC0, 0x0F, 0x8F, + 0x00, 0x3C, 0x3E, 0x01, 0xF0, 0x7C, 0x1F, 0x81, 0xFF, 0xFE, 0x03, 0xFF, + 0xF0, 0x03, 0xFF, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x60, 0x1C, 0x03, 0x80, + 0xF0, 0x3E, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x3C, 0x07, 0x80, 0xF0, + 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, + 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, + 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x01, 0xFE, 0x00, 0x1F, 0xFE, 0x01, 0xFF, + 0xFE, 0x0F, 0xFF, 0xFC, 0x3F, 0x03, 0xF9, 0xF0, 0x03, 0xE7, 0x80, 0x07, + 0xFE, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x00, 0x03, 0xC0, + 0x00, 0x0F, 0x00, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, + 0x7C, 0x00, 0x07, 0xF0, 0x00, 0x7F, 0x80, 0x07, 0xF8, 0x00, 0x3F, 0xC0, + 0x03, 0xFC, 0x00, 0x1F, 0xC0, 0x00, 0xFC, 0x00, 0x07, 0xC0, 0x00, 0x3E, + 0x00, 0x00, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1C, 0x00, 0x00, 0x70, 0x00, + 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, + 0x00, 0xFE, 0x00, 0x0F, 0xFF, 0x80, 0x3F, 0xFF, 0x80, 0xFF, 0xFF, 0x83, + 0xF0, 0x1F, 0x87, 0xC0, 0x1F, 0x1F, 0x00, 0x1F, 0x3C, 0x00, 0x1E, 0x78, + 0x00, 0x3C, 0xF0, 0x00, 0x78, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, + 0x07, 0x80, 0x00, 0x7F, 0x00, 0x1F, 0xFC, 0x00, 0x3F, 0xE0, 0x00, 0x7F, + 0xE0, 0x00, 0xFF, 0xF0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x03, + 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x0F, 0xF0, 0x00, 0x1F, + 0xE0, 0x00, 0x3F, 0xE0, 0x00, 0xFB, 0xC0, 0x01, 0xE7, 0xC0, 0x07, 0xC7, + 0xE0, 0x3F, 0x0F, 0xFF, 0xFE, 0x0F, 0xFF, 0xF8, 0x07, 0xFF, 0xC0, 0x03, + 0xFC, 0x00, 0x00, 0x01, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x1F, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xF8, 0x00, 0x0F, 0xF0, 0x00, 0x3F, + 0xE0, 0x00, 0x7B, 0xC0, 0x01, 0xE7, 0x80, 0x07, 0x8F, 0x00, 0x0F, 0x1E, + 0x00, 0x3C, 0x3C, 0x00, 0xF0, 0x78, 0x03, 0xC0, 0xF0, 0x07, 0x81, 0xE0, + 0x1E, 0x03, 0xC0, 0x78, 0x07, 0x81, 0xE0, 0x0F, 0x03, 0xC0, 0x1E, 0x0F, + 0x00, 0x3C, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFE, 0x00, 0x07, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0x78, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x03, + 0xC0, 0x1F, 0xFF, 0xF0, 0x7F, 0xFF, 0xC1, 0xFF, 0xFF, 0x07, 0xFF, 0xFC, + 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x1F, 0x3F, 0x80, 0x7B, 0xFF, + 0x81, 0xFF, 0xFF, 0x07, 0xFF, 0xFE, 0x1F, 0x80, 0xFC, 0x78, 0x01, 0xF8, + 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3F, 0xC0, 0x00, + 0xFF, 0x80, 0x07, 0x9E, 0x00, 0x1E, 0x7C, 0x00, 0xF1, 0xFC, 0x0F, 0xC3, + 0xFF, 0xFE, 0x07, 0xFF, 0xF0, 0x0F, 0xFF, 0x80, 0x07, 0xF0, 0x00, 0x00, + 0xFE, 0x00, 0x0F, 0xFE, 0x00, 0x7F, 0xFC, 0x03, 0xFF, 0xF8, 0x1F, 0x83, + 0xF0, 0xF8, 0x07, 0xC3, 0xC0, 0x0F, 0x8F, 0x00, 0x1E, 0x78, 0x00, 0x79, + 0xE0, 0x00, 0x07, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF0, 0xFE, 0x03, 0xCF, + 0xFE, 0x0F, 0x7F, 0xFE, 0x3F, 0xFF, 0xFC, 0xFF, 0x03, 0xF3, 0xF0, 0x03, + 0xEF, 0x80, 0x07, 0xBE, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, + 0x00, 0x03, 0xFC, 0x00, 0x0F, 0x70, 0x00, 0x3D, 0xC0, 0x00, 0xF7, 0x80, + 0x07, 0x9F, 0x00, 0x3E, 0x3E, 0x00, 0xF8, 0xFC, 0x0F, 0xC1, 0xFF, 0xFE, + 0x03, 0xFF, 0xF0, 0x07, 0xFF, 0x80, 0x07, 0xF8, 0x00, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x07, 0x00, 0x00, + 0x78, 0x00, 0x07, 0x80, 0x00, 0x38, 0x00, 0x03, 0xC0, 0x00, 0x3C, 0x00, + 0x01, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x70, + 0x00, 0x07, 0x80, 0x00, 0x38, 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x01, + 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x38, 0x00, + 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, + 0x01, 0xFE, 0x00, 0x1F, 0xFE, 0x00, 0xFF, 0xFC, 0x07, 0xFF, 0xF8, 0x3F, + 0x03, 0xF1, 0xF0, 0x03, 0xC7, 0xC0, 0x0F, 0x9E, 0x00, 0x1E, 0x78, 0x00, + 0x79, 0xE0, 0x01, 0xE7, 0x80, 0x0F, 0x8F, 0x00, 0x3C, 0x3F, 0x03, 0xF0, + 0x7F, 0xFF, 0x80, 0x7F, 0xF8, 0x03, 0xFF, 0xF0, 0x1F, 0xFF, 0xE0, 0xFC, + 0x0F, 0xC7, 0xC0, 0x0F, 0x9E, 0x00, 0x1E, 0xF8, 0x00, 0x7F, 0xC0, 0x00, + 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, + 0x80, 0x07, 0xDE, 0x00, 0x1E, 0x7C, 0x00, 0xF8, 0xFC, 0x0F, 0xC3, 0xFF, + 0xFF, 0x07, 0xFF, 0xF8, 0x07, 0xFF, 0x80, 0x07, 0xF8, 0x00, 0x01, 0xFC, + 0x00, 0x3F, 0xF8, 0x03, 0xFF, 0xE0, 0x3F, 0xFF, 0x83, 0xF0, 0x7E, 0x3E, + 0x00, 0xF1, 0xE0, 0x07, 0xCF, 0x00, 0x1E, 0xF0, 0x00, 0x77, 0x80, 0x03, + 0xBC, 0x00, 0x1F, 0xE0, 0x00, 0xFF, 0x00, 0x07, 0xF8, 0x00, 0x3F, 0xE0, + 0x03, 0xEF, 0x00, 0x1F, 0x7C, 0x01, 0xF9, 0xF8, 0x3F, 0xCF, 0xFF, 0xFE, + 0x3F, 0xFE, 0xF0, 0xFF, 0xE7, 0x80, 0xFC, 0x3C, 0x00, 0x01, 0xE0, 0x00, + 0x0E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x9E, 0x00, 0x3C, 0xF0, 0x03, 0xC7, + 0xC0, 0x3E, 0x1F, 0x03, 0xE0, 0xFF, 0xFE, 0x03, 0xFF, 0xE0, 0x0F, 0xFE, + 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xF3, 0x33, 0x36, 0xEC, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x1C, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x7F, 0xC0, + 0x03, 0xFC, 0x00, 0x3F, 0xE0, 0x01, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, + 0x80, 0x03, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x0F, 0xF0, + 0x00, 0x07, 0xFC, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, + 0xC0, 0x00, 0x3F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x07, 0xE0, 0x00, 0x01, + 0xC0, 0x00, 0x00, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xF0, 0x80, 0x00, 0x01, 0xC0, 0x00, 0x03, 0xF0, 0x00, 0x07, + 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFF, 0x00, 0x00, 0xFF, 0x80, 0x00, + 0x3F, 0xC0, 0x00, 0x1F, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x03, 0xF8, 0x00, + 0x01, 0xF0, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0xC0, 0x03, 0xFC, 0x00, 0x1F, + 0xE0, 0x01, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x80, 0x07, 0xFC, 0x00, + 0x0F, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0x30, 0x00, 0x00, 0x00, 0x03, 0xF8, + 0x00, 0xFF, 0xF0, 0x1F, 0xFF, 0x83, 0xFF, 0xFC, 0x7E, 0x0F, 0xE7, 0x80, + 0x3E, 0x78, 0x01, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, + 0x00, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, + 0x01, 0xF0, 0x00, 0x1E, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xE0, + 0x00, 0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, + 0xE0, 0x00, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xC0, + 0x00, 0x00, 0x3F, 0xFF, 0xFE, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xF0, 0x00, + 0x07, 0xFC, 0x03, 0xFF, 0x00, 0x01, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x7E, + 0x00, 0x00, 0x7F, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xF0, 0x07, 0xC0, 0x00, + 0x00, 0x3F, 0x01, 0xF0, 0x00, 0x00, 0x03, 0xF0, 0x3C, 0x00, 0x7E, 0x00, + 0x3E, 0x0F, 0x00, 0x3F, 0xE3, 0xC3, 0xE3, 0xE0, 0x1F, 0xFE, 0x78, 0x3C, + 0x78, 0x07, 0xE1, 0xFF, 0x07, 0xDF, 0x01, 0xF0, 0x1F, 0xC0, 0xFB, 0xC0, + 0x7C, 0x01, 0xF8, 0x0F, 0x78, 0x0F, 0x00, 0x3F, 0x01, 0xEF, 0x03, 0xC0, + 0x07, 0xC0, 0x3F, 0xC0, 0x78, 0x00, 0xF8, 0x07, 0xF8, 0x0F, 0x00, 0x1F, + 0x00, 0xFF, 0x03, 0xC0, 0x03, 0xC0, 0x1F, 0xE0, 0x78, 0x00, 0x78, 0x07, + 0xFC, 0x0F, 0x00, 0x1F, 0x00, 0xF7, 0x81, 0xE0, 0x03, 0xC0, 0x1E, 0xF0, + 0x3C, 0x00, 0x78, 0x07, 0x9E, 0x07, 0x80, 0x1F, 0x01, 0xF3, 0xE0, 0xF8, + 0x07, 0xC0, 0x3C, 0x3C, 0x0F, 0x81, 0xF8, 0x0F, 0x87, 0x81, 0xF8, 0x7F, + 0x87, 0xE0, 0xF8, 0x1F, 0xFE, 0xFF, 0xF8, 0x0F, 0x01, 0xFF, 0x1F, 0xFC, + 0x01, 0xF0, 0x0F, 0x80, 0xFE, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x00, 0x03, + 0xF0, 0x00, 0x00, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00, 0x00, 0x03, 0xF8, + 0x00, 0x00, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x00, 0x03, 0xFE, 0x00, + 0x7C, 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0x80, 0x00, 0x01, 0xFF, 0xFF, 0xF8, + 0x00, 0x00, 0x0F, 0xFF, 0xFC, 0x00, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, + 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x00, 0xF7, 0xC0, 0x00, 0x03, + 0xDF, 0x00, 0x00, 0x1F, 0x3C, 0x00, 0x00, 0x78, 0xF8, 0x00, 0x01, 0xE3, + 0xE0, 0x00, 0x0F, 0x87, 0x80, 0x00, 0x3C, 0x1F, 0x00, 0x01, 0xF0, 0x7C, + 0x00, 0x07, 0x80, 0xF0, 0x00, 0x1E, 0x03, 0xE0, 0x00, 0xF8, 0x0F, 0x80, + 0x03, 0xC0, 0x1E, 0x00, 0x0F, 0x00, 0x7C, 0x00, 0x7C, 0x01, 0xF0, 0x01, + 0xE0, 0x03, 0xC0, 0x07, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xFE, 0x00, 0xFF, + 0xFF, 0xFC, 0x07, 0xFF, 0xFF, 0xF0, 0x1F, 0x00, 0x07, 0xC0, 0x78, 0x00, + 0x0F, 0x83, 0xE0, 0x00, 0x3E, 0x0F, 0x80, 0x00, 0xF8, 0x3C, 0x00, 0x01, + 0xF1, 0xF0, 0x00, 0x07, 0xC7, 0xC0, 0x00, 0x1F, 0x1E, 0x00, 0x00, 0x3E, + 0xF8, 0x00, 0x00, 0xFB, 0xE0, 0x00, 0x01, 0xE0, 0xFF, 0xFF, 0x80, 0x7F, + 0xFF, 0xF0, 0x3F, 0xFF, 0xFE, 0x1F, 0xFF, 0xFF, 0x0F, 0x00, 0x0F, 0xC7, + 0x80, 0x01, 0xE3, 0xC0, 0x00, 0xF9, 0xE0, 0x00, 0x3C, 0xF0, 0x00, 0x1E, + 0x78, 0x00, 0x0F, 0x3C, 0x00, 0x07, 0x9E, 0x00, 0x07, 0x8F, 0x00, 0x03, + 0xC7, 0x80, 0x07, 0xC3, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, + 0xF8, 0x7F, 0xFF, 0xFE, 0x3C, 0x00, 0x0F, 0x9E, 0x00, 0x03, 0xEF, 0x00, + 0x00, 0xF7, 0x80, 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x0F, 0xF0, + 0x00, 0x07, 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x01, 0xFF, + 0x00, 0x01, 0xF7, 0x80, 0x01, 0xFB, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, 0xF8, + 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, 0xF0, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x07, + 0xFF, 0xE0, 0x00, 0x7F, 0xFF, 0xC0, 0x0F, 0xFF, 0xFF, 0x00, 0xFE, 0x01, + 0xF8, 0x07, 0xC0, 0x03, 0xE0, 0x7C, 0x00, 0x0F, 0x87, 0xC0, 0x00, 0x3C, + 0x3C, 0x00, 0x01, 0xE3, 0xE0, 0x00, 0x07, 0x9E, 0x00, 0x00, 0x3C, 0xF0, + 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x78, 0x00, 0x00, 0x03, 0xC0, 0x00, + 0x00, 0x1E, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x0F, 0x78, 0x00, + 0x00, 0x7B, 0xC0, 0x00, 0x07, 0xDF, 0x00, 0x00, 0x3C, 0x78, 0x00, 0x01, + 0xE3, 0xE0, 0x00, 0x1F, 0x0F, 0x80, 0x01, 0xF0, 0x3E, 0x00, 0x1F, 0x81, + 0xFE, 0x03, 0xF8, 0x07, 0xFF, 0xFF, 0x80, 0x0F, 0xFF, 0xF8, 0x00, 0x3F, + 0xFF, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0xFF, 0x80, 0x1F, 0xFF, 0xFE, + 0x03, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0xFE, 0x0F, 0x00, 0x0F, 0xE1, 0xE0, + 0x00, 0x7E, 0x3C, 0x00, 0x07, 0xE7, 0x80, 0x00, 0x7C, 0xF0, 0x00, 0x07, + 0xDE, 0x00, 0x00, 0x7B, 0xC0, 0x00, 0x0F, 0x78, 0x00, 0x01, 0xEF, 0x00, + 0x00, 0x1F, 0xE0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x0F, + 0xF0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x07, 0xF8, 0x00, + 0x00, 0xFF, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xF7, + 0x80, 0x00, 0x1E, 0xF0, 0x00, 0x03, 0xDE, 0x00, 0x00, 0xFB, 0xC0, 0x00, + 0x3E, 0x78, 0x00, 0x0F, 0xCF, 0x00, 0x03, 0xF1, 0xE0, 0x01, 0xFC, 0x3F, + 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xF0, 0x1F, 0xFF, 0xF0, + 0x00, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, + 0xFE, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xFF, 0xFF, + 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, + 0x3F, 0xFF, 0xFC, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0x3C, + 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF0, + 0x00, 0x03, 0xC0, 0x00, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0xFF, 0xFE, + 0x00, 0x07, 0xFF, 0xFF, 0x00, 0x1F, 0xFF, 0xFF, 0x00, 0x7F, 0x80, 0x7F, + 0x01, 0xF8, 0x00, 0x3F, 0x07, 0xE0, 0x00, 0x1F, 0x0F, 0x80, 0x00, 0x1E, + 0x3E, 0x00, 0x00, 0x3E, 0x78, 0x00, 0x00, 0x3D, 0xF0, 0x00, 0x00, 0x03, + 0xC0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x01, 0xE0, + 0x00, 0xFF, 0xFF, 0xC0, 0x01, 0xFF, 0xFF, 0x80, 0x03, 0xFF, 0xFF, 0x00, + 0x07, 0xFF, 0xFE, 0x00, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x07, 0xBC, 0x00, + 0x00, 0x0F, 0x78, 0x00, 0x00, 0x1E, 0xF8, 0x00, 0x00, 0x7D, 0xF0, 0x00, + 0x00, 0xF9, 0xF0, 0x00, 0x03, 0xF3, 0xF0, 0x00, 0x07, 0xE3, 0xF0, 0x00, + 0x1F, 0xC3, 0xF0, 0x00, 0xFF, 0x83, 0xFC, 0x07, 0xEF, 0x03, 0xFF, 0xFF, + 0x9E, 0x03, 0xFF, 0xFE, 0x1C, 0x01, 0xFF, 0xF0, 0x38, 0x00, 0x7F, 0x80, + 0x00, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x3F, 0xC0, + 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x3F, + 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, + 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, + 0x00, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, + 0x00, 0xFF, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, + 0x00, 0x00, 0xFF, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, + 0xFC, 0x00, 0x00, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x01, 0xE0, + 0x00, 0x3C, 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, + 0x00, 0x78, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x07, 0x80, + 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x0F, 0x00, + 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x1E, 0x00, + 0x03, 0xC0, 0x00, 0x7F, 0x80, 0x0F, 0xF0, 0x01, 0xFE, 0x00, 0x3F, 0xC0, + 0x07, 0xF8, 0x01, 0xFF, 0x80, 0x3E, 0xF0, 0x0F, 0x9F, 0x83, 0xF1, 0xFF, + 0xFC, 0x3F, 0xFF, 0x01, 0xFF, 0xC0, 0x0F, 0xE0, 0x00, 0xF0, 0x00, 0x07, + 0xDE, 0x00, 0x01, 0xF3, 0xC0, 0x00, 0x7C, 0x78, 0x00, 0x1F, 0x0F, 0x00, + 0x07, 0xC1, 0xE0, 0x01, 0xF0, 0x3C, 0x00, 0x7C, 0x07, 0x80, 0x1F, 0x00, + 0xF0, 0x07, 0xC0, 0x1E, 0x01, 0xF0, 0x03, 0xC0, 0x7C, 0x00, 0x78, 0x1F, + 0x00, 0x0F, 0x07, 0xC0, 0x01, 0xE1, 0xF0, 0x00, 0x3C, 0x7E, 0x00, 0x07, + 0x9F, 0xE0, 0x00, 0xF7, 0xFE, 0x00, 0x1F, 0xF7, 0xC0, 0x03, 0xFC, 0x7C, + 0x00, 0x7F, 0x07, 0xC0, 0x0F, 0xC0, 0xF8, 0x01, 0xF0, 0x0F, 0x80, 0x3C, + 0x00, 0xF8, 0x07, 0x80, 0x1F, 0x80, 0xF0, 0x01, 0xF0, 0x1E, 0x00, 0x1F, + 0x03, 0xC0, 0x03, 0xF0, 0x78, 0x00, 0x3E, 0x0F, 0x00, 0x03, 0xE1, 0xE0, + 0x00, 0x3E, 0x3C, 0x00, 0x07, 0xC7, 0x80, 0x00, 0x7C, 0xF0, 0x00, 0x07, + 0xDE, 0x00, 0x00, 0xFC, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x3C, 0x00, 0x01, + 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, + 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, + 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, + 0x07, 0x80, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, + 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFC, 0x00, + 0x00, 0x3F, 0xFC, 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x00, 0x7F, 0xFE, 0x00, + 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x7F, 0xFF, 0x00, 0x00, 0xFF, 0xFF, 0x00, + 0x00, 0xFF, 0xF7, 0x00, 0x00, 0xEF, 0xF7, 0x80, 0x01, 0xEF, 0xF7, 0x80, + 0x01, 0xEF, 0xF3, 0xC0, 0x01, 0xCF, 0xF3, 0xC0, 0x03, 0xCF, 0xF3, 0xC0, + 0x03, 0xCF, 0xF1, 0xE0, 0x03, 0x8F, 0xF1, 0xE0, 0x07, 0x8F, 0xF1, 0xE0, + 0x07, 0x8F, 0xF0, 0xF0, 0x0F, 0x0F, 0xF0, 0xF0, 0x0F, 0x0F, 0xF0, 0xF0, + 0x0F, 0x0F, 0xF0, 0x78, 0x1E, 0x0F, 0xF0, 0x78, 0x1E, 0x0F, 0xF0, 0x78, + 0x1E, 0x0F, 0xF0, 0x3C, 0x3C, 0x0F, 0xF0, 0x3C, 0x3C, 0x0F, 0xF0, 0x3C, + 0x3C, 0x0F, 0xF0, 0x1E, 0x78, 0x0F, 0xF0, 0x1E, 0x78, 0x0F, 0xF0, 0x0E, + 0x78, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x07, + 0xF0, 0x0F, 0xF0, 0x07, 0xE0, 0x0F, 0xF0, 0x07, 0xE0, 0x0F, 0xF0, 0x03, + 0xE0, 0x0F, 0xF8, 0x00, 0x03, 0xFF, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x3F, + 0xF8, 0x00, 0x0F, 0xFE, 0x00, 0x03, 0xFF, 0xC0, 0x00, 0xFF, 0xF8, 0x00, + 0x3F, 0xDE, 0x00, 0x0F, 0xF7, 0xC0, 0x03, 0xFC, 0xF8, 0x00, 0xFF, 0x1E, + 0x00, 0x3F, 0xC7, 0xC0, 0x0F, 0xF0, 0xF0, 0x03, 0xFC, 0x3E, 0x00, 0xFF, + 0x07, 0xC0, 0x3F, 0xC0, 0xF0, 0x0F, 0xF0, 0x3E, 0x03, 0xFC, 0x07, 0xC0, + 0xFF, 0x00, 0xF0, 0x3F, 0xC0, 0x3E, 0x0F, 0xF0, 0x07, 0x83, 0xFC, 0x01, + 0xF0, 0xFF, 0x00, 0x3E, 0x3F, 0xC0, 0x07, 0x8F, 0xF0, 0x01, 0xF3, 0xFC, + 0x00, 0x3E, 0xFF, 0x00, 0x07, 0xBF, 0xC0, 0x01, 0xFF, 0xF0, 0x00, 0x3F, + 0xFC, 0x00, 0x0F, 0xFF, 0x00, 0x01, 0xFF, 0xC0, 0x00, 0x3F, 0xF0, 0x00, + 0x0F, 0xFC, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x3F, 0xFF, + 0x80, 0x00, 0x7F, 0xFF, 0xF0, 0x00, 0x7F, 0xFF, 0xFC, 0x00, 0x7F, 0x80, + 0xFF, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x7E, 0x00, 0x03, 0xF0, 0x3E, 0x00, + 0x00, 0xF8, 0x3E, 0x00, 0x00, 0x3E, 0x1E, 0x00, 0x00, 0x0F, 0x1F, 0x00, + 0x00, 0x07, 0xCF, 0x00, 0x00, 0x01, 0xE7, 0x80, 0x00, 0x00, 0xF7, 0xC0, + 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x00, 0x3F, + 0xC0, 0x00, 0x00, 0x3E, 0xF0, 0x00, 0x00, 0x1E, 0x78, 0x00, 0x00, 0x0F, + 0x3E, 0x00, 0x00, 0x0F, 0x8F, 0x00, 0x00, 0x07, 0x87, 0xC0, 0x00, 0x07, + 0xC1, 0xF0, 0x00, 0x07, 0xC0, 0xFC, 0x00, 0x07, 0xE0, 0x3F, 0x00, 0x07, + 0xE0, 0x0F, 0xF0, 0x1F, 0xE0, 0x03, 0xFF, 0xFF, 0xE0, 0x00, 0xFF, 0xFF, + 0xE0, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0xFF, 0xFF, + 0x80, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xFC, 0xF0, 0x00, + 0xFE, 0xF0, 0x00, 0x3E, 0xF0, 0x00, 0x1F, 0xF0, 0x00, 0x0F, 0xF0, 0x00, + 0x0F, 0xF0, 0x00, 0x0F, 0xF0, 0x00, 0x0F, 0xF0, 0x00, 0x0F, 0xF0, 0x00, + 0x0F, 0xF0, 0x00, 0x1F, 0xF0, 0x00, 0x3E, 0xF0, 0x00, 0xFE, 0xFF, 0xFF, + 0xFC, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xC0, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x3F, 0xFF, 0x80, + 0x00, 0x7F, 0xFF, 0xE0, 0x00, 0x7F, 0xFF, 0xFC, 0x00, 0x7F, 0x80, 0xFF, + 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x7E, 0x00, 0x03, 0xF0, 0x3E, 0x00, 0x00, + 0xF8, 0x3E, 0x00, 0x00, 0x3E, 0x1E, 0x00, 0x00, 0x0F, 0x1F, 0x00, 0x00, + 0x07, 0xCF, 0x00, 0x00, 0x01, 0xE7, 0x80, 0x00, 0x00, 0xF7, 0xC0, 0x00, + 0x00, 0x7F, 0xC0, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x0F, 0xF0, 0x00, + 0x00, 0x07, 0xF8, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x01, 0xFE, 0x00, + 0x00, 0x00, 0xFF, 0x00, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x00, 0x3F, 0xC0, + 0x00, 0x00, 0x3E, 0xF0, 0x00, 0x00, 0x1E, 0x78, 0x00, 0x00, 0x0F, 0x3E, + 0x00, 0x00, 0x0F, 0x8F, 0x00, 0x03, 0x87, 0x87, 0xC0, 0x03, 0xE7, 0xC1, + 0xF0, 0x00, 0xFF, 0xC0, 0xFC, 0x00, 0x3F, 0xE0, 0x3F, 0x00, 0x0F, 0xE0, + 0x0F, 0xF0, 0x1F, 0xF0, 0x03, 0xFF, 0xFF, 0xFC, 0x00, 0xFF, 0xFF, 0xFF, + 0x00, 0x1F, 0xFF, 0xC7, 0xC0, 0x01, 0xFF, 0x01, 0xE0, 0x00, 0x00, 0x00, + 0x70, 0x00, 0x00, 0x00, 0x10, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, 0xFE, 0x0F, + 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xF8, 0xF0, 0x00, 0x3F, 0x3C, 0x00, 0x07, + 0xCF, 0x00, 0x00, 0xFB, 0xC0, 0x00, 0x1E, 0xF0, 0x00, 0x07, 0xBC, 0x00, + 0x01, 0xEF, 0x00, 0x00, 0x7B, 0xC0, 0x00, 0x1E, 0xF0, 0x00, 0x07, 0xBC, + 0x00, 0x03, 0xCF, 0x00, 0x01, 0xF3, 0xC0, 0x00, 0xF8, 0xFF, 0xFF, 0xFC, + 0x3F, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xF8, 0xF0, 0x00, + 0x3F, 0x3C, 0x00, 0x03, 0xCF, 0x00, 0x00, 0xFB, 0xC0, 0x00, 0x1E, 0xF0, + 0x00, 0x07, 0xBC, 0x00, 0x01, 0xEF, 0x00, 0x00, 0x7B, 0xC0, 0x00, 0x1E, + 0xF0, 0x00, 0x07, 0xBC, 0x00, 0x01, 0xEF, 0x00, 0x00, 0x7B, 0xC0, 0x00, + 0x1E, 0xF0, 0x00, 0x07, 0xFC, 0x00, 0x01, 0xF0, 0x00, 0x7F, 0xC0, 0x00, + 0x7F, 0xFF, 0x00, 0x1F, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0x81, 0xF8, 0x07, + 0xF0, 0x7C, 0x00, 0x1F, 0x0F, 0x00, 0x01, 0xE3, 0xE0, 0x00, 0x3E, 0x78, + 0x00, 0x03, 0xCF, 0x00, 0x00, 0x79, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x07, 0xC0, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0xFF, + 0xE0, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x7F, 0xFF, 0x00, 0x01, 0xFF, 0xF8, + 0x00, 0x03, 0xFF, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x01, 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x3F, + 0xC0, 0x00, 0x07, 0xF8, 0x00, 0x00, 0xF7, 0x80, 0x00, 0x3E, 0xF8, 0x00, + 0x07, 0x9F, 0x80, 0x01, 0xF1, 0xFE, 0x01, 0xFC, 0x1F, 0xFF, 0xFF, 0x01, + 0xFF, 0xFF, 0xC0, 0x0F, 0xFF, 0xE0, 0x00, 0x3F, 0xE0, 0x00, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, + 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x78, 0x00, + 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, + 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, 0x00, + 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, + 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, + 0x01, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, + 0x00, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x3F, 0xC0, + 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x3F, + 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, + 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, + 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, + 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, + 0x00, 0xFF, 0x00, 0x00, 0x7D, 0xE0, 0x00, 0x1E, 0x7C, 0x00, 0x0F, 0x9F, + 0x80, 0x07, 0xE3, 0xF8, 0x07, 0xF0, 0x7F, 0xFF, 0xF8, 0x0F, 0xFF, 0xFC, + 0x00, 0xFF, 0xFC, 0x00, 0x0F, 0xF8, 0x00, 0xF8, 0x00, 0x00, 0xF7, 0xC0, + 0x00, 0x0F, 0x9E, 0x00, 0x00, 0x7C, 0xF8, 0x00, 0x03, 0xC7, 0xC0, 0x00, + 0x3E, 0x1E, 0x00, 0x01, 0xF0, 0xF8, 0x00, 0x0F, 0x07, 0xC0, 0x00, 0xF8, + 0x1E, 0x00, 0x07, 0xC0, 0xF8, 0x00, 0x3C, 0x07, 0xC0, 0x03, 0xE0, 0x1E, + 0x00, 0x1F, 0x00, 0xF8, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x80, 0x1E, 0x00, + 0x7C, 0x00, 0xF8, 0x03, 0xC0, 0x03, 0xC0, 0x1E, 0x00, 0x1F, 0x01, 0xF0, + 0x00, 0xF8, 0x0F, 0x00, 0x03, 0xC0, 0x78, 0x00, 0x1F, 0x07, 0x80, 0x00, + 0xF8, 0x3C, 0x00, 0x03, 0xC1, 0xE0, 0x00, 0x1F, 0x1E, 0x00, 0x00, 0x78, + 0xF0, 0x00, 0x03, 0xC7, 0x80, 0x00, 0x1F, 0x78, 0x00, 0x00, 0x7B, 0xC0, + 0x00, 0x03, 0xDE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, + 0x00, 0x3F, 0x00, 0x07, 0xFE, 0x00, 0x0F, 0xC0, 0x01, 0xFF, 0x80, 0x03, + 0xF0, 0x00, 0x7D, 0xE0, 0x00, 0xFC, 0x00, 0x1E, 0x7C, 0x00, 0x7F, 0x80, + 0x0F, 0x9F, 0x00, 0x1F, 0xE0, 0x03, 0xE7, 0xC0, 0x07, 0xF8, 0x00, 0xF8, + 0xF0, 0x01, 0xFF, 0x00, 0x3C, 0x3E, 0x00, 0xF3, 0xC0, 0x1F, 0x0F, 0x80, + 0x3C, 0xF0, 0x07, 0xC3, 0xE0, 0x0F, 0x3C, 0x01, 0xF0, 0x78, 0x07, 0xC7, + 0x80, 0x78, 0x1F, 0x01, 0xE1, 0xE0, 0x1E, 0x07, 0xC0, 0x78, 0x78, 0x0F, + 0x80, 0xF0, 0x1E, 0x1E, 0x03, 0xE0, 0x3C, 0x0F, 0x83, 0xC0, 0xF0, 0x0F, + 0x83, 0xC0, 0xF0, 0x3C, 0x03, 0xE0, 0xF0, 0x3C, 0x1F, 0x00, 0x78, 0x3C, + 0x0F, 0x87, 0xC0, 0x1E, 0x1E, 0x01, 0xE1, 0xE0, 0x07, 0x87, 0x80, 0x78, + 0x78, 0x01, 0xF1, 0xE0, 0x1E, 0x1E, 0x00, 0x3C, 0xF8, 0x03, 0xCF, 0x80, + 0x0F, 0x3C, 0x00, 0xF3, 0xC0, 0x03, 0xCF, 0x00, 0x3C, 0xF0, 0x00, 0xFB, + 0xC0, 0x0F, 0xBC, 0x00, 0x1F, 0xF0, 0x01, 0xFF, 0x00, 0x07, 0xF8, 0x00, + 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x03, 0xF8, + 0x00, 0x0F, 0xC0, 0x00, 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x00, + 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x01, 0xF3, 0xF0, 0x00, 0x1F, 0x8F, 0x80, 0x00, 0xF8, 0x3E, 0x00, 0x0F, + 0x80, 0xF8, 0x00, 0xF8, 0x07, 0xC0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x00, + 0x7C, 0x07, 0xC0, 0x03, 0xE0, 0x3E, 0x00, 0x0F, 0x83, 0xE0, 0x00, 0x3E, + 0x3E, 0x00, 0x01, 0xF1, 0xF0, 0x00, 0x07, 0xDF, 0x00, 0x00, 0x1F, 0xF0, + 0x00, 0x00, 0xFF, 0x80, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x07, + 0xDF, 0x00, 0x00, 0x7C, 0x78, 0x00, 0x03, 0xE3, 0xE0, 0x00, 0x3E, 0x0F, + 0x80, 0x03, 0xE0, 0x3E, 0x00, 0x1F, 0x01, 0xF0, 0x01, 0xF0, 0x07, 0xC0, + 0x1F, 0x00, 0x3F, 0x00, 0xF8, 0x00, 0xF8, 0x0F, 0x80, 0x03, 0xE0, 0xF8, + 0x00, 0x1F, 0x8F, 0xC0, 0x00, 0x7C, 0x7C, 0x00, 0x01, 0xF7, 0xC0, 0x00, + 0x0F, 0xC0, 0xFC, 0x00, 0x00, 0xFD, 0xF0, 0x00, 0x03, 0xE7, 0xE0, 0x00, + 0x1F, 0x0F, 0x80, 0x00, 0x7C, 0x1F, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x1F, + 0x00, 0xF8, 0x00, 0x7C, 0x01, 0xF0, 0x03, 0xE0, 0x07, 0xC0, 0x0F, 0x80, + 0x0F, 0x80, 0x7C, 0x00, 0x1E, 0x01, 0xE0, 0x00, 0x7C, 0x0F, 0x80, 0x00, + 0xF8, 0x7C, 0x00, 0x03, 0xE1, 0xE0, 0x00, 0x07, 0xCF, 0x80, 0x00, 0x0F, + 0x3C, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x00, 0xFC, + 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x07, 0x80, 0x00, + 0x00, 0x1E, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, + 0x07, 0x80, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, + 0xE0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x3F, 0xFF, + 0xFF, 0xC7, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0xE0, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x01, + 0xF8, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0xFC, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x07, 0xE0, 0x00, 0x01, + 0xF8, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xF0, 0x00, + 0x00, 0xFC, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x7E, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x03, 0xE0, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xFF, 0xFF, 0xFF, + 0xFF, 0xE0, 0x07, 0x00, 0x18, 0x00, 0xE0, 0x07, 0x00, 0x18, 0x00, 0xE0, + 0x07, 0x00, 0x18, 0x00, 0xC0, 0x07, 0x00, 0x38, 0x00, 0xC0, 0x07, 0x00, + 0x38, 0x00, 0xC0, 0x06, 0x00, 0x38, 0x00, 0xC0, 0x06, 0x00, 0x38, 0x01, + 0xC0, 0x06, 0x00, 0x38, 0x01, 0xC0, 0x06, 0x00, 0x30, 0x01, 0xC0, 0x0E, + 0x00, 0x30, 0x01, 0xC0, 0x0E, 0x00, 0x30, 0x01, 0xC0, 0x0E, 0xFF, 0xFF, + 0xFF, 0xFF, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x3F, + 0x00, 0x0F, 0xC0, 0x07, 0xF8, 0x01, 0xCE, 0x00, 0x73, 0x80, 0x3C, 0x70, + 0x0E, 0x1C, 0x07, 0x87, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x38, 0x07, 0x0E, + 0x01, 0xC7, 0x80, 0x79, 0xC0, 0x0E, 0x70, 0x03, 0xB8, 0x00, 0x70, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x0F, 0x01, 0xE0, 0x3C, 0x07, + 0x00, 0xE0, 0x1C, 0x01, 0xFF, 0x00, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0xE0, + 0x3F, 0xFF, 0xF0, 0x7E, 0x03, 0xF8, 0x7C, 0x00, 0xF8, 0x78, 0x00, 0x78, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x78, 0x00, 0x00, 0x78, 0x00, 0x00, 0xF8, + 0x00, 0x03, 0xF8, 0x00, 0xFF, 0xF8, 0x0F, 0xFF, 0xF8, 0x3F, 0xFE, 0x78, + 0x7F, 0x80, 0x78, 0xFC, 0x00, 0x78, 0xF8, 0x00, 0x78, 0xF0, 0x00, 0x78, + 0xF0, 0x00, 0xF8, 0xF0, 0x00, 0xF8, 0xF8, 0x03, 0xF8, 0x7E, 0x0F, 0xF8, + 0x7F, 0xFF, 0x7F, 0x3F, 0xFE, 0x3F, 0x1F, 0xFC, 0x3F, 0x07, 0xE0, 0x1F, + 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF0, + 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF0, 0x7E, + 0x03, 0xC7, 0xFE, 0x0F, 0x7F, 0xFC, 0x3D, 0xFF, 0xF8, 0xFF, 0x07, 0xF3, + 0xF8, 0x07, 0xCF, 0xC0, 0x0F, 0xBE, 0x00, 0x1E, 0xF8, 0x00, 0x7B, 0xE0, + 0x01, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, + 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x01, 0xFF, + 0x80, 0x07, 0xBE, 0x00, 0x1E, 0xFC, 0x00, 0xFB, 0xF8, 0x07, 0xCF, 0xF0, + 0x7F, 0x3B, 0xFF, 0xF8, 0xE7, 0xFF, 0xC3, 0x8F, 0xFE, 0x00, 0x0F, 0xE0, + 0x00, 0x00, 0xFE, 0x00, 0x3F, 0xFC, 0x03, 0xFF, 0xF0, 0x3F, 0xFF, 0xC3, + 0xF0, 0x3F, 0x1F, 0x00, 0xF9, 0xF0, 0x03, 0xCF, 0x00, 0x0F, 0x78, 0x00, + 0x07, 0xC0, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, + 0x1E, 0x00, 0x1E, 0xF0, 0x00, 0xF7, 0xC0, 0x0F, 0x9F, 0x00, 0xF8, 0xFC, + 0x0F, 0xC3, 0xFF, 0xFC, 0x0F, 0xFF, 0xC0, 0x3F, 0xFC, 0x00, 0x7F, 0x00, + 0x00, 0x00, 0x1E, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x78, 0x00, 0x00, 0xF0, + 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x0F, 0x01, + 0xFC, 0x1E, 0x0F, 0xFE, 0x3C, 0x3F, 0xFF, 0x78, 0xFF, 0xFF, 0xF3, 0xF8, + 0x3F, 0xE7, 0xC0, 0x1F, 0xDF, 0x00, 0x1F, 0xBE, 0x00, 0x1F, 0x78, 0x00, + 0x3F, 0xF0, 0x00, 0x7F, 0xC0, 0x00, 0x7F, 0x80, 0x00, 0xFF, 0x00, 0x01, + 0xFE, 0x00, 0x03, 0xFC, 0x00, 0x07, 0xF8, 0x00, 0x0F, 0xF0, 0x00, 0x1F, + 0xF0, 0x00, 0x7D, 0xE0, 0x00, 0xFB, 0xC0, 0x01, 0xF7, 0xC0, 0x07, 0xE7, + 0xC0, 0x1F, 0xCF, 0xE0, 0xFF, 0x8F, 0xFF, 0xF7, 0x0F, 0xFF, 0xCE, 0x0F, + 0xFF, 0x1C, 0x07, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x0F, 0xFE, 0x00, 0xFF, + 0xFC, 0x07, 0xFF, 0xF8, 0x1F, 0x83, 0xF0, 0xF8, 0x07, 0xC7, 0xC0, 0x0F, + 0x9E, 0x00, 0x1E, 0x78, 0x00, 0x7B, 0xC0, 0x00, 0xFF, 0x00, 0x03, 0xFC, + 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, + 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x1E, + 0x7C, 0x00, 0x78, 0xF8, 0x03, 0xE3, 0xF0, 0x3F, 0x07, 0xFF, 0xF8, 0x0F, + 0xFF, 0xE0, 0x1F, 0xFE, 0x00, 0x0F, 0xE0, 0x00, 0x03, 0xC3, 0xF0, 0xFC, + 0x7F, 0x1F, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x3F, 0xFF, 0xFF, 0xFF, 0x1E, + 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, + 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x78, + 0x1E, 0x07, 0x80, 0x00, 0xFC, 0x00, 0x1F, 0xF8, 0xF0, 0xFF, 0xFB, 0xC7, + 0xFF, 0xFF, 0x3F, 0x83, 0xFC, 0xF8, 0x07, 0xF7, 0xC0, 0x0F, 0xDE, 0x00, + 0x1F, 0x78, 0x00, 0x7F, 0xE0, 0x00, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, + 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, + 0x00, 0x3F, 0xC0, 0x00, 0xF7, 0x80, 0x07, 0xDE, 0x00, 0x1F, 0x7C, 0x00, + 0xFC, 0xF8, 0x07, 0xF3, 0xF8, 0x3F, 0xC7, 0xFF, 0xEF, 0x0F, 0xFF, 0x3C, + 0x1F, 0xF8, 0xF0, 0x1F, 0x83, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x79, 0xE0, + 0x01, 0xE7, 0xC0, 0x0F, 0x8F, 0x80, 0xFC, 0x3F, 0xFF, 0xF0, 0x7F, 0xFF, + 0x80, 0xFF, 0xFC, 0x00, 0x7F, 0x80, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, + 0x00, 0x78, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x07, 0x80, + 0x00, 0xF0, 0xFE, 0x1E, 0x3F, 0xE3, 0xCF, 0xFF, 0x7B, 0xFF, 0xEF, 0xF0, + 0xFF, 0xF8, 0x07, 0xFF, 0x00, 0x7F, 0xC0, 0x0F, 0xF8, 0x01, 0xFE, 0x00, + 0x3F, 0xC0, 0x07, 0xF8, 0x00, 0xFF, 0x00, 0x1F, 0xE0, 0x03, 0xFC, 0x00, + 0x7F, 0x80, 0x0F, 0xF0, 0x01, 0xFE, 0x00, 0x3F, 0xC0, 0x07, 0xF8, 0x00, + 0xFF, 0x00, 0x1F, 0xE0, 0x03, 0xFC, 0x00, 0x7F, 0x80, 0x0F, 0xF0, 0x01, + 0xFE, 0x00, 0x3C, 0xFF, 0xFF, 0xF0, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x1F, + 0xFF, 0xFE, 0xFE, 0xF8, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x3C, 0x00, 0x01, + 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, + 0x00, 0xF0, 0x00, 0x07, 0x80, 0x1F, 0x3C, 0x01, 0xF1, 0xE0, 0x1F, 0x0F, + 0x01, 0xF0, 0x78, 0x1F, 0x03, 0xC1, 0xF0, 0x1E, 0x1F, 0x00, 0xF1, 0xF0, + 0x07, 0x9F, 0x00, 0x3D, 0xF8, 0x01, 0xFF, 0xE0, 0x0F, 0xFF, 0x80, 0x7F, + 0x7C, 0x03, 0xF1, 0xF0, 0x1F, 0x07, 0xC0, 0xF0, 0x3E, 0x07, 0x80, 0xF8, + 0x3C, 0x03, 0xC1, 0xE0, 0x1F, 0x0F, 0x00, 0x7C, 0x78, 0x03, 0xE3, 0xC0, + 0x0F, 0x9E, 0x00, 0x3C, 0xF0, 0x01, 0xF7, 0x80, 0x07, 0xC0, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0x00, 0xFC, 0x03, 0xF0, 0xE3, 0xFE, 0x0F, 0xFC, 0xE7, + 0xFF, 0x1F, 0xFE, 0xEF, 0xFF, 0xBF, 0xFE, 0xFE, 0x0F, 0xF8, 0x3F, 0xFC, + 0x07, 0xF0, 0x1F, 0xF8, 0x03, 0xE0, 0x0F, 0xF8, 0x03, 0xE0, 0x0F, 0xF0, + 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, + 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, + 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, + 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, + 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, + 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0xF0, 0x03, 0xC0, 0x0F, 0x00, + 0x7E, 0x0E, 0x1F, 0xF8, 0xE7, 0xFF, 0xCE, 0xFF, 0xFE, 0xEF, 0x07, 0xFF, + 0xE0, 0x1F, 0xFC, 0x01, 0xFF, 0x80, 0x0F, 0xF8, 0x00, 0xFF, 0x00, 0x0F, + 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, + 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, + 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, + 0x00, 0xFF, 0x00, 0x0F, 0x00, 0xFE, 0x00, 0x07, 0xFF, 0x00, 0x3F, 0xFF, + 0x80, 0xFF, 0xFF, 0x83, 0xF8, 0x3F, 0x87, 0xC0, 0x1F, 0x1F, 0x00, 0x1F, + 0x3C, 0x00, 0x1E, 0x78, 0x00, 0x3D, 0xF0, 0x00, 0x7F, 0xC0, 0x00, 0x7F, + 0x80, 0x00, 0xFF, 0x00, 0x01, 0xFE, 0x00, 0x03, 0xFC, 0x00, 0x07, 0xF8, + 0x00, 0x0F, 0xF0, 0x00, 0x1F, 0xF0, 0x00, 0x7D, 0xE0, 0x00, 0xF3, 0xC0, + 0x01, 0xE7, 0xC0, 0x07, 0xC7, 0xC0, 0x1F, 0x0F, 0xE0, 0xFE, 0x0F, 0xFF, + 0xF8, 0x0F, 0xFF, 0xE0, 0x0F, 0xFF, 0x80, 0x03, 0xF8, 0x00, 0x00, 0xFE, + 0x03, 0x8F, 0xFE, 0x0E, 0x7F, 0xFC, 0x3B, 0xFF, 0xF8, 0xFF, 0x87, 0xF3, + 0xF8, 0x07, 0xCF, 0xC0, 0x0F, 0xBE, 0x00, 0x1E, 0xF8, 0x00, 0x7B, 0xE0, + 0x01, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, + 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x01, 0xFF, + 0x80, 0x07, 0xBE, 0x00, 0x1E, 0xFC, 0x00, 0xFB, 0xF8, 0x07, 0xCF, 0xF0, + 0x7F, 0x3F, 0xFF, 0xF8, 0xF7, 0xFF, 0xC3, 0xC7, 0xFE, 0x0F, 0x07, 0xE0, + 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x00, + 0xFE, 0x00, 0x07, 0xFF, 0x1C, 0x3F, 0xFF, 0x38, 0xFF, 0xFF, 0x73, 0xF8, + 0x3F, 0xE7, 0xC0, 0x1F, 0xDF, 0x00, 0x1F, 0xBE, 0x00, 0x1F, 0x78, 0x00, + 0x3F, 0xF0, 0x00, 0x7F, 0xC0, 0x00, 0x7F, 0x80, 0x00, 0xFF, 0x00, 0x01, + 0xFE, 0x00, 0x03, 0xFC, 0x00, 0x07, 0xF8, 0x00, 0x0F, 0xF0, 0x00, 0x1F, + 0xF0, 0x00, 0x7D, 0xE0, 0x00, 0xFB, 0xC0, 0x01, 0xF7, 0xC0, 0x07, 0xE7, + 0xC0, 0x1F, 0xCF, 0xE0, 0xFF, 0x8F, 0xFF, 0xEF, 0x0F, 0xFF, 0xDE, 0x0F, + 0xFE, 0x3C, 0x07, 0xF0, 0x78, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, + 0x03, 0xC0, 0x00, 0x07, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0x78, 0x00, 0xFE, 0x1F, 0xE7, 0xFE, 0xFF, 0xFF, 0x8F, + 0xC0, 0xF8, 0x0F, 0x80, 0xF8, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0x01, 0xFC, 0x00, 0xFF, 0xF0, + 0x1F, 0xFF, 0x83, 0xFF, 0xFC, 0x3E, 0x07, 0xE7, 0xC0, 0x3E, 0x78, 0x01, + 0xE7, 0x80, 0x00, 0x78, 0x00, 0x07, 0xC0, 0x00, 0x7E, 0x00, 0x03, 0xFC, + 0x00, 0x1F, 0xFC, 0x00, 0xFF, 0xF8, 0x03, 0xFF, 0xC0, 0x03, 0xFE, 0x00, + 0x03, 0xF0, 0x00, 0x1F, 0x00, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, + 0x80, 0x1F, 0x7E, 0x07, 0xE7, 0xFF, 0xFE, 0x3F, 0xFF, 0xC1, 0xFF, 0xF0, + 0x03, 0xFC, 0x00, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x8F, 0xFF, + 0xFF, 0xFF, 0xC7, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1E, + 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1E, 0x07, 0x81, + 0xE0, 0x78, 0x1F, 0xC7, 0xF0, 0xFC, 0x1F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, + 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, + 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, + 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0xFF, 0x00, 0x0F, 0xF0, + 0x00, 0xFF, 0x00, 0x1F, 0xF0, 0x01, 0xFF, 0x00, 0x3F, 0xF8, 0x07, 0xFF, + 0xE0, 0xFF, 0x7F, 0xFF, 0x77, 0xFF, 0xE7, 0x1F, 0xFC, 0x70, 0x7E, 0x00, + 0x78, 0x00, 0x3E, 0xF0, 0x00, 0x79, 0xF0, 0x00, 0xF1, 0xE0, 0x03, 0xE3, + 0xC0, 0x07, 0x87, 0xC0, 0x0F, 0x07, 0x80, 0x3C, 0x0F, 0x00, 0x78, 0x1F, + 0x01, 0xF0, 0x1E, 0x03, 0xC0, 0x3C, 0x07, 0x80, 0x7C, 0x1F, 0x00, 0x78, + 0x3C, 0x00, 0xF0, 0x78, 0x01, 0xF1, 0xE0, 0x01, 0xE3, 0xC0, 0x03, 0xC7, + 0x80, 0x03, 0xDE, 0x00, 0x07, 0xBC, 0x00, 0x0F, 0x70, 0x00, 0x0F, 0xE0, + 0x00, 0x1F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, + 0xF8, 0x03, 0xE0, 0x07, 0x9E, 0x00, 0xFC, 0x01, 0xE7, 0x80, 0x3F, 0x00, + 0x79, 0xF0, 0x0F, 0xC0, 0x3E, 0x3C, 0x07, 0xF0, 0x0F, 0x0F, 0x01, 0xFE, + 0x03, 0xC3, 0xC0, 0x7F, 0x80, 0xF0, 0x78, 0x1D, 0xE0, 0x78, 0x1E, 0x0F, + 0x38, 0x1E, 0x07, 0x83, 0xCF, 0x07, 0x81, 0xE0, 0xF3, 0xC1, 0xE0, 0x3C, + 0x38, 0xF0, 0xF0, 0x0F, 0x1E, 0x1C, 0x3C, 0x03, 0xC7, 0x87, 0x8F, 0x00, + 0x71, 0xE1, 0xE3, 0x80, 0x1E, 0x70, 0x79, 0xE0, 0x07, 0xBC, 0x0E, 0x78, + 0x01, 0xEF, 0x03, 0xDE, 0x00, 0x3B, 0xC0, 0xF7, 0x00, 0x0F, 0xE0, 0x3F, + 0xC0, 0x03, 0xF8, 0x07, 0xF0, 0x00, 0x7E, 0x01, 0xF8, 0x00, 0x1F, 0x80, + 0x7E, 0x00, 0x07, 0xC0, 0x1F, 0x80, 0x01, 0xF0, 0x03, 0xC0, 0x00, 0x7C, + 0x00, 0x78, 0xF0, 0x03, 0xE1, 0xE0, 0x0F, 0x07, 0xC0, 0x78, 0x0F, 0x03, + 0xE0, 0x1E, 0x0F, 0x00, 0x7C, 0x78, 0x00, 0xF3, 0xE0, 0x01, 0xEF, 0x00, + 0x07, 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0x1F, 0x00, 0x00, 0x7C, 0x00, 0x03, + 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x7F, 0xC0, 0x03, 0xCF, 0x00, 0x0F, 0x1E, + 0x00, 0x78, 0x7C, 0x03, 0xE0, 0xF0, 0x0F, 0x03, 0xE0, 0x78, 0x07, 0xC3, + 0xE0, 0x0F, 0x1F, 0x00, 0x3E, 0x78, 0x00, 0x7C, 0x78, 0x00, 0x3D, 0xE0, + 0x01, 0xF7, 0x80, 0x07, 0x8F, 0x00, 0x1E, 0x3C, 0x00, 0xF0, 0xF0, 0x03, + 0xC1, 0xE0, 0x0F, 0x07, 0x80, 0x78, 0x1E, 0x01, 0xE0, 0x3C, 0x07, 0x80, + 0xF0, 0x3C, 0x03, 0xC0, 0xF0, 0x07, 0x87, 0xC0, 0x1E, 0x1E, 0x00, 0x78, + 0x78, 0x00, 0xF3, 0xC0, 0x03, 0xCF, 0x00, 0x0F, 0x3C, 0x00, 0x1F, 0xE0, + 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xC0, 0x00, + 0x3E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x3C, + 0x00, 0x01, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x3E, 0x00, 0x0F, 0xF0, 0x00, + 0x3F, 0xC0, 0x00, 0xFE, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x7F, 0xFF, 0xF7, + 0xFF, 0xFF, 0x7F, 0xFF, 0xF7, 0xFF, 0xFF, 0x00, 0x01, 0xE0, 0x00, 0x3E, + 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7C, + 0x00, 0x07, 0x80, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7C, + 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x03, 0xC0, 0x00, 0x7C, + 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, + 0x01, 0xE0, 0xFC, 0x1F, 0x87, 0x80, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, + 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, + 0xC0, 0x78, 0x1E, 0x0F, 0x81, 0xE0, 0x3C, 0x07, 0xC0, 0x3C, 0x03, 0x80, + 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, + 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0F, 0x00, 0xFC, 0x1F, 0x80, + 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xF0, 0x1F, 0x83, 0xF0, 0x0F, 0x00, + 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, + 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x1C, 0x03, 0xC0, 0x3E, 0x03, + 0xC0, 0x78, 0x1F, 0x07, 0x80, 0xE0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, + 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, + 0x70, 0x1E, 0x1F, 0x83, 0xF0, 0x78, 0x00, 0x3E, 0x00, 0x0F, 0xF0, 0x0D, + 0xFF, 0x01, 0xF0, 0xF8, 0x7C, 0x0F, 0xFD, 0x80, 0x7F, 0x80, 0x03, 0xE0 }; + +const GFXglyph FreeSans24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 12, 0, 1 }, // 0x20 ' ' + { 0, 4, 34, 16, 6, -33 }, // 0x21 '!' + { 17, 11, 12, 16, 2, -32 }, // 0x22 '"' + { 34, 24, 33, 26, 1, -31 }, // 0x23 '#' + { 133, 23, 41, 26, 1, -34 }, // 0x24 '$' + { 251, 39, 34, 42, 1, -32 }, // 0x25 '%' + { 417, 28, 34, 31, 2, -32 }, // 0x26 '&' + { 536, 4, 12, 9, 2, -32 }, // 0x27 ''' + { 542, 10, 44, 16, 3, -33 }, // 0x28 '(' + { 597, 10, 44, 16, 2, -33 }, // 0x29 ')' + { 652, 14, 14, 18, 2, -33 }, // 0x2A '*' + { 677, 23, 22, 27, 2, -21 }, // 0x2B '+' + { 741, 4, 12, 13, 4, -4 }, // 0x2C ',' + { 747, 11, 4, 16, 2, -14 }, // 0x2D '-' + { 753, 4, 5, 12, 4, -4 }, // 0x2E '.' + { 756, 13, 35, 13, 0, -33 }, // 0x2F '/' + { 813, 22, 34, 26, 2, -32 }, // 0x30 '0' + { 907, 11, 33, 26, 5, -32 }, // 0x31 '1' + { 953, 22, 33, 26, 2, -32 }, // 0x32 '2' + { 1044, 23, 34, 26, 1, -32 }, // 0x33 '3' + { 1142, 23, 33, 26, 1, -32 }, // 0x34 '4' + { 1237, 22, 34, 26, 2, -32 }, // 0x35 '5' + { 1331, 22, 34, 26, 2, -32 }, // 0x36 '6' + { 1425, 21, 33, 26, 2, -32 }, // 0x37 '7' + { 1512, 22, 34, 26, 2, -32 }, // 0x38 '8' + { 1606, 21, 34, 26, 2, -32 }, // 0x39 '9' + { 1696, 4, 25, 12, 4, -24 }, // 0x3A ':' + { 1709, 4, 32, 12, 4, -24 }, // 0x3B ';' + { 1725, 23, 23, 27, 2, -22 }, // 0x3C '<' + { 1792, 23, 12, 27, 2, -16 }, // 0x3D '=' + { 1827, 23, 23, 27, 2, -22 }, // 0x3E '>' + { 1894, 20, 35, 26, 4, -34 }, // 0x3F '?' + { 1982, 43, 42, 48, 2, -34 }, // 0x40 '@' + { 2208, 30, 34, 31, 1, -33 }, // 0x41 'A' + { 2336, 25, 34, 31, 4, -33 }, // 0x42 'B' + { 2443, 29, 36, 33, 2, -34 }, // 0x43 'C' + { 2574, 27, 34, 33, 4, -33 }, // 0x44 'D' + { 2689, 24, 34, 30, 4, -33 }, // 0x45 'E' + { 2791, 22, 34, 28, 4, -33 }, // 0x46 'F' + { 2885, 31, 36, 36, 2, -34 }, // 0x47 'G' + { 3025, 26, 34, 34, 4, -33 }, // 0x48 'H' + { 3136, 4, 34, 13, 5, -33 }, // 0x49 'I' + { 3153, 19, 35, 25, 2, -33 }, // 0x4A 'J' + { 3237, 27, 34, 32, 4, -33 }, // 0x4B 'K' + { 3352, 21, 34, 26, 4, -33 }, // 0x4C 'L' + { 3442, 32, 34, 40, 4, -33 }, // 0x4D 'M' + { 3578, 26, 34, 34, 4, -33 }, // 0x4E 'N' + { 3689, 33, 36, 37, 2, -34 }, // 0x4F 'O' + { 3838, 24, 34, 31, 4, -33 }, // 0x50 'P' + { 3940, 33, 38, 37, 2, -34 }, // 0x51 'Q' + { 4097, 26, 34, 33, 4, -33 }, // 0x52 'R' + { 4208, 27, 36, 31, 2, -34 }, // 0x53 'S' + { 4330, 26, 34, 30, 2, -33 }, // 0x54 'T' + { 4441, 26, 35, 34, 4, -33 }, // 0x55 'U' + { 4555, 29, 34, 30, 1, -33 }, // 0x56 'V' + { 4679, 42, 34, 44, 1, -33 }, // 0x57 'W' + { 4858, 29, 34, 31, 1, -33 }, // 0x58 'X' + { 4982, 30, 34, 32, 1, -33 }, // 0x59 'Y' + { 5110, 27, 34, 29, 1, -33 }, // 0x5A 'Z' + { 5225, 8, 44, 13, 3, -33 }, // 0x5B '[' + { 5269, 13, 35, 13, 0, -33 }, // 0x5C '\' + { 5326, 8, 44, 13, 1, -33 }, // 0x5D ']' + { 5370, 18, 18, 22, 2, -32 }, // 0x5E '^' + { 5411, 28, 2, 26, -1, 7 }, // 0x5F '_' + { 5418, 10, 7, 12, 1, -34 }, // 0x60 '`' + { 5427, 24, 27, 26, 1, -25 }, // 0x61 'a' + { 5508, 22, 35, 26, 3, -33 }, // 0x62 'b' + { 5605, 21, 27, 24, 1, -25 }, // 0x63 'c' + { 5676, 23, 35, 26, 1, -33 }, // 0x64 'd' + { 5777, 22, 27, 25, 1, -25 }, // 0x65 'e' + { 5852, 10, 34, 13, 1, -33 }, // 0x66 'f' + { 5895, 22, 36, 26, 1, -25 }, // 0x67 'g' + { 5994, 19, 34, 25, 3, -33 }, // 0x68 'h' + { 6075, 4, 34, 10, 3, -33 }, // 0x69 'i' + { 6092, 8, 44, 11, 0, -33 }, // 0x6A 'j' + { 6136, 21, 34, 24, 3, -33 }, // 0x6B 'k' + { 6226, 4, 34, 10, 3, -33 }, // 0x6C 'l' + { 6243, 32, 26, 38, 3, -25 }, // 0x6D 'm' + { 6347, 20, 26, 25, 3, -25 }, // 0x6E 'n' + { 6412, 23, 27, 25, 1, -25 }, // 0x6F 'o' + { 6490, 22, 35, 26, 3, -25 }, // 0x70 'p' + { 6587, 23, 35, 26, 1, -25 }, // 0x71 'q' + { 6688, 12, 26, 16, 3, -25 }, // 0x72 'r' + { 6727, 20, 27, 23, 1, -25 }, // 0x73 's' + { 6795, 10, 32, 13, 1, -30 }, // 0x74 't' + { 6835, 20, 26, 25, 3, -24 }, // 0x75 'u' + { 6900, 23, 25, 23, 0, -24 }, // 0x76 'v' + { 6972, 34, 25, 34, 0, -24 }, // 0x77 'w' + { 7079, 22, 25, 22, 0, -24 }, // 0x78 'x' + { 7148, 22, 35, 22, 0, -24 }, // 0x79 'y' + { 7245, 20, 25, 23, 1, -24 }, // 0x7A 'z' + { 7308, 11, 44, 16, 2, -33 }, // 0x7B '{' + { 7369, 3, 44, 12, 4, -33 }, // 0x7C '|' + { 7386, 11, 44, 16, 2, -33 }, // 0x7D '}' + { 7447, 19, 7, 24, 2, -19 } }; // 0x7E '~' + +const GFXfont FreeSans24pt7b PROGMEM = { + (uint8_t *)FreeSans24pt7bBitmaps, + (GFXglyph *)FreeSans24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 8136 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSans9pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSans9pt7b.h new file mode 100644 index 0000000..1f006a1 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSans9pt7b.h @@ -0,0 +1,201 @@ +const uint8_t FreeSans9pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xF8, 0xC0, 0xDE, 0xF7, 0x20, 0x09, 0x86, 0x41, 0x91, 0xFF, + 0x13, 0x04, 0xC3, 0x20, 0xC8, 0xFF, 0x89, 0x82, 0x61, 0x90, 0x10, 0x1F, + 0x14, 0xDA, 0x3D, 0x1E, 0x83, 0x40, 0x78, 0x17, 0x08, 0xF4, 0x7A, 0x35, + 0x33, 0xF0, 0x40, 0x20, 0x38, 0x10, 0xEC, 0x20, 0xC6, 0x20, 0xC6, 0x40, + 0xC6, 0x40, 0x6C, 0x80, 0x39, 0x00, 0x01, 0x3C, 0x02, 0x77, 0x02, 0x63, + 0x04, 0x63, 0x04, 0x77, 0x08, 0x3C, 0x0E, 0x06, 0x60, 0xCC, 0x19, 0x81, + 0xE0, 0x18, 0x0F, 0x03, 0x36, 0xC2, 0xD8, 0x73, 0x06, 0x31, 0xE3, 0xC4, + 0xFE, 0x13, 0x26, 0x6C, 0xCC, 0xCC, 0xC4, 0x66, 0x23, 0x10, 0x8C, 0x46, + 0x63, 0x33, 0x33, 0x32, 0x66, 0x4C, 0x80, 0x25, 0x7E, 0xA5, 0x00, 0x30, + 0xC3, 0x3F, 0x30, 0xC3, 0x0C, 0xD6, 0xF0, 0xC0, 0x08, 0x44, 0x21, 0x10, + 0x84, 0x42, 0x11, 0x08, 0x00, 0x3C, 0x66, 0x42, 0xC3, 0xC3, 0xC3, 0xC3, + 0xC3, 0xC3, 0xC3, 0x42, 0x66, 0x3C, 0x11, 0x3F, 0x33, 0x33, 0x33, 0x33, + 0x30, 0x3E, 0x31, 0xB0, 0x78, 0x30, 0x18, 0x1C, 0x1C, 0x1C, 0x18, 0x18, + 0x10, 0x08, 0x07, 0xF8, 0x3C, 0x66, 0xC3, 0xC3, 0x03, 0x06, 0x1C, 0x07, + 0x03, 0xC3, 0xC3, 0x66, 0x3C, 0x0C, 0x18, 0x71, 0x62, 0xC9, 0xA3, 0x46, + 0xFE, 0x18, 0x30, 0x60, 0xC0, 0x7F, 0x20, 0x10, 0x08, 0x08, 0x07, 0xF3, + 0x8C, 0x03, 0x01, 0x80, 0xF0, 0x6C, 0x63, 0xE0, 0x1E, 0x31, 0x98, 0x78, + 0x0C, 0x06, 0xF3, 0x8D, 0x83, 0xC1, 0xE0, 0xD0, 0x6C, 0x63, 0xE0, 0xFF, + 0x03, 0x02, 0x06, 0x04, 0x0C, 0x08, 0x18, 0x18, 0x18, 0x10, 0x30, 0x30, + 0x3E, 0x31, 0xB0, 0x78, 0x3C, 0x1B, 0x18, 0xF8, 0xC6, 0xC1, 0xE0, 0xF0, + 0x6C, 0x63, 0xE0, 0x3C, 0x66, 0xC2, 0xC3, 0xC3, 0xC3, 0x67, 0x3B, 0x03, + 0x03, 0xC2, 0x66, 0x3C, 0xC0, 0x00, 0x30, 0xC0, 0x00, 0x00, 0x64, 0xA0, + 0x00, 0x81, 0xC7, 0x8E, 0x0C, 0x07, 0x80, 0x70, 0x0E, 0x01, 0x80, 0xFF, + 0x80, 0x00, 0x1F, 0xF0, 0x00, 0x70, 0x0E, 0x01, 0xC0, 0x18, 0x38, 0x71, + 0xC0, 0x80, 0x00, 0x3E, 0x31, 0xB0, 0x78, 0x30, 0x18, 0x18, 0x38, 0x18, + 0x18, 0x0C, 0x00, 0x00, 0x01, 0x80, 0x03, 0xF0, 0x06, 0x0E, 0x06, 0x01, + 0x86, 0x00, 0x66, 0x1D, 0xBB, 0x31, 0xCF, 0x18, 0xC7, 0x98, 0x63, 0xCC, + 0x31, 0xE6, 0x11, 0xB3, 0x99, 0xCC, 0xF7, 0x86, 0x00, 0x01, 0x80, 0x00, + 0x70, 0x40, 0x0F, 0xE0, 0x06, 0x00, 0xF0, 0x0F, 0x00, 0x90, 0x19, 0x81, + 0x98, 0x10, 0x83, 0x0C, 0x3F, 0xC2, 0x04, 0x60, 0x66, 0x06, 0xC0, 0x30, + 0xFF, 0x18, 0x33, 0x03, 0x60, 0x6C, 0x0D, 0x83, 0x3F, 0xC6, 0x06, 0xC0, + 0x78, 0x0F, 0x01, 0xE0, 0x6F, 0xF8, 0x1F, 0x86, 0x19, 0x81, 0xA0, 0x3C, + 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, 0x68, 0x0D, 0x83, 0x18, 0x61, 0xF0, + 0xFF, 0x18, 0x33, 0x03, 0x60, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, + 0x78, 0x0F, 0x03, 0x60, 0xCF, 0xF0, 0xFF, 0xE0, 0x30, 0x18, 0x0C, 0x06, + 0x03, 0xFD, 0x80, 0xC0, 0x60, 0x30, 0x18, 0x0F, 0xF8, 0xFF, 0xC0, 0xC0, + 0xC0, 0xC0, 0xC0, 0xFE, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0x0F, 0x83, + 0x0E, 0x60, 0x66, 0x03, 0xC0, 0x0C, 0x00, 0xC1, 0xFC, 0x03, 0xC0, 0x36, + 0x03, 0x60, 0x73, 0x0F, 0x0F, 0x10, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, + 0x07, 0x80, 0xFF, 0xFE, 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x06, + 0xFF, 0xFF, 0xFF, 0xC0, 0x06, 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x07, + 0x8F, 0x1E, 0x27, 0x80, 0xC0, 0xD8, 0x33, 0x0C, 0x63, 0x0C, 0xC1, 0xB8, + 0x3F, 0x07, 0x30, 0xC3, 0x18, 0x63, 0x06, 0x60, 0x6C, 0x0C, 0xC0, 0xC0, + 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xFF, 0xE0, + 0x3F, 0x01, 0xFC, 0x1F, 0xE0, 0xFD, 0x05, 0xEC, 0x6F, 0x63, 0x79, 0x13, + 0xCD, 0x9E, 0x6C, 0xF1, 0x47, 0x8E, 0x3C, 0x71, 0x80, 0xE0, 0x7C, 0x0F, + 0xC1, 0xE8, 0x3D, 0x87, 0x98, 0xF1, 0x1E, 0x33, 0xC3, 0x78, 0x6F, 0x07, + 0xE0, 0x7C, 0x0E, 0x0F, 0x81, 0x83, 0x18, 0x0C, 0xC0, 0x6C, 0x01, 0xE0, + 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1B, 0x01, 0x98, 0x0C, 0x60, 0xC0, 0xF8, + 0x00, 0xFF, 0x30, 0x6C, 0x0F, 0x03, 0xC0, 0xF0, 0x6F, 0xF3, 0x00, 0xC0, + 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x00, 0x0F, 0x81, 0x83, 0x18, 0x0C, 0xC0, + 0x6C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1B, 0x01, 0x98, 0x6C, + 0x60, 0xC0, 0xFB, 0x00, 0x08, 0xFF, 0x8C, 0x0E, 0xC0, 0x6C, 0x06, 0xC0, + 0x6C, 0x0C, 0xFF, 0x8C, 0x0E, 0xC0, 0x6C, 0x06, 0xC0, 0x6C, 0x06, 0xC0, + 0x70, 0x3F, 0x18, 0x6C, 0x0F, 0x03, 0xC0, 0x1E, 0x01, 0xF0, 0x0E, 0x00, + 0xF0, 0x3C, 0x0D, 0x86, 0x3F, 0x00, 0xFF, 0x86, 0x03, 0x01, 0x80, 0xC0, + 0x60, 0x30, 0x18, 0x0C, 0x06, 0x03, 0x01, 0x80, 0xC0, 0xC0, 0x78, 0x0F, + 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x01, + 0xB0, 0x61, 0xF0, 0xC0, 0x6C, 0x0D, 0x81, 0x10, 0x63, 0x0C, 0x61, 0x04, + 0x60, 0xCC, 0x19, 0x01, 0x60, 0x3C, 0x07, 0x00, 0x60, 0xC1, 0x81, 0x30, + 0xE1, 0x98, 0x70, 0xCC, 0x28, 0x66, 0x26, 0x21, 0x13, 0x30, 0xC8, 0x98, + 0x6C, 0x4C, 0x14, 0x34, 0x0A, 0x1A, 0x07, 0x07, 0x03, 0x03, 0x80, 0x81, + 0x80, 0x60, 0x63, 0x0C, 0x30, 0xC1, 0x98, 0x0F, 0x00, 0xE0, 0x06, 0x00, + 0xF0, 0x19, 0x01, 0x98, 0x30, 0xC6, 0x0E, 0x60, 0x60, 0xC0, 0x36, 0x06, + 0x30, 0xC3, 0x0C, 0x19, 0x81, 0xD8, 0x0F, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x06, 0x00, 0x60, 0x06, 0x00, 0xFF, 0xC0, 0x60, 0x30, 0x0C, 0x06, 0x03, + 0x01, 0xC0, 0x60, 0x30, 0x18, 0x06, 0x03, 0x00, 0xFF, 0xC0, 0xFB, 0x6D, + 0xB6, 0xDB, 0x6D, 0xB6, 0xE0, 0x84, 0x10, 0x84, 0x10, 0x84, 0x10, 0x84, + 0x10, 0x80, 0xED, 0xB6, 0xDB, 0x6D, 0xB6, 0xDB, 0xE0, 0x30, 0x60, 0xA2, + 0x44, 0xD8, 0xA1, 0x80, 0xFF, 0xC0, 0xC6, 0x30, 0x7E, 0x71, 0xB0, 0xC0, + 0x60, 0xF3, 0xDB, 0x0D, 0x86, 0xC7, 0x3D, 0xC0, 0xC0, 0x60, 0x30, 0x1B, + 0xCE, 0x36, 0x0F, 0x07, 0x83, 0xC1, 0xE0, 0xF0, 0x7C, 0x6D, 0xE0, 0x3C, + 0x66, 0xC3, 0xC0, 0xC0, 0xC0, 0xC0, 0xC3, 0x66, 0x3C, 0x03, 0x03, 0x03, + 0x3B, 0x67, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0x67, 0x3B, 0x3C, 0x66, + 0xC3, 0xC3, 0xFF, 0xC0, 0xC0, 0xC3, 0x66, 0x3C, 0x36, 0x6F, 0x66, 0x66, + 0x66, 0x66, 0x60, 0x3B, 0x67, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0x67, + 0x3B, 0x03, 0x03, 0xC6, 0x7C, 0xC0, 0xC0, 0xC0, 0xDE, 0xE3, 0xC3, 0xC3, + 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xFF, 0xFF, 0xC0, 0x30, 0x03, + 0x33, 0x33, 0x33, 0x33, 0x33, 0x33, 0xE0, 0xC0, 0x60, 0x30, 0x18, 0x4C, + 0x46, 0x63, 0x61, 0xF0, 0xEC, 0x62, 0x31, 0x98, 0x6C, 0x30, 0xFF, 0xFF, + 0xFF, 0xC0, 0xDE, 0xF7, 0x1C, 0xF0, 0xC7, 0x86, 0x3C, 0x31, 0xE1, 0x8F, + 0x0C, 0x78, 0x63, 0xC3, 0x1E, 0x18, 0xC0, 0xDE, 0xE3, 0xC3, 0xC3, 0xC3, + 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0x3C, 0x66, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, + 0xC3, 0x66, 0x3C, 0xDE, 0x71, 0xB0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, + 0xE3, 0x6F, 0x30, 0x18, 0x0C, 0x00, 0x3B, 0x67, 0xC3, 0xC3, 0xC3, 0xC3, + 0xC3, 0xC3, 0x67, 0x3B, 0x03, 0x03, 0x03, 0xDF, 0x31, 0x8C, 0x63, 0x18, + 0xC6, 0x00, 0x3E, 0xE3, 0xC0, 0xC0, 0xE0, 0x3C, 0x07, 0xC3, 0xE3, 0x7E, + 0x66, 0xF6, 0x66, 0x66, 0x66, 0x67, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, 0xC3, + 0xC3, 0xC3, 0xC7, 0x7B, 0xC1, 0xA0, 0x98, 0xCC, 0x42, 0x21, 0xB0, 0xD0, + 0x28, 0x1C, 0x0C, 0x00, 0xC6, 0x1E, 0x38, 0x91, 0xC4, 0xCA, 0x66, 0xD3, + 0x16, 0xD0, 0xA6, 0x87, 0x1C, 0x38, 0xC0, 0xC6, 0x00, 0x43, 0x62, 0x36, + 0x1C, 0x18, 0x1C, 0x3C, 0x26, 0x62, 0x43, 0xC1, 0x21, 0x98, 0xCC, 0x42, + 0x61, 0xB0, 0xD0, 0x38, 0x1C, 0x0C, 0x06, 0x03, 0x01, 0x03, 0x00, 0xFE, + 0x0C, 0x30, 0xC1, 0x86, 0x18, 0x20, 0xC1, 0xFC, 0x36, 0x66, 0x66, 0x6E, + 0xCE, 0x66, 0x66, 0x66, 0x30, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xC6, 0x66, + 0x66, 0x67, 0x37, 0x66, 0x66, 0x66, 0xC0, 0x61, 0x24, 0x38 }; + +const GFXglyph FreeSans9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 2, 13, 6, 2, -12 }, // 0x21 '!' + { 4, 5, 4, 6, 1, -12 }, // 0x22 '"' + { 7, 10, 12, 10, 0, -11 }, // 0x23 '#' + { 22, 9, 16, 10, 1, -13 }, // 0x24 '$' + { 40, 16, 13, 16, 1, -12 }, // 0x25 '%' + { 66, 11, 13, 12, 1, -12 }, // 0x26 '&' + { 84, 2, 4, 4, 1, -12 }, // 0x27 ''' + { 85, 4, 17, 6, 1, -12 }, // 0x28 '(' + { 94, 4, 17, 6, 1, -12 }, // 0x29 ')' + { 103, 5, 5, 7, 1, -12 }, // 0x2A '*' + { 107, 6, 8, 11, 3, -7 }, // 0x2B '+' + { 113, 2, 4, 5, 2, 0 }, // 0x2C ',' + { 114, 4, 1, 6, 1, -4 }, // 0x2D '-' + { 115, 2, 1, 5, 1, 0 }, // 0x2E '.' + { 116, 5, 13, 5, 0, -12 }, // 0x2F '/' + { 125, 8, 13, 10, 1, -12 }, // 0x30 '0' + { 138, 4, 13, 10, 3, -12 }, // 0x31 '1' + { 145, 9, 13, 10, 1, -12 }, // 0x32 '2' + { 160, 8, 13, 10, 1, -12 }, // 0x33 '3' + { 173, 7, 13, 10, 2, -12 }, // 0x34 '4' + { 185, 9, 13, 10, 1, -12 }, // 0x35 '5' + { 200, 9, 13, 10, 1, -12 }, // 0x36 '6' + { 215, 8, 13, 10, 0, -12 }, // 0x37 '7' + { 228, 9, 13, 10, 1, -12 }, // 0x38 '8' + { 243, 8, 13, 10, 1, -12 }, // 0x39 '9' + { 256, 2, 10, 5, 1, -9 }, // 0x3A ':' + { 259, 3, 12, 5, 1, -8 }, // 0x3B ';' + { 264, 9, 9, 11, 1, -8 }, // 0x3C '<' + { 275, 9, 4, 11, 1, -5 }, // 0x3D '=' + { 280, 9, 9, 11, 1, -8 }, // 0x3E '>' + { 291, 9, 13, 10, 1, -12 }, // 0x3F '?' + { 306, 17, 16, 18, 1, -12 }, // 0x40 '@' + { 340, 12, 13, 12, 0, -12 }, // 0x41 'A' + { 360, 11, 13, 12, 1, -12 }, // 0x42 'B' + { 378, 11, 13, 13, 1, -12 }, // 0x43 'C' + { 396, 11, 13, 13, 1, -12 }, // 0x44 'D' + { 414, 9, 13, 11, 1, -12 }, // 0x45 'E' + { 429, 8, 13, 11, 1, -12 }, // 0x46 'F' + { 442, 12, 13, 14, 1, -12 }, // 0x47 'G' + { 462, 11, 13, 13, 1, -12 }, // 0x48 'H' + { 480, 2, 13, 5, 2, -12 }, // 0x49 'I' + { 484, 7, 13, 10, 1, -12 }, // 0x4A 'J' + { 496, 11, 13, 12, 1, -12 }, // 0x4B 'K' + { 514, 8, 13, 10, 1, -12 }, // 0x4C 'L' + { 527, 13, 13, 15, 1, -12 }, // 0x4D 'M' + { 549, 11, 13, 13, 1, -12 }, // 0x4E 'N' + { 567, 13, 13, 14, 1, -12 }, // 0x4F 'O' + { 589, 10, 13, 12, 1, -12 }, // 0x50 'P' + { 606, 13, 14, 14, 1, -12 }, // 0x51 'Q' + { 629, 12, 13, 13, 1, -12 }, // 0x52 'R' + { 649, 10, 13, 12, 1, -12 }, // 0x53 'S' + { 666, 9, 13, 11, 1, -12 }, // 0x54 'T' + { 681, 11, 13, 13, 1, -12 }, // 0x55 'U' + { 699, 11, 13, 12, 0, -12 }, // 0x56 'V' + { 717, 17, 13, 17, 0, -12 }, // 0x57 'W' + { 745, 12, 13, 12, 0, -12 }, // 0x58 'X' + { 765, 12, 13, 12, 0, -12 }, // 0x59 'Y' + { 785, 10, 13, 11, 1, -12 }, // 0x5A 'Z' + { 802, 3, 17, 5, 1, -12 }, // 0x5B '[' + { 809, 5, 13, 5, 0, -12 }, // 0x5C '\' + { 818, 3, 17, 5, 0, -12 }, // 0x5D ']' + { 825, 7, 7, 8, 1, -12 }, // 0x5E '^' + { 832, 10, 1, 10, 0, 3 }, // 0x5F '_' + { 834, 4, 3, 5, 0, -12 }, // 0x60 '`' + { 836, 9, 10, 10, 1, -9 }, // 0x61 'a' + { 848, 9, 13, 10, 1, -12 }, // 0x62 'b' + { 863, 8, 10, 9, 1, -9 }, // 0x63 'c' + { 873, 8, 13, 10, 1, -12 }, // 0x64 'd' + { 886, 8, 10, 10, 1, -9 }, // 0x65 'e' + { 896, 4, 13, 5, 1, -12 }, // 0x66 'f' + { 903, 8, 14, 10, 1, -9 }, // 0x67 'g' + { 917, 8, 13, 10, 1, -12 }, // 0x68 'h' + { 930, 2, 13, 4, 1, -12 }, // 0x69 'i' + { 934, 4, 17, 4, 0, -12 }, // 0x6A 'j' + { 943, 9, 13, 9, 1, -12 }, // 0x6B 'k' + { 958, 2, 13, 4, 1, -12 }, // 0x6C 'l' + { 962, 13, 10, 15, 1, -9 }, // 0x6D 'm' + { 979, 8, 10, 10, 1, -9 }, // 0x6E 'n' + { 989, 8, 10, 10, 1, -9 }, // 0x6F 'o' + { 999, 9, 13, 10, 1, -9 }, // 0x70 'p' + { 1014, 8, 13, 10, 1, -9 }, // 0x71 'q' + { 1027, 5, 10, 6, 1, -9 }, // 0x72 'r' + { 1034, 8, 10, 9, 1, -9 }, // 0x73 's' + { 1044, 4, 12, 5, 1, -11 }, // 0x74 't' + { 1050, 8, 10, 10, 1, -9 }, // 0x75 'u' + { 1060, 9, 10, 9, 0, -9 }, // 0x76 'v' + { 1072, 13, 10, 13, 0, -9 }, // 0x77 'w' + { 1089, 8, 10, 9, 0, -9 }, // 0x78 'x' + { 1099, 9, 14, 9, 0, -9 }, // 0x79 'y' + { 1115, 7, 10, 9, 1, -9 }, // 0x7A 'z' + { 1124, 4, 17, 6, 1, -12 }, // 0x7B '{' + { 1133, 2, 17, 4, 2, -12 }, // 0x7C '|' + { 1138, 4, 17, 6, 1, -12 }, // 0x7D '}' + { 1147, 7, 3, 9, 1, -7 } }; // 0x7E '~' + +const GFXfont FreeSans9pt7b PROGMEM = { + (uint8_t *)FreeSans9pt7bBitmaps, + (GFXglyph *)FreeSans9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 1822 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBold12pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBold12pt7b.h new file mode 100644 index 0000000..e0922be --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBold12pt7b.h @@ -0,0 +1,288 @@ +const uint8_t FreeSansBold12pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xFF, 0x76, 0x66, 0x60, 0xFF, 0xF0, 0xF3, 0xFC, 0xFF, + 0x3F, 0xCF, 0x61, 0x98, 0x60, 0x0E, 0x70, 0x73, 0x83, 0x18, 0xFF, 0xF7, + 0xFF, 0xBF, 0xFC, 0x73, 0x83, 0x18, 0x18, 0xC7, 0xFF, 0xBF, 0xFD, 0xFF, + 0xE3, 0x18, 0x39, 0xC1, 0xCE, 0x0E, 0x70, 0x02, 0x00, 0x7E, 0x0F, 0xF8, + 0x7F, 0xE7, 0xAF, 0xB9, 0x3D, 0xC8, 0x0F, 0x40, 0x3F, 0x00, 0xFF, 0x00, + 0xFC, 0x05, 0xFF, 0x27, 0xF9, 0x3F, 0xEB, 0xEF, 0xFE, 0x3F, 0xE0, 0x7C, + 0x00, 0x80, 0x04, 0x00, 0x3C, 0x06, 0x0F, 0xC1, 0x81, 0xFC, 0x30, 0x73, + 0x8C, 0x0C, 0x31, 0x81, 0xCE, 0x60, 0x1F, 0xCC, 0x03, 0xF3, 0x00, 0x3C, + 0x67, 0x80, 0x19, 0xF8, 0x02, 0x7F, 0x80, 0xCE, 0x70, 0x11, 0x86, 0x06, + 0x39, 0xC1, 0x87, 0xF8, 0x30, 0x7E, 0x0C, 0x07, 0x80, 0x07, 0x80, 0x1F, + 0xC0, 0x3F, 0xE0, 0x3C, 0xE0, 0x3C, 0xE0, 0x3E, 0xE0, 0x0F, 0xC0, 0x07, + 0x00, 0x3F, 0x8C, 0x7F, 0xCC, 0xF1, 0xFC, 0xF0, 0xF8, 0xF0, 0x78, 0xF8, + 0xF8, 0x7F, 0xFC, 0x3F, 0xDE, 0x1F, 0x8E, 0xFF, 0xFF, 0x66, 0x0C, 0x73, + 0x8E, 0x71, 0xC7, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x8E, 0x1C, 0x71, 0xC3, + 0x8E, 0x18, 0x70, 0xC3, 0x87, 0x1C, 0x38, 0xE3, 0x87, 0x1C, 0x71, 0xC7, + 0x1C, 0x71, 0xCE, 0x38, 0xE7, 0x1C, 0x63, 0x80, 0x10, 0x23, 0x5F, 0xF3, + 0x87, 0x1B, 0x14, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x0F, 0xFF, 0xFF, 0xFF, + 0xF8, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x00, 0xFF, 0xF3, 0x36, 0xC0, 0xFF, + 0xFF, 0xC0, 0xFF, 0xF0, 0x0C, 0x30, 0x86, 0x18, 0x61, 0x0C, 0x30, 0xC2, + 0x18, 0x61, 0x84, 0x30, 0xC0, 0x1F, 0x83, 0xFC, 0x7F, 0xE7, 0x9E, 0xF0, + 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, + 0xF7, 0x9E, 0x7F, 0xE3, 0xFC, 0x0F, 0x00, 0x06, 0x1C, 0x7F, 0xFF, 0xE3, + 0xC7, 0x8F, 0x1E, 0x3C, 0x78, 0xF1, 0xE3, 0xC7, 0x8F, 0x1E, 0x1F, 0x83, + 0xFC, 0x7F, 0xEF, 0x9F, 0xF0, 0xFF, 0x0F, 0x00, 0xF0, 0x0F, 0x01, 0xE0, + 0x3C, 0x0F, 0x81, 0xE0, 0x3C, 0x03, 0x80, 0x7F, 0xF7, 0xFF, 0x7F, 0xF0, + 0x1F, 0x07, 0xFC, 0xFF, 0xEF, 0x1E, 0xF1, 0xE0, 0x1E, 0x03, 0xC0, 0x78, + 0x07, 0xC0, 0x1E, 0x00, 0xF0, 0x0F, 0xF0, 0xFF, 0x1F, 0x7F, 0xE7, 0xFC, + 0x1F, 0x80, 0x03, 0xC0, 0xF8, 0x1F, 0x07, 0xE1, 0xBC, 0x27, 0x8C, 0xF3, + 0x1E, 0x63, 0xD8, 0x7B, 0xFF, 0xFF, 0xFF, 0xFE, 0x07, 0x80, 0xF0, 0x1E, + 0x03, 0xC0, 0x3F, 0xE7, 0xFE, 0x7F, 0xE7, 0x00, 0x60, 0x06, 0xF8, 0x7F, + 0xCF, 0xFE, 0xF1, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xFE, 0x1E, 0xFF, + 0xE7, 0xFC, 0x3F, 0x00, 0x0F, 0x83, 0xFC, 0x7F, 0xE7, 0x9F, 0xF0, 0x0F, + 0x78, 0xFF, 0xCF, 0xFE, 0xF9, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xF7, + 0x9F, 0x7F, 0xE3, 0xFC, 0x0F, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0xE0, + 0x1C, 0x07, 0x01, 0xE0, 0x38, 0x0F, 0x01, 0xC0, 0x78, 0x0F, 0x01, 0xE0, + 0x38, 0x0F, 0x01, 0xE0, 0x3C, 0x00, 0x0F, 0x03, 0xFC, 0x7F, 0xC7, 0x9E, + 0x70, 0xE7, 0x0E, 0x39, 0xC1, 0xF8, 0x3F, 0xC7, 0x9E, 0xF0, 0xFF, 0x0F, + 0xF0, 0xFF, 0x9F, 0x7F, 0xE3, 0xFC, 0x1F, 0x80, 0x1F, 0x03, 0xFC, 0x7F, + 0xEF, 0x9E, 0xF0, 0xEF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF9, 0xF7, 0xFF, 0x3F, + 0xF1, 0xEF, 0x00, 0xEF, 0x1E, 0x7F, 0xE7, 0xFC, 0x1F, 0x00, 0xFF, 0xF0, + 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x0F, 0xFF, 0x11, 0x6C, + 0x00, 0x10, 0x07, 0x03, 0xF1, 0xFC, 0x7E, 0x0F, 0x80, 0xE0, 0x0F, 0xC0, + 0x3F, 0x80, 0x7F, 0x00, 0xF0, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, + 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x0E, 0x00, 0xFC, + 0x07, 0xF0, 0x0F, 0xE0, 0x1F, 0x00, 0xF0, 0x7F, 0x1F, 0x8F, 0xE0, 0xF0, + 0x08, 0x00, 0x1F, 0x07, 0xFC, 0x7F, 0xEF, 0x9F, 0xF0, 0xFF, 0x0F, 0x00, + 0xF0, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x0E, 0x00, 0xE0, 0x00, + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x00, 0xFE, 0x00, 0x1F, 0xFC, 0x03, 0xC0, + 0xF0, 0x38, 0x01, 0xC3, 0x80, 0x07, 0x18, 0x3D, 0x99, 0x87, 0xEC, 0x6C, + 0x71, 0xC3, 0xC3, 0x06, 0x1E, 0x18, 0x30, 0xF1, 0x81, 0x87, 0x8C, 0x18, + 0x7C, 0x60, 0xC3, 0x63, 0x8E, 0x3B, 0x8F, 0xDF, 0x8C, 0x3C, 0xF0, 0x70, + 0x00, 0x01, 0xC0, 0x00, 0x07, 0x80, 0x80, 0x1F, 0xFE, 0x00, 0x1F, 0xC0, + 0x00, 0x03, 0xE0, 0x03, 0xE0, 0x03, 0xE0, 0x07, 0xF0, 0x07, 0xF0, 0x07, + 0x70, 0x0F, 0x78, 0x0E, 0x78, 0x0E, 0x38, 0x1E, 0x3C, 0x1C, 0x3C, 0x3F, + 0xFC, 0x3F, 0xFE, 0x3F, 0xFE, 0x78, 0x0E, 0x78, 0x0F, 0x70, 0x0F, 0xF0, + 0x07, 0xFF, 0xC3, 0xFF, 0xCF, 0xFF, 0x3C, 0x3E, 0xF0, 0x7B, 0xC1, 0xEF, + 0x0F, 0xBF, 0xFC, 0xFF, 0xE3, 0xFF, 0xCF, 0x07, 0xBC, 0x0F, 0xF0, 0x3F, + 0xC0, 0xFF, 0x07, 0xFF, 0xFE, 0xFF, 0xFB, 0xFF, 0x80, 0x07, 0xE0, 0x1F, + 0xF8, 0x3F, 0xFC, 0x7C, 0x3E, 0x78, 0x1F, 0xF8, 0x0F, 0xF0, 0x00, 0xF0, + 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF8, 0x0F, 0x78, + 0x1F, 0x7C, 0x3E, 0x3F, 0xFE, 0x1F, 0xFC, 0x07, 0xF0, 0xFF, 0xE1, 0xFF, + 0xE3, 0xFF, 0xE7, 0x83, 0xEF, 0x03, 0xDE, 0x07, 0xFC, 0x07, 0xF8, 0x0F, + 0xF0, 0x1F, 0xE0, 0x3F, 0xC0, 0x7F, 0x80, 0xFF, 0x03, 0xFE, 0x07, 0xBC, + 0x1F, 0x7F, 0xFC, 0xFF, 0xF1, 0xFF, 0x80, 0xFF, 0xF7, 0xFF, 0xBF, 0xFD, + 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1F, 0xFC, 0xFF, 0xE7, 0xFF, 0x3C, + 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0xFE, 0xFF, 0xEF, 0xFE, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x0F, 0x00, 0x03, 0xF0, 0x0F, 0xFC, 0x3F, 0xFE, 0x3E, 0x1F, + 0x78, 0x07, 0x78, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF0, 0x7F, 0xF0, 0x7F, + 0xF0, 0x7F, 0xF0, 0x07, 0x78, 0x07, 0x7C, 0x0F, 0x3E, 0x1F, 0x3F, 0xFB, + 0x0F, 0xFB, 0x03, 0xE3, 0xF0, 0x3F, 0xC0, 0xFF, 0x03, 0xFC, 0x0F, 0xF0, + 0x3F, 0xC0, 0xFF, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFC, + 0x0F, 0xF0, 0x3F, 0xC0, 0xFF, 0x03, 0xFC, 0x0F, 0xF0, 0x3F, 0xC0, 0xF0, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x01, 0xE0, 0x3C, + 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, + 0xF8, 0xFF, 0x1F, 0xE3, 0xFC, 0x7B, 0xFE, 0x7F, 0xC3, 0xE0, 0xF0, 0x3E, + 0xF0, 0x3C, 0xF0, 0x78, 0xF0, 0xF0, 0xF1, 0xE0, 0xF3, 0xC0, 0xF7, 0x80, + 0xFF, 0x00, 0xFF, 0x80, 0xFF, 0x80, 0xFB, 0xC0, 0xF1, 0xE0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0x78, 0xF0, 0x3C, 0xF0, 0x3E, 0xF0, 0x1E, 0xF0, 0x1E, + 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, + 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0xFF, 0xFF, 0xFF, 0xFC, 0xF8, + 0x1F, 0xFE, 0x0F, 0xFF, 0x0F, 0xFF, 0x87, 0xFF, 0xC3, 0xFF, 0xE1, 0xFF, + 0xF9, 0xFF, 0xFC, 0xEF, 0xFE, 0x77, 0xFB, 0x3B, 0xFD, 0xDD, 0xFE, 0xFC, + 0xFF, 0x7E, 0x7F, 0x9F, 0x3F, 0xCF, 0x9F, 0xE7, 0x8F, 0xF3, 0xC7, 0xF8, + 0xE3, 0xC0, 0xF0, 0x1F, 0xF0, 0x3F, 0xF0, 0x7F, 0xE0, 0xFF, 0xE1, 0xFF, + 0xC3, 0xFD, 0xC7, 0xFB, 0x8F, 0xF3, 0x9F, 0xE7, 0x3F, 0xC7, 0x7F, 0x8F, + 0xFF, 0x0F, 0xFE, 0x1F, 0xFC, 0x1F, 0xF8, 0x1F, 0xF0, 0x3F, 0xE0, 0x3C, + 0x03, 0xE0, 0x0F, 0xFC, 0x0F, 0xFF, 0x87, 0xC7, 0xC7, 0x80, 0xF3, 0xC0, + 0x7B, 0xC0, 0x1F, 0xE0, 0x0F, 0xF0, 0x07, 0xF8, 0x03, 0xFC, 0x01, 0xFE, + 0x00, 0xF7, 0x80, 0xF3, 0xC0, 0x78, 0xF0, 0xF8, 0x7F, 0xFC, 0x1F, 0xFC, + 0x03, 0xF8, 0x00, 0xFF, 0xE3, 0xFF, 0xEF, 0xFF, 0xBC, 0x1F, 0xF0, 0x3F, + 0xC0, 0xFF, 0x03, 0xFC, 0x1F, 0xFF, 0xFB, 0xFF, 0xCF, 0xFE, 0x3C, 0x00, + 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x00, 0x03, + 0xE0, 0x0F, 0xFC, 0x0F, 0xFF, 0x87, 0xC7, 0xC7, 0x80, 0xF3, 0xC0, 0x7B, + 0xC0, 0x1F, 0xE0, 0x0F, 0xF0, 0x07, 0xF8, 0x03, 0xFC, 0x01, 0xFE, 0x04, + 0xF7, 0x87, 0xF3, 0xC3, 0xF8, 0xF0, 0xF8, 0x7F, 0xFC, 0x1F, 0xFF, 0x83, + 0xF1, 0x80, 0x00, 0x00, 0xFF, 0xF8, 0xFF, 0xFC, 0xFF, 0xFC, 0xF0, 0x3E, + 0xF0, 0x1E, 0xF0, 0x1E, 0xF0, 0x1E, 0xF0, 0x3C, 0xFF, 0xF8, 0xFF, 0xF0, + 0xFF, 0xF8, 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, 0x3C, + 0xF0, 0x3C, 0xF0, 0x1F, 0x0F, 0xC0, 0x7F, 0xE1, 0xFF, 0xE7, 0xC3, 0xEF, + 0x03, 0xDE, 0x00, 0x3C, 0x00, 0x7F, 0x00, 0x7F, 0xF0, 0x3F, 0xF8, 0x0F, + 0xF8, 0x01, 0xF0, 0x01, 0xFE, 0x03, 0xDE, 0x0F, 0xBF, 0xFE, 0x3F, 0xF8, + 0x1F, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0xF0, 0x3F, 0xC0, 0xFF, 0x03, 0xFC, 0x0F, + 0xF0, 0x3F, 0xC0, 0xFF, 0x03, 0xFC, 0x0F, 0xF0, 0x3F, 0xC0, 0xFF, 0x03, + 0xFC, 0x0F, 0xF0, 0x3F, 0xC0, 0xF7, 0x87, 0x9F, 0xFE, 0x3F, 0xF0, 0x3F, + 0x00, 0x70, 0x0E, 0xF0, 0x3D, 0xE0, 0x79, 0xC0, 0xE3, 0x81, 0xC7, 0x87, + 0x87, 0x0E, 0x0E, 0x1C, 0x1E, 0x78, 0x1C, 0xE0, 0x39, 0xC0, 0x73, 0x80, + 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x70, + 0x38, 0x1C, 0xE0, 0xF0, 0x79, 0xE1, 0xF0, 0xF3, 0xC3, 0xE1, 0xE3, 0x87, + 0xC3, 0x87, 0x0F, 0x87, 0x0E, 0x3B, 0x9E, 0x1E, 0x77, 0x38, 0x1C, 0xEE, + 0x70, 0x39, 0xCC, 0xE0, 0x73, 0x99, 0xC0, 0x6E, 0x3F, 0x00, 0xFC, 0x7E, + 0x01, 0xF8, 0xFC, 0x03, 0xF0, 0xF8, 0x03, 0xE1, 0xE0, 0x07, 0x83, 0xC0, + 0x0F, 0x07, 0x80, 0xF0, 0x3C, 0xF0, 0xF9, 0xE1, 0xE1, 0xE7, 0x83, 0xCF, + 0x03, 0xFC, 0x03, 0xF0, 0x07, 0xE0, 0x07, 0x80, 0x0F, 0x00, 0x3F, 0x00, + 0xFF, 0x01, 0xFE, 0x07, 0x9E, 0x0F, 0x1E, 0x3C, 0x3C, 0xF8, 0x3D, 0xE0, + 0x78, 0xF0, 0x1E, 0x78, 0x1E, 0x78, 0x3C, 0x3C, 0x3C, 0x3C, 0x78, 0x1E, + 0x78, 0x0E, 0x70, 0x0F, 0xF0, 0x07, 0xE0, 0x07, 0xE0, 0x03, 0xC0, 0x03, + 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, + 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x01, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF8, 0x07, 0x80, 0x78, 0x07, 0x80, 0x7C, 0x03, 0xC0, 0x3C, 0x03, + 0xC0, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFC, 0xF3, 0xCF, + 0x3C, 0xF3, 0xCF, 0x3C, 0xF3, 0xCF, 0x3C, 0xF3, 0xCF, 0x3C, 0xFF, 0xFF, + 0xC0, 0xC1, 0x81, 0x03, 0x06, 0x04, 0x0C, 0x18, 0x10, 0x30, 0x60, 0x40, + 0xC1, 0x81, 0x03, 0x06, 0xFF, 0xFF, 0xCF, 0x3C, 0xF3, 0xCF, 0x3C, 0xF3, + 0xCF, 0x3C, 0xF3, 0xCF, 0x3C, 0xF3, 0xCF, 0xFF, 0xFF, 0xC0, 0x0F, 0x00, + 0xF0, 0x0F, 0x01, 0xF8, 0x1B, 0x83, 0x9C, 0x39, 0xC3, 0x0C, 0x70, 0xE7, + 0x0E, 0xE0, 0x70, 0xFF, 0xFF, 0xFF, 0xFC, 0xE6, 0x30, 0x1F, 0x83, 0xFF, + 0x1F, 0xFD, 0xE1, 0xE0, 0x0F, 0x03, 0xF9, 0xFF, 0xDF, 0x1E, 0xF0, 0xF7, + 0x8F, 0xBF, 0xFC, 0xFF, 0xE3, 0xCF, 0x80, 0xF0, 0x07, 0x80, 0x3C, 0x01, + 0xE0, 0x0F, 0x00, 0x7B, 0xC3, 0xFF, 0x9F, 0xFE, 0xF8, 0xF7, 0x83, 0xFC, + 0x1F, 0xE0, 0xFF, 0x07, 0xF8, 0x3F, 0xE3, 0xDF, 0xFE, 0xFF, 0xE7, 0xBE, + 0x00, 0x0F, 0x83, 0xFE, 0x7F, 0xF7, 0x8F, 0xF0, 0x7F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x77, 0x8F, 0x7F, 0xF3, 0xFE, 0x0F, 0x80, 0x00, 0x78, 0x03, + 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x8F, 0xBC, 0xFF, 0xEF, 0xFF, 0x78, 0xFF, + 0x83, 0xFC, 0x1F, 0xE0, 0xFF, 0x07, 0xF8, 0x3D, 0xE3, 0xEF, 0xFF, 0x3F, + 0xF8, 0xFB, 0xC0, 0x1F, 0x81, 0xFE, 0x1F, 0xF9, 0xF1, 0xCF, 0x07, 0x7F, + 0xFB, 0xFF, 0xDE, 0x00, 0xF0, 0x03, 0xC3, 0x9F, 0xFC, 0x7F, 0xC0, 0xF8, + 0x00, 0x3E, 0xFD, 0xFB, 0xC7, 0x9F, 0xBF, 0x3C, 0x78, 0xF1, 0xE3, 0xC7, + 0x8F, 0x1E, 0x3C, 0x78, 0xF0, 0x1E, 0x79, 0xFB, 0xDF, 0xFE, 0xF1, 0xFF, + 0x07, 0xF8, 0x3F, 0xC1, 0xFE, 0x0F, 0xF0, 0x7F, 0xC7, 0xDF, 0xFE, 0x7F, + 0xF1, 0xF7, 0x80, 0x3C, 0x01, 0xFF, 0x1E, 0x7F, 0xF0, 0xFE, 0x00, 0xF0, + 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x7C, 0xFF, 0xEF, 0xFF, 0xF9, + 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, + 0xFF, 0x0F, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x3C, + 0xF3, 0xC0, 0x00, 0xF3, 0xCF, 0x3C, 0xF3, 0xCF, 0x3C, 0xF3, 0xCF, 0x3C, + 0xF3, 0xCF, 0xFF, 0xFF, 0x80, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, + 0x0F, 0x0F, 0xF1, 0xEF, 0x3C, 0xF7, 0x8F, 0xF0, 0xFF, 0x0F, 0xF8, 0xFF, + 0x8F, 0x3C, 0xF1, 0xCF, 0x1E, 0xF0, 0xEF, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF7, 0x8F, 0x9F, 0xFB, 0xFB, 0xFF, 0xFF, + 0xFC, 0xF8, 0xFF, 0x1E, 0x1F, 0xE3, 0xC3, 0xFC, 0x78, 0x7F, 0x8F, 0x0F, + 0xF1, 0xE1, 0xFE, 0x3C, 0x3F, 0xC7, 0x87, 0xF8, 0xF0, 0xFF, 0x1E, 0x1E, + 0xF7, 0xCF, 0xFE, 0xFF, 0xFF, 0x9F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, + 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xF0, 0x0F, 0x81, 0xFF, 0x1F, + 0xFC, 0xF1, 0xEF, 0x07, 0xF8, 0x3F, 0xC1, 0xFE, 0x0F, 0xF0, 0x7B, 0xC7, + 0x9F, 0xFC, 0x7F, 0xC0, 0xF8, 0x00, 0xF7, 0xC7, 0xFF, 0x3F, 0xFD, 0xF1, + 0xEF, 0x07, 0xF8, 0x3F, 0xC1, 0xFE, 0x0F, 0xF0, 0x7F, 0xC7, 0xBF, 0xFD, + 0xFF, 0xCF, 0x78, 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x00, + 0x0F, 0x79, 0xFF, 0xDF, 0xFE, 0xF1, 0xFF, 0x07, 0xF8, 0x3F, 0xC1, 0xFE, + 0x0F, 0xF0, 0x7B, 0xC7, 0xDF, 0xFE, 0x7F, 0xF1, 0xF7, 0x80, 0x3C, 0x01, + 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0xF3, 0xF7, 0xFF, 0xF8, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0x1F, 0x87, 0xFC, 0xFF, 0xEF, + 0x0F, 0xF8, 0x0F, 0xF0, 0x7F, 0xE0, 0xFF, 0x01, 0xFF, 0x0F, 0xFF, 0xE7, + 0xFE, 0x1F, 0x80, 0x79, 0xE7, 0xBF, 0xFD, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, + 0x7D, 0xF3, 0xC0, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, + 0xF0, 0xFF, 0x0F, 0xF0, 0xFF, 0x1F, 0xFF, 0xF7, 0xFF, 0x3E, 0xF0, 0xF0, + 0x7B, 0x83, 0x9E, 0x1C, 0xF1, 0xE3, 0x8E, 0x1C, 0x70, 0x77, 0x83, 0xB8, + 0x1D, 0xC0, 0x7E, 0x03, 0xE0, 0x1F, 0x00, 0x70, 0x00, 0xF0, 0xE1, 0xDC, + 0x78, 0x77, 0x1F, 0x3D, 0xE7, 0xCF, 0x79, 0xB3, 0x8E, 0x6C, 0xE3, 0xBB, + 0x38, 0xEE, 0xFC, 0x1F, 0x3F, 0x07, 0xC7, 0xC1, 0xF1, 0xF0, 0x7C, 0x78, + 0x0E, 0x1E, 0x00, 0x78, 0xF3, 0xC7, 0x8F, 0x78, 0x3B, 0x81, 0xFC, 0x07, + 0xC0, 0x1E, 0x01, 0xF0, 0x1F, 0xC0, 0xEF, 0x0F, 0x78, 0xF1, 0xE7, 0x87, + 0x00, 0xF0, 0x7B, 0x83, 0x9E, 0x1C, 0x71, 0xE3, 0x8E, 0x1E, 0x70, 0x73, + 0x83, 0xB8, 0x1F, 0xC0, 0x7E, 0x03, 0xE0, 0x0F, 0x00, 0x70, 0x03, 0x80, + 0x3C, 0x07, 0xC0, 0x3E, 0x01, 0xE0, 0x00, 0xFF, 0xFF, 0xFF, 0xFC, 0x0F, + 0x07, 0x83, 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x0F, 0xFF, 0xFF, 0xFF, 0xC0, + 0x1C, 0xF3, 0xCE, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0xBC, 0xF0, 0xE3, 0x8E, + 0x38, 0xE3, 0x8E, 0x3C, 0xF1, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, + 0xE3, 0x8F, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x0F, 0x3D, 0xC7, 0x1C, + 0x71, 0xC7, 0x1C, 0xF3, 0xCE, 0x00, 0x78, 0x0F, 0xE0, 0xCF, 0x30, 0x7F, + 0x01, 0xE0 }; + +const GFXglyph FreeSansBold12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 7, 0, 1 }, // 0x20 ' ' + { 0, 4, 17, 8, 3, -16 }, // 0x21 '!' + { 9, 10, 6, 11, 1, -17 }, // 0x22 '"' + { 17, 13, 16, 13, 0, -15 }, // 0x23 '#' + { 43, 13, 20, 13, 0, -17 }, // 0x24 '$' + { 76, 19, 17, 21, 1, -16 }, // 0x25 '%' + { 117, 16, 17, 17, 1, -16 }, // 0x26 '&' + { 151, 4, 6, 6, 1, -17 }, // 0x27 ''' + { 154, 6, 22, 8, 1, -17 }, // 0x28 '(' + { 171, 6, 22, 8, 1, -17 }, // 0x29 ')' + { 188, 7, 8, 9, 1, -17 }, // 0x2A '*' + { 195, 11, 11, 14, 2, -10 }, // 0x2B '+' + { 211, 4, 7, 6, 1, -2 }, // 0x2C ',' + { 215, 6, 3, 8, 1, -7 }, // 0x2D '-' + { 218, 4, 3, 6, 1, -2 }, // 0x2E '.' + { 220, 6, 17, 7, 0, -16 }, // 0x2F '/' + { 233, 12, 17, 13, 1, -16 }, // 0x30 '0' + { 259, 7, 17, 14, 3, -16 }, // 0x31 '1' + { 274, 12, 17, 13, 1, -16 }, // 0x32 '2' + { 300, 12, 17, 13, 1, -16 }, // 0x33 '3' + { 326, 11, 17, 13, 1, -16 }, // 0x34 '4' + { 350, 12, 17, 13, 1, -16 }, // 0x35 '5' + { 376, 12, 17, 13, 1, -16 }, // 0x36 '6' + { 402, 11, 17, 13, 1, -16 }, // 0x37 '7' + { 426, 12, 17, 13, 1, -16 }, // 0x38 '8' + { 452, 12, 17, 13, 1, -16 }, // 0x39 '9' + { 478, 4, 12, 6, 1, -11 }, // 0x3A ':' + { 484, 4, 16, 6, 1, -11 }, // 0x3B ';' + { 492, 12, 12, 14, 1, -11 }, // 0x3C '<' + { 510, 12, 9, 14, 1, -9 }, // 0x3D '=' + { 524, 12, 12, 14, 1, -11 }, // 0x3E '>' + { 542, 12, 18, 15, 2, -17 }, // 0x3F '?' + { 569, 21, 21, 23, 1, -17 }, // 0x40 '@' + { 625, 16, 18, 17, 0, -17 }, // 0x41 'A' + { 661, 14, 18, 17, 2, -17 }, // 0x42 'B' + { 693, 16, 18, 17, 1, -17 }, // 0x43 'C' + { 729, 15, 18, 17, 2, -17 }, // 0x44 'D' + { 763, 13, 18, 16, 2, -17 }, // 0x45 'E' + { 793, 12, 18, 15, 2, -17 }, // 0x46 'F' + { 820, 16, 18, 18, 1, -17 }, // 0x47 'G' + { 856, 14, 18, 18, 2, -17 }, // 0x48 'H' + { 888, 4, 18, 7, 2, -17 }, // 0x49 'I' + { 897, 11, 18, 14, 1, -17 }, // 0x4A 'J' + { 922, 16, 18, 17, 2, -17 }, // 0x4B 'K' + { 958, 11, 18, 15, 2, -17 }, // 0x4C 'L' + { 983, 17, 18, 21, 2, -17 }, // 0x4D 'M' + { 1022, 15, 18, 18, 2, -17 }, // 0x4E 'N' + { 1056, 17, 18, 19, 1, -17 }, // 0x4F 'O' + { 1095, 14, 18, 16, 2, -17 }, // 0x50 'P' + { 1127, 17, 19, 19, 1, -17 }, // 0x51 'Q' + { 1168, 16, 18, 17, 2, -17 }, // 0x52 'R' + { 1204, 15, 18, 16, 1, -17 }, // 0x53 'S' + { 1238, 12, 18, 15, 2, -17 }, // 0x54 'T' + { 1265, 14, 18, 18, 2, -17 }, // 0x55 'U' + { 1297, 15, 18, 16, 0, -17 }, // 0x56 'V' + { 1331, 23, 18, 23, 0, -17 }, // 0x57 'W' + { 1383, 15, 18, 16, 1, -17 }, // 0x58 'X' + { 1417, 16, 18, 15, 0, -17 }, // 0x59 'Y' + { 1453, 13, 18, 15, 1, -17 }, // 0x5A 'Z' + { 1483, 6, 23, 8, 2, -17 }, // 0x5B '[' + { 1501, 7, 17, 7, 0, -16 }, // 0x5C '\' + { 1516, 6, 23, 8, 0, -17 }, // 0x5D ']' + { 1534, 12, 11, 14, 1, -16 }, // 0x5E '^' + { 1551, 15, 2, 13, -1, 4 }, // 0x5F '_' + { 1555, 4, 3, 6, 0, -17 }, // 0x60 '`' + { 1557, 13, 13, 14, 1, -12 }, // 0x61 'a' + { 1579, 13, 18, 15, 2, -17 }, // 0x62 'b' + { 1609, 12, 13, 13, 1, -12 }, // 0x63 'c' + { 1629, 13, 18, 15, 1, -17 }, // 0x64 'd' + { 1659, 13, 13, 14, 1, -12 }, // 0x65 'e' + { 1681, 7, 18, 8, 1, -17 }, // 0x66 'f' + { 1697, 13, 18, 15, 1, -12 }, // 0x67 'g' + { 1727, 12, 18, 14, 2, -17 }, // 0x68 'h' + { 1754, 4, 18, 7, 2, -17 }, // 0x69 'i' + { 1763, 6, 23, 7, 0, -17 }, // 0x6A 'j' + { 1781, 12, 18, 14, 2, -17 }, // 0x6B 'k' + { 1808, 4, 18, 6, 2, -17 }, // 0x6C 'l' + { 1817, 19, 13, 21, 2, -12 }, // 0x6D 'm' + { 1848, 12, 13, 15, 2, -12 }, // 0x6E 'n' + { 1868, 13, 13, 15, 1, -12 }, // 0x6F 'o' + { 1890, 13, 18, 15, 2, -12 }, // 0x70 'p' + { 1920, 13, 18, 15, 1, -12 }, // 0x71 'q' + { 1950, 8, 13, 9, 2, -12 }, // 0x72 'r' + { 1963, 12, 13, 13, 1, -12 }, // 0x73 's' + { 1983, 6, 15, 8, 1, -14 }, // 0x74 't' + { 1995, 12, 13, 15, 2, -12 }, // 0x75 'u' + { 2015, 13, 13, 13, 0, -12 }, // 0x76 'v' + { 2037, 18, 13, 19, 0, -12 }, // 0x77 'w' + { 2067, 13, 13, 13, 0, -12 }, // 0x78 'x' + { 2089, 13, 18, 13, 0, -12 }, // 0x79 'y' + { 2119, 10, 13, 12, 1, -12 }, // 0x7A 'z' + { 2136, 6, 23, 9, 1, -17 }, // 0x7B '{' + { 2154, 2, 22, 7, 2, -17 }, // 0x7C '|' + { 2160, 6, 23, 9, 3, -17 }, // 0x7D '}' + { 2178, 12, 5, 12, 0, -7 } }; // 0x7E '~' + +const GFXfont FreeSansBold12pt7b PROGMEM = { + (uint8_t *)FreeSansBold12pt7bBitmaps, + (GFXglyph *)FreeSansBold12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 2858 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBold18pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBold18pt7b.h new file mode 100644 index 0000000..d5927cd --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBold18pt7b.h @@ -0,0 +1,481 @@ +const uint8_t FreeSansBold18pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xE7, 0x39, 0xCE, 0x73, 0x80, + 0x0F, 0xFF, 0xFF, 0xF8, 0xF8, 0xFF, 0xC7, 0xFE, 0x3F, 0xF1, 0xFF, 0x8F, + 0xFC, 0x7D, 0xC1, 0xCE, 0x0E, 0x70, 0x70, 0x03, 0xC3, 0x80, 0x3C, 0x78, + 0x03, 0xC7, 0x80, 0x38, 0x78, 0x07, 0x87, 0x07, 0xFF, 0xFF, 0x7F, 0xFF, + 0xF7, 0xFF, 0xFF, 0x7F, 0xFF, 0xF0, 0xF0, 0xE0, 0x0F, 0x0E, 0x00, 0xF1, + 0xE0, 0x0F, 0x1E, 0x00, 0xE1, 0xE0, 0xFF, 0xFF, 0xCF, 0xFF, 0xFC, 0xFF, + 0xFF, 0xCF, 0xFF, 0xFC, 0x1C, 0x3C, 0x03, 0xC3, 0x80, 0x3C, 0x78, 0x03, + 0xC7, 0x80, 0x38, 0x78, 0x03, 0x87, 0x80, 0x00, 0x60, 0x00, 0x7F, 0x80, + 0x3F, 0xFC, 0x0F, 0xFF, 0xC3, 0xFF, 0xFC, 0xFC, 0xDF, 0x9F, 0x19, 0xFB, + 0xC3, 0x1F, 0x78, 0x63, 0xEF, 0x8C, 0x01, 0xFD, 0x80, 0x1F, 0xF0, 0x01, + 0xFF, 0xC0, 0x1F, 0xFE, 0x00, 0x7F, 0xE0, 0x03, 0xFE, 0x00, 0x67, 0xE0, + 0x0C, 0x7F, 0xE1, 0x8F, 0xFC, 0x31, 0xFF, 0xC6, 0x3E, 0xFC, 0xDF, 0x9F, + 0xFF, 0xF1, 0xFF, 0xFC, 0x0F, 0xFF, 0x00, 0x7F, 0x80, 0x01, 0x80, 0x00, + 0x30, 0x00, 0x06, 0x00, 0x0F, 0x00, 0x1C, 0x01, 0xFE, 0x00, 0xE0, 0x1F, + 0xF8, 0x0E, 0x00, 0xFF, 0xC0, 0x70, 0x0F, 0x0F, 0x07, 0x00, 0x70, 0x38, + 0x38, 0x03, 0x81, 0xC3, 0x80, 0x1C, 0x0E, 0x3C, 0x00, 0xF0, 0xF1, 0xC0, + 0x03, 0xFF, 0x1C, 0x00, 0x1F, 0xF8, 0xE0, 0x00, 0x7F, 0x8E, 0x00, 0x00, + 0xF0, 0x70, 0xF8, 0x00, 0x07, 0x1F, 0xF0, 0x00, 0x39, 0xFF, 0xC0, 0x03, + 0x8F, 0xFE, 0x00, 0x1C, 0xF0, 0x78, 0x01, 0xC7, 0x01, 0xC0, 0x0C, 0x38, + 0x0E, 0x00, 0xE1, 0xC0, 0x70, 0x06, 0x0F, 0x07, 0x80, 0x70, 0x3F, 0xF8, + 0x07, 0x01, 0xFF, 0xC0, 0x38, 0x07, 0xFC, 0x03, 0x80, 0x0F, 0x80, 0x01, + 0xF0, 0x00, 0x1F, 0xE0, 0x00, 0xFF, 0xC0, 0x03, 0xFF, 0x80, 0x1F, 0x1E, + 0x00, 0x7C, 0x78, 0x01, 0xF1, 0xE0, 0x07, 0xE7, 0x80, 0x0F, 0xBC, 0x00, + 0x1F, 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0xF0, 0xF0, 0xFF, + 0xE3, 0xC7, 0xE7, 0xCF, 0x3F, 0x0F, 0xF8, 0xF8, 0x3F, 0xE3, 0xE0, 0x7F, + 0x8F, 0x80, 0xFC, 0x3F, 0x03, 0xF0, 0x7E, 0x3F, 0xE1, 0xFF, 0xFF, 0x83, + 0xFF, 0xFF, 0x07, 0xFE, 0x7E, 0x07, 0xF0, 0xFC, 0xFF, 0xFF, 0xFF, 0xFD, + 0xCE, 0x70, 0x07, 0x87, 0x83, 0xC3, 0xC1, 0xE1, 0xE0, 0xF0, 0x78, 0x78, + 0x3C, 0x1E, 0x1E, 0x0F, 0x07, 0x83, 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, + 0x0F, 0x03, 0x81, 0xE0, 0xF0, 0x78, 0x1E, 0x0F, 0x03, 0x81, 0xE0, 0x70, + 0x3C, 0x0E, 0x07, 0x80, 0xF0, 0x38, 0x1E, 0x07, 0x83, 0xC0, 0xF0, 0x78, + 0x3C, 0x0F, 0x07, 0x83, 0xC0, 0xF0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, + 0xC1, 0xE0, 0xF0, 0x78, 0x78, 0x3C, 0x1E, 0x0F, 0x0F, 0x07, 0x87, 0x83, + 0xC1, 0xC1, 0xE0, 0xE0, 0xF0, 0x00, 0x06, 0x00, 0x60, 0x06, 0x07, 0x6E, + 0x7F, 0xE3, 0xFC, 0x0F, 0x01, 0xF8, 0x1F, 0x83, 0x9C, 0x10, 0x80, 0x03, + 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xC0, 0x03, 0xC0, 0x03, + 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0xFF, 0xFF, 0xFF, 0x8C, 0x63, + 0x37, 0xB0, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0x80, 0x01, + 0x81, 0xC0, 0xC0, 0x60, 0x70, 0x38, 0x18, 0x0C, 0x0E, 0x06, 0x03, 0x01, + 0x81, 0xC0, 0xC0, 0x60, 0x30, 0x38, 0x18, 0x0C, 0x0E, 0x07, 0x03, 0x01, + 0x81, 0xC0, 0xC0, 0x00, 0x07, 0xF0, 0x0F, 0xFE, 0x0F, 0xFF, 0x87, 0xFF, + 0xC7, 0xE3, 0xF3, 0xE0, 0xF9, 0xF0, 0x7D, 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, + 0x07, 0xFE, 0x03, 0xFF, 0x01, 0xFF, 0x80, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, + 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, 0x07, 0xDF, 0x07, 0xCF, 0x83, 0xE7, 0xE3, + 0xF1, 0xFF, 0xF0, 0xFF, 0xF8, 0x3F, 0xF8, 0x07, 0xF0, 0x00, 0x01, 0xC0, + 0xF0, 0x3C, 0x1F, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0x07, 0xC1, 0xF0, 0x7C, + 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, + 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC0, 0x07, 0xF0, 0x0F, 0xFE, 0x0F, 0xFF, + 0x8F, 0xFF, 0xE7, 0xE3, 0xF7, 0xE0, 0xFF, 0xE0, 0x3F, 0xF0, 0x1F, 0xF8, + 0x0F, 0x80, 0x07, 0xC0, 0x07, 0xE0, 0x03, 0xE0, 0x03, 0xF0, 0x03, 0xF0, + 0x07, 0xF0, 0x07, 0xF0, 0x07, 0xE0, 0x07, 0xE0, 0x07, 0xC0, 0x07, 0xC0, + 0x03, 0xE0, 0x03, 0xFF, 0xFD, 0xFF, 0xFE, 0xFF, 0xFF, 0x7F, 0xFF, 0x80, + 0x07, 0xE0, 0x0F, 0xFC, 0x0F, 0xFF, 0x0F, 0xFF, 0xCF, 0xC3, 0xF7, 0xC0, + 0xFB, 0xE0, 0x7D, 0xF0, 0x3E, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x0F, 0x80, + 0x3F, 0x80, 0x1F, 0xC0, 0x0F, 0xF0, 0x00, 0xFC, 0x00, 0x3F, 0x00, 0x0F, + 0xFC, 0x07, 0xFE, 0x03, 0xFF, 0x83, 0xF7, 0xC3, 0xF3, 0xFF, 0xF8, 0xFF, + 0xF8, 0x3F, 0xF8, 0x07, 0xF0, 0x00, 0x00, 0xFC, 0x00, 0xFC, 0x01, 0xFC, + 0x01, 0xFC, 0x03, 0xFC, 0x07, 0x7C, 0x07, 0x7C, 0x0E, 0x7C, 0x0E, 0x7C, + 0x1C, 0x7C, 0x18, 0x7C, 0x38, 0x7C, 0x70, 0x7C, 0x60, 0x7C, 0xE0, 0x7C, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x7C, 0x00, 0x7C, + 0x00, 0x7C, 0x00, 0x7C, 0x00, 0x7C, 0x00, 0x7C, 0x1F, 0xFF, 0x0F, 0xFF, + 0x8F, 0xFF, 0xC7, 0xFF, 0xE3, 0xC0, 0x01, 0xE0, 0x00, 0xE0, 0x00, 0x70, + 0x00, 0x79, 0xF0, 0x3F, 0xFE, 0x1F, 0xFF, 0x8F, 0xFF, 0xE7, 0xC3, 0xF0, + 0x00, 0xFC, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xFE, 0x03, + 0xFF, 0x03, 0xFF, 0xC3, 0xF3, 0xFF, 0xF1, 0xFF, 0xF8, 0x3F, 0xF0, 0x07, + 0xE0, 0x00, 0x03, 0xF8, 0x03, 0xFF, 0x81, 0xFF, 0xF0, 0xFF, 0xFE, 0x3E, + 0x1F, 0x9F, 0x03, 0xE7, 0xC0, 0x03, 0xE0, 0x00, 0xF8, 0xF8, 0x3E, 0xFF, + 0x8F, 0xFF, 0xF3, 0xFF, 0xFE, 0xFE, 0x1F, 0xBF, 0x03, 0xFF, 0x80, 0x7F, + 0xE0, 0x1F, 0xF8, 0x07, 0xFE, 0x01, 0xF7, 0x80, 0x7D, 0xF0, 0x3E, 0x7E, + 0x1F, 0x8F, 0xFF, 0xC1, 0xFF, 0xF0, 0x3F, 0xF0, 0x03, 0xF0, 0x00, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0xF0, 0x00, 0xF8, + 0x00, 0xF8, 0x00, 0x78, 0x00, 0x7C, 0x00, 0x3C, 0x00, 0x3E, 0x00, 0x1E, + 0x00, 0x1F, 0x00, 0x0F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xC0, 0x03, + 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x78, 0x00, 0x7C, 0x00, 0x3E, 0x00, + 0x1F, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xE0, 0x07, 0xFC, 0x0F, 0xFF, 0x07, + 0xFF, 0xC7, 0xC3, 0xF3, 0xC0, 0xF9, 0xE0, 0x3C, 0xF0, 0x1E, 0x78, 0x1F, + 0x1E, 0x1F, 0x07, 0xFF, 0x01, 0xFF, 0x03, 0xFF, 0xE3, 0xF1, 0xF9, 0xF0, + 0x7D, 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, 0x07, 0xFE, 0x03, 0xFF, 0x83, 0xF7, + 0xC3, 0xF3, 0xFF, 0xF8, 0xFF, 0xF8, 0x3F, 0xF8, 0x07, 0xF0, 0x00, 0x07, + 0xE0, 0x0F, 0xFC, 0x0F, 0xFF, 0x0F, 0xFF, 0xC7, 0xE3, 0xF7, 0xE0, 0xFB, + 0xE0, 0x3D, 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, 0x07, 0xFE, 0x03, 0xFF, 0x83, + 0xF7, 0xE3, 0xFB, 0xFF, 0xFC, 0xFF, 0xFE, 0x3F, 0xDF, 0x07, 0xCF, 0x80, + 0x07, 0x80, 0x03, 0xDF, 0x03, 0xE7, 0xC3, 0xE3, 0xFF, 0xF0, 0xFF, 0xF0, + 0x3F, 0xF0, 0x07, 0xE0, 0x00, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00, + 0x00, 0x7F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00, + 0x00, 0x7F, 0xFF, 0xFF, 0xC6, 0x33, 0x9B, 0xD8, 0x00, 0x00, 0xC0, 0x00, + 0xF0, 0x01, 0xFC, 0x03, 0xFF, 0x03, 0xFF, 0x07, 0xFE, 0x0F, 0xFC, 0x03, + 0xF8, 0x00, 0xF0, 0x00, 0x3F, 0x80, 0x0F, 0xFC, 0x00, 0x7F, 0xE0, 0x07, + 0xFF, 0x00, 0x3F, 0xF0, 0x01, 0xFC, 0x00, 0x1F, 0x00, 0x00, 0xC0, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF0, 0xC0, 0x00, 0x3C, 0x00, 0x0F, 0xE0, 0x03, 0xFF, 0x00, 0x3F, 0xF0, + 0x01, 0xFF, 0x80, 0x0F, 0xFC, 0x00, 0x7F, 0x00, 0x03, 0xC0, 0x07, 0xF0, + 0x0F, 0xFC, 0x1F, 0xF8, 0x3F, 0xF8, 0x3F, 0xF0, 0x0F, 0xE0, 0x03, 0xC0, + 0x00, 0xC0, 0x00, 0x00, 0x07, 0xF0, 0x07, 0xFF, 0x03, 0xFF, 0xF1, 0xFF, + 0xFC, 0x7E, 0x3F, 0xBF, 0x03, 0xFF, 0x80, 0x7F, 0xE0, 0x1F, 0xF8, 0x07, + 0xC0, 0x03, 0xF0, 0x01, 0xFC, 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x3F, 0x80, + 0x1F, 0xC0, 0x07, 0xC0, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, + 0x00, 0xF8, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x3F, 0xFF, 0x00, 0x00, + 0xFF, 0xFF, 0xC0, 0x01, 0xF8, 0x07, 0xF0, 0x03, 0xE0, 0x01, 0xF8, 0x07, + 0x80, 0x00, 0x7C, 0x0F, 0x00, 0x00, 0x3C, 0x1E, 0x03, 0xE3, 0x9E, 0x3C, + 0x0F, 0xF7, 0x8E, 0x38, 0x1F, 0xFF, 0x0E, 0x78, 0x3E, 0x1F, 0x07, 0x70, + 0x38, 0x0F, 0x07, 0x70, 0x78, 0x0F, 0x07, 0xE0, 0x70, 0x0E, 0x07, 0xE0, + 0x70, 0x0E, 0x07, 0xE0, 0xE0, 0x0E, 0x07, 0xE0, 0xE0, 0x1E, 0x0F, 0xE0, + 0xE0, 0x1C, 0x0E, 0xE0, 0xE0, 0x3C, 0x1E, 0xE0, 0xF0, 0x3C, 0x3C, 0xF0, + 0xF0, 0xFC, 0x7C, 0x70, 0x7F, 0xFF, 0xF8, 0x78, 0x3F, 0xCF, 0xF0, 0x3C, + 0x1F, 0x07, 0xC0, 0x3E, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x0F, + 0xC0, 0x01, 0x00, 0x07, 0xF0, 0x0F, 0x00, 0x03, 0xFF, 0xFF, 0x00, 0x00, + 0xFF, 0xFF, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0x00, 0x00, 0xFF, 0x80, 0x01, 0xFF, + 0x80, 0x01, 0xFF, 0x80, 0x01, 0xF7, 0xC0, 0x03, 0xE7, 0xC0, 0x03, 0xE7, + 0xC0, 0x03, 0xE3, 0xE0, 0x07, 0xC3, 0xE0, 0x07, 0xC3, 0xE0, 0x07, 0xC1, + 0xF0, 0x0F, 0x81, 0xF0, 0x0F, 0x81, 0xF0, 0x0F, 0xFF, 0xF8, 0x1F, 0xFF, + 0xF8, 0x1F, 0xFF, 0xFC, 0x1F, 0xFF, 0xFC, 0x3E, 0x00, 0x7C, 0x3E, 0x00, + 0x7E, 0x3E, 0x00, 0x3E, 0x7C, 0x00, 0x3E, 0x7C, 0x00, 0x3F, 0x7C, 0x00, + 0x1F, 0xFF, 0xFC, 0x0F, 0xFF, 0xF0, 0xFF, 0xFF, 0x8F, 0xFF, 0xFC, 0xF8, + 0x07, 0xEF, 0x80, 0x3E, 0xF8, 0x03, 0xEF, 0x80, 0x3E, 0xF8, 0x03, 0xEF, + 0x80, 0x3E, 0xF8, 0x07, 0xCF, 0xFF, 0xF8, 0xFF, 0xFF, 0x0F, 0xFF, 0xF8, + 0xFF, 0xFF, 0xCF, 0x80, 0x7E, 0xF8, 0x01, 0xEF, 0x80, 0x1F, 0xF8, 0x01, + 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x3E, 0xFF, 0xFF, 0xEF, 0xFF, + 0xFC, 0xFF, 0xFF, 0x8F, 0xFF, 0xE0, 0x00, 0xFF, 0x00, 0x07, 0xFF, 0x80, + 0x3F, 0xFF, 0xC0, 0xFF, 0xFF, 0xC3, 0xF8, 0x1F, 0x87, 0xE0, 0x1F, 0x9F, + 0x80, 0x1F, 0x3E, 0x00, 0x1F, 0x7C, 0x00, 0x3F, 0xF0, 0x00, 0x03, 0xE0, + 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x7D, 0xF0, 0x00, + 0xFB, 0xF0, 0x03, 0xF3, 0xF0, 0x0F, 0xC7, 0xF0, 0x3F, 0x87, 0xFF, 0xFE, + 0x07, 0xFF, 0xF8, 0x03, 0xFF, 0xC0, 0x01, 0xFE, 0x00, 0xFF, 0xFC, 0x07, + 0xFF, 0xF8, 0x3F, 0xFF, 0xE1, 0xFF, 0xFF, 0x8F, 0x80, 0xFE, 0x7C, 0x01, + 0xF3, 0xE0, 0x07, 0xDF, 0x00, 0x3E, 0xF8, 0x01, 0xF7, 0xC0, 0x07, 0xFE, + 0x00, 0x3F, 0xF0, 0x01, 0xFF, 0x80, 0x0F, 0xFC, 0x00, 0x7F, 0xE0, 0x03, + 0xFF, 0x00, 0x1F, 0xF8, 0x00, 0xFF, 0xC0, 0x0F, 0xFE, 0x00, 0x7D, 0xF0, + 0x03, 0xEF, 0x80, 0x3E, 0x7C, 0x07, 0xF3, 0xFF, 0xFF, 0x1F, 0xFF, 0xF0, + 0xFF, 0xFF, 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFF, 0xDF, 0xFF, 0xFB, 0xFF, + 0xFF, 0x7F, 0xFF, 0xEF, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7F, 0xFF, 0xCF, 0xFF, + 0xF9, 0xFF, 0xFF, 0x3F, 0xFF, 0xE7, 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, + 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, + 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0xFF, 0xEF, 0xFF, 0xF7, + 0xFF, 0xFB, 0xFF, 0xFD, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, + 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, + 0x00, 0x7C, 0x00, 0x00, 0x00, 0x7F, 0x80, 0x03, 0xFF, 0xE0, 0x07, 0xFF, + 0xF8, 0x0F, 0xFF, 0xFC, 0x1F, 0xC0, 0xFE, 0x3F, 0x00, 0x7E, 0x7E, 0x00, + 0x3F, 0x7C, 0x00, 0x1F, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x03, 0xFF, 0xF8, 0x03, 0xFF, 0xF8, 0x03, + 0xFF, 0xF8, 0x03, 0xFF, 0xFC, 0x00, 0x0F, 0x7C, 0x00, 0x1F, 0x7C, 0x00, + 0x1F, 0x7E, 0x00, 0x3F, 0x3F, 0x00, 0x7F, 0x1F, 0xC1, 0xFF, 0x0F, 0xFF, + 0xFF, 0x07, 0xFF, 0xE7, 0x03, 0xFF, 0xC7, 0x00, 0xFF, 0x07, 0xF8, 0x01, + 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, + 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0x01, 0xFF, + 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, + 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, + 0xFF, 0x80, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x00, 0x1F, 0x00, 0x1F, + 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, + 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, + 0x00, 0x1F, 0x00, 0x1F, 0xF8, 0x1F, 0xF8, 0x1F, 0xF8, 0x1F, 0xF8, 0x1F, + 0xF8, 0x1F, 0xFC, 0x3F, 0x7F, 0xFE, 0x3F, 0xFC, 0x1F, 0xF8, 0x07, 0xE0, + 0xF8, 0x01, 0xFB, 0xE0, 0x0F, 0xCF, 0x80, 0x7E, 0x3E, 0x03, 0xF0, 0xF8, + 0x1F, 0x83, 0xE0, 0xFC, 0x0F, 0x87, 0xE0, 0x3E, 0x3F, 0x00, 0xF8, 0xF8, + 0x03, 0xE7, 0xE0, 0x0F, 0xBF, 0x00, 0x3F, 0xF8, 0x00, 0xFF, 0xF0, 0x03, + 0xFF, 0xE0, 0x0F, 0xFF, 0x80, 0x3F, 0xBF, 0x00, 0xFC, 0x7E, 0x03, 0xE0, + 0xFC, 0x0F, 0x81, 0xF8, 0x3E, 0x07, 0xE0, 0xF8, 0x0F, 0xC3, 0xE0, 0x1F, + 0x8F, 0x80, 0x7F, 0x3E, 0x00, 0xFC, 0xF8, 0x01, 0xFB, 0xE0, 0x03, 0xF0, + 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, + 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, + 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, + 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0x00, 0xFF, 0xFF, + 0x00, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, + 0x81, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0x81, 0xFF, 0xFB, 0xC3, 0xDF, 0xFB, + 0xC3, 0xDF, 0xFB, 0xC3, 0xDF, 0xFB, 0xC3, 0xDF, 0xF9, 0xC7, 0xDF, 0xF9, + 0xE7, 0x9F, 0xF9, 0xE7, 0x9F, 0xF9, 0xE7, 0x9F, 0xF9, 0xE7, 0x9F, 0xF8, + 0xFF, 0x1F, 0xF8, 0xFF, 0x1F, 0xF8, 0xFF, 0x1F, 0xF8, 0xFF, 0x1F, 0xF8, + 0x7F, 0x1F, 0xF8, 0x7E, 0x1F, 0xF8, 0x7E, 0x1F, 0xF8, 0x7E, 0x1F, 0xF8, + 0x3E, 0x1F, 0xF8, 0x01, 0xFF, 0xC0, 0x1F, 0xFE, 0x01, 0xFF, 0xE0, 0x1F, + 0xFF, 0x01, 0xFF, 0xF0, 0x1F, 0xFF, 0x81, 0xFF, 0xF8, 0x1F, 0xFF, 0xC1, + 0xFF, 0xBC, 0x1F, 0xFB, 0xE1, 0xFF, 0x9F, 0x1F, 0xF9, 0xF1, 0xFF, 0x8F, + 0x9F, 0xF8, 0x79, 0xFF, 0x87, 0xDF, 0xF8, 0x3D, 0xFF, 0x83, 0xFF, 0xF8, + 0x1F, 0xFF, 0x81, 0xFF, 0xF8, 0x0F, 0xFF, 0x80, 0xFF, 0xF8, 0x07, 0xFF, + 0x80, 0x3F, 0xF8, 0x03, 0xFF, 0x80, 0x1F, 0x00, 0x7F, 0x00, 0x01, 0xFF, + 0xF0, 0x01, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x01, 0xFC, 0x1F, 0xC1, 0xF8, + 0x03, 0xF1, 0xF8, 0x00, 0xFC, 0xF8, 0x00, 0x3E, 0x7C, 0x00, 0x1F, 0x7C, + 0x00, 0x07, 0xFE, 0x00, 0x03, 0xFF, 0x00, 0x01, 0xFF, 0x80, 0x00, 0xFF, + 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0xF0, 0x00, 0x1F, 0xF8, 0x00, 0x0F, + 0xBE, 0x00, 0x0F, 0x9F, 0x00, 0x07, 0xCF, 0xC0, 0x07, 0xE3, 0xF0, 0x07, + 0xE0, 0xFE, 0x0F, 0xE0, 0x7F, 0xFF, 0xE0, 0x0F, 0xFF, 0xE0, 0x03, 0xFF, + 0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFF, 0xFC, 0x1F, 0xFF, 0xE3, 0xFF, 0xFE, + 0x7F, 0xFF, 0xEF, 0x80, 0xFF, 0xF0, 0x0F, 0xFE, 0x00, 0xFF, 0xC0, 0x1F, + 0xF8, 0x03, 0xFF, 0x00, 0x7F, 0xE0, 0x1F, 0xFC, 0x07, 0xEF, 0xFF, 0xFD, + 0xFF, 0xFF, 0x3F, 0xFF, 0xC7, 0xFF, 0xE0, 0xF8, 0x00, 0x1F, 0x00, 0x03, + 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, + 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x01, 0xFF, + 0xF0, 0x01, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x01, 0xFC, 0x1F, 0xC1, 0xF8, + 0x03, 0xF1, 0xF8, 0x00, 0xFC, 0xF8, 0x00, 0x3E, 0x7C, 0x00, 0x1F, 0x7C, + 0x00, 0x07, 0xFE, 0x00, 0x03, 0xFF, 0x00, 0x01, 0xFF, 0x80, 0x00, 0xFF, + 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0xF0, 0x00, 0x1F, 0xF8, 0x01, 0x0F, + 0xBE, 0x01, 0xCF, 0x9F, 0x01, 0xFF, 0xCF, 0xC0, 0x7F, 0xE3, 0xF0, 0x1F, + 0xE0, 0xFE, 0x0F, 0xF0, 0x7F, 0xFF, 0xF8, 0x0F, 0xFF, 0xFE, 0x03, 0xFF, + 0xEF, 0x80, 0x3F, 0xC3, 0x80, 0x00, 0x00, 0x80, 0xFF, 0xFF, 0x07, 0xFF, + 0xFE, 0x3F, 0xFF, 0xF9, 0xFF, 0xFF, 0xCF, 0x80, 0x3F, 0x7C, 0x00, 0xFB, + 0xE0, 0x07, 0xDF, 0x00, 0x3E, 0xF8, 0x01, 0xF7, 0xC0, 0x0F, 0x3E, 0x00, + 0xF9, 0xFF, 0xFF, 0x8F, 0xFF, 0xF8, 0x7F, 0xFF, 0xC3, 0xFF, 0xFF, 0x1F, + 0x00, 0xFC, 0xF8, 0x03, 0xE7, 0xC0, 0x1F, 0x3E, 0x00, 0xF9, 0xF0, 0x07, + 0xCF, 0x80, 0x3E, 0x7C, 0x01, 0xF3, 0xE0, 0x0F, 0x9F, 0x00, 0x7C, 0xF8, + 0x03, 0xF7, 0xC0, 0x0F, 0xC0, 0x07, 0xF8, 0x01, 0xFF, 0xF0, 0x3F, 0xFF, + 0x87, 0xFF, 0xFC, 0x7E, 0x0F, 0xCF, 0xC0, 0x7E, 0xF8, 0x03, 0xEF, 0x80, + 0x3E, 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0xFF, 0x00, 0x07, 0xFF, 0xC0, 0x3F, + 0xFF, 0x81, 0xFF, 0xFC, 0x03, 0xFF, 0xE0, 0x01, 0xFF, 0x00, 0x03, 0xF0, + 0x00, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xFC, 0x03, 0xFF, 0xE0, 0x7E, + 0x7F, 0xFF, 0xE3, 0xFF, 0xFC, 0x1F, 0xFF, 0x00, 0x3F, 0xC0, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x1F, 0x00, 0x03, 0xE0, + 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, + 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, + 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, + 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, + 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, + 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, + 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x01, 0xFF, + 0x80, 0x1F, 0x7C, 0x03, 0xE7, 0xE0, 0x7E, 0x3F, 0xFF, 0xC3, 0xFF, 0xFC, + 0x0F, 0xFF, 0x00, 0x3F, 0xC0, 0xF8, 0x00, 0xFB, 0xE0, 0x03, 0xE7, 0xC0, + 0x1F, 0x9F, 0x00, 0x7C, 0x7C, 0x01, 0xF0, 0xF8, 0x07, 0xC3, 0xE0, 0x3E, + 0x0F, 0x80, 0xF8, 0x1E, 0x03, 0xE0, 0x7C, 0x1F, 0x01, 0xF0, 0x7C, 0x03, + 0xC1, 0xF0, 0x0F, 0x87, 0x80, 0x3E, 0x3E, 0x00, 0xF8, 0xF8, 0x01, 0xE3, + 0xC0, 0x07, 0xCF, 0x00, 0x1F, 0x7C, 0x00, 0x3D, 0xE0, 0x00, 0xFF, 0x80, + 0x03, 0xFE, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0x00, 0x00, + 0xF8, 0x00, 0x03, 0xE0, 0x00, 0xF8, 0x07, 0xC0, 0x3F, 0xF8, 0x07, 0xE0, + 0x3E, 0xFC, 0x07, 0xE0, 0x3E, 0x7C, 0x0F, 0xE0, 0x3E, 0x7C, 0x0F, 0xE0, + 0x7E, 0x7C, 0x0F, 0xE0, 0x7C, 0x7C, 0x0F, 0xF0, 0x7C, 0x3E, 0x0F, 0xF0, + 0x7C, 0x3E, 0x1E, 0xF0, 0x78, 0x3E, 0x1E, 0x70, 0xF8, 0x1E, 0x1E, 0x70, + 0xF8, 0x1E, 0x1E, 0x78, 0xF8, 0x1F, 0x1E, 0x78, 0xF0, 0x1F, 0x3C, 0x78, + 0xF0, 0x0F, 0x3C, 0x39, 0xF0, 0x0F, 0x3C, 0x3D, 0xF0, 0x0F, 0x3C, 0x3D, + 0xE0, 0x0F, 0xBC, 0x3D, 0xE0, 0x07, 0xF8, 0x3D, 0xE0, 0x07, 0xF8, 0x1F, + 0xE0, 0x07, 0xF8, 0x1F, 0xC0, 0x03, 0xF8, 0x1F, 0xC0, 0x03, 0xF8, 0x1F, + 0xC0, 0x03, 0xF0, 0x0F, 0x80, 0x03, 0xF0, 0x0F, 0x80, 0x01, 0xF0, 0x0F, + 0x80, 0xFE, 0x01, 0xF9, 0xF8, 0x07, 0xE3, 0xF0, 0x3F, 0x0F, 0xC0, 0xF8, + 0x1F, 0x87, 0xE0, 0x7E, 0x3F, 0x00, 0xFC, 0xFC, 0x01, 0xF7, 0xE0, 0x07, + 0xFF, 0x00, 0x0F, 0xFC, 0x00, 0x3F, 0xE0, 0x00, 0x7F, 0x00, 0x00, 0xFC, + 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xE0, 0x00, 0xFF, 0x80, 0x03, 0xFF, 0x00, + 0x1F, 0x7E, 0x00, 0xFC, 0xF8, 0x03, 0xE3, 0xF0, 0x1F, 0x87, 0xC0, 0x7C, + 0x1F, 0x83, 0xF0, 0x3F, 0x1F, 0x80, 0xFC, 0x7E, 0x01, 0xFB, 0xF0, 0x07, + 0xF0, 0xFC, 0x01, 0xFF, 0xE0, 0x0F, 0x9F, 0x00, 0xFC, 0xFC, 0x07, 0xC3, + 0xE0, 0x7E, 0x1F, 0x83, 0xE0, 0x7C, 0x1F, 0x03, 0xF1, 0xF0, 0x0F, 0x8F, + 0x80, 0x7E, 0xF8, 0x01, 0xF7, 0xC0, 0x0F, 0xFC, 0x00, 0x3F, 0xE0, 0x00, + 0xFE, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, + 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x03, + 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x7E, 0x00, 0x1F, + 0x80, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x3F, 0x00, 0x0F, 0xC0, 0x03, 0xF8, + 0x00, 0x7E, 0x00, 0x1F, 0x80, 0x07, 0xE0, 0x01, 0xFC, 0x00, 0x3F, 0x00, + 0x0F, 0xC0, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x1F, 0x80, 0x07, 0xE0, 0x01, + 0xFC, 0x00, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, + 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, + 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, + 0xF8, 0xF8, 0xF8, 0xF8, 0xF8, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x38, 0x06, + 0x01, 0x80, 0x70, 0x0C, 0x03, 0x00, 0xE0, 0x18, 0x06, 0x01, 0xC0, 0x30, + 0x0C, 0x03, 0x00, 0xE0, 0x18, 0x06, 0x01, 0xC0, 0x30, 0x0C, 0x03, 0x80, + 0x60, 0x18, 0x07, 0x01, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0x1F, 0x1F, 0x1F, + 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, + 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0x1F, 0xFF, 0xFF, + 0xFF, 0xFF, 0x03, 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x0F, 0xF0, 0x0F, 0xF0, + 0x0F, 0x78, 0x1E, 0x78, 0x1E, 0x78, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x1E, + 0x78, 0x1E, 0x78, 0x1E, 0x70, 0x0F, 0xF0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFE, 0xF8, 0xF0, 0xF0, 0xE0, 0xE0, 0x07, 0xF8, 0x07, + 0xFF, 0x83, 0xFF, 0xF1, 0xFF, 0xFE, 0x7C, 0x1F, 0xBE, 0x03, 0xE0, 0x00, + 0xF8, 0x01, 0xFE, 0x0F, 0xFF, 0x8F, 0xFF, 0xE7, 0xF8, 0xFB, 0xF0, 0x3E, + 0xF8, 0x0F, 0xBE, 0x07, 0xEF, 0xC3, 0xFB, 0xFF, 0xFE, 0x7F, 0xFF, 0x8F, + 0xFB, 0xF1, 0xF8, 0xFC, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, + 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE7, 0xE0, 0xFB, 0xFC, + 0x3F, 0xFF, 0xCF, 0xFF, 0xF3, 0xF8, 0x7E, 0xFC, 0x0F, 0xBF, 0x03, 0xFF, + 0x80, 0x7F, 0xE0, 0x1F, 0xF8, 0x07, 0xFE, 0x01, 0xFF, 0x80, 0x7F, 0xF0, + 0x3F, 0xFC, 0x0F, 0xBF, 0x87, 0xEF, 0xFF, 0xF3, 0xFF, 0xFC, 0xFB, 0xFC, + 0x3E, 0x7E, 0x00, 0x03, 0xF0, 0x07, 0xFE, 0x0F, 0xFF, 0x87, 0xFF, 0xE7, + 0xE1, 0xFB, 0xE0, 0x7F, 0xE0, 0x3F, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, + 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0xFB, 0xE0, 0x7D, 0xF8, 0x7E, 0x7F, + 0xFE, 0x3F, 0xFE, 0x0F, 0xFE, 0x00, 0xFC, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, + 0xF8, 0x1F, 0x1F, 0x0F, 0xFB, 0xE3, 0xFF, 0xFC, 0xFF, 0xFF, 0xBF, 0x8F, + 0xF7, 0xC0, 0x7F, 0xF8, 0x0F, 0xFE, 0x00, 0xFF, 0xC0, 0x1F, 0xF8, 0x03, + 0xFF, 0x00, 0x7F, 0xE0, 0x0F, 0xFE, 0x03, 0xF7, 0xC0, 0x7E, 0xFC, 0x3F, + 0xCF, 0xFF, 0xF8, 0xFF, 0xFF, 0x0F, 0xFB, 0xE0, 0xFC, 0x7C, 0x07, 0xE0, + 0x07, 0xFE, 0x03, 0xFF, 0xE0, 0xFF, 0xF8, 0x7E, 0x1F, 0x1F, 0x03, 0xCF, + 0x80, 0xFB, 0xE0, 0x1E, 0xFF, 0xFF, 0xBF, 0xFF, 0xEF, 0xFF, 0xFB, 0xE0, + 0x00, 0xF8, 0x00, 0x3F, 0x03, 0xE7, 0xE1, 0xF9, 0xFF, 0xFC, 0x3F, 0xFE, + 0x07, 0xFF, 0x00, 0x7F, 0x00, 0x0F, 0xC7, 0xF3, 0xFC, 0xFF, 0x3E, 0x0F, + 0x83, 0xE3, 0xFE, 0xFF, 0xBF, 0xE3, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, + 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, + 0x0F, 0x80, 0x07, 0xC7, 0xC3, 0xFD, 0xF3, 0xFF, 0xFC, 0xFF, 0xFF, 0x7E, + 0x1F, 0xDF, 0x03, 0xFF, 0xC0, 0xFF, 0xE0, 0x1F, 0xF8, 0x07, 0xFE, 0x01, + 0xFF, 0x80, 0x7F, 0xE0, 0x1F, 0xFC, 0x0F, 0xDF, 0x03, 0xF7, 0xE1, 0xFD, + 0xFF, 0xFF, 0x3F, 0xFF, 0xC7, 0xFD, 0xF0, 0x7C, 0x7C, 0x00, 0x1F, 0x00, + 0x07, 0xFF, 0x03, 0xF7, 0xE1, 0xF9, 0xFF, 0xFC, 0x3F, 0xFE, 0x01, 0xFE, + 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, + 0xC0, 0x03, 0xE0, 0x01, 0xF1, 0xF0, 0xFB, 0xFE, 0x7F, 0xFF, 0xBF, 0xFF, + 0xDF, 0xC3, 0xFF, 0xC0, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xF0, 0x1F, 0xF8, + 0x0F, 0xFC, 0x07, 0xFE, 0x03, 0xFF, 0x01, 0xFF, 0x80, 0xFF, 0xC0, 0x7F, + 0xE0, 0x3F, 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, 0x07, 0xC0, 0xFF, 0xFF, 0xF0, + 0x00, 0x1F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xC0, 0x3E, 0x7C, 0xF9, 0xF0, 0x00, 0x00, 0x1F, 0x3E, 0x7C, 0xF9, + 0xF3, 0xE7, 0xCF, 0x9F, 0x3E, 0x7C, 0xF9, 0xF3, 0xE7, 0xCF, 0x9F, 0x3E, + 0x7C, 0xF9, 0xF3, 0xFF, 0xFF, 0xFE, 0xF8, 0xF8, 0x00, 0x7C, 0x00, 0x3E, + 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x3E, + 0xF8, 0x3E, 0x7C, 0x3F, 0x3E, 0x3F, 0x1F, 0x3F, 0x0F, 0x9F, 0x07, 0xDF, + 0x03, 0xFF, 0x81, 0xFF, 0xC0, 0xFF, 0xF0, 0x7F, 0xF8, 0x3F, 0x7E, 0x1F, + 0x1F, 0x0F, 0x87, 0xC7, 0xC3, 0xF3, 0xE0, 0xF9, 0xF0, 0x7E, 0xF8, 0x1F, + 0x7C, 0x0F, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xF8, 0xF8, 0x3F, 0x1F, + 0x7F, 0x9F, 0xF3, 0xFF, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0xFF, 0xC3, 0xF8, + 0x7F, 0xF8, 0x3F, 0x07, 0xFE, 0x07, 0xC0, 0xFF, 0xC0, 0xF8, 0x1F, 0xF8, + 0x1F, 0x03, 0xFF, 0x03, 0xE0, 0x7F, 0xE0, 0x7C, 0x0F, 0xFC, 0x0F, 0x81, + 0xFF, 0x81, 0xF0, 0x3F, 0xF0, 0x3E, 0x07, 0xFE, 0x07, 0xC0, 0xFF, 0xC0, + 0xF8, 0x1F, 0xF8, 0x1F, 0x03, 0xFF, 0x03, 0xE0, 0x7F, 0xE0, 0x7C, 0x0F, + 0x80, 0xF8, 0xF8, 0x7D, 0xFF, 0x3F, 0xFF, 0xDF, 0xFF, 0xEF, 0xE1, 0xFF, + 0xE0, 0x7F, 0xE0, 0x3F, 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, 0x07, 0xFE, 0x03, + 0xFF, 0x01, 0xFF, 0x80, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xF0, 0x1F, 0xF8, + 0x0F, 0xFC, 0x07, 0xFE, 0x03, 0xE0, 0x03, 0xF8, 0x01, 0xFF, 0xC0, 0x7F, + 0xFC, 0x1F, 0xFF, 0xC7, 0xF0, 0xFC, 0xF8, 0x0F, 0xBF, 0x01, 0xFF, 0xC0, + 0x1F, 0xF8, 0x03, 0xFF, 0x00, 0x7F, 0xE0, 0x0F, 0xFC, 0x01, 0xFF, 0xC0, + 0x7E, 0xF8, 0x0F, 0x9F, 0x87, 0xF1, 0xFF, 0xFC, 0x1F, 0xFF, 0x01, 0xFF, + 0xC0, 0x0F, 0xE0, 0x00, 0xF8, 0xF8, 0x3E, 0xFF, 0x8F, 0xFF, 0xF3, 0xFF, + 0xFC, 0xFE, 0x1F, 0xBF, 0x03, 0xEF, 0xC0, 0xFF, 0xE0, 0x1F, 0xF8, 0x07, + 0xFE, 0x01, 0xFF, 0x80, 0x7F, 0xE0, 0x1F, 0xFC, 0x0F, 0xFF, 0x03, 0xEF, + 0xE1, 0xFB, 0xFF, 0xFC, 0xFF, 0xFF, 0x3E, 0xFF, 0x0F, 0x8F, 0x83, 0xE0, + 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF8, 0x00, + 0x3E, 0x00, 0x00, 0x07, 0xE3, 0xE1, 0xFF, 0x7C, 0x7F, 0xFF, 0x9F, 0xFF, + 0xF7, 0xF1, 0xFE, 0xF8, 0x0F, 0xFF, 0x01, 0xFF, 0xC0, 0x1F, 0xF8, 0x03, + 0xFF, 0x00, 0x7F, 0xE0, 0x0F, 0xFC, 0x01, 0xFF, 0xC0, 0x7E, 0xF8, 0x0F, + 0xDF, 0x83, 0xF9, 0xFF, 0xFF, 0x3F, 0xFF, 0xE1, 0xFF, 0x7C, 0x1F, 0x8F, + 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1F, + 0x00, 0x03, 0xE0, 0x00, 0x7C, 0xF8, 0xFF, 0x7F, 0xFF, 0xFF, 0xFF, 0xE1, + 0xF8, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, + 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x00, 0x07, 0xF0, 0x0F, 0xFE, + 0x0F, 0xFF, 0x87, 0xFF, 0xE7, 0xE1, 0xF3, 0xE0, 0x79, 0xF8, 0x00, 0xFF, + 0x80, 0x3F, 0xFC, 0x1F, 0xFF, 0x83, 0xFF, 0xC0, 0x3F, 0xF0, 0x01, 0xFF, + 0xC0, 0x7D, 0xF0, 0x7E, 0xFF, 0xFE, 0x3F, 0xFF, 0x0F, 0xFF, 0x01, 0xFE, + 0x00, 0x3E, 0x1F, 0x0F, 0x87, 0xC3, 0xE7, 0xFF, 0xFF, 0xFF, 0x3E, 0x1F, + 0x0F, 0x87, 0xC3, 0xE1, 0xF0, 0xF8, 0x7C, 0x3E, 0x1F, 0x0F, 0x87, 0xF3, + 0xF8, 0xFC, 0x3E, 0xF8, 0x0F, 0xFC, 0x07, 0xFE, 0x03, 0xFF, 0x01, 0xFF, + 0x80, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xF0, 0x1F, 0xF8, 0x0F, 0xFC, 0x07, + 0xFE, 0x03, 0xFF, 0x01, 0xFF, 0x80, 0xFF, 0xC0, 0xFF, 0xF0, 0xFF, 0xFF, + 0xFF, 0x7F, 0xFF, 0x9F, 0xF7, 0xC7, 0xE3, 0xE0, 0x7C, 0x07, 0xCF, 0x80, + 0xF9, 0xF0, 0x1F, 0x1F, 0x07, 0xC3, 0xE0, 0xF8, 0x7C, 0x1F, 0x07, 0x83, + 0xC0, 0xF8, 0xF8, 0x1F, 0x1F, 0x01, 0xE3, 0xC0, 0x3E, 0x78, 0x07, 0xDF, + 0x00, 0x7B, 0xC0, 0x0F, 0xF8, 0x01, 0xFF, 0x00, 0x1F, 0xC0, 0x03, 0xF8, + 0x00, 0x7F, 0x00, 0x07, 0xC0, 0x00, 0xFC, 0x1F, 0x03, 0xEF, 0x83, 0xE0, + 0x7D, 0xF0, 0x7E, 0x1F, 0x3E, 0x0F, 0xC3, 0xE3, 0xC3, 0xF8, 0x7C, 0x7C, + 0x7F, 0x0F, 0x0F, 0x8F, 0xF3, 0xE1, 0xF1, 0xDE, 0x7C, 0x1E, 0x7B, 0xCF, + 0x83, 0xEF, 0x39, 0xE0, 0x7D, 0xE7, 0x3C, 0x07, 0xB8, 0xFF, 0x80, 0xF7, + 0x1F, 0xE0, 0x1F, 0xE3, 0xFC, 0x03, 0xFC, 0x3F, 0x80, 0x3F, 0x07, 0xF0, + 0x07, 0xE0, 0xFC, 0x00, 0xFC, 0x1F, 0x80, 0x0F, 0x83, 0xF0, 0x00, 0xFC, + 0x1F, 0x9F, 0x07, 0xE7, 0xE3, 0xF0, 0xF8, 0xF8, 0x1F, 0x7E, 0x07, 0xDF, + 0x00, 0xFF, 0x80, 0x1F, 0xE0, 0x07, 0xF0, 0x00, 0xF8, 0x00, 0x7F, 0x00, + 0x3F, 0xE0, 0x0F, 0xF8, 0x07, 0xDF, 0x03, 0xF7, 0xE0, 0xF8, 0xF8, 0x7E, + 0x3F, 0x1F, 0x07, 0xEF, 0xC0, 0xF8, 0x7C, 0x03, 0xEF, 0x80, 0xF9, 0xF8, + 0x1F, 0x1F, 0x03, 0xE3, 0xE0, 0xF8, 0x7C, 0x1F, 0x07, 0xC3, 0xE0, 0xF8, + 0x78, 0x0F, 0x1F, 0x01, 0xF3, 0xC0, 0x3E, 0x78, 0x03, 0xDF, 0x00, 0x7F, + 0xC0, 0x0F, 0xF8, 0x00, 0xFF, 0x00, 0x1F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, + 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1E, 0x00, 0x07, 0xC0, 0x07, 0xF8, + 0x00, 0xFE, 0x00, 0x1F, 0x80, 0x03, 0xE0, 0x00, 0x7F, 0xFE, 0x7F, 0xFE, + 0x7F, 0xFE, 0x7F, 0xFE, 0x00, 0x7E, 0x00, 0xFC, 0x01, 0xF8, 0x03, 0xF0, + 0x03, 0xF0, 0x07, 0xE0, 0x0F, 0xC0, 0x1F, 0x80, 0x3F, 0x00, 0x7E, 0x00, + 0xFE, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x07, 0x87, + 0xC7, 0xE3, 0xF1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, 0xC1, + 0xE0, 0xF0, 0xF9, 0xF8, 0xF0, 0x7E, 0x0F, 0x83, 0xC1, 0xE0, 0xF0, 0x78, + 0x3C, 0x1E, 0x0F, 0x07, 0x83, 0xC1, 0xE0, 0xFC, 0x7E, 0x1F, 0x07, 0x80, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xE0, 0xF0, 0x7C, 0x3E, 0x1F, 0x83, 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, + 0x0F, 0x07, 0x83, 0xC1, 0xE0, 0xF0, 0x7C, 0x1F, 0x83, 0xC7, 0xE7, 0xC3, + 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, 0xC7, 0xE3, 0xE1, + 0xF0, 0xF0, 0x00, 0x3C, 0x00, 0xFE, 0x0F, 0xFE, 0x1E, 0x1F, 0xFC, 0x0F, + 0xC0, 0x0F, 0x00 }; + +const GFXglyph FreeSansBold18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 10, 0, 1 }, // 0x20 ' ' + { 0, 5, 25, 12, 4, -24 }, // 0x21 '!' + { 16, 13, 9, 17, 2, -25 }, // 0x22 '"' + { 31, 20, 24, 19, 0, -23 }, // 0x23 '#' + { 91, 19, 29, 19, 0, -25 }, // 0x24 '$' + { 160, 29, 25, 31, 1, -24 }, // 0x25 '%' + { 251, 22, 25, 25, 2, -24 }, // 0x26 '&' + { 320, 5, 9, 9, 2, -25 }, // 0x27 ''' + { 326, 9, 33, 12, 1, -25 }, // 0x28 '(' + { 364, 9, 33, 12, 1, -25 }, // 0x29 ')' + { 402, 12, 11, 14, 0, -25 }, // 0x2A '*' + { 419, 16, 16, 20, 2, -15 }, // 0x2B '+' + { 451, 5, 11, 9, 2, -4 }, // 0x2C ',' + { 458, 9, 4, 12, 1, -10 }, // 0x2D '-' + { 463, 5, 5, 9, 2, -4 }, // 0x2E '.' + { 467, 9, 25, 10, 0, -24 }, // 0x2F '/' + { 496, 17, 25, 19, 1, -24 }, // 0x30 '0' + { 550, 10, 25, 19, 3, -24 }, // 0x31 '1' + { 582, 17, 25, 19, 1, -24 }, // 0x32 '2' + { 636, 17, 25, 19, 1, -24 }, // 0x33 '3' + { 690, 16, 25, 19, 2, -24 }, // 0x34 '4' + { 740, 17, 25, 19, 1, -24 }, // 0x35 '5' + { 794, 18, 25, 19, 1, -24 }, // 0x36 '6' + { 851, 17, 25, 19, 1, -24 }, // 0x37 '7' + { 905, 17, 25, 19, 1, -24 }, // 0x38 '8' + { 959, 17, 25, 19, 1, -24 }, // 0x39 '9' + { 1013, 5, 18, 9, 2, -17 }, // 0x3A ':' + { 1025, 5, 24, 9, 2, -17 }, // 0x3B ';' + { 1040, 18, 17, 20, 1, -16 }, // 0x3C '<' + { 1079, 17, 12, 20, 2, -13 }, // 0x3D '=' + { 1105, 18, 17, 20, 1, -16 }, // 0x3E '>' + { 1144, 18, 26, 21, 2, -25 }, // 0x3F '?' + { 1203, 32, 31, 34, 1, -25 }, // 0x40 '@' + { 1327, 24, 26, 24, 0, -25 }, // 0x41 'A' + { 1405, 20, 26, 25, 3, -25 }, // 0x42 'B' + { 1470, 23, 26, 25, 1, -25 }, // 0x43 'C' + { 1545, 21, 26, 25, 3, -25 }, // 0x44 'D' + { 1614, 19, 26, 23, 3, -25 }, // 0x45 'E' + { 1676, 17, 26, 22, 3, -25 }, // 0x46 'F' + { 1732, 24, 26, 27, 1, -25 }, // 0x47 'G' + { 1810, 20, 26, 26, 3, -25 }, // 0x48 'H' + { 1875, 5, 26, 11, 3, -25 }, // 0x49 'I' + { 1892, 16, 26, 20, 1, -25 }, // 0x4A 'J' + { 1944, 22, 26, 25, 3, -25 }, // 0x4B 'K' + { 2016, 17, 26, 22, 3, -25 }, // 0x4C 'L' + { 2072, 24, 26, 30, 3, -25 }, // 0x4D 'M' + { 2150, 20, 26, 26, 3, -25 }, // 0x4E 'N' + { 2215, 25, 26, 27, 1, -25 }, // 0x4F 'O' + { 2297, 19, 26, 24, 3, -25 }, // 0x50 'P' + { 2359, 25, 27, 27, 1, -25 }, // 0x51 'Q' + { 2444, 21, 26, 25, 3, -25 }, // 0x52 'R' + { 2513, 20, 26, 24, 2, -25 }, // 0x53 'S' + { 2578, 19, 26, 23, 2, -25 }, // 0x54 'T' + { 2640, 20, 26, 26, 3, -25 }, // 0x55 'U' + { 2705, 22, 26, 23, 1, -25 }, // 0x56 'V' + { 2777, 32, 26, 34, 1, -25 }, // 0x57 'W' + { 2881, 22, 26, 24, 1, -25 }, // 0x58 'X' + { 2953, 21, 26, 22, 1, -25 }, // 0x59 'Y' + { 3022, 19, 26, 21, 1, -25 }, // 0x5A 'Z' + { 3084, 8, 33, 12, 2, -25 }, // 0x5B '[' + { 3117, 10, 25, 10, 0, -24 }, // 0x5C '\' + { 3149, 8, 33, 12, 1, -25 }, // 0x5D ']' + { 3182, 16, 15, 20, 2, -23 }, // 0x5E '^' + { 3212, 21, 3, 19, -1, 5 }, // 0x5F '_' + { 3220, 7, 5, 9, 1, -25 }, // 0x60 '`' + { 3225, 18, 19, 20, 1, -18 }, // 0x61 'a' + { 3268, 18, 26, 22, 2, -25 }, // 0x62 'b' + { 3327, 17, 19, 20, 1, -18 }, // 0x63 'c' + { 3368, 19, 26, 22, 1, -25 }, // 0x64 'd' + { 3430, 18, 19, 20, 1, -18 }, // 0x65 'e' + { 3473, 10, 26, 12, 1, -25 }, // 0x66 'f' + { 3506, 18, 26, 21, 1, -18 }, // 0x67 'g' + { 3565, 17, 26, 21, 2, -25 }, // 0x68 'h' + { 3621, 5, 26, 10, 2, -25 }, // 0x69 'i' + { 3638, 7, 33, 10, 0, -25 }, // 0x6A 'j' + { 3667, 17, 26, 20, 2, -25 }, // 0x6B 'k' + { 3723, 5, 26, 9, 2, -25 }, // 0x6C 'l' + { 3740, 27, 19, 31, 2, -18 }, // 0x6D 'm' + { 3805, 17, 19, 21, 2, -18 }, // 0x6E 'n' + { 3846, 19, 19, 21, 1, -18 }, // 0x6F 'o' + { 3892, 18, 26, 22, 2, -18 }, // 0x70 'p' + { 3951, 19, 26, 22, 1, -18 }, // 0x71 'q' + { 4013, 11, 19, 14, 2, -18 }, // 0x72 'r' + { 4040, 17, 19, 19, 1, -18 }, // 0x73 's' + { 4081, 9, 23, 12, 1, -22 }, // 0x74 't' + { 4107, 17, 19, 21, 2, -18 }, // 0x75 'u' + { 4148, 19, 19, 19, 0, -18 }, // 0x76 'v' + { 4194, 27, 19, 27, 0, -18 }, // 0x77 'w' + { 4259, 18, 19, 19, 1, -18 }, // 0x78 'x' + { 4302, 19, 26, 19, 0, -18 }, // 0x79 'y' + { 4364, 16, 19, 18, 1, -18 }, // 0x7A 'z' + { 4402, 9, 33, 14, 1, -25 }, // 0x7B '{' + { 4440, 3, 33, 10, 4, -25 }, // 0x7C '|' + { 4453, 9, 33, 14, 3, -25 }, // 0x7D '}' + { 4491, 15, 6, 18, 1, -10 } }; // 0x7E '~' + +const GFXfont FreeSansBold18pt7b PROGMEM = { + (uint8_t *)FreeSansBold18pt7bBitmaps, + (GFXglyph *)FreeSansBold18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 5175 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBold24pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBold24pt7b.h new file mode 100644 index 0000000..aadc9a1 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBold24pt7b.h @@ -0,0 +1,784 @@ +const uint8_t FreeSansBold24pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xDF, 0x3E, 0x7C, 0xF9, 0xF3, 0xE7, 0xC7, 0x0E, 0x1C, 0x00, 0x00, 0x07, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFE, 0x1F, 0xFF, 0x87, 0xFF, 0xE1, + 0xFF, 0xF8, 0x7F, 0xFE, 0x1F, 0xFF, 0x87, 0xFF, 0xE1, 0xFD, 0xF0, 0x3E, + 0x7C, 0x0F, 0x9F, 0x03, 0xE3, 0x80, 0x70, 0xE0, 0x1C, 0x00, 0xF8, 0x3E, + 0x00, 0x3E, 0x0F, 0x80, 0x0F, 0x83, 0xE0, 0x03, 0xE0, 0xF8, 0x00, 0xF8, + 0x7C, 0x00, 0x7C, 0x1F, 0x00, 0x1F, 0x07, 0xC1, 0xFF, 0xFF, 0xFF, 0x7F, + 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFD, 0xFF, 0xFF, 0xFF, + 0x03, 0xE0, 0xF8, 0x00, 0xF8, 0x3E, 0x00, 0x3E, 0x1F, 0x00, 0x1F, 0x07, + 0xC0, 0x07, 0xC1, 0xF0, 0x01, 0xF0, 0x7C, 0x00, 0x7C, 0x1F, 0x03, 0xFF, + 0xFF, 0xFC, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0xF3, + 0xFF, 0xFF, 0xFC, 0x0F, 0x87, 0xC0, 0x07, 0xC1, 0xF0, 0x01, 0xF0, 0x7C, + 0x00, 0x7C, 0x1F, 0x00, 0x1F, 0x07, 0xC0, 0x07, 0xC3, 0xE0, 0x03, 0xE0, + 0xF8, 0x00, 0xF8, 0x3E, 0x00, 0x3E, 0x0F, 0x80, 0x00, 0x00, 0x38, 0x00, + 0x00, 0x1C, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0xFF, 0xFC, 0x00, 0xFF, 0xFF, + 0x80, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xF8, 0x7F, 0x73, 0xFE, 0x7F, 0x38, + 0xFF, 0x3F, 0x1C, 0x3F, 0xDF, 0x8E, 0x0F, 0xEF, 0xC7, 0x07, 0xF7, 0xE3, + 0x80, 0x03, 0xF9, 0xC0, 0x01, 0xFE, 0xE0, 0x00, 0x7F, 0xF0, 0x00, 0x3F, + 0xFC, 0x00, 0x0F, 0xFF, 0xC0, 0x03, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, 0x80, + 0x0F, 0xFF, 0xE0, 0x01, 0xFF, 0xF8, 0x00, 0xE7, 0xFC, 0x00, 0x71, 0xFF, + 0x00, 0x38, 0x7F, 0xFF, 0x1C, 0x1F, 0xFF, 0x8E, 0x0F, 0xFF, 0xC7, 0x07, + 0xFF, 0xE3, 0x87, 0xFB, 0xF9, 0xC3, 0xF9, 0xFE, 0xE7, 0xFC, 0x7F, 0xFF, + 0xFC, 0x3F, 0xFF, 0xFC, 0x0F, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x00, 0x3F, + 0xE0, 0x00, 0x03, 0x80, 0x00, 0x01, 0xC0, 0x00, 0x00, 0xE0, 0x00, 0x00, + 0x70, 0x00, 0x03, 0xE0, 0x00, 0x3C, 0x00, 0x1F, 0xF0, 0x00, 0x78, 0x00, + 0x7F, 0xF8, 0x01, 0xE0, 0x01, 0xFF, 0xF0, 0x03, 0xC0, 0x07, 0xFF, 0xF0, + 0x0F, 0x00, 0x0F, 0x83, 0xE0, 0x1E, 0x00, 0x3E, 0x03, 0xE0, 0x78, 0x00, + 0x78, 0x03, 0xC0, 0xF0, 0x00, 0xF0, 0x07, 0x83, 0xC0, 0x01, 0xE0, 0x0F, + 0x07, 0x80, 0x03, 0xE0, 0x3E, 0x1E, 0x00, 0x03, 0xE0, 0xF8, 0x3C, 0x00, + 0x07, 0xFF, 0xF0, 0xF0, 0x00, 0x07, 0xFF, 0xC1, 0xE0, 0x00, 0x07, 0xFF, + 0x07, 0x80, 0x00, 0x07, 0xFC, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x3C, 0x00, + 0x00, 0x00, 0x00, 0xF0, 0x1F, 0x00, 0x00, 0x01, 0xE0, 0xFF, 0x80, 0x00, + 0x07, 0x87, 0xFF, 0xC0, 0x00, 0x0F, 0x0F, 0xFF, 0x80, 0x00, 0x3C, 0x3F, + 0xFF, 0x80, 0x00, 0x78, 0xFC, 0x1F, 0x00, 0x01, 0xE1, 0xF0, 0x1F, 0x00, + 0x03, 0xC3, 0xC0, 0x1E, 0x00, 0x0F, 0x07, 0x80, 0x3C, 0x00, 0x1E, 0x0F, + 0x00, 0x78, 0x00, 0x78, 0x1F, 0x01, 0xF0, 0x00, 0xF0, 0x1F, 0x07, 0xC0, + 0x03, 0xC0, 0x3F, 0xFF, 0x80, 0x07, 0x80, 0x3F, 0xFE, 0x00, 0x1E, 0x00, + 0x7F, 0xF8, 0x00, 0x7C, 0x00, 0x3F, 0xE0, 0x00, 0xF0, 0x00, 0x1F, 0x00, + 0x00, 0x3F, 0x00, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x1F, 0xFC, 0x00, 0x00, + 0xFF, 0xF8, 0x00, 0x07, 0xFF, 0xF0, 0x00, 0x3F, 0xCF, 0xC0, 0x00, 0xFE, + 0x1F, 0x00, 0x03, 0xF8, 0x7C, 0x00, 0x0F, 0xE1, 0xF0, 0x00, 0x3F, 0xC7, + 0xC0, 0x00, 0x7F, 0x3E, 0x00, 0x01, 0xFF, 0xF8, 0x00, 0x03, 0xFF, 0xC0, + 0x00, 0x07, 0xFE, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x7F, 0x80, 0x00, + 0x07, 0xFF, 0x03, 0xE0, 0x3F, 0xFE, 0x0F, 0x83, 0xFF, 0xF8, 0x3E, 0x1F, + 0xF3, 0xF1, 0xF8, 0x7F, 0x07, 0xE7, 0xE3, 0xFC, 0x1F, 0xFF, 0x0F, 0xE0, + 0x3F, 0xFC, 0x3F, 0x80, 0x7F, 0xF0, 0xFE, 0x01, 0xFF, 0x83, 0xF8, 0x03, + 0xFE, 0x0F, 0xF0, 0x0F, 0xF0, 0x3F, 0xE0, 0x7F, 0xE0, 0x7F, 0xC3, 0xFF, + 0xC1, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFE, 0x07, 0xFF, 0xFB, 0xFC, + 0x0F, 0xFF, 0xC7, 0xF8, 0x1F, 0xFE, 0x0F, 0xE0, 0x0F, 0xE0, 0x00, 0x00, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xBE, 0x7C, 0xF8, 0xE1, 0xC0, 0x00, + 0xF0, 0x0F, 0x80, 0xF8, 0x07, 0xC0, 0x7C, 0x07, 0xE0, 0x3E, 0x03, 0xF0, + 0x1F, 0x80, 0xF8, 0x0F, 0xC0, 0x7E, 0x07, 0xE0, 0x3F, 0x01, 0xF8, 0x0F, + 0xC0, 0xFC, 0x07, 0xE0, 0x3F, 0x01, 0xF8, 0x0F, 0xC0, 0x7E, 0x03, 0xF0, + 0x1F, 0x80, 0xFC, 0x07, 0xE0, 0x3F, 0x00, 0xF8, 0x07, 0xE0, 0x3F, 0x01, + 0xF8, 0x07, 0xC0, 0x3F, 0x01, 0xF8, 0x07, 0xC0, 0x3F, 0x00, 0xF8, 0x07, + 0xE0, 0x1F, 0x00, 0xF8, 0x03, 0xE0, 0x1F, 0x00, 0x7C, 0x01, 0xE0, 0x78, + 0x03, 0xE0, 0x0F, 0x80, 0x7C, 0x01, 0xF0, 0x0F, 0x80, 0x3E, 0x01, 0xF0, + 0x0F, 0xC0, 0x3E, 0x01, 0xF8, 0x0F, 0xC0, 0x3F, 0x01, 0xF8, 0x0F, 0xC0, + 0x7E, 0x01, 0xF8, 0x0F, 0xC0, 0x7E, 0x03, 0xF0, 0x1F, 0x80, 0xFC, 0x07, + 0xE0, 0x3F, 0x01, 0xF8, 0x0F, 0xC0, 0x7E, 0x03, 0xE0, 0x3F, 0x01, 0xF8, + 0x0F, 0xC0, 0x7C, 0x07, 0xE0, 0x3F, 0x01, 0xF0, 0x1F, 0x80, 0xF8, 0x0F, + 0xC0, 0x7C, 0x07, 0xE0, 0x3E, 0x03, 0xF0, 0x1F, 0x01, 0xF0, 0x00, 0x03, + 0x80, 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x06, 0x38, 0xDF, 0xFF, 0xFF, 0xFF, + 0x9F, 0xFE, 0x07, 0xC0, 0x1F, 0xC0, 0x3F, 0x80, 0xF7, 0x83, 0xC7, 0x87, + 0x8F, 0x02, 0x08, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, + 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, + 0x00, 0x3E, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x1F, 0x00, 0x00, + 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, + 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0x87, 0x0E, 0x1C, 0x78, 0xEF, 0xDF, 0x38, 0x00, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0x80, 0x00, 0x38, 0x03, 0xC0, 0x1C, 0x00, 0xE0, 0x07, 0x00, + 0x70, 0x03, 0x80, 0x1C, 0x01, 0xE0, 0x0E, 0x00, 0x70, 0x03, 0x80, 0x38, + 0x01, 0xC0, 0x0E, 0x00, 0xF0, 0x07, 0x00, 0x38, 0x03, 0xC0, 0x1C, 0x00, + 0xE0, 0x07, 0x00, 0x70, 0x03, 0x80, 0x1C, 0x01, 0xE0, 0x0E, 0x00, 0x70, + 0x03, 0x80, 0x38, 0x01, 0xC0, 0x0E, 0x00, 0xF0, 0x07, 0x00, 0x00, 0x00, + 0xFF, 0x00, 0x03, 0xFF, 0xC0, 0x0F, 0xFF, 0xF0, 0x1F, 0xFF, 0xF8, 0x1F, + 0xFF, 0xF8, 0x3F, 0xFF, 0xFC, 0x3F, 0xC3, 0xFC, 0x7F, 0x81, 0xFE, 0x7F, + 0x00, 0xFE, 0x7F, 0x00, 0xFE, 0x7F, 0x00, 0xFE, 0xFE, 0x00, 0x7F, 0xFE, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0x7F, + 0x00, 0xFE, 0x7F, 0x00, 0xFE, 0x7F, 0x00, 0xFE, 0x7F, 0x81, 0xFE, 0x3F, + 0xC3, 0xFC, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, 0xF8, 0x1F, 0xFF, 0xF8, 0x0F, + 0xFF, 0xF0, 0x03, 0xFF, 0xC0, 0x00, 0xFF, 0x00, 0x00, 0x3C, 0x01, 0xF0, + 0x07, 0xC0, 0x3F, 0x01, 0xFC, 0x3F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, + 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, + 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, + 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x01, 0xFE, 0x00, 0x0F, 0xFF, 0x80, + 0x3F, 0xFF, 0x80, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0x8F, 0xFF, 0xFF, 0x9F, + 0xE0, 0xFF, 0x7F, 0x80, 0xFF, 0xFE, 0x01, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, + 0x03, 0xFF, 0xF0, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, + 0x7F, 0x80, 0x00, 0xFE, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x7F, + 0xC0, 0x01, 0xFF, 0x00, 0x07, 0xF8, 0x00, 0x3F, 0xE0, 0x00, 0xFF, 0x00, + 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0x7F, 0x00, 0x01, + 0xFC, 0x00, 0x03, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xBF, + 0xFF, 0xFF, 0x7F, 0xFF, 0xFE, 0xFF, 0xFF, 0xFC, 0x01, 0xFE, 0x00, 0x0F, + 0xFF, 0x80, 0x7F, 0xFF, 0x81, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0x8F, 0xFF, + 0xFF, 0x1F, 0xE1, 0xFF, 0x7F, 0x81, 0xFE, 0xFE, 0x01, 0xFD, 0xFC, 0x03, + 0xFB, 0xF8, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x7F, + 0x00, 0x01, 0xFC, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0x7F, 0xC0, + 0x00, 0xFF, 0xE0, 0x00, 0x3F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x3F, 0xC0, + 0x00, 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, + 0x07, 0xFF, 0xF8, 0x0F, 0xF7, 0xF8, 0x3F, 0xCF, 0xFF, 0xFF, 0x9F, 0xFF, + 0xFE, 0x1F, 0xFF, 0xF8, 0x1F, 0xFF, 0xE0, 0x0F, 0xFF, 0x80, 0x07, 0xF8, + 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x03, 0xFE, 0x00, 0x0F, 0xF8, + 0x00, 0x7F, 0xE0, 0x03, 0xFF, 0x80, 0x0F, 0xFE, 0x00, 0x7B, 0xF8, 0x01, + 0xEF, 0xE0, 0x0F, 0x3F, 0x80, 0x78, 0xFE, 0x01, 0xE3, 0xF8, 0x0F, 0x0F, + 0xE0, 0x38, 0x3F, 0x81, 0xE0, 0xFE, 0x07, 0x03, 0xF8, 0x3C, 0x0F, 0xE1, + 0xE0, 0x3F, 0x87, 0x00, 0xFE, 0x3C, 0x03, 0xF8, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF0, 0x00, 0xFE, 0x00, 0x03, 0xF8, 0x00, 0x0F, 0xE0, 0x00, 0x3F, 0x80, + 0x00, 0xFE, 0x00, 0x03, 0xF8, 0x00, 0x0F, 0xE0, 0x1F, 0xFF, 0xFC, 0x3F, + 0xFF, 0xF8, 0x7F, 0xFF, 0xF0, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0xC7, 0xFF, + 0xFF, 0x8F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x78, 0x00, + 0x01, 0xF1, 0xF8, 0x03, 0xEF, 0xFE, 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xFE, + 0x1F, 0xFF, 0xFE, 0x7F, 0xFF, 0xFC, 0xFE, 0x07, 0xFC, 0x00, 0x07, 0xF8, + 0x00, 0x07, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, + 0x00, 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0xF8, 0x03, 0xFF, 0xF8, + 0x0F, 0xF7, 0xF8, 0x3F, 0xEF, 0xFF, 0xFF, 0x8F, 0xFF, 0xFF, 0x0F, 0xFF, + 0xFC, 0x0F, 0xFF, 0xE0, 0x0F, 0xFF, 0x80, 0x03, 0xF8, 0x00, 0x00, 0xFF, + 0x00, 0x07, 0xFF, 0x80, 0x1F, 0xFF, 0xC0, 0x7F, 0xFF, 0x81, 0xFF, 0xFF, + 0x87, 0xFF, 0xFF, 0x8F, 0xF0, 0xFF, 0x3F, 0xC0, 0xFE, 0x7F, 0x00, 0x00, + 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE3, 0xF0, 0x1F, + 0xDF, 0xF8, 0x3F, 0xFF, 0xFC, 0x7F, 0xFF, 0xFC, 0xFF, 0xFF, 0xF9, 0xFF, + 0x87, 0xFB, 0xFC, 0x07, 0xF7, 0xF8, 0x0F, 0xFF, 0xE0, 0x0F, 0xFF, 0xC0, + 0x1F, 0xFF, 0x80, 0x3F, 0xFF, 0x00, 0x7F, 0x7E, 0x00, 0xFE, 0xFC, 0x01, + 0xFD, 0xFC, 0x07, 0xFB, 0xF8, 0x0F, 0xE3, 0xFC, 0x7F, 0xC7, 0xFF, 0xFF, + 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xF8, 0x0F, 0xFF, 0xE0, 0x07, 0xFF, 0x80, + 0x03, 0xF8, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x00, 0x3F, 0x00, + 0x00, 0xFC, 0x00, 0x03, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x80, 0x00, + 0x7F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x1F, + 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xF8, 0x00, 0x07, 0xF0, + 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFC, 0x00, + 0x01, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, + 0x3F, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x03, 0xF8, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x03, 0xFF, 0xC0, 0x0F, 0xFF, 0xE0, 0x1F, + 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, 0x3F, 0xFF, 0xF8, 0x7F, 0x83, 0xFC, 0x7F, + 0x00, 0xFC, 0x7E, 0x00, 0xFC, 0x7E, 0x00, 0x7C, 0x7E, 0x00, 0x7C, 0x7E, + 0x00, 0xFC, 0x3F, 0x00, 0xF8, 0x3F, 0x83, 0xF8, 0x0F, 0xFF, 0xF0, 0x07, + 0xFF, 0xC0, 0x0F, 0xFF, 0xF0, 0x1F, 0xFF, 0xF8, 0x3F, 0xC3, 0xFC, 0x7F, + 0x00, 0xFE, 0x7F, 0x00, 0xFE, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFF, 0x00, 0xFF, 0xFF, + 0x00, 0xFE, 0x7F, 0x83, 0xFE, 0x7F, 0xFF, 0xFE, 0x3F, 0xFF, 0xFC, 0x1F, + 0xFF, 0xF8, 0x0F, 0xFF, 0xF0, 0x07, 0xFF, 0xC0, 0x00, 0xFF, 0x00, 0x00, + 0xFF, 0x00, 0x03, 0xFF, 0xC0, 0x0F, 0xFF, 0xE0, 0x1F, 0xFF, 0xF0, 0x3F, + 0xFF, 0xF8, 0x3F, 0xFF, 0xFC, 0x7F, 0xC3, 0xFC, 0x7F, 0x01, 0xFE, 0xFF, + 0x00, 0xFE, 0xFE, 0x00, 0x7E, 0xFE, 0x00, 0x7E, 0xFE, 0x00, 0x7F, 0xFE, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFF, 0x00, 0xFF, 0x7F, + 0x01, 0xFF, 0x7F, 0xC3, 0xFF, 0x7F, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0x1F, + 0xFF, 0xFF, 0x0F, 0xFF, 0x7F, 0x07, 0xFE, 0x7F, 0x01, 0xFC, 0x7E, 0x00, + 0x00, 0x7E, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x7F, 0x01, 0xFC, 0x7F, + 0x83, 0xFC, 0x7F, 0xFF, 0xF8, 0x3F, 0xFF, 0xF8, 0x3F, 0xFF, 0xF0, 0x1F, + 0xFF, 0xE0, 0x07, 0xFF, 0x80, 0x01, 0xFE, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFE, 0x1C, 0x38, 0x71, 0xE7, 0xBF, 0x7C, 0xE0, 0x00, + 0x00, 0x02, 0x00, 0x00, 0x3C, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0xF0, 0x01, + 0xFF, 0xE0, 0x0F, 0xFF, 0xC0, 0xFF, 0xFC, 0x0F, 0xFF, 0xC0, 0x7F, 0xFC, + 0x01, 0xFF, 0xC0, 0x03, 0xFC, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0xE0, 0x00, + 0x1F, 0xF8, 0x00, 0x3F, 0xFE, 0x00, 0x0F, 0xFF, 0x80, 0x07, 0xFF, 0xE0, + 0x01, 0xFF, 0xF8, 0x00, 0x7F, 0xF8, 0x00, 0x3F, 0xF0, 0x00, 0x0F, 0xE0, + 0x00, 0x03, 0xC0, 0x00, 0x00, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x80, 0x00, + 0x01, 0xC0, 0x00, 0x03, 0xF0, 0x00, 0x07, 0xFC, 0x00, 0x0F, 0xFE, 0x00, + 0x1F, 0xFF, 0x80, 0x07, 0xFF, 0xE0, 0x01, 0xFF, 0xF0, 0x00, 0x7F, 0xFC, + 0x00, 0x1F, 0xFC, 0x00, 0x07, 0xF8, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0xE0, + 0x01, 0xFF, 0xC0, 0x0F, 0xFF, 0x80, 0xFF, 0xF8, 0x0F, 0xFF, 0x80, 0xFF, + 0xFC, 0x03, 0xFF, 0xC0, 0x07, 0xFC, 0x00, 0x0F, 0xE0, 0x00, 0x1E, 0x00, + 0x00, 0x20, 0x00, 0x00, 0x00, 0x01, 0xFE, 0x00, 0x07, 0xFF, 0xC0, 0x1F, + 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, 0x3F, 0xFF, 0xFC, 0x7F, 0xFF, 0xFC, 0x7F, + 0x83, 0xFE, 0x7F, 0x01, 0xFE, 0xFF, 0x00, 0xFF, 0xFE, 0x00, 0x7F, 0xFE, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0x00, + 0x01, 0xFE, 0x00, 0x03, 0xFE, 0x00, 0x07, 0xFC, 0x00, 0x0F, 0xF8, 0x00, + 0x3F, 0xF0, 0x00, 0x3F, 0xE0, 0x00, 0x7F, 0x80, 0x00, 0x7F, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0x00, 0x3F, 0xFF, 0xE0, + 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xF8, 0x00, + 0x03, 0xFE, 0x01, 0xFF, 0x80, 0x01, 0xFE, 0x00, 0x07, 0xF8, 0x00, 0x7F, + 0x80, 0x00, 0x3F, 0x80, 0x1F, 0xC0, 0x00, 0x03, 0xF8, 0x07, 0xF0, 0x00, + 0x00, 0x1F, 0x00, 0xFC, 0x00, 0x00, 0x01, 0xF0, 0x3F, 0x00, 0x00, 0x00, + 0x3E, 0x0F, 0xC0, 0x07, 0xE3, 0xC3, 0xE1, 0xF0, 0x03, 0xFE, 0xF8, 0x3C, + 0x7E, 0x01, 0xFF, 0xFF, 0x07, 0x8F, 0x80, 0x7E, 0x1F, 0xC0, 0x7B, 0xF0, + 0x1F, 0x81, 0xF8, 0x0F, 0x7C, 0x03, 0xE0, 0x1F, 0x01, 0xEF, 0x80, 0xF8, + 0x03, 0xC0, 0x3F, 0xF0, 0x1E, 0x00, 0x78, 0x07, 0xFC, 0x07, 0xC0, 0x0F, + 0x00, 0xFF, 0x80, 0xF0, 0x01, 0xE0, 0x1F, 0xF0, 0x1E, 0x00, 0x38, 0x07, + 0xFE, 0x07, 0xC0, 0x0F, 0x00, 0xFF, 0xC0, 0xF8, 0x01, 0xE0, 0x1E, 0xF8, + 0x1F, 0x00, 0x38, 0x07, 0xDF, 0x03, 0xE0, 0x0F, 0x00, 0xF3, 0xF0, 0x7C, + 0x03, 0xE0, 0x3E, 0x3E, 0x0F, 0xC0, 0xFC, 0x0F, 0x87, 0xC0, 0xFC, 0x3F, + 0xC7, 0xF0, 0xFC, 0x1F, 0xFF, 0xFF, 0xFC, 0x0F, 0xC1, 0xFF, 0xEF, 0xFF, + 0x01, 0xFC, 0x1F, 0xF8, 0xFF, 0x80, 0x1F, 0xC0, 0xFC, 0x07, 0xC0, 0x01, + 0xFC, 0x00, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x60, 0x00, 0x01, 0xFF, 0xFF, + 0xFE, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x7F, 0xFF, 0xF0, + 0x00, 0x00, 0x00, 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, + 0x0F, 0xF8, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x1F, 0xFC, 0x00, 0x00, + 0x1F, 0xFC, 0x00, 0x00, 0x1F, 0xFC, 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x00, + 0x3F, 0xFE, 0x00, 0x00, 0x3F, 0x7E, 0x00, 0x00, 0x7F, 0x7F, 0x00, 0x00, + 0x7F, 0x7F, 0x00, 0x00, 0x7E, 0x3F, 0x00, 0x00, 0xFE, 0x3F, 0x80, 0x00, + 0xFE, 0x3F, 0x80, 0x01, 0xFC, 0x1F, 0x80, 0x01, 0xFC, 0x1F, 0xC0, 0x01, + 0xF8, 0x1F, 0xC0, 0x03, 0xF8, 0x0F, 0xE0, 0x03, 0xF8, 0x0F, 0xE0, 0x03, + 0xF0, 0x0F, 0xE0, 0x07, 0xF0, 0x07, 0xF0, 0x07, 0xFF, 0xFF, 0xF0, 0x07, + 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xF8, 0x1F, + 0xFF, 0xFF, 0xF8, 0x1F, 0xFF, 0xFF, 0xFC, 0x1F, 0xC0, 0x01, 0xFC, 0x3F, + 0x80, 0x01, 0xFC, 0x3F, 0x80, 0x00, 0xFE, 0x3F, 0x80, 0x00, 0xFE, 0x7F, + 0x00, 0x00, 0xFE, 0x7F, 0x00, 0x00, 0x7F, 0x7F, 0x00, 0x00, 0x7F, 0xFF, + 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, 0xFF, + 0x8F, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, 0xFF, 0x3F, 0x80, 0x1F, 0xF7, 0xF0, + 0x01, 0xFE, 0xFE, 0x00, 0x1F, 0xDF, 0xC0, 0x03, 0xFB, 0xF8, 0x00, 0x7F, + 0x7F, 0x00, 0x1F, 0xCF, 0xE0, 0x07, 0xF9, 0xFF, 0xFF, 0xFE, 0x3F, 0xFF, + 0xFF, 0x87, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFE, 0x1F, 0xFF, 0xFF, 0xE3, + 0xFF, 0xFF, 0xFE, 0x7F, 0x00, 0x1F, 0xEF, 0xE0, 0x01, 0xFD, 0xFC, 0x00, + 0x1F, 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, 0x7F, 0xFE, 0x00, 0x0F, 0xFF, + 0xC0, 0x01, 0xFF, 0xF8, 0x00, 0x7F, 0xFF, 0x00, 0x1F, 0xEF, 0xFF, 0xFF, + 0xFD, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xF8, 0xFF, + 0xFF, 0xFC, 0x1F, 0xFF, 0xFC, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x03, 0xFF, + 0xF8, 0x00, 0x1F, 0xFF, 0xF8, 0x01, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, + 0xE0, 0x3F, 0xFF, 0xFF, 0xC1, 0xFF, 0x81, 0xFF, 0x0F, 0xF8, 0x01, 0xFE, + 0x3F, 0xC0, 0x07, 0xF9, 0xFE, 0x00, 0x0F, 0xE7, 0xF8, 0x00, 0x1F, 0xDF, + 0xC0, 0x00, 0x7F, 0x7F, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x0F, 0xE0, + 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x03, 0xF8, 0x00, + 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, + 0x7F, 0x00, 0x01, 0xFD, 0xFC, 0x00, 0x07, 0xF7, 0xF8, 0x00, 0x3F, 0xCF, + 0xF0, 0x00, 0xFE, 0x3F, 0xE0, 0x07, 0xF8, 0x7F, 0xE0, 0x7F, 0xC0, 0xFF, + 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0xC0, 0x07, 0xFF, + 0xFE, 0x00, 0x0F, 0xFF, 0xE0, 0x00, 0x07, 0xFC, 0x00, 0xFF, 0xFF, 0xC0, + 0x0F, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xFC, 0x0F, 0xFF, 0xFF, 0xE0, 0xFF, + 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xF8, 0xFE, 0x00, 0xFF, 0xCF, 0xE0, 0x03, + 0xFC, 0xFE, 0x00, 0x1F, 0xEF, 0xE0, 0x01, 0xFE, 0xFE, 0x00, 0x0F, 0xEF, + 0xE0, 0x00, 0xFE, 0xFE, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x7F, 0xFE, 0x00, + 0x07, 0xFF, 0xE0, 0x00, 0x7F, 0xFE, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x7F, + 0xFE, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x7F, 0xFE, 0x00, 0x07, 0xFF, 0xE0, + 0x00, 0x7F, 0xFE, 0x00, 0x0F, 0xEF, 0xE0, 0x00, 0xFE, 0xFE, 0x00, 0x1F, + 0xEF, 0xE0, 0x01, 0xFE, 0xFE, 0x00, 0x3F, 0xCF, 0xE0, 0x0F, 0xFC, 0xFF, + 0xFF, 0xFF, 0x8F, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, + 0xC0, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFC, 0x00, 0xFF, 0xFF, 0xFF, 0x7F, + 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xF7, + 0xFF, 0xFF, 0xFB, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0x7F, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x0F, 0xE0, 0x00, + 0x07, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, + 0xFE, 0x7F, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0x9F, 0xC0, 0x00, 0x0F, 0xE0, + 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x0F, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFF, 0xFF, + 0xFC, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, + 0xFC, 0xFF, 0xFF, 0xFC, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0xFF, 0xFE, 0x00, 0x07, 0xFF, 0xFF, + 0x00, 0x1F, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0xFF, + 0x07, 0xFE, 0x03, 0xFF, 0x0F, 0xF0, 0x01, 0xFE, 0x3F, 0xC0, 0x01, 0xFC, + 0x7F, 0x00, 0x01, 0xFD, 0xFE, 0x00, 0x03, 0xFB, 0xF8, 0x00, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x00, 0xFE, 0x00, 0x3F, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, 0xF8, + 0x00, 0xFF, 0xFF, 0xF0, 0x01, 0xFF, 0xFF, 0xE0, 0x03, 0xFF, 0xFF, 0xC0, + 0x07, 0xFF, 0xFF, 0xC0, 0x00, 0x1F, 0xBF, 0x80, 0x00, 0x3F, 0x7F, 0x00, + 0x00, 0x7E, 0xFF, 0x00, 0x01, 0xFC, 0xFF, 0x00, 0x03, 0xF9, 0xFF, 0x00, + 0x0F, 0xF1, 0xFF, 0x00, 0x3F, 0xE3, 0xFF, 0x83, 0xFF, 0xC3, 0xFF, 0xFF, + 0xFF, 0x83, 0xFF, 0xFF, 0xDF, 0x03, 0xFF, 0xFF, 0x9E, 0x03, 0xFF, 0xFE, + 0x3C, 0x01, 0xFF, 0xF0, 0x78, 0x00, 0x7F, 0x80, 0x00, 0xFE, 0x00, 0x0F, + 0xFF, 0xC0, 0x01, 0xFF, 0xF8, 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFF, 0xE0, + 0x00, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, 0x7F, + 0xFE, 0x00, 0x0F, 0xFF, 0xC0, 0x01, 0xFF, 0xF8, 0x00, 0x3F, 0xFF, 0x00, + 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, + 0x80, 0x03, 0xFF, 0xF0, 0x00, 0x7F, 0xFE, 0x00, 0x0F, 0xFF, 0xC0, 0x01, + 0xFF, 0xF8, 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFC, + 0x00, 0x1F, 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, 0x7F, 0xFE, 0x00, 0x0F, + 0xFF, 0xC0, 0x01, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x01, + 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFC, + 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, + 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x07, + 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xF0, + 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xFF, 0xE0, + 0x1F, 0xFF, 0x80, 0x7F, 0xFE, 0x01, 0xFF, 0xF8, 0x07, 0xFF, 0xE0, 0x1F, + 0xFF, 0xC0, 0xFF, 0xFF, 0x87, 0xFD, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0x8F, + 0xFF, 0xFC, 0x1F, 0xFF, 0xE0, 0x3F, 0xFF, 0x00, 0x1F, 0xE0, 0x00, 0xFE, + 0x00, 0x0F, 0xF3, 0xF8, 0x00, 0x7F, 0x8F, 0xE0, 0x03, 0xFC, 0x3F, 0x80, + 0x1F, 0xE0, 0xFE, 0x00, 0xFF, 0x83, 0xF8, 0x07, 0xFC, 0x0F, 0xE0, 0x1F, + 0xE0, 0x3F, 0x80, 0xFF, 0x00, 0xFE, 0x07, 0xF8, 0x03, 0xF8, 0x3F, 0xC0, + 0x0F, 0xE1, 0xFE, 0x00, 0x3F, 0x8F, 0xF0, 0x00, 0xFE, 0x7F, 0x80, 0x03, + 0xFB, 0xFC, 0x00, 0x0F, 0xFF, 0xE0, 0x00, 0x3F, 0xFF, 0xC0, 0x00, 0xFF, + 0xFF, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x0F, 0xFF, 0xFC, 0x00, 0x3F, 0xF7, + 0xF8, 0x00, 0xFF, 0x8F, 0xF0, 0x03, 0xFC, 0x3F, 0xC0, 0x0F, 0xE0, 0x7F, + 0x80, 0x3F, 0x80, 0xFF, 0x00, 0xFE, 0x01, 0xFE, 0x03, 0xF8, 0x07, 0xFC, + 0x0F, 0xE0, 0x0F, 0xF0, 0x3F, 0x80, 0x1F, 0xE0, 0xFE, 0x00, 0x3F, 0xC3, + 0xF8, 0x00, 0xFF, 0x8F, 0xE0, 0x01, 0xFE, 0x3F, 0x80, 0x03, 0xFC, 0xFE, + 0x00, 0x07, 0xFB, 0xF8, 0x00, 0x1F, 0xF0, 0xFE, 0x00, 0x01, 0xFC, 0x00, + 0x03, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, + 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x03, + 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x3F, + 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x03, 0xF8, + 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x3F, 0x80, + 0x00, 0x7F, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x03, 0xF8, 0x00, + 0x07, 0xF0, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFF, 0xE0, 0x03, + 0xFF, 0xFF, 0xF0, 0x01, 0xFF, 0xFF, 0xF8, 0x00, 0xFF, 0xFF, 0xFC, 0x00, + 0x7F, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xFF, 0xC0, + 0x1F, 0xFF, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xF0, 0x07, 0xFF, 0xFF, 0xFC, + 0x07, 0xFF, 0xFF, 0xBE, 0x03, 0xEF, 0xFF, 0xDF, 0x01, 0xF7, 0xFF, 0xEF, + 0x80, 0xFB, 0xFF, 0xF7, 0xC0, 0xFD, 0xFF, 0xFB, 0xF0, 0x7C, 0xFF, 0xFC, + 0xF8, 0x3E, 0x7F, 0xFE, 0x7C, 0x1F, 0x3F, 0xFF, 0x3E, 0x0F, 0x9F, 0xFF, + 0x9F, 0x8F, 0x8F, 0xFF, 0xC7, 0xC7, 0xC7, 0xFF, 0xE3, 0xE3, 0xE3, 0xFF, + 0xF1, 0xF1, 0xF1, 0xFF, 0xF8, 0xFC, 0xF8, 0xFF, 0xFC, 0x3E, 0xF8, 0x7F, + 0xFE, 0x1F, 0x7C, 0x3F, 0xFF, 0x0F, 0xBE, 0x1F, 0xFF, 0x87, 0xDF, 0x0F, + 0xFF, 0xC3, 0xFF, 0x07, 0xFF, 0xE0, 0xFF, 0x83, 0xFF, 0xF0, 0x7F, 0xC1, + 0xFF, 0xF8, 0x3F, 0xE0, 0xFF, 0xFC, 0x1F, 0xF0, 0x7F, 0xFE, 0x07, 0xF0, + 0x3F, 0xFF, 0x03, 0xF8, 0x1F, 0xC0, 0xFE, 0x00, 0x07, 0xFF, 0xF0, 0x00, + 0x7F, 0xFF, 0x80, 0x07, 0xFF, 0xF8, 0x00, 0x7F, 0xFF, 0xC0, 0x07, 0xFF, + 0xFC, 0x00, 0x7F, 0xFF, 0xE0, 0x07, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xF0, + 0x07, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xF8, 0x07, 0xFF, 0xEF, 0xC0, 0x7F, + 0xFE, 0xFE, 0x07, 0xFF, 0xE7, 0xE0, 0x7F, 0xFE, 0x7F, 0x07, 0xFF, 0xE3, + 0xF0, 0x7F, 0xFE, 0x1F, 0x87, 0xFF, 0xE1, 0xFC, 0x7F, 0xFE, 0x0F, 0xC7, + 0xFF, 0xE0, 0xFE, 0x7F, 0xFE, 0x07, 0xE7, 0xFF, 0xE0, 0x3F, 0x7F, 0xFE, + 0x03, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, 0xE0, 0x0F, + 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xE0, 0x07, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, + 0xE0, 0x03, 0xFF, 0xFE, 0x00, 0x1F, 0xFF, 0xE0, 0x00, 0xFF, 0xFE, 0x00, + 0x0F, 0xFF, 0xE0, 0x00, 0x7F, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x3F, 0xFF, + 0x80, 0x00, 0x7F, 0xFF, 0xE0, 0x00, 0x7F, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, + 0xFF, 0x00, 0x7F, 0xFF, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xF0, 0x3F, 0xC0, + 0x0F, 0xF8, 0x3F, 0xC0, 0x01, 0xFE, 0x1F, 0xC0, 0x00, 0x7F, 0x1F, 0xE0, + 0x00, 0x3F, 0xCF, 0xE0, 0x00, 0x0F, 0xE7, 0xF0, 0x00, 0x07, 0xF7, 0xF8, + 0x00, 0x03, 0xFF, 0xF8, 0x00, 0x00, 0xFF, 0xFC, 0x00, 0x00, 0x7F, 0xFE, + 0x00, 0x00, 0x3F, 0xFF, 0x00, 0x00, 0x1F, 0xFF, 0x80, 0x00, 0x0F, 0xFF, + 0xC0, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x01, 0xFF, + 0xFC, 0x00, 0x01, 0xFE, 0xFE, 0x00, 0x00, 0xFE, 0x7F, 0x00, 0x00, 0x7F, + 0x3F, 0xC0, 0x00, 0x7F, 0x8F, 0xE0, 0x00, 0x3F, 0x87, 0xF8, 0x00, 0x3F, + 0xC1, 0xFE, 0x00, 0x3F, 0xC0, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xFF, 0xFF, + 0xE0, 0x0F, 0xFF, 0xFF, 0xE0, 0x03, 0xFF, 0xFF, 0xE0, 0x00, 0xFF, 0xFF, + 0xE0, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0xFF, 0xFF, + 0xE0, 0x3F, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0xFC, 0xFF, + 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0xEF, 0xE0, 0x0F, 0xFB, 0xF8, 0x00, 0xFF, + 0xFE, 0x00, 0x1F, 0xFF, 0x80, 0x07, 0xFF, 0xE0, 0x01, 0xFF, 0xF8, 0x00, + 0x7F, 0xFE, 0x00, 0x1F, 0xFF, 0x80, 0x07, 0xFF, 0xE0, 0x03, 0xFF, 0xF8, + 0x03, 0xFE, 0xFF, 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0xF3, + 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xF8, 0x3F, 0xFF, 0xF8, 0x0F, 0xE0, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x0F, 0xE0, + 0x00, 0x03, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x0F, + 0xE0, 0x00, 0x03, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x3F, 0xFF, 0x80, 0x00, 0x7F, 0xFF, + 0xE0, 0x00, 0x7F, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, + 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xF0, 0x3F, 0xC0, 0x07, 0xF8, 0x3F, 0xC0, + 0x01, 0xFE, 0x1F, 0xC0, 0x00, 0x7F, 0x1F, 0xE0, 0x00, 0x3F, 0xCF, 0xE0, + 0x00, 0x0F, 0xE7, 0xF0, 0x00, 0x07, 0xF7, 0xF8, 0x00, 0x03, 0xFF, 0xF8, + 0x00, 0x00, 0xFF, 0xFC, 0x00, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x3F, 0xFF, + 0x00, 0x00, 0x1F, 0xFF, 0x80, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x07, 0xFF, + 0xE0, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x01, 0xFF, 0xFC, 0x00, 0x21, 0xFE, + 0xFE, 0x00, 0x38, 0xFE, 0x7F, 0x00, 0x3E, 0x7F, 0x3F, 0xC0, 0x3F, 0xFF, + 0x8F, 0xE0, 0x0F, 0xFF, 0x87, 0xF8, 0x03, 0xFF, 0xC1, 0xFE, 0x00, 0xFF, + 0xC0, 0xFF, 0xC0, 0x7F, 0xE0, 0x3F, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, + 0xFC, 0x03, 0xFF, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xFF, 0xC0, 0x1F, 0xFF, + 0xCF, 0xC0, 0x01, 0xFF, 0x03, 0xC0, 0x00, 0x00, 0x00, 0xC0, 0xFF, 0xFF, + 0xF8, 0x0F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFF, 0x8F, 0xFF, 0xFF, 0xF8, + 0xFF, 0xFF, 0xFF, 0xCF, 0xFF, 0xFF, 0xFC, 0xFE, 0x00, 0x3F, 0xEF, 0xE0, + 0x01, 0xFE, 0xFE, 0x00, 0x0F, 0xEF, 0xE0, 0x00, 0xFE, 0xFE, 0x00, 0x0F, + 0xEF, 0xE0, 0x00, 0xFE, 0xFE, 0x00, 0x0F, 0xEF, 0xE0, 0x01, 0xFC, 0xFE, + 0x00, 0x3F, 0xCF, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, + 0xC0, 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0x8F, + 0xE0, 0x07, 0xF8, 0xFE, 0x00, 0x1F, 0xCF, 0xE0, 0x01, 0xFC, 0xFE, 0x00, + 0x1F, 0xCF, 0xE0, 0x01, 0xFC, 0xFE, 0x00, 0x1F, 0xCF, 0xE0, 0x01, 0xFC, + 0xFE, 0x00, 0x1F, 0xCF, 0xE0, 0x01, 0xFC, 0xFE, 0x00, 0x1F, 0xCF, 0xE0, + 0x01, 0xFC, 0xFE, 0x00, 0x1F, 0xEF, 0xE0, 0x00, 0xFF, 0x00, 0xFF, 0xC0, + 0x00, 0x3F, 0xFF, 0x80, 0x0F, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, 0xF0, 0x3F, + 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xFC, 0x7F, 0xC0, 0xFF, 0xCF, 0xF0, 0x03, + 0xFE, 0xFE, 0x00, 0x1F, 0xEF, 0xE0, 0x00, 0xFE, 0xFE, 0x00, 0x0F, 0xEF, + 0xE0, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x0F, 0xFC, 0x00, 0x00, 0x7F, 0xFC, + 0x00, 0x07, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0xFC, 0x01, 0xFF, 0xFF, 0xF0, + 0x07, 0xFF, 0xFF, 0xC0, 0x0F, 0xFF, 0xFE, 0x00, 0x07, 0xFF, 0xE0, 0x00, + 0x03, 0xFF, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x07, + 0xFF, 0xE0, 0x00, 0x7F, 0xFE, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFF, + 0x00, 0x0F, 0xE7, 0xFC, 0x03, 0xFE, 0x7F, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, + 0xFC, 0x1F, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xF0, 0x03, 0xFF, 0xFC, 0x00, + 0x07, 0xFE, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, + 0x0F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, + 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0x7F, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, + 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, + 0xF8, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x0F, 0xE0, 0x00, + 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0xFE, 0x00, + 0x0F, 0xFF, 0xC0, 0x01, 0xFF, 0xF8, 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFF, + 0xE0, 0x00, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, + 0x7F, 0xFE, 0x00, 0x0F, 0xFF, 0xC0, 0x01, 0xFF, 0xF8, 0x00, 0x3F, 0xFF, + 0x00, 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0x80, 0x03, + 0xFF, 0xF0, 0x00, 0x7F, 0xFE, 0x00, 0x0F, 0xFF, 0xC0, 0x01, 0xFF, 0xF8, + 0x00, 0x3F, 0xFF, 0x00, 0x07, 0xFF, 0xE0, 0x00, 0xFF, 0xFC, 0x00, 0x1F, + 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, 0x7F, 0xFE, 0x00, 0x0F, 0xFF, 0xC0, + 0x01, 0xFF, 0xFC, 0x00, 0x7F, 0xBF, 0xC0, 0x1F, 0xE7, 0xFC, 0x07, 0xFC, + 0x7F, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, + 0xFE, 0x00, 0x7F, 0xFF, 0x00, 0x01, 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x03, + 0xFF, 0xF0, 0x00, 0x1F, 0xDF, 0xC0, 0x01, 0xFC, 0xFE, 0x00, 0x0F, 0xE7, + 0xF0, 0x00, 0x7F, 0x1F, 0xC0, 0x03, 0xF0, 0xFE, 0x00, 0x3F, 0x87, 0xF0, + 0x01, 0xFC, 0x1F, 0xC0, 0x0F, 0xC0, 0xFE, 0x00, 0xFE, 0x03, 0xF0, 0x07, + 0xF0, 0x1F, 0x80, 0x3F, 0x00, 0xFE, 0x03, 0xF8, 0x03, 0xF0, 0x1F, 0xC0, + 0x1F, 0x80, 0xFC, 0x00, 0xFE, 0x07, 0xE0, 0x03, 0xF0, 0x7F, 0x00, 0x1F, + 0x83, 0xF0, 0x00, 0xFE, 0x1F, 0x80, 0x03, 0xF1, 0xF8, 0x00, 0x1F, 0x8F, + 0xC0, 0x00, 0xFC, 0x7E, 0x00, 0x03, 0xF3, 0xE0, 0x00, 0x1F, 0xBF, 0x00, + 0x00, 0xFD, 0xF8, 0x00, 0x03, 0xFF, 0x80, 0x00, 0x1F, 0xFC, 0x00, 0x00, + 0xFF, 0xE0, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0xFF, + 0x80, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0xFF, 0x00, 0x3F, 0x80, 0x1F, 0xFF, 0xE0, 0x07, 0xF0, 0x03, 0xFD, + 0xFC, 0x01, 0xFE, 0x00, 0x7F, 0x3F, 0x80, 0x3F, 0xE0, 0x0F, 0xE7, 0xF0, + 0x07, 0xFC, 0x01, 0xFC, 0x7F, 0x00, 0xFF, 0x80, 0x7F, 0x8F, 0xE0, 0x1F, + 0xF0, 0x0F, 0xE1, 0xFC, 0x07, 0xFF, 0x01, 0xFC, 0x3F, 0x80, 0xFB, 0xE0, + 0x3F, 0x83, 0xF0, 0x1F, 0x7C, 0x07, 0xE0, 0x7F, 0x03, 0xEF, 0x81, 0xFC, + 0x0F, 0xE0, 0x7D, 0xF0, 0x3F, 0x80, 0xFC, 0x1F, 0x9F, 0x07, 0xF0, 0x1F, + 0x83, 0xE3, 0xE0, 0xFC, 0x03, 0xF0, 0x7C, 0x7C, 0x1F, 0x80, 0x7F, 0x0F, + 0x8F, 0x87, 0xF0, 0x07, 0xE1, 0xF0, 0xF8, 0xFC, 0x00, 0xFC, 0x7E, 0x1F, + 0x1F, 0x80, 0x1F, 0x8F, 0x83, 0xE3, 0xF0, 0x01, 0xF9, 0xF0, 0x7C, 0x7E, + 0x00, 0x3F, 0x3E, 0x0F, 0x9F, 0x80, 0x07, 0xE7, 0xC0, 0xFB, 0xF0, 0x00, + 0xFD, 0xF0, 0x1F, 0x7E, 0x00, 0x0F, 0xBE, 0x03, 0xEF, 0xC0, 0x01, 0xFF, + 0xC0, 0x7D, 0xF0, 0x00, 0x3F, 0xF8, 0x0F, 0xFE, 0x00, 0x03, 0xFF, 0x00, + 0xFF, 0xC0, 0x00, 0x7F, 0xC0, 0x1F, 0xF0, 0x00, 0x0F, 0xF8, 0x03, 0xFE, + 0x00, 0x01, 0xFF, 0x00, 0x7F, 0xC0, 0x00, 0x1F, 0xE0, 0x07, 0xF8, 0x00, + 0x03, 0xFC, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x1F, 0xC0, 0x00, 0x07, + 0xE0, 0x03, 0xF8, 0x00, 0x7F, 0x80, 0x07, 0xF9, 0xFF, 0x00, 0x3F, 0xC3, + 0xFC, 0x00, 0xFF, 0x07, 0xF8, 0x07, 0xF8, 0x1F, 0xE0, 0x1F, 0xC0, 0x3F, + 0xC0, 0xFF, 0x00, 0xFF, 0x07, 0xF8, 0x01, 0xFE, 0x1F, 0xE0, 0x03, 0xF8, + 0xFF, 0x00, 0x0F, 0xF3, 0xF8, 0x00, 0x1F, 0xDF, 0xE0, 0x00, 0x3F, 0xFF, + 0x00, 0x00, 0xFF, 0xF8, 0x00, 0x01, 0xFF, 0xE0, 0x00, 0x07, 0xFF, 0x00, + 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0xFF, 0x80, 0x00, + 0x03, 0xFF, 0x00, 0x00, 0x1F, 0xFC, 0x00, 0x00, 0x7F, 0xF8, 0x00, 0x03, + 0xFF, 0xF0, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x7F, 0x7F, 0x80, 0x03, 0xF8, + 0xFF, 0x00, 0x1F, 0xE1, 0xFC, 0x00, 0x7F, 0x07, 0xF8, 0x03, 0xFC, 0x0F, + 0xF0, 0x1F, 0xE0, 0x3F, 0xC0, 0x7F, 0x80, 0x7F, 0x83, 0xFC, 0x01, 0xFE, + 0x0F, 0xF0, 0x03, 0xFC, 0x7F, 0x80, 0x0F, 0xFB, 0xFE, 0x00, 0x1F, 0xE0, + 0xFF, 0x00, 0x07, 0xFF, 0xF8, 0x00, 0x7F, 0x9F, 0xE0, 0x03, 0xFC, 0xFF, + 0x00, 0x3F, 0xC3, 0xFC, 0x01, 0xFE, 0x0F, 0xE0, 0x0F, 0xE0, 0x7F, 0x00, + 0xFF, 0x01, 0xFC, 0x07, 0xF0, 0x0F, 0xE0, 0x7F, 0x80, 0x3F, 0x83, 0xF8, + 0x01, 0xFC, 0x3F, 0xC0, 0x07, 0xF1, 0xFC, 0x00, 0x3F, 0x8F, 0xE0, 0x00, + 0xFE, 0xFE, 0x00, 0x07, 0xF7, 0xF0, 0x00, 0x1F, 0xFF, 0x00, 0x00, 0xFF, + 0xF8, 0x00, 0x03, 0xFF, 0x80, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x7F, 0xC0, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x0F, 0xE0, + 0x00, 0x00, 0x7F, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x1F, 0xC0, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, + 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, + 0x80, 0x00, 0x3F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x03, + 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x3F, 0xC0, 0x00, + 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x03, 0xFE, 0x00, + 0x00, 0xFF, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, + 0x00, 0x0F, 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFC, 0x3F, 0x87, 0xF0, 0xFE, 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, + 0xE1, 0xFC, 0x3F, 0x87, 0xF0, 0xFE, 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, + 0xFC, 0x3F, 0x87, 0xF0, 0xFE, 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, 0xFC, + 0x3F, 0x87, 0xF0, 0xFE, 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, 0xFC, 0x3F, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0xE0, 0x03, 0xC0, 0x07, 0x00, + 0x1C, 0x00, 0x78, 0x00, 0xE0, 0x03, 0x80, 0x0F, 0x00, 0x1C, 0x00, 0x70, + 0x01, 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x38, 0x00, 0x70, 0x01, 0xC0, 0x07, + 0x00, 0x0E, 0x00, 0x38, 0x00, 0xE0, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, + 0x78, 0x00, 0xE0, 0x03, 0x80, 0x0F, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xE0, + 0x03, 0x80, 0x0E, 0x00, 0x3C, 0x00, 0x70, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFE, 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, 0xFC, 0x3F, 0x87, 0xF0, + 0xFE, 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, 0xFC, 0x3F, 0x87, 0xF0, 0xFE, + 0x1F, 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, 0xFC, 0x3F, 0x87, 0xF0, 0xFE, 0x1F, + 0xC3, 0xF8, 0x7F, 0x0F, 0xE1, 0xFC, 0x3F, 0x87, 0xF0, 0xFE, 0x1F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xF0, + 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0x80, 0x03, 0xFE, 0x00, 0x0F, 0xFC, 0x00, + 0x7D, 0xF0, 0x01, 0xF7, 0xC0, 0x0F, 0xDF, 0x80, 0x3E, 0x3E, 0x00, 0xF8, + 0xFC, 0x07, 0xE1, 0xF0, 0x1F, 0x07, 0xC0, 0xFC, 0x1F, 0x83, 0xE0, 0x3E, + 0x0F, 0x80, 0xFC, 0x7E, 0x01, 0xF1, 0xF0, 0x07, 0xC7, 0xC0, 0x1F, 0xBE, + 0x00, 0x3E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x3E, 0x0F, 0x83, 0xC0, 0xF0, 0x38, 0x1E, + 0x01, 0xFF, 0x00, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, + 0x7F, 0xFF, 0xF8, 0x7F, 0xFF, 0xFC, 0x7F, 0x03, 0xFC, 0x7E, 0x01, 0xFC, + 0x00, 0x01, 0xFC, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xFC, 0x03, 0xFF, 0xFC, + 0x1F, 0xFF, 0xFC, 0x3F, 0xFF, 0xFC, 0x7F, 0xC1, 0xFC, 0xFF, 0x01, 0xFC, + 0xFE, 0x01, 0xFC, 0xFE, 0x03, 0xFC, 0xFE, 0x03, 0xFC, 0xFF, 0x07, 0xFC, + 0xFF, 0xFF, 0xFC, 0x7F, 0xFF, 0xFC, 0x7F, 0xFF, 0xFC, 0x3F, 0xFD, 0xFE, + 0x1F, 0xF0, 0xFF, 0x07, 0xE0, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x3F, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0x00, + 0x03, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x0F, + 0xC0, 0x3F, 0x9F, 0xF8, 0x1F, 0xDF, 0xFF, 0x0F, 0xFF, 0xFF, 0xC7, 0xFF, + 0xFF, 0xE3, 0xFF, 0xFF, 0xF9, 0xFF, 0x83, 0xFE, 0xFF, 0x80, 0xFF, 0x7F, + 0x80, 0x3F, 0xBF, 0xC0, 0x1F, 0xFF, 0xC0, 0x07, 0xFF, 0xE0, 0x03, 0xFF, + 0xF0, 0x01, 0xFF, 0xF8, 0x00, 0xFF, 0xFC, 0x00, 0x7F, 0xFE, 0x00, 0x3F, + 0xFF, 0x80, 0x3F, 0xFF, 0xC0, 0x1F, 0xDF, 0xF0, 0x1F, 0xEF, 0xFC, 0x1F, + 0xF7, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xF1, 0xFF, 0xFF, 0xF8, 0xFE, 0xFF, + 0xF8, 0x7F, 0x3F, 0xF0, 0x00, 0x07, 0xE0, 0x00, 0x00, 0xFF, 0x00, 0x07, + 0xFF, 0xC0, 0x3F, 0xFF, 0xC0, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xC7, 0xFF, + 0xFF, 0x9F, 0xF0, 0x7F, 0xBF, 0xC0, 0x7F, 0x7F, 0x00, 0x7F, 0xFC, 0x00, + 0x03, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, + 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0xFD, + 0xFE, 0x03, 0xFB, 0xFE, 0x0F, 0xF3, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0x87, + 0xFF, 0xFE, 0x07, 0xFF, 0xF8, 0x03, 0xFF, 0xE0, 0x01, 0xFE, 0x00, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, + 0x00, 0x03, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x3F, 0x80, 0x7E, 0x1F, 0xC0, 0xFF, 0xCF, 0xE1, 0xFF, 0xF7, + 0xF1, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFE, 0xFF, 0x83, + 0xFF, 0x7F, 0x80, 0xFF, 0xBF, 0x80, 0x3F, 0xFF, 0xC0, 0x1F, 0xFF, 0xC0, + 0x07, 0xFF, 0xE0, 0x03, 0xFF, 0xF0, 0x01, 0xFF, 0xF8, 0x00, 0xFF, 0xFC, + 0x00, 0x7F, 0xFE, 0x00, 0x3F, 0xFF, 0x80, 0x3F, 0xDF, 0xC0, 0x1F, 0xEF, + 0xF0, 0x1F, 0xF7, 0xFC, 0x1F, 0xF9, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, 0xFE, + 0x3F, 0xFF, 0xFF, 0x0F, 0xFF, 0xBF, 0x81, 0xFF, 0x9F, 0xC0, 0x3F, 0x00, + 0x00, 0x00, 0xFE, 0x00, 0x03, 0xFF, 0x80, 0x0F, 0xFF, 0xE0, 0x1F, 0xFF, + 0xF0, 0x3F, 0xFF, 0xF8, 0x3F, 0xC3, 0xF8, 0x7F, 0x80, 0xFC, 0x7F, 0x00, + 0xFC, 0x7F, 0x00, 0x7C, 0xFE, 0x00, 0x7E, 0xFE, 0x00, 0x7E, 0xFF, 0xFF, + 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0xFE, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x7F, 0x7F, 0x00, + 0xFE, 0x3F, 0xC1, 0xFE, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, 0xF8, 0x0F, 0xFF, + 0xF0, 0x03, 0xFF, 0xC0, 0x00, 0xFF, 0x00, 0x01, 0xFC, 0x1F, 0xF0, 0xFF, + 0xC3, 0xFF, 0x1F, 0xFC, 0x7F, 0x81, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, + 0x0F, 0xFF, 0xBF, 0xFE, 0xFF, 0xFB, 0xFF, 0xE1, 0xFC, 0x07, 0xF0, 0x1F, + 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, + 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, + 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x00, 0x00, 0xF8, 0x7F, 0x07, 0xFE, + 0x7F, 0x0F, 0xFF, 0x7F, 0x1F, 0xFF, 0x7F, 0x3F, 0xFF, 0xFF, 0x3F, 0xFF, + 0xFF, 0x7F, 0xC3, 0xFF, 0x7F, 0x81, 0xFF, 0x7F, 0x00, 0xFF, 0xFF, 0x00, + 0xFF, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, + 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0xFF, 0xFF, 0x00, + 0xFF, 0x7F, 0x81, 0xFF, 0x7F, 0xC3, 0xFF, 0x3F, 0xFF, 0xFF, 0x3F, 0xFF, + 0xFF, 0x1F, 0xFF, 0xFF, 0x0F, 0xFF, 0x7F, 0x07, 0xFE, 0x7F, 0x01, 0xF8, + 0x7F, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0x7F, 0x00, + 0xFF, 0x7F, 0x01, 0xFE, 0x7F, 0xC3, 0xFE, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, + 0xF8, 0x0F, 0xFF, 0xE0, 0x01, 0xFF, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, + 0x03, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, + 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x3F, 0x83, + 0xF8, 0xFF, 0xC7, 0xF7, 0xFF, 0xCF, 0xEF, 0xFF, 0xDF, 0xFF, 0xFF, 0xBF, + 0xFF, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0x01, 0xFF, 0xFE, 0x01, 0xFF, 0xF8, + 0x03, 0xFF, 0xF0, 0x07, 0xFF, 0xE0, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, + 0x3F, 0xFF, 0x00, 0x7F, 0xFE, 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x03, + 0xFF, 0xF0, 0x07, 0xFF, 0xE0, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x3F, + 0xFF, 0x00, 0x7F, 0xFE, 0x00, 0xFF, 0xFC, 0x01, 0xFC, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xC0, 0x00, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFC, 0x1F, 0xC7, 0xF1, 0xFC, 0x7F, 0x1F, 0xC7, 0xF0, 0x00, + 0x00, 0x00, 0x07, 0xF1, 0xFC, 0x7F, 0x1F, 0xC7, 0xF1, 0xFC, 0x7F, 0x1F, + 0xC7, 0xF1, 0xFC, 0x7F, 0x1F, 0xC7, 0xF1, 0xFC, 0x7F, 0x1F, 0xC7, 0xF1, + 0xFC, 0x7F, 0x1F, 0xC7, 0xF1, 0xFC, 0x7F, 0x1F, 0xC7, 0xF1, 0xFC, 0x7F, + 0x1F, 0xC7, 0xF1, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFB, 0xFE, 0xFE, 0x00, + 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x03, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, + 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x3F, 0x80, 0x00, 0x7F, 0x00, 0x00, 0xFE, + 0x00, 0x01, 0xFC, 0x03, 0xFB, 0xF8, 0x0F, 0xE7, 0xF0, 0x3F, 0xCF, 0xE0, + 0xFF, 0x1F, 0xC3, 0xFC, 0x3F, 0x87, 0xF0, 0x7F, 0x1F, 0xC0, 0xFE, 0x7F, + 0x01, 0xFD, 0xFC, 0x03, 0xFF, 0xF0, 0x07, 0xFF, 0xF0, 0x0F, 0xFF, 0xE0, + 0x1F, 0xFF, 0xE0, 0x3F, 0xFF, 0xE0, 0x7F, 0xDF, 0xC0, 0xFF, 0x3F, 0xC1, + 0xFC, 0x3F, 0x83, 0xF8, 0x3F, 0x87, 0xF0, 0x7F, 0x8F, 0xE0, 0x7F, 0x1F, + 0xC0, 0xFF, 0x3F, 0x80, 0xFE, 0x7F, 0x01, 0xFE, 0xFE, 0x01, 0xFD, 0xFC, + 0x03, 0xFC, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xFE, 0x1F, 0x80, 0x7E, + 0x0F, 0xE7, 0xFE, 0x1F, 0xF8, 0xFE, 0xFF, 0xF3, 0xFF, 0xCF, 0xFF, 0xFF, + 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0x83, 0xFF, 0x0F, 0xFF, 0xF0, 0x1F, 0xE0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, + 0xFF, 0xE0, 0x1F, 0xC0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, 0xFF, 0xE0, 0x1F, + 0xC0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, 0xFF, 0xE0, 0x1F, 0xC0, 0x7F, 0xFE, + 0x01, 0xFC, 0x07, 0xFF, 0xE0, 0x1F, 0xC0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, + 0xFF, 0xE0, 0x1F, 0xC0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, 0xFF, 0xE0, 0x1F, + 0xC0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, 0xFF, 0xE0, 0x1F, 0xC0, 0x7F, 0xFE, + 0x01, 0xFC, 0x07, 0xFF, 0xE0, 0x1F, 0xC0, 0x7F, 0xFE, 0x01, 0xFC, 0x07, + 0xF0, 0xFE, 0x1F, 0xC1, 0xFC, 0xFF, 0xE3, 0xFB, 0xFF, 0xE7, 0xFF, 0xFF, + 0xEF, 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0x80, 0xFF, + 0xFE, 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x03, 0xFF, 0xF0, 0x07, 0xFF, + 0xE0, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x3F, 0xFF, 0x00, 0x7F, 0xFE, + 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x03, 0xFF, 0xF0, 0x07, 0xFF, 0xE0, + 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x3F, 0xFF, 0x00, 0x7F, 0xFE, 0x00, + 0xFE, 0x00, 0x7F, 0x80, 0x01, 0xFF, 0xF0, 0x01, 0xFF, 0xFE, 0x01, 0xFF, + 0xFF, 0x81, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xF1, 0xFF, 0x07, 0xFC, 0xFF, + 0x01, 0xFE, 0x7F, 0x00, 0x7F, 0x7F, 0x80, 0x3F, 0xFF, 0x80, 0x0F, 0xFF, + 0xC0, 0x07, 0xFF, 0xE0, 0x03, 0xFF, 0xF0, 0x01, 0xFF, 0xF8, 0x00, 0xFF, + 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x7F, 0xBF, 0x80, 0x3F, 0x9F, 0xE0, 0x3F, + 0xCF, 0xF8, 0x3F, 0xE3, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xF0, 0x3F, 0xFF, + 0xF0, 0x0F, 0xFF, 0xF0, 0x03, 0xFF, 0xE0, 0x00, 0x3F, 0xC0, 0x00, 0xFE, + 0x1F, 0x80, 0x7F, 0x3F, 0xF0, 0x3F, 0xBF, 0xFE, 0x1F, 0xDF, 0xFF, 0x8F, + 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0xF3, 0xFF, 0x07, 0xFD, 0xFF, 0x01, 0xFE, + 0xFF, 0x00, 0x7F, 0x7F, 0x80, 0x3F, 0xFF, 0x80, 0x0F, 0xFF, 0xC0, 0x07, + 0xFF, 0xE0, 0x03, 0xFF, 0xF0, 0x01, 0xFF, 0xF8, 0x00, 0xFF, 0xFC, 0x00, + 0x7F, 0xFF, 0x00, 0x7F, 0xFF, 0x80, 0x3F, 0xBF, 0xE0, 0x3F, 0xDF, 0xF8, + 0x3F, 0xCF, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xE3, 0xFB, 0xFF, 0xE1, 0xFD, + 0xFF, 0xF0, 0xFE, 0x7F, 0xE0, 0x7F, 0x0F, 0xC0, 0x3F, 0x80, 0x00, 0x1F, + 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x1F, 0xC0, 0x00, 0x00, 0x00, 0xFC, 0x3F, 0x81, 0xFF, 0x9F, 0xC3, 0xFF, + 0xEF, 0xE1, 0xFF, 0xF7, 0xF1, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, 0xFD, 0xFF, + 0x07, 0xFE, 0xFF, 0x01, 0xFF, 0x7F, 0x00, 0x7F, 0xFF, 0x80, 0x3F, 0xFF, + 0x80, 0x0F, 0xFF, 0xC0, 0x07, 0xFF, 0xE0, 0x03, 0xFF, 0xF0, 0x01, 0xFF, + 0xF8, 0x00, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x7F, 0xBF, 0x80, 0x3F, + 0xDF, 0xE0, 0x3F, 0xEF, 0xF8, 0x3F, 0xF3, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, + 0xFC, 0x7F, 0xFE, 0xFE, 0x1F, 0xFF, 0x7F, 0x03, 0xFF, 0x3F, 0x80, 0x7E, + 0x1F, 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, 0x00, + 0x01, 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0x80, + 0x00, 0x1F, 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0xFE, 0x1F, 0xFC, + 0x7F, 0xFB, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x7F, 0x80, + 0xFF, 0x01, 0xFC, 0x03, 0xF8, 0x07, 0xF0, 0x0F, 0xE0, 0x1F, 0xC0, 0x3F, + 0x80, 0x7F, 0x00, 0xFE, 0x01, 0xFC, 0x03, 0xF8, 0x07, 0xF0, 0x0F, 0xE0, + 0x1F, 0xC0, 0x3F, 0x80, 0x7F, 0x00, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x07, + 0xFF, 0xE0, 0x0F, 0xFF, 0xF8, 0x1F, 0xFF, 0xFC, 0x3F, 0xFF, 0xFC, 0x7F, + 0x81, 0xFE, 0x7F, 0x00, 0xFE, 0x7F, 0x00, 0xFE, 0x7F, 0xC0, 0x00, 0x7F, + 0xFC, 0x00, 0x7F, 0xFF, 0x80, 0x3F, 0xFF, 0xF0, 0x1F, 0xFF, 0xFC, 0x07, + 0xFF, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x0F, 0xFF, 0x00, 0x01, 0xFF, 0x00, + 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0x7F, 0x00, 0x7F, 0x7F, 0x81, 0xFE, 0x7F, + 0xFF, 0xFE, 0x3F, 0xFF, 0xFC, 0x1F, 0xFF, 0xF8, 0x0F, 0xFF, 0xF0, 0x01, + 0xFF, 0x80, 0x3F, 0x83, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, + 0x8F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF3, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, + 0x83, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, + 0x83, 0xF8, 0x3F, 0x83, 0xF8, 0x3F, 0x83, 0xFF, 0x3F, 0xF1, 0xFF, 0x0F, + 0xF0, 0x7F, 0xFE, 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x03, 0xFF, 0xF0, + 0x07, 0xFF, 0xE0, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x3F, 0xFF, 0x00, + 0x7F, 0xFE, 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xF8, 0x03, 0xFF, 0xF0, 0x07, + 0xFF, 0xE0, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x3F, 0xFF, 0x00, 0x7F, + 0xFE, 0x00, 0xFF, 0xFC, 0x03, 0xFF, 0xFC, 0x07, 0xFF, 0xFC, 0x3F, 0xFF, + 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xDF, 0xFF, 0xBF, 0x9F, 0xFF, 0x7F, 0x1F, + 0xFC, 0xFE, 0x0F, 0xE0, 0x00, 0x7F, 0x00, 0x3F, 0xBF, 0x80, 0x1F, 0x9F, + 0xC0, 0x1F, 0xC7, 0xE0, 0x0F, 0xE3, 0xF8, 0x07, 0xE1, 0xFC, 0x07, 0xF0, + 0x7E, 0x03, 0xF8, 0x3F, 0x81, 0xF8, 0x1F, 0xC0, 0xFC, 0x07, 0xE0, 0xFE, + 0x03, 0xF8, 0x7E, 0x00, 0xFC, 0x3F, 0x00, 0x7E, 0x1F, 0x80, 0x3F, 0x1F, + 0x80, 0x0F, 0xCF, 0xC0, 0x07, 0xE7, 0xE0, 0x03, 0xF7, 0xE0, 0x00, 0xFF, + 0xF0, 0x00, 0x7F, 0xF8, 0x00, 0x3F, 0xF8, 0x00, 0x0F, 0xFC, 0x00, 0x07, + 0xFE, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0xFC, 0x03, 0xF8, 0x0F, 0xFF, 0xC0, 0x7F, 0x01, 0xFF, 0xF8, 0x0F, 0xE0, + 0x3F, 0x3F, 0x03, 0xFE, 0x07, 0xE7, 0xE0, 0x7F, 0xC1, 0xFC, 0xFE, 0x0F, + 0xF8, 0x3F, 0x9F, 0xC1, 0xFF, 0x07, 0xE1, 0xF8, 0x3D, 0xE0, 0xFC, 0x3F, + 0x0F, 0xBE, 0x3F, 0x87, 0xF1, 0xF7, 0xC7, 0xE0, 0x7E, 0x3E, 0xF8, 0xFC, + 0x0F, 0xC7, 0xDF, 0x1F, 0x81, 0xF9, 0xF1, 0xE3, 0xF0, 0x3F, 0x3E, 0x3E, + 0xFC, 0x03, 0xF7, 0xC7, 0xDF, 0x80, 0x7E, 0xF8, 0xFB, 0xF0, 0x0F, 0xDE, + 0x1F, 0x7C, 0x00, 0xFF, 0xC1, 0xFF, 0x80, 0x1F, 0xF8, 0x3F, 0xF0, 0x03, + 0xFF, 0x07, 0xFE, 0x00, 0x7F, 0xC0, 0xFF, 0x80, 0x07, 0xF8, 0x1F, 0xF0, + 0x00, 0xFF, 0x01, 0xFE, 0x00, 0x1F, 0xE0, 0x3F, 0x80, 0x01, 0xFC, 0x07, + 0xF0, 0x00, 0xFF, 0x00, 0xFF, 0x7F, 0x81, 0xFE, 0x3F, 0x81, 0xFC, 0x3F, + 0xC3, 0xFC, 0x1F, 0xC3, 0xF8, 0x0F, 0xE7, 0xF0, 0x0F, 0xEF, 0xF0, 0x07, + 0xFF, 0xE0, 0x03, 0xFF, 0xC0, 0x03, 0xFF, 0xC0, 0x01, 0xFF, 0x80, 0x00, + 0xFF, 0x00, 0x00, 0xFF, 0x00, 0x01, 0xFF, 0x00, 0x01, 0xFF, 0x80, 0x03, + 0xFF, 0xC0, 0x07, 0xFF, 0xC0, 0x07, 0xFF, 0xE0, 0x0F, 0xE7, 0xF0, 0x1F, + 0xE7, 0xF0, 0x1F, 0xC3, 0xF8, 0x3F, 0xC3, 0xFC, 0x7F, 0x81, 0xFC, 0x7F, + 0x01, 0xFE, 0xFF, 0x00, 0xFF, 0x7F, 0x00, 0x3F, 0xBF, 0x80, 0x1F, 0xDF, + 0xC0, 0x0F, 0xC7, 0xF0, 0x07, 0xE3, 0xF8, 0x07, 0xF1, 0xFC, 0x03, 0xF0, + 0x7F, 0x01, 0xF8, 0x3F, 0x81, 0xFC, 0x0F, 0xC0, 0xFC, 0x07, 0xF0, 0x7E, + 0x03, 0xF8, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0x7E, 0x1F, 0x80, 0x3F, 0x8F, + 0xC0, 0x0F, 0xCF, 0xC0, 0x07, 0xE7, 0xE0, 0x03, 0xFB, 0xF0, 0x00, 0xFD, + 0xF0, 0x00, 0x7F, 0xF8, 0x00, 0x3F, 0xFC, 0x00, 0x0F, 0xFC, 0x00, 0x07, + 0xFE, 0x00, 0x03, 0xFF, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, 0x80, 0x00, + 0x1F, 0xC0, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03, 0xF0, 0x00, + 0x03, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x1F, 0xF8, 0x00, 0x0F, 0xFC, 0x00, + 0x07, 0xFC, 0x00, 0x03, 0xFC, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x7F, 0xFF, + 0xFB, 0xFF, 0xFF, 0xDF, 0xFF, 0xFE, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xBF, + 0xFF, 0xFC, 0x00, 0x3F, 0xE0, 0x03, 0xFE, 0x00, 0x1F, 0xE0, 0x01, 0xFE, + 0x00, 0x1F, 0xE0, 0x01, 0xFE, 0x00, 0x1F, 0xE0, 0x01, 0xFE, 0x00, 0x1F, + 0xE0, 0x01, 0xFE, 0x00, 0x1F, 0xE0, 0x01, 0xFE, 0x00, 0x1F, 0xE0, 0x01, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xF8, 0x01, 0xF8, 0x1F, 0xC1, 0xFE, 0x0F, 0xF0, 0xFF, + 0x87, 0xE0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x00, + 0xF8, 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x3F, + 0x0F, 0xF0, 0x7F, 0x03, 0xF8, 0x1F, 0xE0, 0x1F, 0x80, 0x7C, 0x03, 0xE0, + 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, + 0xE0, 0x1F, 0x00, 0xF8, 0x07, 0xE0, 0x3F, 0xE0, 0xFF, 0x07, 0xF8, 0x1F, + 0xC0, 0x7E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFC, 0x07, 0xF0, 0x3F, 0xC1, 0xFE, 0x0F, 0xF8, 0x0F, 0xC0, 0x3E, 0x01, + 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x3E, + 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x80, 0x7F, 0x81, 0xFC, + 0x0F, 0xE0, 0xFF, 0x0F, 0xC0, 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x07, + 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0xF8, + 0x0F, 0xC3, 0xFE, 0x1F, 0xE0, 0xFF, 0x07, 0xF0, 0x3F, 0x00, 0x1F, 0x00, + 0x03, 0xFE, 0x00, 0x1F, 0xF8, 0x0F, 0xFF, 0xF0, 0xFF, 0x0F, 0xFF, 0xF0, + 0x1F, 0xF8, 0x00, 0x7F, 0x80, 0x00, 0xF8 }; + +const GFXglyph FreeSansBold24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 13, 0, 1 }, // 0x20 ' ' + { 0, 7, 34, 16, 5, -33 }, // 0x21 '!' + { 30, 18, 12, 22, 2, -33 }, // 0x22 '"' + { 57, 26, 33, 26, 0, -31 }, // 0x23 '#' + { 165, 25, 40, 26, 1, -34 }, // 0x24 '$' + { 290, 39, 34, 42, 1, -32 }, // 0x25 '%' + { 456, 30, 35, 34, 3, -33 }, // 0x26 '&' + { 588, 7, 12, 12, 3, -33 }, // 0x27 ''' + { 599, 13, 44, 16, 2, -33 }, // 0x28 '(' + { 671, 13, 44, 16, 1, -33 }, // 0x29 ')' + { 743, 15, 15, 18, 1, -33 }, // 0x2A '*' + { 772, 23, 22, 27, 2, -21 }, // 0x2B '+' + { 836, 7, 15, 12, 2, -6 }, // 0x2C ',' + { 850, 13, 6, 16, 1, -15 }, // 0x2D '-' + { 860, 7, 7, 12, 2, -6 }, // 0x2E '.' + { 867, 13, 34, 13, 0, -32 }, // 0x2F '/' + { 923, 24, 35, 26, 1, -33 }, // 0x30 '0' + { 1028, 14, 33, 26, 4, -32 }, // 0x31 '1' + { 1086, 23, 34, 26, 2, -33 }, // 0x32 '2' + { 1184, 23, 35, 26, 2, -33 }, // 0x33 '3' + { 1285, 22, 33, 26, 2, -32 }, // 0x34 '4' + { 1376, 23, 34, 26, 2, -32 }, // 0x35 '5' + { 1474, 23, 35, 26, 2, -33 }, // 0x36 '6' + { 1575, 23, 33, 26, 1, -32 }, // 0x37 '7' + { 1670, 24, 35, 26, 1, -33 }, // 0x38 '8' + { 1775, 24, 35, 26, 1, -33 }, // 0x39 '9' + { 1880, 7, 25, 12, 2, -24 }, // 0x3A ':' + { 1902, 7, 33, 12, 2, -24 }, // 0x3B ';' + { 1931, 23, 23, 27, 2, -22 }, // 0x3C '<' + { 1998, 23, 18, 27, 2, -19 }, // 0x3D '=' + { 2050, 23, 23, 27, 2, -22 }, // 0x3E '>' + { 2117, 24, 35, 29, 3, -34 }, // 0x3F '?' + { 2222, 43, 41, 46, 1, -34 }, // 0x40 '@' + { 2443, 32, 34, 33, 0, -33 }, // 0x41 'A' + { 2579, 27, 34, 33, 4, -33 }, // 0x42 'B' + { 2694, 30, 36, 34, 2, -34 }, // 0x43 'C' + { 2829, 28, 34, 34, 4, -33 }, // 0x44 'D' + { 2948, 25, 34, 31, 4, -33 }, // 0x45 'E' + { 3055, 24, 34, 30, 4, -33 }, // 0x46 'F' + { 3157, 31, 36, 36, 2, -34 }, // 0x47 'G' + { 3297, 27, 34, 35, 4, -33 }, // 0x48 'H' + { 3412, 7, 34, 15, 4, -33 }, // 0x49 'I' + { 3442, 22, 35, 27, 1, -33 }, // 0x4A 'J' + { 3539, 30, 34, 34, 4, -33 }, // 0x4B 'K' + { 3667, 23, 34, 29, 4, -33 }, // 0x4C 'L' + { 3765, 33, 34, 41, 4, -33 }, // 0x4D 'M' + { 3906, 28, 34, 35, 4, -33 }, // 0x4E 'N' + { 4025, 33, 36, 37, 2, -34 }, // 0x4F 'O' + { 4174, 26, 34, 32, 4, -33 }, // 0x50 'P' + { 4285, 33, 37, 37, 2, -34 }, // 0x51 'Q' + { 4438, 28, 34, 34, 4, -33 }, // 0x52 'R' + { 4557, 28, 36, 32, 2, -34 }, // 0x53 'S' + { 4683, 27, 34, 30, 2, -33 }, // 0x54 'T' + { 4798, 27, 35, 35, 4, -33 }, // 0x55 'U' + { 4917, 29, 34, 31, 1, -33 }, // 0x56 'V' + { 5041, 43, 34, 45, 1, -33 }, // 0x57 'W' + { 5224, 30, 34, 32, 1, -33 }, // 0x58 'X' + { 5352, 29, 34, 30, 1, -33 }, // 0x59 'Y' + { 5476, 26, 34, 29, 1, -33 }, // 0x5A 'Z' + { 5587, 11, 43, 16, 3, -33 }, // 0x5B '[' + { 5647, 14, 34, 13, -1, -32 }, // 0x5C '\' + { 5707, 11, 43, 16, 1, -33 }, // 0x5D ']' + { 5767, 22, 20, 27, 3, -32 }, // 0x5E '^' + { 5822, 28, 4, 26, -1, 6 }, // 0x5F '_' + { 5836, 9, 7, 12, 1, -35 }, // 0x60 '`' + { 5844, 24, 26, 27, 2, -24 }, // 0x61 'a' + { 5922, 25, 35, 29, 3, -33 }, // 0x62 'b' + { 6032, 23, 26, 26, 2, -24 }, // 0x63 'c' + { 6107, 25, 35, 29, 2, -33 }, // 0x64 'd' + { 6217, 24, 26, 27, 2, -24 }, // 0x65 'e' + { 6295, 14, 34, 16, 1, -33 }, // 0x66 'f' + { 6355, 24, 36, 29, 2, -24 }, // 0x67 'g' + { 6463, 23, 34, 28, 3, -33 }, // 0x68 'h' + { 6561, 7, 34, 13, 3, -33 }, // 0x69 'i' + { 6591, 10, 45, 13, 0, -33 }, // 0x6A 'j' + { 6648, 23, 34, 27, 3, -33 }, // 0x6B 'k' + { 6746, 7, 34, 13, 3, -33 }, // 0x6C 'l' + { 6776, 36, 25, 42, 3, -24 }, // 0x6D 'm' + { 6889, 23, 25, 29, 3, -24 }, // 0x6E 'n' + { 6961, 25, 26, 29, 2, -24 }, // 0x6F 'o' + { 7043, 25, 36, 29, 3, -24 }, // 0x70 'p' + { 7156, 25, 36, 29, 2, -24 }, // 0x71 'q' + { 7269, 15, 25, 18, 3, -24 }, // 0x72 'r' + { 7316, 24, 26, 26, 1, -24 }, // 0x73 's' + { 7394, 12, 32, 16, 2, -30 }, // 0x74 't' + { 7442, 23, 26, 29, 3, -24 }, // 0x75 'u' + { 7517, 25, 25, 25, 0, -24 }, // 0x76 'v' + { 7596, 35, 25, 37, 1, -24 }, // 0x77 'w' + { 7706, 24, 25, 26, 1, -24 }, // 0x78 'x' + { 7781, 25, 36, 26, 0, -24 }, // 0x79 'y' + { 7894, 21, 25, 24, 1, -24 }, // 0x7A 'z' + { 7960, 13, 43, 18, 2, -33 }, // 0x7B '{' + { 8030, 4, 44, 13, 5, -33 }, // 0x7C '|' + { 8052, 13, 43, 18, 3, -33 }, // 0x7D '}' + { 8122, 21, 8, 23, 1, -14 } }; // 0x7E '~' + +const GFXfont FreeSansBold24pt7b PROGMEM = { + (uint8_t *)FreeSansBold24pt7bBitmaps, + (GFXglyph *)FreeSansBold24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 8815 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBold9pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBold9pt7b.h new file mode 100644 index 0000000..aeea463 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBold9pt7b.h @@ -0,0 +1,208 @@ +const uint8_t FreeSansBold9pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFF, 0xFE, 0x48, 0x7E, 0xEF, 0xDF, 0xBF, 0x74, 0x40, 0x19, 0x86, + 0x67, 0xFD, 0xFF, 0x33, 0x0C, 0xC3, 0x33, 0xFE, 0xFF, 0x99, 0x86, 0x61, + 0x90, 0x10, 0x1F, 0x1F, 0xDE, 0xFF, 0x3F, 0x83, 0xC0, 0xFC, 0x1F, 0x09, + 0xFC, 0xFE, 0xF7, 0xF1, 0xE0, 0x40, 0x38, 0x10, 0x7C, 0x30, 0xC6, 0x20, + 0xC6, 0x40, 0xC6, 0x40, 0x7C, 0x80, 0x39, 0x9C, 0x01, 0x3E, 0x03, 0x63, + 0x02, 0x63, 0x04, 0x63, 0x0C, 0x3E, 0x08, 0x1C, 0x0E, 0x01, 0xF8, 0x3B, + 0x83, 0xB8, 0x3F, 0x01, 0xE0, 0x3E, 0x67, 0x76, 0xE3, 0xEE, 0x1C, 0xF3, + 0xC7, 0xFE, 0x3F, 0x70, 0xFF, 0xF4, 0x18, 0x63, 0x1C, 0x73, 0x8E, 0x38, + 0xE3, 0x8E, 0x18, 0x70, 0xC3, 0x06, 0x08, 0x61, 0x83, 0x0E, 0x38, 0x71, + 0xC7, 0x1C, 0x71, 0xC6, 0x38, 0xE3, 0x18, 0x40, 0x21, 0x3E, 0x45, 0x28, + 0x38, 0x70, 0xE7, 0xFF, 0xE7, 0x0E, 0x1C, 0xFC, 0x9C, 0xFF, 0xC0, 0xFC, + 0x08, 0xC4, 0x23, 0x10, 0x84, 0x62, 0x11, 0x88, 0x00, 0x3E, 0x3F, 0x9D, + 0xDC, 0x7E, 0x3F, 0x1F, 0x8F, 0xC7, 0xE3, 0xF1, 0xDD, 0xCF, 0xE3, 0xE0, + 0x08, 0xFF, 0xF3, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x80, 0x3E, 0x3F, 0xB8, + 0xFC, 0x70, 0x38, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x0F, 0xF7, 0xF8, + 0x3C, 0x7F, 0xE7, 0xE7, 0x07, 0x0C, 0x0E, 0x07, 0x07, 0xE7, 0xE7, 0x7E, + 0x3C, 0x0E, 0x1E, 0x1E, 0x2E, 0x2E, 0x4E, 0x4E, 0x8E, 0xFF, 0xFF, 0x0E, + 0x0E, 0x0E, 0x7F, 0x3F, 0x90, 0x18, 0x0D, 0xE7, 0xFB, 0x9E, 0x07, 0x03, + 0x81, 0xF1, 0xFF, 0xE7, 0xC0, 0x3E, 0x3F, 0x9C, 0xFC, 0x0E, 0xE7, 0xFB, + 0xDF, 0xC7, 0xE3, 0xF1, 0xDD, 0xEF, 0xE3, 0xE0, 0xFF, 0xFF, 0xC0, 0xE0, + 0xE0, 0x60, 0x70, 0x30, 0x38, 0x1C, 0x0C, 0x0E, 0x07, 0x03, 0x80, 0x3F, + 0x1F, 0xEE, 0x3F, 0x87, 0xE3, 0xCF, 0xC7, 0xFB, 0xCF, 0xE1, 0xF8, 0x7F, + 0x3D, 0xFE, 0x3F, 0x00, 0x3E, 0x3F, 0xBD, 0xDC, 0x7E, 0x3F, 0x1F, 0xDE, + 0xFF, 0x3B, 0x81, 0xF9, 0xCF, 0xE3, 0xC0, 0xFC, 0x00, 0x07, 0xE0, 0xFC, + 0x00, 0x07, 0xE5, 0xE0, 0x00, 0x83, 0xC7, 0xDF, 0x0C, 0x07, 0x80, 0xF8, + 0x1F, 0x01, 0x80, 0xFF, 0xFF, 0xC0, 0x00, 0x0F, 0xFF, 0xFC, 0x00, 0x70, + 0x3F, 0x03, 0xE0, 0x38, 0x7D, 0xF1, 0xE0, 0x80, 0x00, 0x3E, 0x3F, 0xB8, + 0xFC, 0x70, 0x38, 0x1C, 0x1C, 0x1C, 0x1C, 0x0E, 0x00, 0x03, 0x81, 0xC0, + 0x03, 0xF0, 0x0F, 0xFC, 0x1E, 0x0E, 0x38, 0x02, 0x70, 0xE9, 0x63, 0x19, + 0xC2, 0x19, 0xC6, 0x11, 0xC6, 0x33, 0xC6, 0x32, 0x63, 0xFE, 0x73, 0xDC, + 0x3C, 0x00, 0x1F, 0xF8, 0x07, 0xF0, 0x07, 0x00, 0xF0, 0x0F, 0x80, 0xF8, + 0x1D, 0x81, 0x9C, 0x19, 0xC3, 0x8C, 0x3F, 0xE7, 0xFE, 0x70, 0x66, 0x07, + 0xE0, 0x70, 0xFF, 0x9F, 0xFB, 0x83, 0xF0, 0x7E, 0x0F, 0xFF, 0x3F, 0xF7, + 0x06, 0xE0, 0xFC, 0x1F, 0x83, 0xFF, 0xEF, 0xF8, 0x1F, 0x83, 0xFE, 0x78, + 0xE7, 0x07, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x07, 0x07, 0x78, + 0xF3, 0xFE, 0x1F, 0x80, 0xFF, 0x8F, 0xFC, 0xE0, 0xEE, 0x0E, 0xE0, 0x7E, + 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0x7E, 0x0E, 0xE0, 0xEF, 0xFC, 0xFF, 0x80, + 0xFF, 0xFF, 0xF8, 0x1C, 0x0E, 0x07, 0xFB, 0xFD, 0xC0, 0xE0, 0x70, 0x38, + 0x1F, 0xFF, 0xF8, 0xFF, 0xFF, 0xF8, 0x1C, 0x0E, 0x07, 0xFB, 0xFD, 0xC0, + 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x00, 0x0F, 0x87, 0xF9, 0xE3, 0xB8, 0x3E, + 0x01, 0xC0, 0x38, 0xFF, 0x1F, 0xE0, 0x6E, 0x0D, 0xE3, 0x9F, 0xD0, 0xF2, + 0xE0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xFF, 0xFF, 0xFF, 0x07, 0xE0, + 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0E, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x07, + 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0x07, 0xE7, 0xE7, 0xE7, 0x7E, 0x3C, + 0xE0, 0xEE, 0x1C, 0xE3, 0x8E, 0x70, 0xEE, 0x0F, 0xC0, 0xFE, 0x0F, 0x70, + 0xE7, 0x0E, 0x38, 0xE1, 0xCE, 0x0E, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, + 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0xFF, 0xFF, 0xF8, 0x7F, 0xE1, + 0xFF, 0x87, 0xFE, 0x1F, 0xEC, 0x7F, 0xB3, 0x7E, 0xCD, 0xFB, 0x37, 0xEC, + 0xDF, 0x9E, 0x7E, 0x79, 0xF9, 0xE7, 0xE7, 0x9C, 0xE0, 0xFE, 0x1F, 0xC3, + 0xFC, 0x7F, 0xCF, 0xD9, 0xFB, 0xBF, 0x37, 0xE7, 0xFC, 0x7F, 0x87, 0xF0, + 0xFE, 0x0E, 0x0F, 0x81, 0xFF, 0x1E, 0x3C, 0xE0, 0xEE, 0x03, 0xF0, 0x1F, + 0x80, 0xFC, 0x07, 0xE0, 0x3B, 0x83, 0x9E, 0x3C, 0x7F, 0xC0, 0xF8, 0x00, + 0xFF, 0x9F, 0xFB, 0x87, 0xF0, 0x7E, 0x0F, 0xC3, 0xFF, 0xF7, 0xFC, 0xE0, + 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x00, 0x0F, 0x81, 0xFF, 0x1E, 0x3C, 0xE0, + 0xEE, 0x03, 0xF0, 0x1F, 0x80, 0xFC, 0x07, 0xE1, 0xBB, 0x8F, 0x9E, 0x3C, + 0x7F, 0xE0, 0xFB, 0x80, 0x08, 0xFF, 0x8F, 0xFC, 0xE0, 0xEE, 0x0E, 0xE0, + 0xEE, 0x0E, 0xFF, 0xCF, 0xFC, 0xE0, 0xEE, 0x0E, 0xE0, 0xEE, 0x0E, 0xE0, + 0xF0, 0x3F, 0x0F, 0xFB, 0xC7, 0xF0, 0x7E, 0x01, 0xFC, 0x1F, 0xF0, 0x3F, + 0x00, 0xFC, 0x1D, 0xC7, 0xBF, 0xE1, 0xF8, 0xFF, 0xFF, 0xC7, 0x03, 0x81, + 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0xFC, + 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x07, 0xE0, 0xFC, 0x1F, + 0xC7, 0xBF, 0xE1, 0xF0, 0x60, 0x67, 0x0E, 0x70, 0xE3, 0x0C, 0x30, 0xC3, + 0x9C, 0x19, 0x81, 0x98, 0x1F, 0x80, 0xF0, 0x0F, 0x00, 0xF0, 0x06, 0x00, + 0x61, 0xC3, 0xB8, 0xE1, 0x9C, 0x70, 0xCE, 0x3C, 0xE3, 0x36, 0x71, 0x9B, + 0x30, 0xED, 0x98, 0x36, 0x7C, 0x1B, 0x3C, 0x0F, 0x1E, 0x07, 0x8F, 0x01, + 0xC3, 0x80, 0xE1, 0x80, 0x70, 0xE7, 0x8E, 0x39, 0xC1, 0xF8, 0x1F, 0x80, + 0xF0, 0x07, 0x00, 0xF0, 0x1F, 0x81, 0x9C, 0x39, 0xC7, 0x0E, 0x70, 0xE0, + 0xE0, 0xFC, 0x39, 0xC7, 0x18, 0xC3, 0xB8, 0x36, 0x07, 0xC0, 0x70, 0x0E, + 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0xFF, 0xFF, 0xC0, 0xE0, 0xE0, 0xF0, + 0x70, 0x70, 0x70, 0x78, 0x38, 0x38, 0x1F, 0xFF, 0xF8, 0xFF, 0xEE, 0xEE, + 0xEE, 0xEE, 0xEE, 0xEE, 0xEF, 0xF0, 0x86, 0x10, 0x86, 0x10, 0x84, 0x30, + 0x84, 0x30, 0x80, 0xFF, 0x77, 0x77, 0x77, 0x77, 0x77, 0x77, 0x7F, 0xF0, + 0x18, 0x1C, 0x3C, 0x3E, 0x36, 0x66, 0x63, 0xC3, 0xFF, 0xC0, 0xCC, 0x3F, + 0x1F, 0xEE, 0x38, 0x0E, 0x3F, 0x9E, 0xEE, 0x3B, 0x9E, 0xFF, 0x9E, 0xE0, + 0xE0, 0x38, 0x0E, 0x03, 0xBC, 0xFF, 0xBC, 0xEE, 0x1F, 0x87, 0xE1, 0xF8, + 0x7F, 0x3B, 0xFE, 0xEF, 0x00, 0x1F, 0x3F, 0xDC, 0x7C, 0x0E, 0x07, 0x03, + 0x80, 0xE3, 0x7F, 0x8F, 0x00, 0x03, 0x81, 0xC0, 0xE7, 0x77, 0xFB, 0xBF, + 0x8F, 0xC7, 0xE3, 0xF1, 0xFD, 0xEF, 0xF3, 0xB8, 0x3E, 0x3F, 0x9C, 0xDC, + 0x3F, 0xFF, 0xFF, 0x81, 0xC3, 0x7F, 0x8F, 0x00, 0x3B, 0xDD, 0xFF, 0xB9, + 0xCE, 0x73, 0x9C, 0xE7, 0x00, 0x3B, 0xBF, 0xDD, 0xFC, 0x7E, 0x3F, 0x1F, + 0x8F, 0xEF, 0x7F, 0x9D, 0xC0, 0xFC, 0x77, 0xF1, 0xF0, 0xE0, 0x70, 0x38, + 0x1D, 0xEF, 0xFF, 0x9F, 0x8F, 0xC7, 0xE3, 0xF1, 0xF8, 0xFC, 0x7E, 0x38, + 0xFC, 0x7F, 0xFF, 0xFF, 0xFE, 0x77, 0x07, 0x77, 0x77, 0x77, 0x77, 0x77, + 0x7F, 0xE0, 0xE0, 0x70, 0x38, 0x1C, 0x7E, 0x77, 0x73, 0xF1, 0xF8, 0xFE, + 0x77, 0x39, 0xDC, 0x6E, 0x38, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0xEF, 0x7B, + 0xFF, 0xFE, 0x39, 0xF8, 0xE7, 0xE3, 0x9F, 0x8E, 0x7E, 0x39, 0xF8, 0xE7, + 0xE3, 0x9F, 0x8E, 0x70, 0xEF, 0x7F, 0xF8, 0xFC, 0x7E, 0x3F, 0x1F, 0x8F, + 0xC7, 0xE3, 0xF1, 0xC0, 0x1E, 0x1F, 0xE7, 0x3B, 0x87, 0xE1, 0xF8, 0x7E, + 0x1D, 0xCE, 0x7F, 0x87, 0x80, 0xEF, 0x3F, 0xEF, 0x3B, 0x87, 0xE1, 0xF8, + 0x7E, 0x1F, 0xCE, 0xFF, 0xBB, 0xCE, 0x03, 0x80, 0xE0, 0x38, 0x00, 0x3B, + 0xBF, 0xFD, 0xFC, 0x7E, 0x3F, 0x1F, 0x8F, 0xEF, 0x7F, 0x9D, 0xC0, 0xE0, + 0x70, 0x38, 0x1C, 0xEF, 0xFF, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x80, 0x3E, + 0x3F, 0xB8, 0xFC, 0x0F, 0xC3, 0xFC, 0x3F, 0xC7, 0xFF, 0x1F, 0x00, 0x73, + 0xBF, 0xF7, 0x39, 0xCE, 0x73, 0x9E, 0x70, 0xE3, 0xF1, 0xF8, 0xFC, 0x7E, + 0x3F, 0x1F, 0x8F, 0xC7, 0xFF, 0xBD, 0xC0, 0xE1, 0x98, 0x67, 0x39, 0xCC, + 0x33, 0x0D, 0xC3, 0xE0, 0x78, 0x1E, 0x07, 0x00, 0xE3, 0x1D, 0x9E, 0x66, + 0x79, 0x99, 0xE6, 0x77, 0xB8, 0xD2, 0xC3, 0xCF, 0x0F, 0x3C, 0x3C, 0xF0, + 0x73, 0x80, 0x73, 0x9C, 0xE3, 0xF0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0xFC, + 0x73, 0x9C, 0xE0, 0xE1, 0xD8, 0x67, 0x39, 0xCE, 0x33, 0x0E, 0xC3, 0xE0, + 0x78, 0x1E, 0x03, 0x00, 0xC0, 0x70, 0x38, 0x0E, 0x00, 0xFE, 0xFE, 0x0E, + 0x1C, 0x38, 0x38, 0x70, 0xE0, 0xFF, 0xFF, 0x37, 0x66, 0x66, 0x6E, 0xE6, + 0x66, 0x66, 0x67, 0x30, 0xFF, 0xFF, 0x80, 0xCE, 0x66, 0x66, 0x67, 0x76, + 0x66, 0x66, 0x6E, 0xC0, 0x71, 0x8E }; + +const GFXglyph FreeSansBold9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 3, 13, 6, 2, -12 }, // 0x21 '!' + { 5, 7, 5, 9, 1, -12 }, // 0x22 '"' + { 10, 10, 12, 10, 0, -11 }, // 0x23 '#' + { 25, 9, 15, 10, 1, -13 }, // 0x24 '$' + { 42, 16, 13, 16, 0, -12 }, // 0x25 '%' + { 68, 12, 13, 13, 1, -12 }, // 0x26 '&' + { 88, 3, 5, 5, 1, -12 }, // 0x27 ''' + { 90, 6, 17, 6, 1, -12 }, // 0x28 '(' + { 103, 6, 17, 6, 0, -12 }, // 0x29 ')' + { 116, 5, 6, 7, 1, -12 }, // 0x2A '*' + { 120, 7, 8, 11, 2, -7 }, // 0x2B '+' + { 127, 3, 5, 4, 1, -1 }, // 0x2C ',' + { 129, 5, 2, 6, 0, -5 }, // 0x2D '-' + { 131, 3, 2, 4, 1, -1 }, // 0x2E '.' + { 132, 5, 13, 5, 0, -12 }, // 0x2F '/' + { 141, 9, 13, 10, 1, -12 }, // 0x30 '0' + { 156, 5, 13, 10, 2, -12 }, // 0x31 '1' + { 165, 9, 13, 10, 1, -12 }, // 0x32 '2' + { 180, 8, 13, 10, 1, -12 }, // 0x33 '3' + { 193, 8, 13, 10, 2, -12 }, // 0x34 '4' + { 206, 9, 13, 10, 1, -12 }, // 0x35 '5' + { 221, 9, 13, 10, 1, -12 }, // 0x36 '6' + { 236, 9, 13, 10, 0, -12 }, // 0x37 '7' + { 251, 10, 13, 10, 0, -12 }, // 0x38 '8' + { 268, 9, 13, 10, 1, -12 }, // 0x39 '9' + { 283, 3, 9, 4, 1, -8 }, // 0x3A ':' + { 287, 3, 12, 4, 1, -8 }, // 0x3B ';' + { 292, 9, 9, 11, 1, -8 }, // 0x3C '<' + { 303, 9, 6, 11, 1, -6 }, // 0x3D '=' + { 310, 9, 9, 11, 1, -8 }, // 0x3E '>' + { 321, 9, 13, 11, 1, -12 }, // 0x3F '?' + { 336, 16, 15, 18, 0, -12 }, // 0x40 '@' + { 366, 12, 13, 13, 0, -12 }, // 0x41 'A' + { 386, 11, 13, 13, 1, -12 }, // 0x42 'B' + { 404, 12, 13, 13, 1, -12 }, // 0x43 'C' + { 424, 12, 13, 13, 1, -12 }, // 0x44 'D' + { 444, 9, 13, 12, 1, -12 }, // 0x45 'E' + { 459, 9, 13, 11, 1, -12 }, // 0x46 'F' + { 474, 11, 13, 14, 1, -12 }, // 0x47 'G' + { 492, 11, 13, 13, 1, -12 }, // 0x48 'H' + { 510, 3, 13, 6, 1, -12 }, // 0x49 'I' + { 515, 8, 13, 10, 1, -12 }, // 0x4A 'J' + { 528, 12, 13, 13, 1, -12 }, // 0x4B 'K' + { 548, 8, 13, 11, 1, -12 }, // 0x4C 'L' + { 561, 14, 13, 16, 1, -12 }, // 0x4D 'M' + { 584, 11, 13, 14, 1, -12 }, // 0x4E 'N' + { 602, 13, 13, 14, 1, -12 }, // 0x4F 'O' + { 624, 11, 13, 12, 1, -12 }, // 0x50 'P' + { 642, 13, 14, 14, 1, -12 }, // 0x51 'Q' + { 665, 12, 13, 13, 1, -12 }, // 0x52 'R' + { 685, 11, 13, 12, 1, -12 }, // 0x53 'S' + { 703, 9, 13, 12, 2, -12 }, // 0x54 'T' + { 718, 11, 13, 13, 1, -12 }, // 0x55 'U' + { 736, 12, 13, 12, 0, -12 }, // 0x56 'V' + { 756, 17, 13, 17, 0, -12 }, // 0x57 'W' + { 784, 12, 13, 12, 0, -12 }, // 0x58 'X' + { 804, 11, 13, 12, 1, -12 }, // 0x59 'Y' + { 822, 9, 13, 11, 1, -12 }, // 0x5A 'Z' + { 837, 4, 17, 6, 1, -12 }, // 0x5B '[' + { 846, 5, 13, 5, 0, -12 }, // 0x5C '\' + { 855, 4, 17, 6, 0, -12 }, // 0x5D ']' + { 864, 8, 8, 11, 1, -12 }, // 0x5E '^' + { 872, 10, 1, 10, 0, 4 }, // 0x5F '_' + { 874, 3, 2, 5, 0, -12 }, // 0x60 '`' + { 875, 10, 10, 10, 1, -9 }, // 0x61 'a' + { 888, 10, 13, 11, 1, -12 }, // 0x62 'b' + { 905, 9, 10, 10, 1, -9 }, // 0x63 'c' + { 917, 9, 13, 11, 1, -12 }, // 0x64 'd' + { 932, 9, 10, 10, 1, -9 }, // 0x65 'e' + { 944, 5, 13, 6, 1, -12 }, // 0x66 'f' + { 953, 9, 14, 11, 1, -9 }, // 0x67 'g' + { 969, 9, 13, 11, 1, -12 }, // 0x68 'h' + { 984, 3, 13, 5, 1, -12 }, // 0x69 'i' + { 989, 4, 17, 5, 0, -12 }, // 0x6A 'j' + { 998, 9, 13, 10, 1, -12 }, // 0x6B 'k' + { 1013, 3, 13, 5, 1, -12 }, // 0x6C 'l' + { 1018, 14, 10, 16, 1, -9 }, // 0x6D 'm' + { 1036, 9, 10, 11, 1, -9 }, // 0x6E 'n' + { 1048, 10, 10, 11, 1, -9 }, // 0x6F 'o' + { 1061, 10, 14, 11, 1, -9 }, // 0x70 'p' + { 1079, 9, 14, 11, 1, -9 }, // 0x71 'q' + { 1095, 6, 10, 7, 1, -9 }, // 0x72 'r' + { 1103, 9, 10, 10, 1, -9 }, // 0x73 's' + { 1115, 5, 12, 6, 1, -11 }, // 0x74 't' + { 1123, 9, 10, 11, 1, -9 }, // 0x75 'u' + { 1135, 10, 10, 10, 0, -9 }, // 0x76 'v' + { 1148, 14, 10, 14, 0, -9 }, // 0x77 'w' + { 1166, 10, 10, 10, 0, -9 }, // 0x78 'x' + { 1179, 10, 14, 10, 0, -9 }, // 0x79 'y' + { 1197, 8, 10, 9, 1, -9 }, // 0x7A 'z' + { 1207, 4, 17, 7, 1, -12 }, // 0x7B '{' + { 1216, 1, 17, 5, 2, -12 }, // 0x7C '|' + { 1219, 4, 17, 7, 2, -12 }, // 0x7D '}' + { 1228, 8, 2, 9, 0, -4 } }; // 0x7E '~' + +const GFXfont FreeSansBold9pt7b PROGMEM = { + (uint8_t *)FreeSansBold9pt7bBitmaps, + (GFXglyph *)FreeSansBold9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 1902 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique12pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique12pt7b.h new file mode 100644 index 0000000..fabbad3 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique12pt7b.h @@ -0,0 +1,317 @@ +const uint8_t FreeSansBoldOblique12pt7bBitmaps[] PROGMEM = { + 0x1C, 0x3C, 0x78, 0xE1, 0xC3, 0x8F, 0x1C, 0x38, 0x70, 0xC1, 0x83, 0x00, + 0x1C, 0x78, 0xF0, 0x71, 0xFC, 0xFE, 0x3B, 0x8E, 0xC3, 0x30, 0xC0, 0x01, + 0x8C, 0x07, 0x38, 0x0C, 0x61, 0xFF, 0xF3, 0xFF, 0xE7, 0xFF, 0x83, 0x9C, + 0x0E, 0x70, 0x1C, 0xE1, 0xFF, 0xF3, 0xFF, 0xC7, 0xFF, 0x83, 0x18, 0x0E, + 0x70, 0x18, 0xC0, 0x73, 0x80, 0x00, 0x40, 0x07, 0xF0, 0x3F, 0xF0, 0xFF, + 0xF3, 0xC9, 0xE7, 0xB3, 0xCF, 0x60, 0x1F, 0xC0, 0x3F, 0xC0, 0x3F, 0xE0, + 0x1F, 0xE0, 0x1B, 0xE0, 0x33, 0xDE, 0x47, 0xBC, 0x8F, 0x7F, 0x7C, 0x7F, + 0xF0, 0x7F, 0x80, 0x18, 0x00, 0x20, 0x00, 0xC0, 0x00, 0x00, 0x01, 0x87, + 0x80, 0xC3, 0xF0, 0x61, 0xFE, 0x10, 0xE1, 0x8C, 0x30, 0x66, 0x0C, 0x3B, + 0x03, 0xFC, 0x80, 0x7E, 0x60, 0x0F, 0x30, 0x00, 0x18, 0x70, 0x0C, 0x7E, + 0x03, 0x1F, 0xC1, 0x8E, 0x30, 0xC3, 0x1C, 0x60, 0xFE, 0x18, 0x1F, 0x8C, + 0x07, 0x80, 0x01, 0xE0, 0x07, 0xF0, 0x1F, 0xE0, 0x79, 0xC0, 0xF3, 0x81, + 0xEE, 0x01, 0xF8, 0x01, 0xE0, 0x1F, 0xC6, 0x7B, 0xDD, 0xE3, 0xF7, 0x87, + 0xEF, 0x07, 0x9F, 0x1F, 0x3F, 0xFF, 0x3F, 0xDE, 0x3F, 0x1C, 0x7F, 0xEE, + 0xCC, 0x03, 0x83, 0x81, 0x81, 0xC1, 0xC0, 0xE0, 0xE0, 0x70, 0x70, 0x38, + 0x3C, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x18, 0x0E, 0x07, + 0x01, 0x80, 0x06, 0x03, 0x81, 0xC0, 0x60, 0x38, 0x1C, 0x0E, 0x07, 0x03, + 0x81, 0xC0, 0xE0, 0xE0, 0x70, 0x38, 0x38, 0x1C, 0x1C, 0x0E, 0x0E, 0x06, + 0x07, 0x07, 0x00, 0x0C, 0x0C, 0x4F, 0xFF, 0x1C, 0x3C, 0x6C, 0x44, 0x03, + 0x80, 0x38, 0x07, 0x00, 0x70, 0x7F, 0xFF, 0xFF, 0xFF, 0xF0, 0xE0, 0x0E, + 0x00, 0xE0, 0x0C, 0x00, 0x7B, 0xDC, 0x23, 0x33, 0x00, 0x7F, 0xFF, 0xF0, + 0x7F, 0xE0, 0x00, 0xC0, 0x30, 0x18, 0x04, 0x03, 0x00, 0x80, 0x60, 0x10, + 0x0C, 0x02, 0x01, 0x80, 0x40, 0x30, 0x08, 0x06, 0x01, 0x00, 0xC0, 0x00, + 0x03, 0xC0, 0x7F, 0x87, 0xFC, 0x78, 0xF3, 0xC7, 0xBC, 0x3D, 0xE1, 0xEF, + 0x0F, 0xF0, 0x7F, 0x87, 0xBC, 0x3D, 0xE1, 0xEF, 0x1E, 0x78, 0xF3, 0xFF, + 0x0F, 0xF0, 0x3E, 0x00, 0x03, 0x83, 0x83, 0xCF, 0xEF, 0xF0, 0x78, 0x38, + 0x1C, 0x0E, 0x0F, 0x07, 0x03, 0x81, 0xC1, 0xE0, 0xF0, 0x70, 0x38, 0x00, + 0x03, 0xF0, 0x0F, 0xF8, 0x7F, 0xF8, 0xF1, 0xF3, 0xC1, 0xE7, 0x83, 0xC0, + 0x07, 0x80, 0x1E, 0x00, 0x78, 0x03, 0xE0, 0x0F, 0x00, 0x7C, 0x01, 0xE0, + 0x07, 0x00, 0x1F, 0xFC, 0x3F, 0xF8, 0xFF, 0xF0, 0x07, 0xE0, 0xFF, 0x8F, + 0xFE, 0xF8, 0xF7, 0x87, 0x80, 0x78, 0x0F, 0x80, 0xFC, 0x07, 0xE0, 0x0F, + 0x80, 0x3C, 0x01, 0xEF, 0x0F, 0x78, 0xF3, 0xFF, 0x8F, 0xF8, 0x3F, 0x00, + 0x00, 0x78, 0x07, 0xC0, 0x7E, 0x03, 0xF0, 0x37, 0x03, 0x38, 0x31, 0xC3, + 0x9E, 0x38, 0xF1, 0x87, 0x1F, 0xFE, 0xFF, 0xF7, 0xFF, 0x80, 0xF0, 0x07, + 0x00, 0x38, 0x03, 0xC0, 0x07, 0xFC, 0x1F, 0xF0, 0xFF, 0xC3, 0x00, 0x1C, + 0x00, 0x7F, 0x81, 0xFF, 0x0F, 0xFE, 0x38, 0xF8, 0x01, 0xE0, 0x07, 0x80, + 0x1E, 0xF0, 0xF3, 0xC7, 0xCF, 0xFE, 0x1F, 0xF0, 0x3F, 0x00, 0x03, 0xE0, + 0x7F, 0x87, 0xFE, 0x78, 0xF3, 0xC0, 0x3D, 0xE1, 0xFF, 0x8F, 0xFE, 0xF8, + 0xF7, 0xC7, 0xBC, 0x3D, 0xE1, 0xEF, 0x1E, 0x7C, 0xF3, 0xFF, 0x0F, 0xF0, + 0x1F, 0x00, 0x7F, 0xFB, 0xFF, 0xDF, 0xFE, 0x00, 0xE0, 0x0E, 0x00, 0xE0, + 0x0E, 0x00, 0xE0, 0x0F, 0x00, 0x70, 0x07, 0x00, 0x78, 0x03, 0x80, 0x3C, + 0x01, 0xC0, 0x0E, 0x00, 0xF0, 0x00, 0x03, 0xF0, 0x1F, 0xE0, 0xFF, 0xC7, + 0x8F, 0x1C, 0x3C, 0x71, 0xE0, 0xFF, 0x03, 0xF8, 0x3F, 0xF1, 0xF1, 0xE7, + 0x87, 0xBC, 0x1E, 0xF0, 0x7B, 0xE3, 0xCF, 0xFF, 0x1F, 0xF8, 0x1F, 0x80, + 0x03, 0xE0, 0x3F, 0xE1, 0xFF, 0x8F, 0x9F, 0x3C, 0x3D, 0xE0, 0xF7, 0x83, + 0xDE, 0x1F, 0x78, 0xFD, 0xFF, 0xE3, 0xFF, 0x87, 0xDE, 0x00, 0xF3, 0xC7, + 0x8F, 0xFE, 0x1F, 0xF0, 0x3F, 0x00, 0x1C, 0xF3, 0x80, 0x00, 0x00, 0x00, + 0x01, 0xCF, 0x38, 0x0E, 0x3C, 0x70, 0x00, 0x00, 0x00, 0x00, 0x00, 0xF1, + 0xE3, 0x81, 0x06, 0x18, 0x60, 0x00, 0x00, 0x01, 0xC0, 0x7E, 0x1F, 0xE7, + 0xF8, 0x7E, 0x03, 0xE0, 0x1F, 0xE0, 0x3F, 0xC0, 0x7F, 0x00, 0x78, 0x00, + 0xC0, 0x3F, 0xFC, 0xFF, 0xF3, 0xFF, 0x80, 0x00, 0x00, 0x00, 0x00, 0x07, + 0xFF, 0x9F, 0xFC, 0x7F, 0xF0, 0x30, 0x01, 0xE0, 0x0F, 0xE0, 0x3F, 0xC0, + 0x7F, 0x80, 0x7C, 0x07, 0xE1, 0xFE, 0x7F, 0x87, 0xE0, 0x38, 0x00, 0x00, + 0x00, 0x0F, 0xC1, 0xFF, 0x8F, 0xFC, 0xF1, 0xFF, 0x07, 0xF0, 0x3C, 0x01, + 0xE0, 0x1E, 0x01, 0xE0, 0x3E, 0x03, 0xE0, 0x1C, 0x01, 0xC0, 0x0E, 0x00, + 0x00, 0x07, 0x80, 0x3C, 0x01, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x03, 0xFF, + 0x80, 0x3C, 0x0F, 0x01, 0xC0, 0x0E, 0x0E, 0x00, 0x1C, 0x70, 0xF7, 0x73, + 0x87, 0xF8, 0xCC, 0x31, 0xE3, 0x61, 0x87, 0x0D, 0x8C, 0x1C, 0x3C, 0x30, + 0x61, 0xB1, 0x81, 0x86, 0xC6, 0x0C, 0x3B, 0x18, 0x71, 0xCC, 0x63, 0xCE, + 0x31, 0xFB, 0xF0, 0xE3, 0xCF, 0x01, 0xC0, 0x00, 0x03, 0xC0, 0xC0, 0x07, + 0xFF, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x3F, 0x00, 0x1F, 0x80, + 0x1F, 0xC0, 0x0F, 0xE0, 0x0F, 0xF0, 0x07, 0x7C, 0x07, 0x1E, 0x03, 0x8F, + 0x03, 0x87, 0x83, 0xC3, 0xC1, 0xFF, 0xE1, 0xFF, 0xF0, 0xFF, 0xFC, 0xF0, + 0x1E, 0x70, 0x0F, 0x78, 0x07, 0xB8, 0x03, 0xC0, 0x0F, 0xFE, 0x0F, 0xFF, + 0x87, 0xFF, 0xE3, 0xC0, 0xF1, 0xC0, 0x78, 0xE0, 0x3C, 0xF0, 0x3C, 0x7F, + 0xFC, 0x3F, 0xFC, 0x1F, 0xFF, 0x0E, 0x07, 0xCF, 0x01, 0xE7, 0x80, 0xF3, + 0x80, 0x79, 0xC0, 0x79, 0xFF, 0xF8, 0xFF, 0xFC, 0x7F, 0xF8, 0x00, 0x01, + 0xF8, 0x03, 0xFF, 0x03, 0xFF, 0xC3, 0xE1, 0xF3, 0xC0, 0x79, 0xE0, 0x3D, + 0xE0, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1E, 0x00, + 0x0F, 0x00, 0xE7, 0x80, 0xF3, 0xE0, 0xF0, 0xFF, 0xF8, 0x3F, 0xF0, 0x07, + 0xE0, 0x00, 0x1F, 0xFC, 0x0F, 0xFF, 0x87, 0xFF, 0xC3, 0x81, 0xF1, 0xC0, + 0x79, 0xE0, 0x3C, 0xF0, 0x1E, 0x78, 0x0F, 0x38, 0x07, 0x9C, 0x03, 0xDE, + 0x03, 0xCF, 0x01, 0xE7, 0x81, 0xF3, 0x80, 0xF1, 0xC1, 0xF1, 0xFF, 0xF0, + 0xFF, 0xF0, 0x7F, 0xE0, 0x00, 0x0F, 0xFF, 0x1F, 0xFF, 0x1F, 0xFF, 0x1C, + 0x00, 0x1C, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, + 0xFC, 0x78, 0x00, 0x78, 0x00, 0x78, 0x00, 0x70, 0x00, 0x70, 0x00, 0xFF, + 0xF8, 0xFF, 0xF8, 0xFF, 0xF8, 0x1F, 0xFF, 0x1F, 0xFE, 0x1F, 0xFE, 0x1C, + 0x00, 0x1C, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x3F, 0xF8, 0x3F, 0xF8, 0x3F, + 0xF8, 0x78, 0x00, 0x78, 0x00, 0x78, 0x00, 0x70, 0x00, 0xF0, 0x00, 0xF0, + 0x00, 0xF0, 0x00, 0xE0, 0x00, 0x01, 0xFC, 0x03, 0xFF, 0x03, 0xFF, 0xC3, + 0xE0, 0xF3, 0xC0, 0x39, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, 0xF0, 0x7F, + 0x78, 0x3F, 0xBC, 0x1F, 0xDE, 0x01, 0xCF, 0x00, 0xE7, 0xC0, 0xF1, 0xF0, + 0xF8, 0xFF, 0xFC, 0x3F, 0xEC, 0x07, 0xE6, 0x00, 0x1E, 0x03, 0x8F, 0x01, + 0xC7, 0x01, 0xE3, 0x80, 0xF3, 0xC0, 0x79, 0xE0, 0x38, 0xF0, 0x1C, 0x7F, + 0xFE, 0x3F, 0xFF, 0x3F, 0xFF, 0x9E, 0x03, 0x8F, 0x01, 0xC7, 0x01, 0xE3, + 0x80, 0xF3, 0xC0, 0x71, 0xE0, 0x38, 0xF0, 0x3C, 0x70, 0x1E, 0x00, 0x1E, + 0x3C, 0x78, 0xE1, 0xC7, 0x8F, 0x1E, 0x38, 0x71, 0xE3, 0xC7, 0x8E, 0x1C, + 0x78, 0xF1, 0xE0, 0x00, 0x1C, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x38, + 0x00, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, 0xC0, 0x07, 0x3C, 0x3C, + 0xF0, 0xF3, 0xC3, 0x8F, 0x1E, 0x3F, 0xF8, 0x7F, 0xC0, 0xFC, 0x00, 0x1E, + 0x07, 0xC7, 0x83, 0xE1, 0xE1, 0xE0, 0x70, 0xF0, 0x1C, 0x78, 0x0F, 0x3C, + 0x03, 0xDE, 0x00, 0xFF, 0x00, 0x3F, 0xC0, 0x0F, 0xF0, 0x07, 0xDE, 0x01, + 0xE7, 0xC0, 0x78, 0xF0, 0x1C, 0x3E, 0x0F, 0x07, 0x83, 0xC0, 0xF0, 0xF0, + 0x3C, 0x38, 0x07, 0x80, 0x0E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xC0, + 0x0E, 0x00, 0xF0, 0x07, 0x80, 0x38, 0x01, 0xC0, 0x1E, 0x00, 0xF0, 0x07, + 0x80, 0x38, 0x01, 0xC0, 0x1F, 0xFE, 0xFF, 0xF7, 0xFF, 0x80, 0x1F, 0x03, + 0xF1, 0xF0, 0x3F, 0x1F, 0x07, 0xF1, 0xF0, 0x7F, 0x3F, 0x0F, 0xE3, 0xF0, + 0xEE, 0x3B, 0x1E, 0xE3, 0xB1, 0xDE, 0x3B, 0x1D, 0xE7, 0xB3, 0x9C, 0x7B, + 0x39, 0xC7, 0x37, 0x9C, 0x73, 0x73, 0xCF, 0x3F, 0x3C, 0xF3, 0xE3, 0x8F, + 0x3E, 0x38, 0xE3, 0xC3, 0x8E, 0x3C, 0x78, 0x1E, 0x03, 0x87, 0xC0, 0xE1, + 0xF0, 0x38, 0x7C, 0x1E, 0x1F, 0x87, 0x8F, 0xE1, 0xC3, 0xB8, 0x70, 0xEF, + 0x1C, 0x39, 0xCF, 0x1E, 0x73, 0xC7, 0x8E, 0xE1, 0xC3, 0xB8, 0x70, 0xEE, + 0x1C, 0x1F, 0x8F, 0x07, 0xE3, 0xC1, 0xF0, 0xE0, 0x3C, 0x38, 0x0F, 0x00, + 0x01, 0xF8, 0x03, 0xFF, 0x03, 0xFF, 0xC3, 0xE3, 0xE3, 0xC0, 0xF9, 0xE0, + 0x3D, 0xE0, 0x1E, 0xF0, 0x0F, 0xF0, 0x07, 0xF8, 0x03, 0xFC, 0x03, 0xDE, + 0x01, 0xEF, 0x00, 0xF7, 0xC0, 0xF1, 0xF0, 0xF0, 0xFF, 0xF0, 0x3F, 0xF0, + 0x07, 0xE0, 0x00, 0x1F, 0xFC, 0x1F, 0xFE, 0x1F, 0xFF, 0x1C, 0x1F, 0x1C, + 0x0F, 0x3C, 0x0F, 0x3C, 0x0F, 0x3C, 0x1E, 0x3F, 0xFC, 0x3F, 0xFC, 0x7F, + 0xF0, 0x78, 0x00, 0x78, 0x00, 0x70, 0x00, 0x70, 0x00, 0xF0, 0x00, 0xF0, + 0x00, 0xF0, 0x00, 0x01, 0xF8, 0x03, 0xFF, 0x03, 0xFF, 0xC3, 0xE3, 0xE3, + 0xC0, 0xF9, 0xC0, 0x3D, 0xE0, 0x1E, 0xF0, 0x0F, 0xF0, 0x07, 0xF8, 0x03, + 0xFC, 0x03, 0xDE, 0x09, 0xEF, 0x0E, 0xE7, 0xC7, 0xF1, 0xF1, 0xF0, 0xFF, + 0xF8, 0x3F, 0xFE, 0x07, 0xE6, 0x00, 0x02, 0x00, 0x0F, 0xFE, 0x0F, 0xFF, + 0x87, 0xFF, 0xE3, 0x81, 0xF1, 0xC0, 0x78, 0xE0, 0x3C, 0xF0, 0x1C, 0x78, + 0x1E, 0x3F, 0xFC, 0x1F, 0xFC, 0x1F, 0xFF, 0x8F, 0x03, 0xC7, 0x81, 0xE3, + 0x80, 0xF1, 0xC0, 0xF1, 0xE0, 0x78, 0xF0, 0x3C, 0x78, 0x1F, 0x00, 0x03, + 0xF8, 0x0F, 0xFE, 0x1F, 0xFF, 0x1E, 0x1F, 0x3C, 0x0F, 0x3C, 0x0F, 0x3C, + 0x00, 0x3F, 0x00, 0x1F, 0xF0, 0x0F, 0xFC, 0x01, 0xFE, 0x00, 0x3E, 0xF0, + 0x1E, 0xF0, 0x1E, 0xF8, 0x3C, 0x7F, 0xF8, 0x7F, 0xF0, 0x1F, 0xC0, 0x7F, + 0xFE, 0xFF, 0xFD, 0xFF, 0xF8, 0x1C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, + 0x03, 0x80, 0x07, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xE0, 0x01, + 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x38, 0x00, 0x1E, 0x07, 0x1C, + 0x0F, 0x3C, 0x0F, 0x3C, 0x0F, 0x3C, 0x0E, 0x38, 0x0E, 0x78, 0x1E, 0x78, + 0x1E, 0x78, 0x1E, 0x78, 0x1C, 0x70, 0x1C, 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, + 0x38, 0xF8, 0x78, 0xFF, 0xF0, 0x7F, 0xE0, 0x1F, 0x80, 0xF0, 0x1F, 0xE0, + 0x39, 0xC0, 0xF3, 0x81, 0xC7, 0x07, 0x8E, 0x0E, 0x1C, 0x3C, 0x3C, 0x70, + 0x79, 0xE0, 0xF3, 0x80, 0xEF, 0x01, 0xDC, 0x03, 0xB8, 0x07, 0xE0, 0x0F, + 0x80, 0x1F, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x70, 0x7F, 0x87, 0x83, + 0xFC, 0x3C, 0x3D, 0xE1, 0xE1, 0xEF, 0x1F, 0x0E, 0x78, 0xD8, 0xF3, 0xC6, + 0xC7, 0x0E, 0x76, 0x78, 0x73, 0x33, 0x83, 0xB9, 0x9C, 0x1D, 0xCD, 0xC0, + 0xEC, 0x6E, 0x07, 0xE3, 0xE0, 0x3E, 0x1F, 0x01, 0xF0, 0xF0, 0x0F, 0x87, + 0x80, 0x78, 0x38, 0x03, 0xC1, 0xC0, 0x00, 0x0F, 0x03, 0xC3, 0xC1, 0xE0, + 0xF8, 0xF0, 0x1E, 0x78, 0x07, 0x9E, 0x00, 0xFF, 0x00, 0x3F, 0x80, 0x0F, + 0xC0, 0x01, 0xE0, 0x00, 0xF8, 0x00, 0x3F, 0x00, 0x1F, 0xC0, 0x0F, 0xF0, + 0x07, 0x9E, 0x03, 0xC7, 0x80, 0xF0, 0xF0, 0x78, 0x3C, 0x3C, 0x0F, 0x80, + 0x78, 0x1E, 0xF0, 0x79, 0xE0, 0xF3, 0xC3, 0xC3, 0xCF, 0x07, 0x9E, 0x0F, + 0x78, 0x0F, 0xE0, 0x1F, 0x80, 0x3F, 0x00, 0x3C, 0x00, 0x70, 0x00, 0xE0, + 0x03, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x1F, 0xFF, + 0x0F, 0xFF, 0x87, 0xFF, 0xC0, 0x03, 0xC0, 0x03, 0xE0, 0x03, 0xE0, 0x03, + 0xE0, 0x03, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, + 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xFF, 0xF0, 0xFF, 0xF8, 0x7F, 0xFC, + 0x00, 0x0F, 0xC3, 0xF0, 0xFC, 0x38, 0x1E, 0x07, 0x01, 0xC0, 0x70, 0x1C, + 0x0F, 0x03, 0x80, 0xE0, 0x38, 0x0E, 0x07, 0x01, 0xC0, 0x70, 0x1C, 0x0F, + 0x03, 0x80, 0xFC, 0x3F, 0x0F, 0xC0, 0x08, 0x88, 0xC4, 0x44, 0x66, 0x66, + 0x66, 0x62, 0x22, 0x33, 0x33, 0x30, 0x0F, 0xC3, 0xF0, 0xFC, 0x07, 0x03, + 0xC0, 0xE0, 0x38, 0x0E, 0x03, 0x81, 0xC0, 0x70, 0x1C, 0x07, 0x03, 0xC0, + 0xE0, 0x38, 0x0E, 0x03, 0x81, 0xE0, 0x70, 0xFC, 0x3F, 0x0F, 0xC0, 0x03, + 0x80, 0xF0, 0x1E, 0x07, 0xE1, 0xDC, 0x3B, 0x8E, 0x71, 0x86, 0x70, 0xFC, + 0x1F, 0x83, 0x80, 0x7F, 0xFE, 0xFF, 0xFC, 0xE6, 0x30, 0x07, 0xE0, 0xFF, + 0x8F, 0xFE, 0x70, 0xE0, 0x07, 0x03, 0xF8, 0xFF, 0xCF, 0x9E, 0xF0, 0xF7, + 0x8F, 0x3F, 0xF8, 0xFF, 0xC3, 0xDF, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, + 0x00, 0xF0, 0x01, 0xE0, 0x03, 0x9F, 0x07, 0xFF, 0x0F, 0xFF, 0x3E, 0x3E, + 0x78, 0x3C, 0xF0, 0x79, 0xC0, 0xF3, 0x81, 0xEF, 0x07, 0x9F, 0x1F, 0x3F, + 0xFC, 0x7F, 0xF0, 0xEF, 0x80, 0x07, 0xC0, 0xFF, 0x8F, 0xFE, 0xF8, 0xF7, + 0x87, 0xB8, 0x03, 0xC0, 0x1E, 0x00, 0xF0, 0xF7, 0x8F, 0x1F, 0xF8, 0xFF, + 0x81, 0xF0, 0x00, 0x00, 0x1E, 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x03, + 0xC0, 0xF7, 0x87, 0xFE, 0x1F, 0xFC, 0x7C, 0x78, 0xF0, 0x73, 0xC0, 0xE7, + 0x81, 0x8F, 0x07, 0x1E, 0x0E, 0x3E, 0x3C, 0x7F, 0xF8, 0x7F, 0xE0, 0x7D, + 0xC0, 0x07, 0xC0, 0xFF, 0x8F, 0xFE, 0xF0, 0xF7, 0x87, 0xFF, 0xFF, 0xFF, + 0xFE, 0x00, 0xF0, 0x07, 0xC7, 0x9F, 0xF8, 0xFF, 0x81, 0xF0, 0x00, 0x07, + 0x87, 0xC7, 0xE3, 0xC1, 0xC3, 0xF9, 0xFC, 0x78, 0x3C, 0x1C, 0x0E, 0x07, + 0x07, 0x83, 0x81, 0xC0, 0xE0, 0xF0, 0x78, 0x00, 0x03, 0xDE, 0x1F, 0xF8, + 0x7F, 0xF1, 0xF1, 0xE3, 0xC1, 0xCF, 0x03, 0x9E, 0x06, 0x3C, 0x0C, 0x78, + 0x38, 0xF8, 0xF1, 0xFF, 0xC1, 0xFF, 0x81, 0xF7, 0x00, 0x0E, 0x3C, 0x3C, + 0x78, 0xF0, 0x7F, 0xC0, 0x7E, 0x00, 0x1E, 0x00, 0x70, 0x01, 0xC0, 0x07, + 0x00, 0x3C, 0x00, 0xF7, 0xC3, 0xBF, 0x8F, 0xFF, 0x3C, 0x3D, 0xE0, 0xE7, + 0x83, 0x9C, 0x0E, 0x70, 0x79, 0xC1, 0xEF, 0x07, 0x3C, 0x1C, 0xE0, 0x73, + 0x83, 0xC0, 0x0E, 0x3C, 0x70, 0x00, 0x03, 0x8F, 0x1E, 0x38, 0x71, 0xE3, + 0xC7, 0x0E, 0x1C, 0x78, 0xF1, 0xC0, 0x03, 0xC0, 0xE0, 0x38, 0x00, 0x00, + 0x01, 0xE0, 0x70, 0x1C, 0x07, 0x03, 0xC0, 0xF0, 0x38, 0x0E, 0x03, 0x81, + 0xE0, 0x70, 0x1C, 0x07, 0x03, 0xC0, 0xF0, 0xF8, 0x3E, 0x0F, 0x00, 0x0E, + 0x00, 0x1C, 0x00, 0x38, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0x87, 0x87, 0x1E, + 0x0E, 0x78, 0x3D, 0xE0, 0x7F, 0x80, 0xFE, 0x01, 0xFE, 0x03, 0xFC, 0x0F, + 0x38, 0x1E, 0x78, 0x38, 0xF0, 0x70, 0xF0, 0xE1, 0xE0, 0x0E, 0x3C, 0x78, + 0xE1, 0xC3, 0x8F, 0x1E, 0x38, 0x71, 0xE3, 0xC7, 0x0E, 0x1C, 0x78, 0xF1, + 0xC0, 0x1C, 0xF1, 0xE0, 0xEF, 0xDF, 0x87, 0xFF, 0xFE, 0x7C, 0x78, 0xF3, + 0xC3, 0x87, 0x9C, 0x1C, 0x38, 0xE1, 0xE1, 0xC7, 0x0E, 0x0E, 0x78, 0x70, + 0xF3, 0xC3, 0x87, 0x9C, 0x3C, 0x38, 0xE1, 0xE1, 0xC7, 0x0E, 0x0E, 0x00, + 0x3D, 0xF0, 0xEF, 0xE3, 0xFF, 0xCF, 0x0F, 0x78, 0x39, 0xC0, 0xE7, 0x03, + 0x9C, 0x1E, 0xF0, 0x7B, 0xC1, 0xCE, 0x07, 0x38, 0x1C, 0xE0, 0xF0, 0x07, + 0xE0, 0x7F, 0xE3, 0xFF, 0x9F, 0x1F, 0x78, 0x3F, 0xC0, 0xFF, 0x03, 0xFC, + 0x1F, 0xF0, 0x7B, 0xE3, 0xE7, 0xFF, 0x1F, 0xF8, 0x1F, 0x80, 0x0E, 0x7C, + 0x0F, 0xFE, 0x0F, 0xFF, 0x1F, 0x1F, 0x1E, 0x0F, 0x1E, 0x0F, 0x1C, 0x0F, + 0x1C, 0x0F, 0x3C, 0x1E, 0x3E, 0x3E, 0x3F, 0xFC, 0x3F, 0xF8, 0x7B, 0xE0, + 0x78, 0x00, 0x70, 0x00, 0x70, 0x00, 0x70, 0x00, 0xF0, 0x00, 0x07, 0xBC, + 0x7F, 0xF3, 0xFF, 0x9F, 0x1E, 0x78, 0x3B, 0xC0, 0xEF, 0x03, 0x3C, 0x0C, + 0xF0, 0x73, 0xE3, 0xCF, 0xFF, 0x1F, 0xF8, 0x3C, 0xE0, 0x03, 0x80, 0x1E, + 0x00, 0x78, 0x01, 0xC0, 0x07, 0x00, 0x3D, 0xCE, 0xE3, 0xF8, 0xF0, 0x78, + 0x1E, 0x07, 0x01, 0xC0, 0xF0, 0x3C, 0x0E, 0x03, 0x80, 0xE0, 0x00, 0x1F, + 0xC3, 0xFE, 0x7F, 0xFF, 0x0F, 0xF0, 0x0F, 0xE0, 0x7F, 0xC1, 0xFE, 0x03, + 0xEE, 0x1E, 0xFF, 0xC7, 0xFC, 0x3F, 0x00, 0x1E, 0x1E, 0x1C, 0x7F, 0xFF, + 0x3C, 0x38, 0x38, 0x38, 0x78, 0x78, 0x70, 0x7C, 0xF8, 0x78, 0x38, 0x3C, + 0xE0, 0xE3, 0x83, 0x9E, 0x0E, 0x70, 0x79, 0xC1, 0xE7, 0x07, 0x3C, 0x1C, + 0xF0, 0xF3, 0xE7, 0xCF, 0xFF, 0x1F, 0xF8, 0x3C, 0xE0, 0xF0, 0x77, 0x87, + 0xBC, 0x38, 0xE3, 0xC7, 0x1C, 0x39, 0xE1, 0xCE, 0x0E, 0xE0, 0x77, 0x03, + 0xF0, 0x0F, 0x80, 0x78, 0x03, 0xC0, 0x00, 0xF1, 0xC3, 0xF8, 0xE3, 0xFC, + 0xF1, 0xDE, 0x79, 0xEF, 0x3C, 0xE7, 0xB6, 0x73, 0xDB, 0x70, 0xED, 0xB8, + 0x7C, 0xF8, 0x3E, 0x7C, 0x1F, 0x3C, 0x0F, 0x1E, 0x07, 0x8E, 0x00, 0x0F, + 0x1E, 0x0F, 0x3C, 0x0F, 0x38, 0x07, 0x70, 0x07, 0xF0, 0x03, 0xE0, 0x03, + 0xC0, 0x07, 0xC0, 0x0F, 0xE0, 0x1E, 0xE0, 0x3C, 0xF0, 0x3C, 0xF0, 0x78, + 0x78, 0x3C, 0x1C, 0x78, 0x78, 0xF0, 0xE1, 0xE3, 0xC1, 0xC7, 0x03, 0x9E, + 0x07, 0x38, 0x0E, 0xE0, 0x1D, 0xC0, 0x3F, 0x00, 0x7E, 0x00, 0x78, 0x00, + 0xF0, 0x01, 0xC0, 0x07, 0x00, 0x7E, 0x00, 0xF8, 0x01, 0xE0, 0x00, 0x1F, + 0xF9, 0xFF, 0xCF, 0xFC, 0x01, 0xE0, 0x3E, 0x03, 0xC0, 0x3C, 0x03, 0xC0, + 0x3C, 0x03, 0xC0, 0x3F, 0xF9, 0xFF, 0xCF, 0xFC, 0x00, 0x07, 0x87, 0xC3, + 0xE3, 0xC1, 0xC0, 0xE0, 0x70, 0x38, 0x3C, 0x1C, 0x0E, 0x1E, 0x0F, 0x03, + 0x81, 0xC0, 0xE0, 0x70, 0x78, 0x38, 0x1C, 0x0F, 0x87, 0xC1, 0xC0, 0x0C, + 0x30, 0x86, 0x18, 0x61, 0x8C, 0x30, 0xC3, 0x0C, 0x61, 0x86, 0x18, 0x63, + 0x0C, 0x30, 0xC2, 0x00, 0x00, 0x07, 0x07, 0xC3, 0xE0, 0x70, 0x38, 0x3C, + 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xE0, 0xF0, 0xE0, 0x70, 0x78, 0x38, 0x1C, + 0x0E, 0x07, 0x07, 0x8F, 0x87, 0xC3, 0xC0, 0x3C, 0x07, 0xE0, 0xC7, 0x30, + 0x7E, 0x01, 0xC0 }; + +const GFXglyph FreeSansBoldOblique12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 7, 0, 1 }, // 0x20 ' ' + { 0, 7, 17, 8, 3, -16 }, // 0x21 '!' + { 15, 10, 6, 11, 4, -17 }, // 0x22 '"' + { 23, 15, 16, 13, 1, -15 }, // 0x23 '#' + { 53, 15, 21, 13, 1, -17 }, // 0x24 '$' + { 93, 18, 18, 21, 3, -17 }, // 0x25 '%' + { 134, 15, 17, 17, 2, -16 }, // 0x26 '&' + { 166, 4, 6, 6, 4, -17 }, // 0x27 ''' + { 169, 9, 22, 8, 2, -17 }, // 0x28 '(' + { 194, 9, 22, 8, -1, -16 }, // 0x29 ')' + { 219, 8, 8, 9, 3, -17 }, // 0x2A '*' + { 227, 12, 11, 14, 2, -10 }, // 0x2B '+' + { 244, 5, 7, 7, 1, -2 }, // 0x2C ',' + { 249, 7, 3, 8, 2, -7 }, // 0x2D '-' + { 252, 4, 3, 7, 2, -2 }, // 0x2E '.' + { 254, 10, 17, 7, 0, -16 }, // 0x2F '/' + { 276, 13, 17, 13, 2, -16 }, // 0x30 '0' + { 304, 9, 17, 13, 4, -16 }, // 0x31 '1' + { 324, 15, 17, 13, 1, -16 }, // 0x32 '2' + { 356, 13, 17, 13, 2, -16 }, // 0x33 '3' + { 384, 13, 17, 13, 1, -16 }, // 0x34 '4' + { 412, 14, 17, 13, 1, -16 }, // 0x35 '5' + { 442, 13, 17, 13, 2, -16 }, // 0x36 '6' + { 470, 13, 17, 13, 3, -16 }, // 0x37 '7' + { 498, 14, 17, 13, 1, -16 }, // 0x38 '8' + { 528, 14, 17, 13, 2, -16 }, // 0x39 '9' + { 558, 6, 12, 8, 3, -11 }, // 0x3A ':' + { 567, 7, 16, 8, 2, -11 }, // 0x3B ';' + { 581, 13, 12, 14, 2, -11 }, // 0x3C '<' + { 601, 14, 9, 14, 1, -9 }, // 0x3D '=' + { 617, 13, 12, 14, 1, -10 }, // 0x3E '>' + { 637, 13, 18, 15, 4, -17 }, // 0x3F '?' + { 667, 22, 21, 23, 2, -17 }, // 0x40 '@' + { 725, 17, 18, 17, 0, -17 }, // 0x41 'A' + { 764, 17, 18, 17, 2, -17 }, // 0x42 'B' + { 803, 17, 18, 17, 3, -17 }, // 0x43 'C' + { 842, 17, 18, 17, 2, -17 }, // 0x44 'D' + { 881, 16, 18, 16, 2, -17 }, // 0x45 'E' + { 917, 16, 18, 15, 2, -17 }, // 0x46 'F' + { 953, 17, 18, 19, 3, -17 }, // 0x47 'G' + { 992, 17, 18, 17, 2, -17 }, // 0x48 'H' + { 1031, 7, 18, 7, 2, -17 }, // 0x49 'I' + { 1047, 14, 18, 13, 1, -17 }, // 0x4A 'J' + { 1079, 18, 18, 17, 2, -17 }, // 0x4B 'K' + { 1120, 13, 18, 15, 2, -17 }, // 0x4C 'L' + { 1150, 20, 18, 20, 2, -17 }, // 0x4D 'M' + { 1195, 18, 18, 17, 2, -17 }, // 0x4E 'N' + { 1236, 17, 18, 19, 3, -17 }, // 0x4F 'O' + { 1275, 16, 18, 16, 2, -17 }, // 0x50 'P' + { 1311, 17, 19, 19, 3, -17 }, // 0x51 'Q' + { 1352, 17, 18, 17, 2, -17 }, // 0x52 'R' + { 1391, 16, 18, 16, 2, -17 }, // 0x53 'S' + { 1427, 15, 18, 15, 3, -17 }, // 0x54 'T' + { 1461, 16, 18, 17, 3, -17 }, // 0x55 'U' + { 1497, 15, 18, 16, 4, -17 }, // 0x56 'V' + { 1531, 21, 18, 23, 4, -17 }, // 0x57 'W' + { 1579, 18, 18, 16, 1, -17 }, // 0x58 'X' + { 1620, 15, 18, 16, 4, -17 }, // 0x59 'Y' + { 1654, 17, 18, 15, 1, -17 }, // 0x5A 'Z' + { 1693, 10, 23, 8, 1, -17 }, // 0x5B '[' + { 1722, 4, 23, 7, 3, -22 }, // 0x5C '\' + { 1734, 10, 23, 8, 0, -17 }, // 0x5D ']' + { 1763, 11, 11, 14, 3, -16 }, // 0x5E '^' + { 1779, 15, 2, 13, -2, 4 }, // 0x5F '_' + { 1783, 4, 3, 8, 4, -17 }, // 0x60 '`' + { 1785, 13, 13, 13, 1, -12 }, // 0x61 'a' + { 1807, 15, 18, 15, 1, -17 }, // 0x62 'b' + { 1841, 13, 13, 13, 2, -12 }, // 0x63 'c' + { 1863, 15, 18, 15, 2, -17 }, // 0x64 'd' + { 1897, 13, 13, 13, 2, -12 }, // 0x65 'e' + { 1919, 9, 18, 8, 2, -17 }, // 0x66 'f' + { 1940, 15, 18, 15, 1, -12 }, // 0x67 'g' + { 1974, 14, 18, 15, 2, -17 }, // 0x68 'h' + { 2006, 7, 18, 7, 2, -17 }, // 0x69 'i' + { 2022, 10, 23, 7, -1, -17 }, // 0x6A 'j' + { 2051, 15, 18, 13, 1, -17 }, // 0x6B 'k' + { 2085, 7, 18, 7, 2, -17 }, // 0x6C 'l' + { 2101, 21, 13, 21, 1, -12 }, // 0x6D 'm' + { 2136, 14, 13, 15, 2, -12 }, // 0x6E 'n' + { 2159, 14, 13, 15, 2, -12 }, // 0x6F 'o' + { 2182, 16, 18, 15, 0, -12 }, // 0x70 'p' + { 2218, 14, 18, 15, 2, -12 }, // 0x71 'q' + { 2250, 10, 13, 9, 2, -12 }, // 0x72 'r' + { 2267, 12, 13, 13, 3, -12 }, // 0x73 's' + { 2287, 8, 15, 8, 2, -14 }, // 0x74 't' + { 2302, 14, 13, 15, 2, -12 }, // 0x75 'u' + { 2325, 13, 13, 13, 3, -12 }, // 0x76 'v' + { 2347, 17, 13, 19, 3, -12 }, // 0x77 'w' + { 2375, 16, 13, 13, 0, -12 }, // 0x78 'x' + { 2401, 15, 18, 13, 1, -12 }, // 0x79 'y' + { 2435, 13, 13, 12, 1, -12 }, // 0x7A 'z' + { 2457, 9, 23, 9, 3, -17 }, // 0x7B '{' + { 2483, 6, 23, 7, 1, -17 }, // 0x7C '|' + { 2501, 9, 23, 9, 0, -17 }, // 0x7D '}' + { 2527, 12, 5, 14, 2, -7 } }; // 0x7E '~' + +const GFXfont FreeSansBoldOblique12pt7b PROGMEM = { + (uint8_t *)FreeSansBoldOblique12pt7bBitmaps, + (GFXglyph *)FreeSansBoldOblique12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 3207 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique18pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique18pt7b.h new file mode 100644 index 0000000..79c748c --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique18pt7b.h @@ -0,0 +1,545 @@ +const uint8_t FreeSansBoldOblique18pt7bBitmaps[] PROGMEM = { + 0x06, 0x01, 0xC0, 0x7C, 0x1F, 0x0F, 0xC3, 0xE0, 0xF8, 0x3E, 0x0F, 0x83, + 0xC0, 0xF0, 0x7C, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1C, 0x07, 0x01, 0xC0, + 0x60, 0x7C, 0x1F, 0x07, 0xC3, 0xF0, 0xF8, 0x00, 0x78, 0x7B, 0xC3, 0xFE, + 0x3F, 0xE1, 0xEF, 0x0F, 0x78, 0x7B, 0x83, 0x9C, 0x1C, 0xC0, 0xC0, 0x00, + 0x3C, 0x38, 0x00, 0xF1, 0xE0, 0x07, 0x87, 0x00, 0x1E, 0x3C, 0x00, 0xF0, + 0xE0, 0x3F, 0xFF, 0xF0, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0x1F, 0xFF, 0xF8, + 0x0F, 0x0E, 0x00, 0x3C, 0x78, 0x00, 0xE1, 0xE0, 0x07, 0x8F, 0x00, 0x1C, + 0x3C, 0x07, 0xFF, 0xFE, 0x1F, 0xFF, 0xF8, 0x7F, 0xFF, 0xE3, 0xFF, 0xFF, + 0x01, 0xE3, 0xC0, 0x0F, 0x0E, 0x00, 0x3C, 0x78, 0x01, 0xE1, 0xC0, 0x07, + 0x8F, 0x00, 0x3C, 0x38, 0x00, 0x00, 0x0C, 0x00, 0x01, 0x80, 0x00, 0xFC, + 0x00, 0xFF, 0xC0, 0x3F, 0xFC, 0x0F, 0xFF, 0xC3, 0xE6, 0x78, 0x78, 0xCF, + 0x1E, 0x39, 0xE3, 0xC7, 0x3C, 0x78, 0xC0, 0x0F, 0x98, 0x01, 0xFF, 0x00, + 0x1F, 0xF8, 0x01, 0xFF, 0x80, 0x1F, 0xF8, 0x00, 0x7F, 0x80, 0x0F, 0xF0, + 0x03, 0xBE, 0x00, 0x67, 0xCF, 0x8C, 0xF9, 0xF1, 0x9F, 0x3E, 0x77, 0xC7, + 0xEF, 0xF8, 0x7F, 0xFE, 0x0F, 0xFF, 0x80, 0xFF, 0xE0, 0x03, 0xE0, 0x00, + 0x38, 0x00, 0x06, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x00, 0x07, 0x01, 0xE0, + 0x03, 0x81, 0xFE, 0x00, 0xC0, 0xFF, 0x80, 0x70, 0x7F, 0xF0, 0x38, 0x1E, + 0x3C, 0x1C, 0x0F, 0x07, 0x06, 0x03, 0x81, 0xC3, 0x80, 0xE0, 0xF1, 0xC0, + 0x3C, 0x78, 0xE0, 0x0F, 0xFE, 0x30, 0x01, 0xFF, 0x1C, 0x00, 0x7F, 0x8E, + 0x00, 0x07, 0x83, 0x00, 0x00, 0x01, 0x83, 0xE0, 0x00, 0xE3, 0xFE, 0x00, + 0x71, 0xFF, 0x80, 0x18, 0xFF, 0xF0, 0x0C, 0x3C, 0x3C, 0x07, 0x1C, 0x07, + 0x03, 0x87, 0x01, 0xC0, 0xC1, 0xE1, 0xE0, 0x60, 0x7F, 0xF8, 0x38, 0x0F, + 0xFC, 0x1C, 0x03, 0xFE, 0x06, 0x00, 0x3E, 0x00, 0x00, 0x1F, 0x00, 0x03, + 0xFC, 0x00, 0x3F, 0xF0, 0x03, 0xFF, 0x80, 0x3F, 0x3C, 0x01, 0xF1, 0xE0, + 0x0F, 0x8F, 0x00, 0x7C, 0xF0, 0x03, 0xFF, 0x80, 0x0F, 0xF8, 0x00, 0x3F, + 0x00, 0x03, 0xF0, 0x00, 0x7F, 0xC7, 0x8F, 0xFE, 0x3C, 0xFC, 0xFB, 0xCF, + 0x83, 0xFE, 0xF8, 0x1F, 0xE7, 0xC0, 0x7E, 0x3E, 0x03, 0xE1, 0xF0, 0x1F, + 0x0F, 0xE3, 0xFC, 0x7F, 0xFF, 0xE1, 0xFF, 0xFF, 0x87, 0xFE, 0x7C, 0x0F, + 0xE1, 0xF0, 0x7B, 0xFF, 0xEF, 0x7B, 0x9C, 0xC0, 0x00, 0x78, 0x07, 0x80, + 0x78, 0x03, 0x80, 0x3C, 0x03, 0xC0, 0x1E, 0x01, 0xE0, 0x1E, 0x00, 0xF0, + 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0xF0, 0x07, + 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xF0, + 0x07, 0x80, 0x1C, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x00, 0xE0, 0x07, 0x80, + 0x1C, 0x00, 0x01, 0xC0, 0x0F, 0x00, 0x38, 0x01, 0xE0, 0x0F, 0x00, 0x78, + 0x01, 0xC0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, + 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0xF8, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x1E, + 0x00, 0xF0, 0x07, 0x80, 0x78, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x1E, 0x01, + 0xE0, 0x1E, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x00, 0x03, 0x00, 0x70, 0x07, + 0x04, 0x63, 0xFF, 0xF7, 0xFF, 0x1F, 0x83, 0xF0, 0x3B, 0x87, 0x38, 0x21, + 0x00, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, + 0x00, 0x7C, 0x07, 0xFF, 0xFD, 0xFF, 0xFF, 0xFF, 0xFF, 0xBF, 0xFF, 0xE0, + 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x7C, 0x00, 0x1E, + 0x00, 0x3E, 0x7C, 0xF3, 0xE7, 0xC1, 0x87, 0x0C, 0x39, 0xE3, 0x00, 0x7F, + 0xDF, 0xFF, 0xFB, 0xFE, 0x7D, 0xF7, 0xBE, 0xF8, 0x00, 0x0E, 0x00, 0x18, + 0x00, 0x70, 0x00, 0xC0, 0x03, 0x80, 0x06, 0x00, 0x1C, 0x00, 0x30, 0x00, + 0xE0, 0x01, 0x80, 0x07, 0x00, 0x0C, 0x00, 0x38, 0x00, 0x60, 0x01, 0xC0, + 0x03, 0x00, 0x0E, 0x00, 0x18, 0x00, 0x70, 0x00, 0xC0, 0x03, 0x80, 0x06, + 0x00, 0x1C, 0x00, 0x30, 0x00, 0xE0, 0x00, 0x00, 0xFC, 0x00, 0x7F, 0xC0, + 0x7F, 0xF8, 0x3F, 0xFE, 0x0F, 0x8F, 0xC7, 0xC1, 0xF1, 0xE0, 0x7C, 0xF8, + 0x1F, 0x3E, 0x07, 0xDF, 0x01, 0xF7, 0xC0, 0x7D, 0xF0, 0x3F, 0x7C, 0x0F, + 0xBF, 0x03, 0xEF, 0x80, 0xFB, 0xE0, 0x3E, 0xF8, 0x1F, 0x3E, 0x07, 0xCF, + 0x81, 0xE3, 0xE0, 0xF8, 0xFC, 0x7C, 0x1F, 0xFF, 0x07, 0xFF, 0x80, 0xFF, + 0xC0, 0x0F, 0x80, 0x00, 0x00, 0x70, 0x03, 0x80, 0x3C, 0x03, 0xE0, 0xFF, + 0x3F, 0xF3, 0xFF, 0x9F, 0xFC, 0x03, 0xE0, 0x1F, 0x01, 0xF0, 0x0F, 0x80, + 0x7C, 0x03, 0xE0, 0x1E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x3E, + 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x3E, 0x00, 0x00, 0x1F, 0x80, + 0x07, 0xFF, 0x00, 0x7F, 0xFC, 0x07, 0xFF, 0xE0, 0x7E, 0x1F, 0x83, 0xE0, + 0x7C, 0x1F, 0x03, 0xE1, 0xF0, 0x1F, 0x0F, 0x80, 0xF8, 0x00, 0x0F, 0x80, + 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xE0, 0x00, 0xFC, + 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x80, 0x03, 0xF8, 0x00, 0x3F, + 0x00, 0x03, 0xF0, 0x00, 0x1F, 0xFF, 0xE1, 0xFF, 0xFF, 0x0F, 0xFF, 0xF0, + 0x7F, 0xFF, 0x80, 0x00, 0x7F, 0x00, 0x1F, 0xFC, 0x03, 0xFF, 0xE0, 0x7F, + 0xFF, 0x0F, 0x83, 0xF0, 0xF0, 0x1F, 0x1F, 0x01, 0xF1, 0xE0, 0x1F, 0x00, + 0x03, 0xE0, 0x00, 0xFC, 0x00, 0xFF, 0x80, 0x0F, 0xF0, 0x00, 0xFF, 0x80, + 0x0F, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xCF, 0x80, 0x7C, + 0xF8, 0x07, 0xCF, 0x80, 0xF8, 0xFC, 0x3F, 0x8F, 0xFF, 0xF0, 0x7F, 0xFE, + 0x03, 0xFF, 0xC0, 0x0F, 0xE0, 0x00, 0x00, 0x07, 0xE0, 0x01, 0xFC, 0x00, + 0x7F, 0x00, 0x1F, 0xE0, 0x03, 0xFC, 0x00, 0xEF, 0x80, 0x3D, 0xF0, 0x0F, + 0x7C, 0x03, 0xCF, 0x80, 0xF1, 0xF0, 0x1C, 0x3E, 0x07, 0x07, 0xC1, 0xE1, + 0xF0, 0x78, 0x3E, 0x1E, 0x07, 0xC3, 0xFF, 0xFE, 0x7F, 0xFF, 0xDF, 0xFF, + 0xFB, 0xFF, 0xFF, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x78, 0x00, 0x1F, + 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x01, 0xFF, 0xF0, 0x3F, 0xFF, 0x03, + 0xFF, 0xF0, 0x3F, 0xFF, 0x07, 0x80, 0x00, 0x78, 0x00, 0x0F, 0x00, 0x00, + 0xF7, 0xE0, 0x0F, 0xFF, 0x01, 0xFF, 0xF8, 0x1F, 0xFF, 0x83, 0xF0, 0xFC, + 0x3E, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, + 0x8F, 0x80, 0xF8, 0xF8, 0x1F, 0x8F, 0xC3, 0xF0, 0xFF, 0xFE, 0x07, 0xFF, + 0xC0, 0x3F, 0xF8, 0x00, 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x3F, 0xF0, 0x0F, + 0xFF, 0x03, 0xFF, 0xE0, 0xF8, 0x7E, 0x3E, 0x07, 0xC7, 0x80, 0x01, 0xF0, + 0x00, 0x3C, 0xFC, 0x07, 0xFF, 0xC1, 0xFF, 0xFC, 0x3F, 0xFF, 0xC7, 0xE1, + 0xF8, 0xF8, 0x1F, 0x3E, 0x03, 0xE7, 0x80, 0x7C, 0xF0, 0x0F, 0x9E, 0x01, + 0xE3, 0xC0, 0x7C, 0x78, 0x1F, 0x0F, 0x87, 0xE0, 0xFF, 0xF8, 0x1F, 0xFE, + 0x01, 0xFF, 0x80, 0x0F, 0xC0, 0x00, 0x7F, 0xFF, 0xEF, 0xFF, 0xF9, 0xFF, + 0xFF, 0x7F, 0xFF, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, + 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x07, 0x80, 0x01, 0xF0, 0x00, 0x7C, + 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x3E, 0x00, + 0x07, 0xC0, 0x00, 0x00, 0x7F, 0x00, 0x1F, 0xFC, 0x07, 0xFF, 0xE0, 0xFF, + 0xFF, 0x0F, 0x81, 0xF1, 0xF0, 0x0F, 0x1E, 0x00, 0xF1, 0xE0, 0x1E, 0x1F, + 0x07, 0xE0, 0xFF, 0xFC, 0x07, 0xFF, 0x00, 0xFF, 0xF8, 0x1F, 0xFF, 0x83, + 0xF0, 0xFC, 0x7C, 0x07, 0xC7, 0xC0, 0x7C, 0xF8, 0x07, 0xCF, 0x80, 0x7C, + 0xF8, 0x0F, 0x8F, 0x80, 0xF8, 0xFC, 0x3F, 0x0F, 0xFF, 0xF0, 0x7F, 0xFE, + 0x03, 0xFF, 0x80, 0x0F, 0xE0, 0x00, 0x00, 0x7E, 0x00, 0x3F, 0xF0, 0x0F, + 0xFF, 0x03, 0xFF, 0xE0, 0xFC, 0x3E, 0x3F, 0x03, 0xC7, 0xC0, 0x79, 0xF0, + 0x0F, 0x3E, 0x01, 0xE7, 0xC0, 0x3C, 0xF8, 0x0F, 0x9F, 0x03, 0xE3, 0xF0, + 0xFC, 0x7F, 0xFF, 0x87, 0xFF, 0xF0, 0x7F, 0xFE, 0x07, 0xE7, 0x80, 0x01, + 0xF0, 0x00, 0x3C, 0x7C, 0x0F, 0x8F, 0xC3, 0xE1, 0xFF, 0xF8, 0x1F, 0xFE, + 0x01, 0xFF, 0x80, 0x0F, 0xC0, 0x00, 0x0F, 0x87, 0xC3, 0xC3, 0xE1, 0xF0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xE1, 0xF0, 0xF0, + 0xF8, 0x7C, 0x00, 0x07, 0xC1, 0xF0, 0x78, 0x3E, 0x0F, 0x80, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0x83, 0xE0, 0xF0, 0x7C, + 0x1F, 0x00, 0xC0, 0x70, 0x18, 0x0E, 0x0F, 0x03, 0x00, 0x00, 0x00, 0x20, + 0x00, 0x3C, 0x00, 0x3F, 0x80, 0x3F, 0xE0, 0x3F, 0xFC, 0x3F, 0xFC, 0x1F, + 0xFC, 0x07, 0xFC, 0x00, 0xFC, 0x00, 0x1F, 0xF0, 0x03, 0xFF, 0x80, 0x1F, + 0xFE, 0x00, 0xFF, 0xF0, 0x03, 0xFE, 0x00, 0x1F, 0xC0, 0x00, 0x78, 0x00, + 0x03, 0x00, 0x1F, 0xFF, 0xF3, 0xFF, 0xFE, 0x3F, 0xFF, 0xE3, 0xFF, 0xFE, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, + 0xC7, 0xFF, 0xFC, 0xFF, 0xFF, 0x8F, 0xFF, 0xF8, 0x18, 0x00, 0x03, 0xC0, + 0x00, 0x7F, 0x00, 0x0F, 0xF8, 0x01, 0xFF, 0xE0, 0x0F, 0xFF, 0x00, 0x3F, + 0xF8, 0x01, 0xFF, 0x00, 0x07, 0xE0, 0x07, 0xFC, 0x07, 0xFF, 0x07, 0xFF, + 0x87, 0xFF, 0x80, 0xFF, 0x80, 0x3F, 0x80, 0x07, 0x80, 0x00, 0x80, 0x00, + 0x00, 0x03, 0xF8, 0x03, 0xFF, 0xC1, 0xFF, 0xF8, 0xFF, 0xFE, 0x7E, 0x1F, + 0xDF, 0x03, 0xFF, 0x80, 0x7F, 0xE0, 0x1F, 0xF8, 0x07, 0xC0, 0x03, 0xE0, + 0x01, 0xF8, 0x00, 0xFC, 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x3F, 0x80, 0x1F, + 0x80, 0x07, 0x80, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x07, 0xC0, 0x01, 0xF0, 0x00, 0xFC, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x00, + 0x00, 0x00, 0x7F, 0x80, 0x00, 0x01, 0xFF, 0xF8, 0x00, 0x03, 0xFF, 0xFE, + 0x00, 0x07, 0xF0, 0x1F, 0xC0, 0x0F, 0xC0, 0x03, 0xE0, 0x0F, 0x80, 0x00, + 0xF8, 0x0F, 0x00, 0x00, 0x3C, 0x0F, 0x01, 0xF1, 0xCF, 0x0F, 0x03, 0xFD, + 0xC7, 0x8F, 0x03, 0xFF, 0xE1, 0xC7, 0x03, 0xE3, 0xE0, 0xE7, 0x03, 0xC0, + 0xF0, 0x73, 0x83, 0xC0, 0x78, 0x3B, 0x81, 0xE0, 0x38, 0x1D, 0xC1, 0xE0, + 0x1C, 0x1C, 0xC0, 0xF0, 0x1C, 0x0E, 0xE0, 0x70, 0x0E, 0x0F, 0x70, 0x78, + 0x0E, 0x07, 0x38, 0x3C, 0x0F, 0x07, 0x1C, 0x1E, 0x0F, 0x87, 0x8E, 0x0F, + 0x8F, 0xCF, 0x87, 0x07, 0xFF, 0xFF, 0x83, 0xC1, 0xFE, 0x7F, 0x00, 0xE0, + 0x3C, 0x1F, 0x00, 0x78, 0x00, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x0F, + 0xC0, 0x01, 0x00, 0x03, 0xF8, 0x07, 0x80, 0x00, 0xFF, 0xFF, 0xC0, 0x00, + 0x1F, 0xFF, 0xE0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x00, 0x03, 0xF0, 0x00, + 0x0F, 0xE0, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0xC0, 0x00, 0xFF, 0x80, 0x03, + 0xFF, 0x00, 0x07, 0xFE, 0x00, 0x1F, 0x7C, 0x00, 0x7E, 0xF8, 0x00, 0xF9, + 0xF0, 0x03, 0xF3, 0xE0, 0x07, 0xC3, 0xE0, 0x1F, 0x87, 0xC0, 0x3E, 0x0F, + 0x80, 0xF8, 0x1F, 0x01, 0xF0, 0x3E, 0x07, 0xFF, 0xFC, 0x1F, 0xFF, 0xF8, + 0x3F, 0xFF, 0xF0, 0xFF, 0xFF, 0xF1, 0xF0, 0x03, 0xE7, 0xC0, 0x07, 0xCF, + 0x80, 0x0F, 0xBE, 0x00, 0x1F, 0x7C, 0x00, 0x3F, 0xF0, 0x00, 0x7C, 0x07, + 0xFF, 0xF0, 0x07, 0xFF, 0xFC, 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0x0F, + 0xC0, 0x3F, 0x0F, 0x80, 0x1F, 0x0F, 0x80, 0x1F, 0x0F, 0x80, 0x1F, 0x1F, + 0x80, 0x1E, 0x1F, 0x80, 0x3E, 0x1F, 0x00, 0x7C, 0x1F, 0xFF, 0xF8, 0x1F, + 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, 0x3F, 0xFF, 0xF8, 0x3E, 0x00, 0xFC, 0x3E, + 0x00, 0x7C, 0x3E, 0x00, 0x7C, 0x7E, 0x00, 0x7C, 0x7C, 0x00, 0x7C, 0x7C, + 0x00, 0xF8, 0x7C, 0x01, 0xF8, 0x7F, 0xFF, 0xF0, 0xFF, 0xFF, 0xE0, 0xFF, + 0xFF, 0xC0, 0xFF, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0xF8, 0x01, + 0xFF, 0xFC, 0x03, 0xFF, 0xFE, 0x07, 0xE0, 0x7F, 0x0F, 0xC0, 0x3F, 0x1F, + 0x80, 0x1F, 0x3F, 0x00, 0x1F, 0x3E, 0x00, 0x1F, 0x7E, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x7C, 0xF8, + 0x00, 0x7C, 0xFC, 0x00, 0xF8, 0xFC, 0x01, 0xF8, 0x7F, 0x07, 0xF0, 0x7F, + 0xFF, 0xE0, 0x3F, 0xFF, 0xC0, 0x0F, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x07, + 0xFF, 0xE0, 0x07, 0xFF, 0xF8, 0x07, 0xFF, 0xFC, 0x0F, 0xFF, 0xFE, 0x0F, + 0x80, 0x7E, 0x0F, 0x80, 0x3F, 0x0F, 0x80, 0x1F, 0x1F, 0x80, 0x1F, 0x1F, + 0x80, 0x1F, 0x1F, 0x00, 0x1F, 0x1F, 0x00, 0x1F, 0x1F, 0x00, 0x1F, 0x3F, + 0x00, 0x1F, 0x3E, 0x00, 0x3E, 0x3E, 0x00, 0x3E, 0x3E, 0x00, 0x3E, 0x3E, + 0x00, 0x3E, 0x7E, 0x00, 0x7C, 0x7C, 0x00, 0x7C, 0x7C, 0x00, 0xF8, 0x7C, + 0x01, 0xF8, 0x7C, 0x07, 0xF0, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xC0, 0xFF, + 0xFF, 0x00, 0xFF, 0xF8, 0x00, 0x07, 0xFF, 0xFF, 0x07, 0xFF, 0xFE, 0x07, + 0xFF, 0xFE, 0x0F, 0xFF, 0xFE, 0x0F, 0x80, 0x00, 0x0F, 0x80, 0x00, 0x0F, + 0x80, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x1F, 0xFF, 0xF0, 0x1F, 0xFF, 0xF0, 0x3F, 0xFF, 0xF0, 0x3F, + 0xFF, 0xF0, 0x3E, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7E, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xFF, + 0xFF, 0xF0, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xE0, 0x07, + 0xFF, 0xFE, 0x0F, 0xFF, 0xFC, 0x3F, 0xFF, 0xF0, 0x7F, 0xFF, 0xE0, 0xF8, + 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x1F, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xFF, 0xFF, 0x03, 0xFF, 0xFE, + 0x07, 0xFF, 0xFC, 0x0F, 0xFF, 0xF0, 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0xFC, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, + 0x80, 0x00, 0x3F, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0xF8, 0x01, 0xFF, 0xFC, 0x03, + 0xFF, 0xFE, 0x07, 0xE0, 0x7E, 0x0F, 0x80, 0x3F, 0x1F, 0x00, 0x1F, 0x3E, + 0x00, 0x1F, 0x3E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0xF8, 0x03, 0xFF, 0xF8, 0x07, 0xFF, 0xF8, 0x07, 0xFE, 0xF8, + 0x07, 0xFE, 0xF8, 0x00, 0x3E, 0xF8, 0x00, 0x3E, 0xFC, 0x00, 0x7E, 0xFC, + 0x00, 0x7C, 0x7E, 0x00, 0xFC, 0x7F, 0x83, 0xFC, 0x3F, 0xFF, 0xFC, 0x1F, + 0xFF, 0xBC, 0x0F, 0xFF, 0x38, 0x03, 0xFC, 0x38, 0x03, 0xE0, 0x07, 0xC0, + 0xF8, 0x01, 0xF0, 0x7E, 0x00, 0x7C, 0x1F, 0x00, 0x3F, 0x07, 0xC0, 0x0F, + 0x81, 0xF0, 0x03, 0xE0, 0xFC, 0x00, 0xF8, 0x3E, 0x00, 0x3E, 0x0F, 0x80, + 0x1F, 0x83, 0xE0, 0x07, 0xC0, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xFC, 0x1F, + 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xC1, 0xF0, 0x03, 0xE0, 0x7C, 0x00, 0xF8, + 0x3F, 0x00, 0x3E, 0x0F, 0x80, 0x0F, 0x83, 0xE0, 0x07, 0xE0, 0xF8, 0x01, + 0xF0, 0x3E, 0x00, 0x7C, 0x1F, 0x80, 0x1F, 0x07, 0xC0, 0x0F, 0xC1, 0xF0, + 0x03, 0xF0, 0x7C, 0x00, 0xF8, 0x3F, 0x00, 0x3E, 0x00, 0x07, 0xC3, 0xF0, + 0xFC, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x7E, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, + 0x3F, 0x0F, 0xC3, 0xE0, 0xF8, 0x3E, 0x0F, 0x87, 0xE1, 0xF0, 0x7C, 0x1F, + 0x07, 0xC3, 0xF0, 0xFC, 0x3E, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, + 0x01, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xE0, + 0x00, 0x3E, 0x00, 0x07, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, + 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x7C, 0x0F, + 0x8F, 0x81, 0xF8, 0xF8, 0x1F, 0x0F, 0x81, 0xF0, 0xF8, 0x1F, 0x0F, 0xC3, + 0xF0, 0xFF, 0xFE, 0x07, 0xFF, 0xC0, 0x3F, 0xF8, 0x01, 0xFC, 0x00, 0x07, + 0xC0, 0x0F, 0xC1, 0xF0, 0x07, 0xE0, 0x7C, 0x03, 0xF0, 0x3F, 0x03, 0xF8, + 0x0F, 0x81, 0xF8, 0x03, 0xE0, 0xFC, 0x00, 0xF8, 0x7E, 0x00, 0x7E, 0x3F, + 0x00, 0x1F, 0x1F, 0x80, 0x07, 0xCF, 0xC0, 0x01, 0xF7, 0xE0, 0x00, 0x7F, + 0xF0, 0x00, 0x3F, 0xFC, 0x00, 0x0F, 0xFF, 0x80, 0x03, 0xFF, 0xF0, 0x00, + 0xFE, 0xFC, 0x00, 0x3F, 0x1F, 0x80, 0x1F, 0x87, 0xE0, 0x07, 0xC0, 0xFC, + 0x01, 0xF0, 0x3F, 0x00, 0x7C, 0x07, 0xE0, 0x1F, 0x01, 0xFC, 0x0F, 0xC0, + 0x3F, 0x03, 0xE0, 0x0F, 0xE0, 0xF8, 0x01, 0xF8, 0x3E, 0x00, 0x3F, 0x00, + 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x0F, 0xC0, 0x03, + 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x1F, 0x80, 0x07, 0xC0, 0x01, 0xF0, + 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x0F, 0xC0, 0x03, 0xE0, 0x00, 0xF8, 0x00, + 0x3E, 0x00, 0x0F, 0x80, 0x07, 0xE0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1F, + 0x00, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xBF, 0xFF, 0xE0, 0x03, + 0xF8, 0x01, 0xFC, 0x07, 0xF0, 0x07, 0xF8, 0x1F, 0xE0, 0x0F, 0xF0, 0x3F, + 0xC0, 0x3F, 0xE0, 0x7F, 0x80, 0x7F, 0xC0, 0xFF, 0x01, 0xFF, 0x01, 0xFE, + 0x03, 0xFE, 0x07, 0xDC, 0x07, 0x7C, 0x0F, 0xB8, 0x1E, 0xF8, 0x1F, 0x70, + 0x3D, 0xF0, 0x3E, 0xF0, 0xF7, 0xC0, 0xF9, 0xE1, 0xEF, 0x81, 0xF3, 0xC7, + 0x9F, 0x03, 0xE7, 0x8F, 0x3E, 0x07, 0xCF, 0x3C, 0x7C, 0x0F, 0x9E, 0x79, + 0xF0, 0x3E, 0x3C, 0xE3, 0xE0, 0x7C, 0x7B, 0xC7, 0xC0, 0xF8, 0xF7, 0x8F, + 0x81, 0xF1, 0xFE, 0x1E, 0x07, 0xE3, 0xFC, 0x7C, 0x0F, 0x87, 0xF0, 0xF8, + 0x1F, 0x0F, 0xE1, 0xF0, 0x3E, 0x1F, 0x83, 0xE0, 0x7C, 0x3F, 0x0F, 0x81, + 0xF0, 0x7E, 0x1F, 0x00, 0x03, 0xE0, 0x07, 0xC0, 0x7E, 0x00, 0xF8, 0x1F, + 0xC0, 0x1F, 0x03, 0xF8, 0x03, 0xE0, 0x7F, 0x80, 0x7C, 0x0F, 0xF0, 0x1F, + 0x01, 0xFF, 0x03, 0xE0, 0x7F, 0xE0, 0x7C, 0x0F, 0xBC, 0x0F, 0x81, 0xF7, + 0xC1, 0xF0, 0x3E, 0xF8, 0x7C, 0x0F, 0x8F, 0x0F, 0x81, 0xF1, 0xF1, 0xF0, + 0x3E, 0x3E, 0x3E, 0x07, 0xC3, 0xC7, 0xC0, 0xF8, 0x7D, 0xF0, 0x3E, 0x0F, + 0xBE, 0x07, 0xC0, 0xF7, 0xC0, 0xF8, 0x1F, 0xF8, 0x1F, 0x01, 0xFE, 0x03, + 0xC0, 0x3F, 0xC0, 0xF8, 0x07, 0xF8, 0x1F, 0x00, 0x7F, 0x03, 0xE0, 0x0F, + 0xE0, 0x7C, 0x01, 0xF8, 0x1F, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0xE0, 0x00, + 0x3F, 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x7F, 0xFF, 0xC0, 0x7E, 0x07, 0xF0, + 0x7E, 0x01, 0xF8, 0x7C, 0x00, 0x7E, 0x3E, 0x00, 0x1F, 0x3E, 0x00, 0x0F, + 0x9E, 0x00, 0x07, 0xDF, 0x00, 0x03, 0xEF, 0x80, 0x01, 0xFF, 0x80, 0x00, + 0xFF, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x7D, 0xF0, 0x00, 0x3E, 0xF8, 0x00, + 0x1F, 0x7C, 0x00, 0x1F, 0x3E, 0x00, 0x1F, 0x9F, 0x80, 0x0F, 0x87, 0xE0, + 0x0F, 0x83, 0xF8, 0x1F, 0x80, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0x80, 0x0F, + 0xFF, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x07, 0xFF, 0xE0, 0x0F, 0xFF, 0xF0, + 0x3F, 0xFF, 0xF0, 0x7F, 0xFF, 0xF0, 0xF8, 0x07, 0xE1, 0xF0, 0x07, 0xC3, + 0xE0, 0x0F, 0x8F, 0xC0, 0x1F, 0x1F, 0x00, 0x3E, 0x3E, 0x00, 0xF8, 0x7C, + 0x01, 0xF0, 0xF8, 0x07, 0xC3, 0xFF, 0xFF, 0x87, 0xFF, 0xFE, 0x0F, 0xFF, + 0xF8, 0x1F, 0xFF, 0x80, 0x3E, 0x00, 0x00, 0xFC, 0x00, 0x01, 0xF0, 0x00, + 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x3F, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x3F, 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x7F, 0xFF, 0xC0, 0x7F, 0x07, + 0xF0, 0x7E, 0x01, 0xF8, 0x7E, 0x00, 0x7E, 0x3E, 0x00, 0x1F, 0x3E, 0x00, + 0x0F, 0x9E, 0x00, 0x07, 0xDF, 0x00, 0x03, 0xEF, 0x80, 0x01, 0xF7, 0x80, + 0x00, 0xFF, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x7D, 0xF0, 0x00, 0x3E, 0xF8, + 0x02, 0x1F, 0x7C, 0x03, 0x9F, 0x3E, 0x03, 0xFF, 0x9F, 0x81, 0xFF, 0x87, + 0xE0, 0x7F, 0x83, 0xF8, 0x3F, 0xC0, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, 0xF0, + 0x0F, 0xFF, 0xFC, 0x01, 0xFE, 0x1C, 0x00, 0x00, 0x0C, 0x00, 0x07, 0xFF, + 0xF8, 0x07, 0xFF, 0xFE, 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0x0F, 0x80, + 0x3F, 0x0F, 0x80, 0x1F, 0x0F, 0x80, 0x1F, 0x0F, 0x80, 0x1F, 0x1F, 0x80, + 0x1E, 0x1F, 0x00, 0x3E, 0x1F, 0x00, 0x7C, 0x1F, 0xFF, 0xF8, 0x1F, 0xFF, + 0xE0, 0x3F, 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, 0x3E, 0x01, 0xF8, 0x3E, 0x00, + 0xF8, 0x3E, 0x00, 0xF8, 0x7E, 0x00, 0xF8, 0x7C, 0x00, 0xF8, 0x7C, 0x01, + 0xF0, 0x7C, 0x01, 0xF0, 0x7C, 0x01, 0xF0, 0xFC, 0x01, 0xF0, 0xF8, 0x01, + 0xF0, 0xF8, 0x01, 0xF0, 0x00, 0x3F, 0xC0, 0x07, 0xFF, 0xC0, 0x3F, 0xFF, + 0x81, 0xFF, 0xFF, 0x0F, 0xC0, 0xFC, 0x3E, 0x01, 0xF1, 0xF0, 0x07, 0xC7, + 0xC0, 0x1F, 0x1F, 0x00, 0x00, 0x7E, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xFF, + 0x80, 0x0F, 0xFF, 0xC0, 0x1F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, 0x03, 0xFE, + 0x00, 0x01, 0xF8, 0x00, 0x03, 0xEF, 0x80, 0x0F, 0xBE, 0x00, 0x3C, 0xFC, + 0x01, 0xF3, 0xF8, 0x1F, 0x87, 0xFF, 0xFE, 0x0F, 0xFF, 0xF0, 0x1F, 0xFF, + 0x00, 0x1F, 0xF0, 0x00, 0x7F, 0xFF, 0xFB, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xF0, 0x0F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xC0, 0x00, 0x3E, + 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xC0, 0x00, + 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xC0, + 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, 0x07, + 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, + 0x00, 0x0F, 0x80, 0x1F, 0x1F, 0x80, 0x1F, 0x1F, 0x00, 0x1F, 0x1F, 0x00, + 0x3F, 0x1F, 0x00, 0x3E, 0x1F, 0x00, 0x3E, 0x3E, 0x00, 0x3E, 0x3E, 0x00, + 0x7E, 0x3E, 0x00, 0x7C, 0x3E, 0x00, 0x7C, 0x3E, 0x00, 0x7C, 0x7C, 0x00, + 0x7C, 0x7C, 0x00, 0xFC, 0x7C, 0x00, 0xF8, 0x7C, 0x00, 0xF8, 0x7C, 0x00, + 0xF8, 0xF8, 0x00, 0xF8, 0xF8, 0x01, 0xF8, 0xF8, 0x01, 0xF0, 0xF8, 0x01, + 0xF0, 0xF8, 0x03, 0xE0, 0xFE, 0x0F, 0xE0, 0x7F, 0xFF, 0xC0, 0x7F, 0xFF, + 0x80, 0x1F, 0xFE, 0x00, 0x07, 0xF8, 0x00, 0xFC, 0x00, 0x7F, 0xF0, 0x03, + 0xE7, 0xC0, 0x0F, 0x9F, 0x00, 0x7C, 0x7C, 0x01, 0xF1, 0xF0, 0x0F, 0x87, + 0xC0, 0x3E, 0x1F, 0x01, 0xF0, 0x7C, 0x07, 0x81, 0xF0, 0x3E, 0x03, 0xC0, + 0xF0, 0x0F, 0x07, 0xC0, 0x3E, 0x1E, 0x00, 0xF8, 0xF8, 0x03, 0xE3, 0xC0, + 0x0F, 0x9F, 0x00, 0x3E, 0x78, 0x00, 0xFB, 0xE0, 0x01, 0xEF, 0x00, 0x07, + 0xFC, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xE0, + 0x00, 0x1F, 0x80, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x07, 0xE0, 0x1F, 0xF8, + 0x07, 0xE0, 0x3F, 0xF8, 0x0F, 0xE0, 0x3E, 0xF8, 0x0F, 0xE0, 0x7E, 0xF8, + 0x1F, 0xE0, 0x7C, 0xF8, 0x1F, 0xE0, 0x7C, 0xF8, 0x3F, 0xE0, 0xF8, 0xF8, + 0x3D, 0xE0, 0xF8, 0x78, 0x3D, 0xE1, 0xF0, 0x78, 0x79, 0xE1, 0xF0, 0x78, + 0x79, 0xE1, 0xE0, 0x78, 0xF9, 0xE3, 0xE0, 0x78, 0xF1, 0xE3, 0xC0, 0x79, + 0xF1, 0xE7, 0xC0, 0x79, 0xE1, 0xE7, 0x80, 0x79, 0xE1, 0xE7, 0x80, 0x7B, + 0xC1, 0xEF, 0x80, 0x7B, 0xC1, 0xEF, 0x00, 0x7F, 0x81, 0xFF, 0x00, 0x7F, + 0x81, 0xFE, 0x00, 0x7F, 0x01, 0xFE, 0x00, 0x7F, 0x01, 0xFC, 0x00, 0x7F, + 0x01, 0xFC, 0x00, 0x7E, 0x01, 0xF8, 0x00, 0x3E, 0x01, 0xF8, 0x00, 0x3C, + 0x01, 0xF0, 0x00, 0x03, 0xF0, 0x07, 0xE0, 0x7E, 0x01, 0xF8, 0x07, 0xE0, + 0x7E, 0x00, 0xFC, 0x1F, 0x80, 0x1F, 0x83, 0xE0, 0x01, 0xF8, 0xF8, 0x00, + 0x3F, 0x3F, 0x00, 0x03, 0xEF, 0xC0, 0x00, 0x7F, 0xF0, 0x00, 0x0F, 0xFC, + 0x00, 0x00, 0xFF, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0x7F, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0xFF, 0xC0, + 0x00, 0x3E, 0xF8, 0x00, 0x0F, 0xDF, 0x80, 0x03, 0xF3, 0xF0, 0x00, 0xFC, + 0x3F, 0x00, 0x3F, 0x07, 0xE0, 0x07, 0xE0, 0xFC, 0x01, 0xF8, 0x0F, 0xC0, + 0x7E, 0x01, 0xF8, 0x1F, 0x80, 0x3F, 0x80, 0x7C, 0x00, 0xFD, 0xF8, 0x07, + 0xE7, 0xE0, 0x1F, 0x1F, 0x80, 0xFC, 0x3E, 0x07, 0xE0, 0xFC, 0x1F, 0x03, + 0xF0, 0xFC, 0x07, 0xC7, 0xE0, 0x1F, 0x1F, 0x00, 0x7E, 0xFC, 0x00, 0xFB, + 0xE0, 0x03, 0xFF, 0x00, 0x0F, 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x00, + 0x01, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0x7C, 0x00, 0x01, + 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, + 0x00, 0x0F, 0x80, 0x00, 0x3E, 0x00, 0x00, 0x07, 0xFF, 0xFF, 0x83, 0xFF, + 0xFF, 0x81, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xE0, 0x00, 0x07, 0xE0, 0x00, + 0x07, 0xE0, 0x00, 0x07, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF0, 0x00, + 0x07, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, + 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, + 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF8, 0x00, + 0x03, 0xF8, 0x00, 0x01, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, + 0xF0, 0x7F, 0xFF, 0xF0, 0x00, 0x01, 0xFE, 0x03, 0xFC, 0x07, 0xF8, 0x1F, + 0xF0, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x07, 0x80, 0x0F, 0x00, + 0x1E, 0x00, 0x3C, 0x00, 0xF8, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, + 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x07, 0x80, 0x0F, 0x00, + 0x1E, 0x00, 0x3C, 0x00, 0xF8, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, + 0xF0, 0x3F, 0xC0, 0x7F, 0x80, 0xFF, 0x00, 0xE7, 0x39, 0xCE, 0x31, 0x8C, + 0x63, 0x1C, 0xE7, 0x39, 0xCE, 0x31, 0x8C, 0x63, 0x9C, 0xE7, 0x38, 0x01, + 0xFE, 0x03, 0xFC, 0x07, 0xF8, 0x1F, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, + 0x00, 0x3E, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x0F, 0x00, + 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, + 0x00, 0x3E, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x0F, 0x00, + 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x1F, 0xF0, 0x3F, 0xC0, 0x7F, 0x80, 0xFF, + 0x00, 0x00, 0x7C, 0x00, 0xFC, 0x01, 0xFC, 0x01, 0xFC, 0x03, 0xFC, 0x03, + 0x9E, 0x07, 0x9E, 0x0F, 0x1E, 0x0F, 0x1E, 0x1E, 0x1E, 0x1C, 0x0F, 0x3C, + 0x0F, 0x78, 0x0F, 0x78, 0x0F, 0xF0, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFE, 0xF3, 0x8C, 0x71, 0x80, 0x01, 0xFE, 0x01, 0xFF, 0xE0, + 0xFF, 0xF8, 0x7F, 0xFF, 0x1F, 0x0F, 0xC7, 0x81, 0xF0, 0x00, 0x7C, 0x00, + 0xFE, 0x07, 0xFF, 0x87, 0xFF, 0xE3, 0xFE, 0xF9, 0xF0, 0x7C, 0xF8, 0x1F, + 0x3E, 0x0F, 0xCF, 0x87, 0xF3, 0xFF, 0xF8, 0xFF, 0xFE, 0x1F, 0xEF, 0x81, + 0xE3, 0xF0, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, + 0x07, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF9, 0xF8, 0x0F, 0xFF, + 0xC1, 0xFF, 0xFE, 0x1F, 0xFF, 0xE1, 0xFC, 0x3F, 0x1F, 0x83, 0xF1, 0xF0, + 0x1F, 0x3E, 0x01, 0xF3, 0xE0, 0x1F, 0x3C, 0x01, 0xF3, 0xC0, 0x1F, 0x3C, + 0x03, 0xE7, 0xC0, 0x3E, 0x7E, 0x07, 0xC7, 0xF1, 0xFC, 0x7F, 0xFF, 0x87, + 0xFF, 0xF0, 0xFB, 0xFE, 0x0F, 0x9F, 0x80, 0x00, 0xFC, 0x01, 0xFF, 0xC0, + 0xFF, 0xF8, 0x7F, 0xFF, 0x3F, 0x0F, 0xCF, 0x81, 0xF7, 0xC0, 0x7D, 0xF0, + 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF8, 0x0F, + 0xBE, 0x07, 0xCF, 0xC3, 0xF1, 0xFF, 0xF8, 0x7F, 0xFC, 0x0F, 0xFE, 0x00, + 0xFE, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0x80, 0x00, + 0x3E, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x1F, 0x00, 0x7E, 0x7C, + 0x07, 0xFD, 0xF0, 0x3F, 0xFF, 0xC1, 0xFF, 0xFE, 0x0F, 0xE3, 0xF8, 0x3E, + 0x07, 0xE1, 0xF0, 0x1F, 0x87, 0xC0, 0x3C, 0x3E, 0x00, 0xF0, 0xF8, 0x07, + 0xC3, 0xE0, 0x1F, 0x0F, 0x80, 0x7C, 0x3E, 0x03, 0xE0, 0xF8, 0x1F, 0x83, + 0xF0, 0xFE, 0x07, 0xFF, 0xF8, 0x1F, 0xFF, 0xE0, 0x3F, 0xFF, 0x00, 0x7E, + 0x7C, 0x00, 0x00, 0xFE, 0x00, 0x7F, 0xE0, 0x3F, 0xFE, 0x0F, 0xFF, 0xE3, + 0xF0, 0x7E, 0x7C, 0x07, 0xDF, 0x00, 0xFB, 0xE0, 0x1F, 0x7F, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x1F, 0x3F, + 0x07, 0xE3, 0xFF, 0xF8, 0x7F, 0xFE, 0x03, 0xFF, 0x00, 0x3F, 0x80, 0x00, + 0x00, 0xF8, 0x1F, 0xC1, 0xFE, 0x0F, 0xF0, 0x7C, 0x07, 0xC0, 0x3E, 0x0F, + 0xFE, 0x7F, 0xF3, 0xFF, 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, + 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x78, 0x07, 0xC0, 0x3E, 0x01, + 0xF0, 0x0F, 0x80, 0xF8, 0x07, 0xC0, 0x00, 0x00, 0x7C, 0x7C, 0x07, 0xFD, + 0xF0, 0x3F, 0xF7, 0x81, 0xFF, 0xFE, 0x0F, 0xE3, 0xF8, 0x3E, 0x07, 0xE1, + 0xF8, 0x0F, 0x87, 0xC0, 0x3C, 0x1E, 0x00, 0xF0, 0xF8, 0x03, 0xC3, 0xE0, + 0x1F, 0x0F, 0x80, 0x78, 0x3E, 0x03, 0xE0, 0xF8, 0x1F, 0x83, 0xF0, 0xFE, + 0x07, 0xFF, 0xF8, 0x1F, 0xFF, 0xC0, 0x3F, 0xEF, 0x00, 0x3E, 0x7C, 0x00, + 0x01, 0xF0, 0x00, 0x07, 0xC3, 0xE0, 0x3E, 0x0F, 0x80, 0xF8, 0x3F, 0x0F, + 0xC0, 0x7F, 0xFE, 0x00, 0xFF, 0xF0, 0x00, 0xFE, 0x00, 0x00, 0x03, 0xE0, + 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, + 0x00, 0x0F, 0x80, 0x00, 0xF8, 0xF8, 0x0F, 0xBF, 0xE0, 0xFF, 0xFF, 0x0F, + 0xFF, 0xF1, 0xFC, 0x3F, 0x1F, 0x81, 0xF1, 0xF0, 0x1F, 0x1F, 0x01, 0xF1, + 0xE0, 0x1F, 0x3E, 0x03, 0xE3, 0xE0, 0x3E, 0x3E, 0x03, 0xE3, 0xE0, 0x3E, + 0x7C, 0x03, 0xE7, 0xC0, 0x7C, 0x7C, 0x07, 0xC7, 0xC0, 0x7C, 0x7C, 0x07, + 0xCF, 0x80, 0x78, 0x07, 0xC1, 0xF0, 0x7C, 0x3E, 0x00, 0x00, 0x00, 0x00, + 0x3E, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, + 0x0F, 0x87, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC3, 0xE0, 0xF8, 0x3E, 0x00, + 0x00, 0x3E, 0x00, 0x78, 0x01, 0xF0, 0x03, 0xE0, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x7C, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, 0x0F, 0x80, 0x1F, + 0x00, 0x3E, 0x00, 0x7C, 0x00, 0xF8, 0x03, 0xE0, 0x07, 0xC0, 0x0F, 0x80, + 0x1F, 0x00, 0x3C, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, 0x07, 0xC0, 0x1F, + 0x00, 0x3E, 0x00, 0x7C, 0x00, 0xF8, 0x03, 0xF0, 0x1F, 0xC0, 0x3F, 0x80, + 0x7E, 0x01, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, + 0x0F, 0x80, 0x00, 0x78, 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, + 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x07, 0xC7, 0xE0, 0x3E, 0x7E, 0x01, + 0xF7, 0xE0, 0x0F, 0xFE, 0x00, 0xFF, 0xE0, 0x07, 0xFF, 0x00, 0x3F, 0xFC, + 0x01, 0xFF, 0xE0, 0x0F, 0xDF, 0x00, 0xFC, 0xFC, 0x07, 0xC3, 0xE0, 0x3E, + 0x1F, 0x01, 0xF0, 0xFC, 0x0F, 0x83, 0xE0, 0xF8, 0x1F, 0x87, 0xC0, 0xFC, + 0x00, 0x07, 0xC1, 0xF0, 0x7C, 0x3E, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x1F, + 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x0F, 0x83, 0xE0, 0xF8, 0x3E, 0x0F, 0x87, + 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC3, 0xE0, 0xF8, 0x3E, 0x00, 0x0F, 0x8F, + 0x83, 0xF0, 0x3E, 0xFF, 0x3F, 0xE0, 0xF7, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, + 0xFF, 0x1F, 0xC7, 0xF8, 0x7C, 0x7C, 0x0F, 0x81, 0xF1, 0xF0, 0x3E, 0x07, + 0xCF, 0x81, 0xF0, 0x3E, 0x3E, 0x07, 0xC0, 0xF8, 0xF8, 0x1F, 0x03, 0xE3, + 0xE0, 0x7C, 0x0F, 0x8F, 0x81, 0xF0, 0x3E, 0x7C, 0x0F, 0x81, 0xF1, 0xF0, + 0x3E, 0x07, 0xC7, 0xC0, 0xF8, 0x1F, 0x1F, 0x03, 0xE0, 0x7C, 0x7C, 0x0F, + 0x81, 0xE3, 0xE0, 0x7C, 0x0F, 0x8F, 0x81, 0xF0, 0x3E, 0x00, 0x0F, 0x8F, + 0x80, 0xFB, 0xFE, 0x0F, 0xFF, 0xF1, 0xFF, 0xFF, 0x1F, 0xC3, 0xF1, 0xF8, + 0x1F, 0x1F, 0x01, 0xF1, 0xF0, 0x1F, 0x3E, 0x01, 0xF3, 0xE0, 0x3E, 0x3E, + 0x03, 0xE3, 0xE0, 0x3E, 0x3C, 0x03, 0xE7, 0xC0, 0x3E, 0x7C, 0x07, 0xC7, + 0xC0, 0x7C, 0x7C, 0x07, 0xC7, 0x80, 0x7C, 0xF8, 0x07, 0x80, 0x00, 0xFE, + 0x00, 0x7F, 0xF0, 0x3F, 0xFF, 0x0F, 0xFF, 0xE3, 0xF8, 0xFE, 0x7C, 0x0F, + 0xDF, 0x00, 0xFB, 0xE0, 0x1F, 0xF8, 0x03, 0xFF, 0x00, 0x7F, 0xE0, 0x1F, + 0xFC, 0x03, 0xEF, 0x80, 0x7D, 0xF8, 0x1F, 0x3F, 0x07, 0xE3, 0xFF, 0xF8, + 0x7F, 0xFE, 0x07, 0xFF, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xE7, 0xE0, 0x0F, + 0xBF, 0xC0, 0x7D, 0xFF, 0x81, 0xFF, 0xFE, 0x07, 0xF0, 0xFC, 0x1F, 0x81, + 0xF0, 0x7C, 0x07, 0xC3, 0xE0, 0x1F, 0x0F, 0x80, 0x7C, 0x3E, 0x01, 0xF0, + 0xF0, 0x07, 0xC3, 0xC0, 0x3E, 0x1F, 0x00, 0xF8, 0x7E, 0x07, 0xC1, 0xFC, + 0x7F, 0x07, 0xFF, 0xF8, 0x1F, 0xFF, 0xC0, 0xFB, 0xFE, 0x03, 0xE7, 0xE0, + 0x0F, 0x80, 0x00, 0x3E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x1F, + 0x00, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x01, + 0xF1, 0xF0, 0x7F, 0xDF, 0x0F, 0xFD, 0xF1, 0xFF, 0xFE, 0x3F, 0x8F, 0xE3, + 0xE0, 0x7E, 0x7C, 0x03, 0xE7, 0xC0, 0x3E, 0xF8, 0x03, 0xCF, 0x80, 0x3C, + 0xF8, 0x07, 0xCF, 0x80, 0x7C, 0xF8, 0x0F, 0x8F, 0x81, 0xF8, 0xFC, 0x3F, + 0x87, 0xFF, 0xF8, 0x7F, 0xFF, 0x83, 0xFF, 0xF0, 0x1F, 0x9F, 0x00, 0x01, + 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, + 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x0F, 0x8E, 0x1F, 0x7C, 0x3F, + 0xF0, 0xFF, 0xE1, 0xFC, 0x03, 0xF0, 0x07, 0xC0, 0x0F, 0x80, 0x3E, 0x00, + 0x7C, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, 0x0F, 0x80, 0x1F, 0x00, 0x3E, + 0x00, 0x7C, 0x00, 0xF0, 0x03, 0xE0, 0x00, 0x01, 0xFC, 0x01, 0xFF, 0xC0, + 0xFF, 0xF8, 0x7F, 0xFF, 0x3F, 0x0F, 0xCF, 0x81, 0xF3, 0xF0, 0x00, 0xFF, + 0x80, 0x3F, 0xFC, 0x07, 0xFF, 0xC0, 0x7F, 0xF8, 0x03, 0xFE, 0x00, 0x1F, + 0xBE, 0x03, 0xEF, 0xC1, 0xFB, 0xFF, 0xFC, 0x7F, 0xFE, 0x0F, 0xFF, 0x00, + 0xFE, 0x00, 0x0F, 0x81, 0xF0, 0x7C, 0x0F, 0x81, 0xF0, 0xFF, 0xBF, 0xF7, + 0xFE, 0x3E, 0x07, 0xC0, 0xF8, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, + 0xF8, 0x1F, 0x03, 0xE0, 0x7F, 0x0F, 0xE1, 0xFC, 0x1F, 0x80, 0x1F, 0x01, + 0xF1, 0xF0, 0x1F, 0x3E, 0x03, 0xE3, 0xE0, 0x3E, 0x3E, 0x03, 0xE3, 0xE0, + 0x3E, 0x3E, 0x03, 0xE7, 0xC0, 0x7C, 0x7C, 0x07, 0xC7, 0xC0, 0x7C, 0x7C, + 0x07, 0xC7, 0xC0, 0x7C, 0xF8, 0x0F, 0x8F, 0x81, 0xF8, 0xF8, 0x3F, 0x8F, + 0xFF, 0xF8, 0xFF, 0xFF, 0x07, 0xFD, 0xF0, 0x3F, 0x1F, 0x00, 0xF8, 0x0F, + 0xFE, 0x03, 0xEF, 0x81, 0xF3, 0xE0, 0x7C, 0xF8, 0x3E, 0x3E, 0x0F, 0x8F, + 0x87, 0xC1, 0xE1, 0xF0, 0x78, 0xF8, 0x1E, 0x3E, 0x07, 0x9F, 0x01, 0xF7, + 0x80, 0x7F, 0xE0, 0x1F, 0xF0, 0x03, 0xFC, 0x00, 0xFE, 0x00, 0x3F, 0x80, + 0x0F, 0xC0, 0x03, 0xF0, 0x00, 0xF8, 0x1F, 0x07, 0xFF, 0x03, 0xE0, 0xFB, + 0xE0, 0xFC, 0x1F, 0x7C, 0x1F, 0x87, 0xCF, 0x87, 0xF0, 0xF9, 0xF0, 0xFE, + 0x3E, 0x3E, 0x3D, 0xC7, 0xC3, 0xC7, 0xB9, 0xF0, 0x79, 0xE7, 0x3E, 0x0F, + 0x3C, 0xE7, 0x81, 0xEF, 0x1D, 0xF0, 0x3D, 0xE3, 0xBC, 0x07, 0xBC, 0x7F, + 0x80, 0xFF, 0x0F, 0xE0, 0x1F, 0xE1, 0xFC, 0x03, 0xF8, 0x3F, 0x00, 0x7F, + 0x07, 0xE0, 0x0F, 0xC0, 0xF8, 0x01, 0xF8, 0x1F, 0x00, 0x00, 0x0F, 0xC1, + 0xF8, 0x3F, 0x07, 0xC0, 0x7C, 0x3E, 0x01, 0xF9, 0xF8, 0x03, 0xEF, 0xC0, + 0x0F, 0xBE, 0x00, 0x1F, 0xF0, 0x00, 0x7F, 0x80, 0x01, 0xFC, 0x00, 0x03, + 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0x00, 0x07, 0xFE, 0x00, 0x3E, 0xF8, + 0x01, 0xFB, 0xF0, 0x07, 0xC7, 0xC0, 0x3E, 0x1F, 0x81, 0xF8, 0x7E, 0x0F, + 0xC0, 0xF8, 0x00, 0x1F, 0x80, 0x7C, 0x3E, 0x03, 0xE0, 0xF8, 0x0F, 0x03, + 0xE0, 0x7C, 0x0F, 0x81, 0xE0, 0x3E, 0x0F, 0x80, 0xF8, 0x3C, 0x03, 0xE1, + 0xF0, 0x07, 0x87, 0x80, 0x1F, 0x3E, 0x00, 0x7C, 0xF0, 0x01, 0xF7, 0xC0, + 0x07, 0xDE, 0x00, 0x1F, 0xF0, 0x00, 0x7F, 0xC0, 0x01, 0xFE, 0x00, 0x03, + 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, + 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x00, 0x01, + 0xF8, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x0F, 0xFF, 0xE1, 0xFF, 0xFC, 0x3F, + 0xFF, 0x87, 0xFF, 0xE0, 0x00, 0xFC, 0x00, 0x3F, 0x00, 0x0F, 0xC0, 0x03, + 0xF0, 0x01, 0xFC, 0x00, 0x7E, 0x00, 0x1F, 0x80, 0x07, 0xE0, 0x01, 0xF8, + 0x00, 0x7E, 0x00, 0x1F, 0x80, 0x07, 0xFF, 0xF8, 0xFF, 0xFF, 0x1F, 0xFF, + 0xE3, 0xFF, 0xFC, 0x00, 0x00, 0x7C, 0x03, 0xF0, 0x1F, 0xC0, 0xFE, 0x03, + 0xE0, 0x0F, 0x00, 0x3C, 0x00, 0xF0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, + 0xE0, 0x0F, 0x80, 0x3C, 0x01, 0xF0, 0x1F, 0x80, 0x70, 0x01, 0xF8, 0x01, + 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x03, 0xC0, 0x0F, 0x00, 0x3C, 0x00, + 0xF0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, 0xFC, 0x07, 0xE0, 0x0F, 0x80, + 0x1E, 0x00, 0x03, 0x81, 0xC0, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0C, 0x0E, + 0x07, 0x03, 0x81, 0xC0, 0xC0, 0xE0, 0x70, 0x38, 0x18, 0x1C, 0x0E, 0x07, + 0x03, 0x81, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x18, 0x1C, 0x0E, 0x07, 0x01, + 0x80, 0x80, 0x00, 0x00, 0x01, 0xE0, 0x07, 0xC0, 0x1F, 0x80, 0xFE, 0x00, + 0x78, 0x01, 0xE0, 0x07, 0x80, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x00, + 0x78, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x7E, 0x00, 0x38, 0x07, 0xE0, + 0x3E, 0x00, 0xF0, 0x07, 0xC0, 0x1E, 0x00, 0x78, 0x01, 0xE0, 0x07, 0x80, + 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x1F, 0x01, 0xF8, 0x0F, 0xE0, 0x3F, 0x00, + 0xF8, 0x00, 0x0F, 0x00, 0x1F, 0xC1, 0xDF, 0xF0, 0xEE, 0x3F, 0xE6, 0x07, + 0xF0, 0x01, 0xE0 }; + +const GFXglyph FreeSansBoldOblique18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 10, 0, 1 }, // 0x20 ' ' + { 0, 10, 25, 12, 4, -24 }, // 0x21 '!' + { 32, 13, 9, 17, 6, -25 }, // 0x22 '"' + { 47, 22, 24, 19, 1, -23 }, // 0x23 '#' + { 113, 19, 31, 19, 2, -26 }, // 0x24 '$' + { 187, 26, 26, 31, 5, -25 }, // 0x25 '%' + { 272, 21, 25, 25, 3, -24 }, // 0x26 '&' + { 338, 5, 9, 8, 6, -25 }, // 0x27 ''' + { 344, 13, 33, 12, 3, -25 }, // 0x28 '(' + { 398, 13, 33, 12, -1, -25 }, // 0x29 ')' + { 452, 12, 11, 14, 5, -25 }, // 0x2A '*' + { 469, 18, 16, 20, 3, -15 }, // 0x2B '+' + { 505, 7, 11, 10, 1, -4 }, // 0x2C ',' + { 515, 10, 4, 12, 2, -10 }, // 0x2D '-' + { 520, 6, 5, 10, 2, -4 }, // 0x2E '.' + { 524, 15, 25, 10, 0, -24 }, // 0x2F '/' + { 571, 18, 25, 19, 3, -24 }, // 0x30 '0' + { 628, 13, 25, 19, 6, -24 }, // 0x31 '1' + { 669, 21, 25, 19, 1, -24 }, // 0x32 '2' + { 735, 20, 25, 19, 2, -24 }, // 0x33 '3' + { 798, 19, 25, 19, 2, -24 }, // 0x34 '4' + { 858, 20, 24, 19, 2, -23 }, // 0x35 '5' + { 918, 19, 25, 19, 3, -24 }, // 0x36 '6' + { 978, 19, 24, 19, 5, -23 }, // 0x37 '7' + { 1035, 20, 25, 19, 2, -24 }, // 0x38 '8' + { 1098, 19, 25, 19, 2, -24 }, // 0x39 '9' + { 1158, 9, 18, 12, 4, -17 }, // 0x3A ':' + { 1179, 10, 24, 12, 3, -17 }, // 0x3B ';' + { 1209, 19, 17, 20, 3, -16 }, // 0x3C '<' + { 1250, 20, 12, 20, 2, -13 }, // 0x3D '=' + { 1280, 19, 17, 20, 1, -15 }, // 0x3E '>' + { 1321, 18, 26, 21, 6, -25 }, // 0x3F '?' + { 1380, 33, 31, 34, 3, -25 }, // 0x40 '@' + { 1508, 23, 26, 25, 1, -25 }, // 0x41 'A' + { 1583, 24, 26, 25, 3, -25 }, // 0x42 'B' + { 1661, 24, 26, 25, 4, -25 }, // 0x43 'C' + { 1739, 24, 26, 25, 3, -25 }, // 0x44 'D' + { 1817, 24, 26, 23, 3, -25 }, // 0x45 'E' + { 1895, 23, 26, 21, 3, -25 }, // 0x46 'F' + { 1970, 24, 26, 27, 4, -25 }, // 0x47 'G' + { 2048, 26, 26, 25, 2, -25 }, // 0x48 'H' + { 2133, 10, 26, 10, 2, -25 }, // 0x49 'I' + { 2166, 20, 26, 19, 2, -25 }, // 0x4A 'J' + { 2231, 26, 26, 25, 3, -25 }, // 0x4B 'K' + { 2316, 18, 26, 21, 3, -25 }, // 0x4C 'L' + { 2375, 31, 26, 29, 2, -25 }, // 0x4D 'M' + { 2476, 27, 26, 25, 2, -25 }, // 0x4E 'N' + { 2564, 25, 26, 27, 4, -25 }, // 0x4F 'O' + { 2646, 23, 26, 23, 3, -25 }, // 0x50 'P' + { 2721, 25, 27, 27, 4, -25 }, // 0x51 'Q' + { 2806, 24, 26, 25, 3, -25 }, // 0x52 'R' + { 2884, 22, 26, 23, 3, -25 }, // 0x53 'S' + { 2956, 21, 26, 21, 5, -25 }, // 0x54 'T' + { 3025, 24, 26, 25, 4, -25 }, // 0x55 'U' + { 3103, 22, 26, 23, 6, -25 }, // 0x56 'V' + { 3175, 32, 26, 33, 6, -25 }, // 0x57 'W' + { 3279, 27, 26, 23, 1, -25 }, // 0x58 'X' + { 3367, 22, 26, 23, 6, -25 }, // 0x59 'Y' + { 3439, 25, 26, 21, 1, -25 }, // 0x5A 'Z' + { 3521, 15, 33, 12, 1, -25 }, // 0x5B '[' + { 3583, 5, 25, 10, 5, -24 }, // 0x5C '\' + { 3599, 15, 33, 12, -1, -25 }, // 0x5D ']' + { 3661, 16, 15, 20, 4, -23 }, // 0x5E '^' + { 3691, 21, 3, 19, -2, 5 }, // 0x5F '_' + { 3699, 5, 5, 12, 6, -25 }, // 0x60 '`' + { 3703, 18, 19, 19, 2, -18 }, // 0x61 'a' + { 3746, 20, 26, 21, 2, -25 }, // 0x62 'b' + { 3811, 18, 19, 19, 3, -18 }, // 0x63 'c' + { 3854, 22, 26, 21, 3, -25 }, // 0x64 'd' + { 3926, 19, 19, 19, 2, -18 }, // 0x65 'e' + { 3972, 13, 26, 12, 3, -25 }, // 0x66 'f' + { 4015, 22, 27, 21, 1, -18 }, // 0x67 'g' + { 4090, 20, 26, 21, 2, -25 }, // 0x68 'h' + { 4155, 10, 26, 10, 2, -25 }, // 0x69 'i' + { 4188, 15, 34, 10, -2, -25 }, // 0x6A 'j' + { 4252, 21, 26, 19, 2, -25 }, // 0x6B 'k' + { 4321, 10, 26, 10, 2, -25 }, // 0x6C 'l' + { 4354, 30, 19, 31, 2, -18 }, // 0x6D 'm' + { 4426, 20, 19, 21, 2, -18 }, // 0x6E 'n' + { 4474, 19, 19, 21, 3, -18 }, // 0x6F 'o' + { 4520, 22, 27, 21, 0, -18 }, // 0x70 'p' + { 4595, 20, 27, 21, 3, -18 }, // 0x71 'q' + { 4663, 15, 19, 14, 2, -18 }, // 0x72 'r' + { 4699, 18, 19, 19, 2, -18 }, // 0x73 's' + { 4742, 11, 23, 12, 4, -22 }, // 0x74 't' + { 4774, 20, 19, 21, 3, -18 }, // 0x75 'u' + { 4822, 18, 19, 19, 5, -18 }, // 0x76 'v' + { 4865, 27, 19, 27, 4, -18 }, // 0x77 'w' + { 4930, 22, 19, 19, 1, -18 }, // 0x78 'x' + { 4983, 22, 27, 19, 1, -18 }, // 0x79 'y' + { 5058, 19, 19, 17, 1, -18 }, // 0x7A 'z' + { 5104, 14, 33, 14, 2, -25 }, // 0x7B '{' + { 5162, 9, 33, 10, 2, -25 }, // 0x7C '|' + { 5200, 14, 33, 14, 2, -25 }, // 0x7D '}' + { 5258, 17, 6, 20, 3, -10 } }; // 0x7E '~' + +const GFXfont FreeSansBoldOblique18pt7b PROGMEM = { + (uint8_t *)FreeSansBoldOblique18pt7bBitmaps, + (GFXglyph *)FreeSansBoldOblique18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 5943 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique24pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique24pt7b.h new file mode 100644 index 0000000..ea65f9b --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique24pt7b.h @@ -0,0 +1,893 @@ +const uint8_t FreeSansBoldOblique24pt7bBitmaps[] PROGMEM = { + 0x01, 0xE0, 0x07, 0xF0, 0x1F, 0xC0, 0xFF, 0x03, 0xF8, 0x0F, 0xE0, 0x3F, + 0x80, 0xFE, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xE0, 0x1F, + 0x80, 0x7E, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0xF8, 0x03, 0xE0, 0x0F, + 0x80, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x1F, + 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0xFE, 0x03, 0xF8, 0x00, + 0x7E, 0x0F, 0xDF, 0x83, 0xF7, 0xE0, 0xFF, 0xF0, 0x7E, 0xFC, 0x1F, 0xBF, + 0x07, 0xEF, 0xC1, 0xFB, 0xE0, 0x7C, 0xF8, 0x1F, 0x3C, 0x07, 0x8F, 0x01, + 0xE3, 0x80, 0x70, 0x00, 0x07, 0xC1, 0xF0, 0x00, 0x3E, 0x0F, 0x80, 0x03, + 0xE0, 0xF8, 0x00, 0x1F, 0x07, 0xC0, 0x01, 0xF0, 0x7C, 0x00, 0x0F, 0x83, + 0xE0, 0x00, 0xF8, 0x3E, 0x00, 0xFF, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xF8, + 0x7F, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xE0, 0x0F, + 0x83, 0xE0, 0x00, 0x7C, 0x3E, 0x00, 0x07, 0xC1, 0xF0, 0x00, 0x3E, 0x0F, + 0x80, 0x03, 0xE0, 0xF8, 0x00, 0x1F, 0x07, 0xC0, 0x00, 0xF8, 0x7C, 0x00, + 0xFF, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, 0xFF, 0x83, 0xFF, + 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0xE0, 0x1F, 0x07, 0xC0, 0x00, 0xF8, 0x3E, + 0x00, 0x0F, 0x83, 0xE0, 0x00, 0x7C, 0x1F, 0x00, 0x07, 0xC1, 0xF0, 0x00, + 0x3E, 0x0F, 0x80, 0x01, 0xF0, 0xF8, 0x00, 0x1F, 0x07, 0xC0, 0x00, 0xF8, + 0x3C, 0x00, 0x00, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x38, 0x00, 0x00, 0x0E, + 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x7F, 0xFF, 0x00, 0x3F, 0xFF, 0xE0, 0x1F, + 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0x07, 0xF3, 0x9F, 0xC1, 0xF8, 0xE3, 0xF0, + 0x7C, 0x38, 0xFC, 0x3F, 0x0E, 0x3F, 0x0F, 0xC7, 0x8F, 0xC3, 0xF1, 0xC0, + 0x00, 0xFE, 0x70, 0x00, 0x3F, 0xDC, 0x00, 0x0F, 0xFF, 0x00, 0x01, 0xFF, + 0xE0, 0x00, 0x3F, 0xFE, 0x00, 0x0F, 0xFF, 0xE0, 0x00, 0xFF, 0xFC, 0x00, + 0x0F, 0xFF, 0x00, 0x01, 0xFF, 0xE0, 0x00, 0x77, 0xF8, 0x00, 0x1C, 0xFE, + 0x00, 0x07, 0x3F, 0x8F, 0xE3, 0xCF, 0xE3, 0xF8, 0xE3, 0xF8, 0xFE, 0x38, + 0xFC, 0x3F, 0x8E, 0x7F, 0x0F, 0xF3, 0x9F, 0xC3, 0xFD, 0xFF, 0xE0, 0x7F, + 0xFF, 0xF0, 0x1F, 0xFF, 0xFC, 0x03, 0xFF, 0xFC, 0x00, 0x7F, 0xFE, 0x00, + 0x03, 0xFC, 0x00, 0x00, 0x38, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x03, 0x80, + 0x00, 0x01, 0xE0, 0x00, 0x00, 0x70, 0x00, 0x00, 0x01, 0xF8, 0x00, 0x07, + 0x80, 0x7F, 0xE0, 0x00, 0xF0, 0x0F, 0xFF, 0x00, 0x1E, 0x01, 0xFF, 0xF0, + 0x01, 0xC0, 0x3F, 0xFF, 0x80, 0x3C, 0x07, 0xE1, 0xF8, 0x07, 0x80, 0x78, + 0x07, 0x80, 0xF0, 0x0F, 0x80, 0x78, 0x0E, 0x00, 0xF0, 0x07, 0x81, 0xC0, + 0x0F, 0x00, 0xF8, 0x3C, 0x00, 0xF0, 0x0F, 0x07, 0x80, 0x0F, 0xC3, 0xF0, + 0xF0, 0x00, 0xFF, 0xFE, 0x0E, 0x00, 0x07, 0xFF, 0xC1, 0xE0, 0x00, 0x7F, + 0xF8, 0x3C, 0x00, 0x03, 0xFF, 0x07, 0x80, 0x00, 0x0F, 0xC0, 0x70, 0x00, + 0x00, 0x00, 0x0E, 0x03, 0xF0, 0x00, 0x01, 0xE0, 0xFF, 0xC0, 0x00, 0x3C, + 0x1F, 0xFE, 0x00, 0x03, 0x83, 0xFF, 0xE0, 0x00, 0x70, 0x7F, 0xFF, 0x00, + 0x0F, 0x0F, 0xC3, 0xF0, 0x01, 0xE0, 0xF0, 0x0F, 0x00, 0x3C, 0x1F, 0x00, + 0xF0, 0x03, 0x81, 0xE0, 0x0F, 0x00, 0x78, 0x1E, 0x01, 0xF0, 0x0F, 0x01, + 0xE0, 0x1E, 0x01, 0xE0, 0x1F, 0x87, 0xE0, 0x1C, 0x01, 0xFF, 0xFC, 0x03, + 0x80, 0x0F, 0xFF, 0x80, 0x78, 0x00, 0xFF, 0xF0, 0x0F, 0x00, 0x07, 0xFE, + 0x01, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x3F, 0xF0, + 0x00, 0x07, 0xFF, 0xC0, 0x00, 0x7F, 0xFF, 0x00, 0x03, 0xFF, 0xF8, 0x00, + 0x3F, 0x9F, 0xC0, 0x03, 0xF8, 0x7E, 0x00, 0x1F, 0xC3, 0xF0, 0x00, 0xFE, + 0x1F, 0x00, 0x07, 0xF1, 0xF8, 0x00, 0x3F, 0xCF, 0xC0, 0x01, 0xFE, 0xFC, + 0x00, 0x07, 0xFF, 0xC0, 0x00, 0x3F, 0xFC, 0x00, 0x00, 0xFF, 0xC0, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x1F, 0xFF, 0x07, 0xC1, 0xFF, + 0xF8, 0x3E, 0x3F, 0xFF, 0xE3, 0xE3, 0xFE, 0x3F, 0x1F, 0x1F, 0xC1, 0xFD, + 0xF1, 0xFC, 0x07, 0xFF, 0x8F, 0xC0, 0x3F, 0xF8, 0xFE, 0x00, 0xFF, 0xC7, + 0xF0, 0x07, 0xFC, 0x3F, 0x80, 0x1F, 0xC1, 0xFC, 0x00, 0xFE, 0x0F, 0xF0, + 0x1F, 0xF8, 0x7F, 0xC1, 0xFF, 0xC1, 0xFF, 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, + 0xFC, 0x3F, 0xFF, 0xCF, 0xE0, 0x7F, 0xF8, 0x7F, 0x80, 0xFF, 0x00, 0x00, + 0x7E, 0xFD, 0xFF, 0xEF, 0xDF, 0xBF, 0x7C, 0xF9, 0xE3, 0xC7, 0x00, 0x00, + 0x0F, 0x80, 0x0F, 0x80, 0x0F, 0x80, 0x0F, 0xC0, 0x07, 0xC0, 0x07, 0xC0, + 0x07, 0xE0, 0x03, 0xE0, 0x03, 0xE0, 0x03, 0xF0, 0x01, 0xF0, 0x01, 0xF8, + 0x00, 0xF8, 0x00, 0xFC, 0x00, 0x7C, 0x00, 0x7E, 0x00, 0x3E, 0x00, 0x1F, + 0x00, 0x1F, 0x80, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x03, 0xF0, 0x01, + 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, + 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x1E, + 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x3E, 0x00, 0x1F, 0x00, 0x07, 0x80, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, + 0x1E, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x7C, + 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x07, 0x80, 0x03, 0xE0, 0x01, 0xF0, 0x00, + 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, + 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, + 0x00, 0x1F, 0x00, 0x1F, 0x80, 0x0F, 0x80, 0x07, 0xC0, 0x07, 0xE0, 0x03, + 0xE0, 0x03, 0xF0, 0x01, 0xF0, 0x01, 0xF8, 0x00, 0xF8, 0x00, 0xFC, 0x00, + 0x7C, 0x00, 0x7C, 0x00, 0x7E, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x3F, 0x00, + 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x00, 0x01, 0xE0, 0x03, 0x80, 0x07, + 0x00, 0x0E, 0x07, 0x3C, 0x6F, 0xFF, 0xFF, 0xFF, 0xBF, 0xFE, 0x0F, 0xE0, + 0x1F, 0xC0, 0x7F, 0x81, 0xEF, 0x87, 0x8F, 0x0E, 0x1E, 0x08, 0x10, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, + 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFE, + 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFE, 0x00, 0xFC, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0xFC, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF8, 0x00, + 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0xC7, 0xF1, 0xF8, 0xFE, 0x3F, + 0x8F, 0xE0, 0x38, 0x1C, 0x07, 0x03, 0xC0, 0xE0, 0xF0, 0xFC, 0x3C, 0x0C, + 0x00, 0x7F, 0xFD, 0xFF, 0xF7, 0xFF, 0x9F, 0xFE, 0xFF, 0xFB, 0xFF, 0xE0, + 0x7F, 0x7F, 0x7F, 0x7E, 0xFE, 0xFE, 0xFE, 0x00, 0x00, 0x70, 0x00, 0x0E, + 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x03, + 0x80, 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x01, + 0xC0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, + 0x70, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, + 0x38, 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, + 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, + 0x07, 0x00, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x00, 0x00, 0x0F, 0xE0, 0x00, + 0x1F, 0xFC, 0x00, 0x3F, 0xFF, 0x80, 0x3F, 0xFF, 0xC0, 0x3F, 0xFF, 0xF0, + 0x1F, 0xC7, 0xF8, 0x1F, 0xC1, 0xFE, 0x1F, 0xC0, 0x7F, 0x0F, 0xC0, 0x3F, + 0x8F, 0xE0, 0x1F, 0xC7, 0xF0, 0x0F, 0xE3, 0xF0, 0x07, 0xF3, 0xF8, 0x03, + 0xF9, 0xFC, 0x01, 0xFC, 0xFC, 0x01, 0xFE, 0xFE, 0x00, 0xFE, 0x7F, 0x00, + 0x7F, 0x3F, 0x80, 0x3F, 0x9F, 0xC0, 0x1F, 0xCF, 0xE0, 0x1F, 0xEF, 0xE0, + 0x0F, 0xE7, 0xF0, 0x07, 0xF3, 0xF8, 0x03, 0xF9, 0xFC, 0x03, 0xF8, 0xFE, + 0x01, 0xFC, 0x7F, 0x00, 0xFE, 0x3F, 0x80, 0xFE, 0x1F, 0xE0, 0x7F, 0x0F, + 0xF8, 0xFF, 0x03, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0x80, + 0x1F, 0xFF, 0x00, 0x07, 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x00, 0x0F, + 0x80, 0x0F, 0x80, 0x07, 0xC0, 0x07, 0xE0, 0x0F, 0xF0, 0x3F, 0xF9, 0xFF, + 0xF8, 0xFF, 0xFC, 0xFF, 0xFE, 0x7F, 0xFF, 0x00, 0x3F, 0x80, 0x1F, 0x80, + 0x0F, 0xC0, 0x0F, 0xE0, 0x07, 0xF0, 0x03, 0xF8, 0x01, 0xF8, 0x01, 0xFC, + 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x3F, 0x00, 0x1F, 0x80, 0x1F, 0xC0, 0x0F, + 0xE0, 0x07, 0xF0, 0x03, 0xF0, 0x01, 0xF8, 0x01, 0xFC, 0x00, 0xFE, 0x00, + 0x7F, 0x00, 0x3F, 0x00, 0x3F, 0x80, 0x1F, 0xC0, 0x00, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x7F, 0xFC, 0x00, 0x0F, 0xFF, 0xF8, 0x00, 0xFF, 0xFF, 0xE0, + 0x0F, 0xFF, 0xFF, 0x00, 0xFF, 0x07, 0xFC, 0x07, 0xF0, 0x1F, 0xE0, 0x7F, + 0x00, 0x7F, 0x03, 0xF0, 0x03, 0xF8, 0x1F, 0x80, 0x1F, 0xC1, 0xF8, 0x00, + 0xFE, 0x0F, 0xC0, 0x0F, 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x07, 0xF0, + 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x7F, 0x80, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x1F, 0xF8, 0x00, 0x01, 0xFF, + 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0x7F, 0xC0, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x7F, + 0x80, 0x00, 0x03, 0xFF, 0xFF, 0xF0, 0x3F, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, + 0xFC, 0x1F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xF0, + 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x0F, 0xFF, 0x80, 0x0F, 0xFF, 0xF0, 0x07, + 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xC0, 0xFE, 0x1F, 0xF0, 0x7F, 0x01, 0xFC, + 0x1F, 0x80, 0x7F, 0x07, 0xE0, 0x1F, 0xC3, 0xF0, 0x07, 0xF0, 0xFC, 0x01, + 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0x80, 0x01, + 0xFF, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x1F, 0xFC, 0x00, 0x07, 0xFF, 0x80, + 0x01, 0xFF, 0xE0, 0x00, 0x07, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x07, 0xF0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x7F, 0x3F, 0x80, + 0x3F, 0xCF, 0xE0, 0x0F, 0xE3, 0xF8, 0x07, 0xF8, 0xFF, 0x83, 0xFC, 0x3F, + 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xE0, + 0x03, 0xFF, 0xE0, 0x00, 0x3F, 0xC0, 0x00, 0x00, 0x00, 0x7F, 0x80, 0x00, + 0x7F, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0xF0, 0x00, + 0x3F, 0xF8, 0x00, 0x3D, 0xFC, 0x00, 0x3C, 0xFE, 0x00, 0x3E, 0x7E, 0x00, + 0x3E, 0x7F, 0x00, 0x1E, 0x3F, 0x80, 0x1E, 0x1F, 0xC0, 0x1E, 0x0F, 0xC0, + 0x1F, 0x07, 0xE0, 0x1F, 0x07, 0xF0, 0x1F, 0x03, 0xF8, 0x1F, 0x01, 0xFC, + 0x0F, 0x80, 0xFC, 0x0F, 0x80, 0xFE, 0x0F, 0x80, 0x7F, 0x07, 0xFF, 0xFF, + 0xF7, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, 0xFD, 0xFF, 0xFF, 0xFC, 0xFF, 0xFF, + 0xFE, 0x00, 0x03, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0x80, 0x00, + 0x7F, 0xFF, 0xE0, 0x0F, 0xFF, 0xFC, 0x01, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, + 0xF0, 0x0F, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x80, 0x7C, 0x00, 0x00, 0x0F, + 0x80, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x03, 0xE3, 0xF0, 0x00, 0x7F, 0xFF, 0x80, 0x1F, 0xFF, 0xF8, 0x03, 0xFF, + 0xFF, 0x80, 0x7F, 0xFF, 0xF0, 0x1F, 0xE1, 0xFF, 0x03, 0xF0, 0x1F, 0xE0, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xF0, 0xFE, 0x00, 0xFE, 0x1F, + 0xC0, 0x3F, 0x83, 0xF8, 0x07, 0xF0, 0x7F, 0x83, 0xFC, 0x0F, 0xFF, 0xFF, + 0x80, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xF8, 0x01, 0xFF, 0xFE, 0x00, 0x0F, + 0xFF, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xFE, + 0x00, 0x1F, 0xFF, 0x80, 0x1F, 0xFF, 0xE0, 0x1F, 0xFF, 0xF8, 0x1F, 0xC3, + 0xFC, 0x1F, 0x80, 0xFE, 0x0F, 0xC0, 0x3F, 0x0F, 0xC0, 0x00, 0x07, 0xE0, + 0x00, 0x07, 0xE0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xF8, 0xFC, 0x01, 0xF9, + 0xFF, 0x80, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xF8, 0x7F, 0xFF, 0xFC, 0x3F, + 0xE1, 0xFF, 0x1F, 0xE0, 0x7F, 0x8F, 0xE0, 0x1F, 0xCF, 0xE0, 0x0F, 0xE7, + 0xF0, 0x07, 0xF3, 0xF0, 0x03, 0xF9, 0xF8, 0x01, 0xF8, 0xFC, 0x01, 0xFC, + 0x7E, 0x00, 0xFE, 0x3F, 0x00, 0xFE, 0x1F, 0xC0, 0xFF, 0x0F, 0xF0, 0xFF, + 0x03, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0x80, 0x1F, 0xFF, + 0x80, 0x07, 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x3F, 0xFF, 0xFF, 0xCF, + 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, 0xF8, 0xFF, 0xFF, 0xFE, 0x7F, 0xFF, 0xFF, + 0x9F, 0xFF, 0xFF, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x1F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03, 0xF0, 0x00, 0x01, 0xF8, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x0F, 0xE0, + 0x00, 0x03, 0xF0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, + 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xF0, 0x00, 0x01, 0xF8, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xF0, 0x00, + 0x01, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x00, 0x00, 0x07, 0xF0, 0x00, + 0x0F, 0xFF, 0x80, 0x07, 0xFF, 0xF0, 0x03, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, + 0xC0, 0xFE, 0x0F, 0xF0, 0x3E, 0x01, 0xFC, 0x1F, 0x80, 0x3F, 0x07, 0xC0, + 0x0F, 0xC1, 0xF0, 0x03, 0xF0, 0x7C, 0x01, 0xF8, 0x1F, 0x00, 0xFC, 0x03, + 0xF0, 0x7F, 0x00, 0xFF, 0xFF, 0x00, 0x1F, 0xFF, 0x80, 0x07, 0xFF, 0xE0, + 0x07, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0x81, 0xFE, 0x1F, 0xE0, 0xFE, 0x03, + 0xFC, 0x3F, 0x00, 0x7F, 0x1F, 0xC0, 0x1F, 0xC7, 0xE0, 0x07, 0xF3, 0xF8, + 0x01, 0xFC, 0xFE, 0x00, 0x7F, 0x3F, 0x80, 0x3F, 0x8F, 0xE0, 0x0F, 0xE3, + 0xFC, 0x07, 0xF0, 0xFF, 0x87, 0xFC, 0x3F, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, + 0x00, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xC0, 0x03, 0xFF, 0xE0, 0x00, 0x3F, + 0xC0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xFC, 0x00, 0x3F, 0xFF, 0x00, + 0x3F, 0xFF, 0xC0, 0x3F, 0xFF, 0xF0, 0x3F, 0xC3, 0xF8, 0x3F, 0xC0, 0xFE, + 0x1F, 0xC0, 0x3F, 0x1F, 0xC0, 0x1F, 0x8F, 0xE0, 0x0F, 0xC7, 0xE0, 0x07, + 0xE7, 0xF0, 0x03, 0xF3, 0xF8, 0x01, 0xF9, 0xFC, 0x01, 0xFC, 0xFE, 0x00, + 0xFE, 0x7F, 0x00, 0xFE, 0x3F, 0xC0, 0xFF, 0x1F, 0xF0, 0xFF, 0x87, 0xFF, + 0xFF, 0xC3, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xE0, 0x3F, 0xF3, 0xF0, 0x07, + 0xE3, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0x7E, 0x1F, 0xC0, 0x7E, 0x0F, 0xF0, 0xFF, 0x07, 0xFF, 0xFF, 0x01, + 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0x00, 0x3F, 0xFF, 0x00, 0x0F, 0xFF, 0x00, + 0x01, 0xFC, 0x00, 0x00, 0x07, 0xF0, 0x7F, 0x07, 0xF0, 0x7E, 0x0F, 0xE0, + 0xFE, 0x0F, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0x07, 0xF0, 0x7F, 0x07, + 0xE0, 0xFE, 0x0F, 0xE0, 0xFE, 0x00, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, + 0x7E, 0x03, 0xF8, 0x0F, 0xE0, 0x3F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0x80, 0xFE, 0x03, 0xF8, 0x0F, 0xE0, + 0x03, 0x80, 0x1C, 0x00, 0x70, 0x03, 0xC0, 0x0E, 0x00, 0xF0, 0x0F, 0xC0, + 0x3C, 0x00, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0xE0, 0x00, + 0x01, 0xF8, 0x00, 0x03, 0xFE, 0x00, 0x07, 0xFF, 0x80, 0x0F, 0xFF, 0xE0, + 0x1F, 0xFF, 0xF0, 0x1F, 0xFF, 0xE0, 0x3F, 0xFF, 0xC0, 0x1F, 0xFF, 0x80, + 0x0F, 0xFF, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFF, 0xE0, 0x00, 0x3F, 0xFE, + 0x00, 0x0F, 0xFF, 0xF0, 0x00, 0xFF, 0xFF, 0x80, 0x07, 0xFF, 0xF8, 0x00, + 0x7F, 0xFF, 0x00, 0x03, 0xFF, 0xC0, 0x00, 0x3F, 0xF0, 0x00, 0x01, 0xF8, + 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x80, 0x1F, 0xFF, 0xFF, 0xC7, 0xFF, + 0xFF, 0xF1, 0xFF, 0xFF, 0xFC, 0x7F, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, 0x8F, + 0xFF, 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, + 0xFF, 0x1F, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0xF8, 0xFF, + 0xFF, 0xFE, 0x3F, 0xFF, 0xFF, 0x80, 0x04, 0x00, 0x00, 0x01, 0xE0, 0x00, + 0x00, 0x7E, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x0F, 0xFF, 0x00, 0x03, 0xFF, + 0xF8, 0x00, 0x7F, 0xFF, 0x80, 0x07, 0xFF, 0xFC, 0x00, 0x3F, 0xFF, 0xC0, + 0x01, 0xFF, 0xF0, 0x00, 0x1F, 0xFC, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xFF, + 0xC0, 0x07, 0xFF, 0xE0, 0x0F, 0xFF, 0xF0, 0x1F, 0xFF, 0xE0, 0x3F, 0xFF, + 0xE0, 0x1F, 0xFF, 0xC0, 0x07, 0xFF, 0x80, 0x01, 0xFF, 0x00, 0x00, 0x7E, + 0x00, 0x00, 0x1C, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x3F, 0x80, + 0x01, 0xFF, 0xF0, 0x07, 0xFF, 0xF8, 0x0F, 0xFF, 0xFC, 0x1F, 0xFF, 0xFE, + 0x1F, 0xFF, 0xFE, 0x3F, 0xC1, 0xFF, 0x3F, 0x80, 0xFF, 0x7F, 0x00, 0x7F, + 0x7E, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xFC, 0x00, 0x0F, 0xF8, + 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0x7F, 0x80, 0x00, 0xFE, 0x00, + 0x01, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xE0, 0x00, + 0x0F, 0xE0, 0x00, 0x0F, 0xE0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, + 0x1F, 0xC0, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xC0, 0x00, + 0x00, 0x00, 0x7F, 0xFF, 0xC0, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0x80, 0x00, + 0x01, 0xFF, 0xFF, 0xFE, 0x00, 0x00, 0x3F, 0xE0, 0x1F, 0xF8, 0x00, 0x07, + 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0x80, 0x07, 0xE0, + 0x00, 0x00, 0xFE, 0x00, 0xFE, 0x00, 0x00, 0x03, 0xF0, 0x0F, 0xC0, 0x00, + 0x00, 0x0F, 0x80, 0xFC, 0x00, 0x00, 0x00, 0x3E, 0x07, 0xC0, 0x03, 0xF1, + 0xF1, 0xF0, 0x7C, 0x00, 0xFF, 0xCF, 0x07, 0x87, 0xE0, 0x1F, 0xFF, 0xF8, + 0x3C, 0x7E, 0x01, 0xF8, 0x7F, 0x81, 0xE3, 0xE0, 0x1F, 0x01, 0xF8, 0x0F, + 0x3E, 0x01, 0xF0, 0x0F, 0xC0, 0x79, 0xF0, 0x1F, 0x00, 0x7C, 0x03, 0xDF, + 0x00, 0xF0, 0x03, 0xE0, 0x1C, 0xF8, 0x0F, 0x80, 0x1E, 0x01, 0xE7, 0xC0, + 0x78, 0x00, 0xF0, 0x0F, 0x3C, 0x07, 0xC0, 0x0F, 0x00, 0xF3, 0xE0, 0x3C, + 0x00, 0x78, 0x07, 0x9F, 0x03, 0xE0, 0x07, 0x80, 0x78, 0xF8, 0x1F, 0x00, + 0x7C, 0x07, 0xC7, 0xC0, 0xF8, 0x07, 0xC0, 0x7C, 0x3E, 0x07, 0xC0, 0x7E, + 0x07, 0xC1, 0xF0, 0x3F, 0x07, 0xF8, 0xFC, 0x0F, 0x81, 0xFF, 0xFF, 0xFF, + 0xC0, 0x7E, 0x07, 0xFF, 0xBF, 0xFC, 0x01, 0xF0, 0x1F, 0xF8, 0xFF, 0x80, + 0x0F, 0xC0, 0x7E, 0x03, 0xF0, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x3F, + 0xE0, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xE0, 0x03, 0x80, 0x00, 0x01, 0xFF, + 0xFF, 0xFE, 0x00, 0x00, 0x07, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x0F, 0xFF, + 0xFE, 0x00, 0x00, 0x00, 0x07, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, + 0xF0, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x7F, + 0xF0, 0x00, 0x00, 0x7F, 0xF0, 0x00, 0x00, 0xFF, 0xF0, 0x00, 0x00, 0xFF, + 0xF0, 0x00, 0x01, 0xFF, 0xF0, 0x00, 0x03, 0xFF, 0xF8, 0x00, 0x03, 0xFB, + 0xF8, 0x00, 0x07, 0xF3, 0xF8, 0x00, 0x07, 0xE3, 0xF8, 0x00, 0x0F, 0xE3, + 0xF8, 0x00, 0x0F, 0xC3, 0xF8, 0x00, 0x1F, 0xC3, 0xF8, 0x00, 0x1F, 0x83, + 0xF8, 0x00, 0x3F, 0x81, 0xFC, 0x00, 0x7F, 0x01, 0xFC, 0x00, 0x7F, 0x01, + 0xFC, 0x00, 0xFE, 0x01, 0xFC, 0x00, 0xFC, 0x01, 0xFC, 0x01, 0xFF, 0xFF, + 0xFC, 0x01, 0xFF, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, + 0xFE, 0x07, 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xFE, 0x0F, 0xE0, 0x00, + 0xFE, 0x1F, 0xC0, 0x00, 0xFE, 0x1F, 0xC0, 0x00, 0xFE, 0x3F, 0x80, 0x00, + 0xFE, 0x3F, 0x80, 0x00, 0x7F, 0x7F, 0x00, 0x00, 0x7F, 0xFF, 0x00, 0x00, + 0x7F, 0x01, 0xFF, 0xFF, 0xC0, 0x01, 0xFF, 0xFF, 0xF8, 0x01, 0xFF, 0xFF, + 0xFC, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, + 0xFF, 0x03, 0xF8, 0x00, 0xFF, 0x03, 0xF8, 0x00, 0x7F, 0x07, 0xF0, 0x00, + 0x7F, 0x07, 0xF0, 0x00, 0x7F, 0x07, 0xF0, 0x00, 0x7E, 0x07, 0xF0, 0x00, + 0xFE, 0x0F, 0xF0, 0x03, 0xFC, 0x0F, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, + 0xF0, 0x0F, 0xFF, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, + 0xF8, 0x1F, 0xFF, 0xFF, 0xF8, 0x1F, 0xC0, 0x07, 0xFC, 0x1F, 0xC0, 0x01, + 0xFC, 0x1F, 0xC0, 0x01, 0xFC, 0x3F, 0x80, 0x01, 0xFC, 0x3F, 0x80, 0x01, + 0xFC, 0x3F, 0x80, 0x01, 0xFC, 0x3F, 0x80, 0x03, 0xF8, 0x7F, 0x00, 0x07, + 0xF8, 0x7F, 0x00, 0x0F, 0xF0, 0x7F, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xFF, + 0xE0, 0x7F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xFE, + 0x00, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x07, 0xFF, + 0xE0, 0x00, 0x1F, 0xFF, 0xF0, 0x00, 0x7F, 0xFF, 0xF8, 0x00, 0xFF, 0xFF, + 0xFC, 0x01, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0x03, 0xFE, 0x07, 0xFC, 0x01, + 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, 0xE0, 0x00, 0x7F, 0x1F, 0xE0, 0x00, + 0x7F, 0x1F, 0xC0, 0x00, 0x7F, 0x3F, 0x80, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x00, 0x7F, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xF8, 0xFE, 0x00, 0x03, + 0xF8, 0xFF, 0x00, 0x07, 0xF8, 0xFF, 0x00, 0x07, 0xF0, 0x7F, 0x80, 0x1F, + 0xF0, 0x7F, 0xE0, 0x7F, 0xE0, 0x3F, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xFF, + 0x80, 0x1F, 0xFF, 0xFF, 0x00, 0x0F, 0xFF, 0xFE, 0x00, 0x03, 0xFF, 0xF8, + 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x01, 0xFF, 0xFF, + 0xE0, 0x03, 0xFF, 0xFF, 0xF8, 0x03, 0xFF, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, + 0xFC, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xF8, 0x03, 0xFE, 0x07, 0xF0, 0x01, + 0xFF, 0x07, 0xF0, 0x00, 0xFF, 0x07, 0xF0, 0x00, 0x7F, 0x07, 0xF0, 0x00, + 0x7F, 0x0F, 0xF0, 0x00, 0x7F, 0x0F, 0xE0, 0x00, 0x7F, 0x0F, 0xE0, 0x00, + 0x7F, 0x0F, 0xE0, 0x00, 0x7F, 0x0F, 0xE0, 0x00, 0x7F, 0x1F, 0xC0, 0x00, + 0x7F, 0x1F, 0xC0, 0x00, 0xFE, 0x1F, 0xC0, 0x00, 0xFE, 0x1F, 0xC0, 0x00, + 0xFE, 0x1F, 0xC0, 0x01, 0xFE, 0x3F, 0x80, 0x01, 0xFC, 0x3F, 0x80, 0x01, + 0xFC, 0x3F, 0x80, 0x03, 0xF8, 0x3F, 0x80, 0x07, 0xF8, 0x7F, 0x00, 0x0F, + 0xF0, 0x7F, 0x00, 0x1F, 0xF0, 0x7F, 0x00, 0x7F, 0xE0, 0x7F, 0xFF, 0xFF, + 0xC0, 0x7F, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xFE, + 0x00, 0xFF, 0xFF, 0xF8, 0x00, 0xFF, 0xFF, 0x80, 0x00, 0x01, 0xFF, 0xFF, + 0xFF, 0x01, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, + 0xFE, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xF8, 0x00, + 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, 0xF0, 0x00, + 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x0F, 0xE0, 0x00, + 0x00, 0x0F, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, + 0xE0, 0x1F, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, + 0xE0, 0x1F, 0xC0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x00, 0x7F, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, + 0xC0, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, + 0x80, 0x00, 0xFF, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, 0xFF, 0x01, 0xFF, 0xFF, + 0xFE, 0x01, 0xFF, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, + 0xFE, 0x03, 0xF8, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x03, 0xF8, 0x00, + 0x00, 0x03, 0xF8, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x07, 0xF0, 0x00, + 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, 0xFF, 0xFF, 0xE0, 0x07, 0xFF, 0xFF, + 0xE0, 0x0F, 0xFF, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xC0, 0x0F, 0xFF, 0xFF, + 0xC0, 0x0F, 0xFF, 0xFF, 0xC0, 0x0F, 0xE0, 0x00, 0x00, 0x1F, 0xC0, 0x00, + 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x1F, 0xC0, 0x00, + 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x00, 0x7F, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x00, 0x7F, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x03, 0xFF, + 0xF8, 0x00, 0x07, 0xFF, 0xFE, 0x00, 0x0F, 0xFF, 0xFF, 0x80, 0x0F, 0xFF, + 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xF8, 0x0F, 0xFC, 0x07, 0xFC, 0x0F, 0xF8, + 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0x3F, 0x87, 0xF0, 0x00, 0x1F, 0xC7, 0xF0, + 0x00, 0x0F, 0xE3, 0xF8, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x01, 0xFC, + 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x00, 0x7F, + 0x00, 0x3F, 0xFF, 0x3F, 0x00, 0x1F, 0xFF, 0xBF, 0x80, 0x0F, 0xFF, 0x9F, + 0xC0, 0x07, 0xFF, 0xCF, 0xE0, 0x03, 0xFF, 0xE7, 0xF0, 0x03, 0xFF, 0xF3, + 0xF8, 0x00, 0x01, 0xF9, 0xFC, 0x00, 0x01, 0xF8, 0xFF, 0x00, 0x00, 0xFC, + 0x7F, 0x80, 0x00, 0xFE, 0x3F, 0xC0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, + 0x87, 0xFC, 0x00, 0xFF, 0x81, 0xFF, 0x81, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, + 0xE0, 0x3F, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFE, 0xF8, 0x03, 0xFF, 0xFC, + 0x78, 0x00, 0x7F, 0xFC, 0x3C, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x01, 0xFC, + 0x00, 0x0F, 0xE0, 0x3F, 0x80, 0x01, 0xFC, 0x07, 0xF0, 0x00, 0x3F, 0x80, + 0xFE, 0x00, 0x0F, 0xE0, 0x1F, 0xC0, 0x01, 0xFC, 0x07, 0xF0, 0x00, 0x3F, + 0x80, 0xFE, 0x00, 0x07, 0xF0, 0x1F, 0xC0, 0x00, 0xFE, 0x03, 0xF8, 0x00, + 0x3F, 0x80, 0xFF, 0x00, 0x07, 0xF0, 0x1F, 0xC0, 0x00, 0xFE, 0x03, 0xF8, + 0x00, 0x1F, 0xC0, 0x7F, 0x00, 0x07, 0xF0, 0x0F, 0xFF, 0xFF, 0xFE, 0x03, + 0xFF, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xFF, + 0x01, 0xFF, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xFF, 0xF8, 0x0F, 0xE0, 0x00, + 0x7F, 0x01, 0xFC, 0x00, 0x0F, 0xE0, 0x3F, 0x80, 0x01, 0xFC, 0x07, 0xF0, + 0x00, 0x7F, 0x01, 0xFC, 0x00, 0x0F, 0xE0, 0x3F, 0x80, 0x01, 0xFC, 0x07, + 0xF0, 0x00, 0x3F, 0x80, 0xFE, 0x00, 0x0F, 0xE0, 0x1F, 0xC0, 0x01, 0xFC, + 0x07, 0xF0, 0x00, 0x3F, 0x80, 0xFE, 0x00, 0x07, 0xF0, 0x1F, 0xC0, 0x00, + 0xFE, 0x03, 0xF8, 0x00, 0x3F, 0x80, 0x7F, 0x00, 0x07, 0xF0, 0x1F, 0xC0, + 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x07, 0xF0, 0x3F, 0x80, 0xFE, 0x03, 0xF8, + 0x0F, 0xE0, 0x3F, 0x81, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, + 0x0F, 0xE0, 0x3F, 0x80, 0xFE, 0x03, 0xF8, 0x0F, 0xE0, 0x7F, 0x01, 0xFC, + 0x07, 0xF0, 0x1F, 0xC0, 0x7F, 0x03, 0xF8, 0x0F, 0xE0, 0x3F, 0x80, 0xFE, + 0x03, 0xF8, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0xFE, + 0x03, 0xF8, 0x00, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x00, + 0x3F, 0x80, 0x00, 0x0F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, + 0x00, 0x07, 0xF0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xF0, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x0F, 0xE0, 0xFE, 0x03, 0xFC, 0x1F, 0xC0, 0x7F, 0x03, 0xF8, 0x0F, 0xE0, + 0xFE, 0x01, 0xFC, 0x1F, 0xC0, 0x3F, 0x83, 0xF8, 0x0F, 0xE0, 0x7F, 0x01, + 0xFC, 0x0F, 0xF0, 0xFF, 0x81, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, 0xF8, 0x03, + 0xFF, 0xFF, 0x00, 0x3F, 0xFF, 0x80, 0x03, 0xFF, 0xE0, 0x00, 0x1F, 0xE0, + 0x00, 0x00, 0x00, 0xFE, 0x00, 0x0F, 0xF0, 0x0F, 0xF0, 0x00, 0xFF, 0x00, + 0x7F, 0x00, 0x1F, 0xF0, 0x03, 0xF8, 0x01, 0xFF, 0x00, 0x1F, 0xC0, 0x1F, + 0xE0, 0x00, 0xFE, 0x01, 0xFE, 0x00, 0x0F, 0xE0, 0x1F, 0xE0, 0x00, 0x7F, + 0x01, 0xFE, 0x00, 0x03, 0xF8, 0x1F, 0xE0, 0x00, 0x1F, 0xC1, 0xFE, 0x00, + 0x00, 0xFE, 0x1F, 0xE0, 0x00, 0x0F, 0xE3, 0xFE, 0x00, 0x00, 0x7F, 0x3F, + 0xC0, 0x00, 0x03, 0xFB, 0xFC, 0x00, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x01, + 0xFF, 0xFE, 0x00, 0x00, 0x0F, 0xFF, 0xF8, 0x00, 0x00, 0x7F, 0xFF, 0xC0, + 0x00, 0x03, 0xFF, 0xFF, 0x00, 0x00, 0x1F, 0xFF, 0xF8, 0x00, 0x01, 0xFF, + 0x9F, 0xE0, 0x00, 0x0F, 0xF8, 0xFF, 0x00, 0x00, 0x7F, 0x83, 0xFC, 0x00, + 0x03, 0xF8, 0x1F, 0xF0, 0x00, 0x1F, 0xC0, 0x7F, 0x80, 0x01, 0xFC, 0x01, + 0xFE, 0x00, 0x0F, 0xE0, 0x0F, 0xF0, 0x00, 0x7F, 0x00, 0x3F, 0xC0, 0x03, + 0xF8, 0x01, 0xFF, 0x00, 0x3F, 0x80, 0x07, 0xF8, 0x01, 0xFC, 0x00, 0x3F, + 0xE0, 0x0F, 0xE0, 0x00, 0xFF, 0x00, 0x7F, 0x00, 0x07, 0xFC, 0x03, 0xF8, + 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x01, 0xFC, 0x00, 0x01, 0xFC, + 0x00, 0x03, 0xF8, 0x00, 0x03, 0xF8, 0x00, 0x03, 0xF8, 0x00, 0x03, 0xF8, + 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF0, + 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x0F, 0xE0, 0x00, 0x0F, 0xE0, + 0x00, 0x0F, 0xE0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x1F, 0xC0, + 0x00, 0x1F, 0xC0, 0x00, 0x1F, 0xC0, 0x00, 0x3F, 0x80, 0x00, 0x3F, 0x80, + 0x00, 0x3F, 0x80, 0x00, 0x3F, 0x80, 0x00, 0x3F, 0x80, 0x00, 0x7F, 0x00, + 0x00, 0x7F, 0x00, 0x00, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x01, 0xFF, + 0x80, 0x03, 0xFF, 0x80, 0xFF, 0xC0, 0x01, 0xFF, 0x80, 0x7F, 0xE0, 0x01, + 0xFF, 0xC0, 0x3F, 0xF0, 0x00, 0xFF, 0xE0, 0x3F, 0xF8, 0x00, 0xFF, 0xF0, + 0x1F, 0xFC, 0x00, 0x7F, 0xF8, 0x0F, 0xFE, 0x00, 0x7D, 0xF8, 0x07, 0xEF, + 0x00, 0x3E, 0xFC, 0x03, 0xF7, 0x80, 0x3F, 0xFE, 0x03, 0xFB, 0xC0, 0x1F, + 0x7F, 0x01, 0xFD, 0xE0, 0x1F, 0xBF, 0x00, 0xFE, 0xF0, 0x0F, 0x9F, 0x80, + 0x7E, 0x78, 0x0F, 0xDF, 0xC0, 0x7F, 0x3E, 0x07, 0xCF, 0xE0, 0x3F, 0x9F, + 0x07, 0xE7, 0xF0, 0x1F, 0xCF, 0x83, 0xE3, 0xF0, 0x0F, 0xE7, 0xC3, 0xF1, + 0xF8, 0x07, 0xE3, 0xE1, 0xF9, 0xFC, 0x07, 0xF1, 0xF0, 0xF8, 0xFE, 0x03, + 0xF8, 0xF8, 0xFC, 0x7F, 0x01, 0xFC, 0x7C, 0x7C, 0x3F, 0x00, 0xFC, 0x3E, + 0x7E, 0x1F, 0x80, 0x7E, 0x1F, 0x3E, 0x1F, 0xC0, 0x7F, 0x0F, 0xBF, 0x0F, + 0xE0, 0x3F, 0x87, 0xDF, 0x07, 0xE0, 0x1F, 0xC3, 0xFF, 0x83, 0xF0, 0x0F, + 0xC1, 0xFF, 0xC3, 0xF8, 0x0F, 0xE0, 0xFF, 0xC1, 0xFC, 0x07, 0xF0, 0x7F, + 0xE0, 0xFE, 0x03, 0xF8, 0x3F, 0xE0, 0x7E, 0x01, 0xFC, 0x1F, 0xF0, 0x3F, + 0x00, 0xFC, 0x0F, 0xF0, 0x3F, 0x80, 0xFE, 0x07, 0xF8, 0x1F, 0xC0, 0x7F, + 0x03, 0xF8, 0x0F, 0xC0, 0x00, 0x01, 0xFE, 0x00, 0x07, 0xE0, 0x3F, 0xC0, + 0x01, 0xFC, 0x07, 0xFC, 0x00, 0x3F, 0x80, 0xFF, 0x80, 0x07, 0xF0, 0x1F, + 0xF0, 0x00, 0xFC, 0x07, 0xFF, 0x00, 0x3F, 0x80, 0xFF, 0xE0, 0x07, 0xF0, + 0x1F, 0xFC, 0x00, 0xFE, 0x03, 0xFF, 0xC0, 0x1F, 0x80, 0xFF, 0xF8, 0x03, + 0xF0, 0x1F, 0xFF, 0x80, 0xFE, 0x03, 0xFB, 0xF0, 0x1F, 0xC0, 0x7E, 0x7E, + 0x03, 0xF8, 0x0F, 0xC7, 0xE0, 0x7E, 0x03, 0xF8, 0xFC, 0x0F, 0xC0, 0x7F, + 0x1F, 0x83, 0xF8, 0x0F, 0xE1, 0xF8, 0x7F, 0x01, 0xF8, 0x3F, 0x0F, 0xE0, + 0x3F, 0x07, 0xF1, 0xF8, 0x0F, 0xE0, 0x7E, 0x3F, 0x01, 0xFC, 0x0F, 0xCF, + 0xE0, 0x3F, 0x00, 0xFD, 0xFC, 0x07, 0xE0, 0x1F, 0xBF, 0x81, 0xFC, 0x03, + 0xF7, 0xE0, 0x3F, 0x80, 0x3F, 0xFC, 0x07, 0xF0, 0x07, 0xFF, 0x80, 0xFC, + 0x00, 0xFF, 0xF0, 0x1F, 0x80, 0x0F, 0xFC, 0x07, 0xF0, 0x01, 0xFF, 0x80, + 0xFE, 0x00, 0x3F, 0xF0, 0x1F, 0xC0, 0x03, 0xFE, 0x03, 0xF0, 0x00, 0x7F, + 0xC0, 0x7E, 0x00, 0x07, 0xF0, 0x1F, 0xC0, 0x00, 0xFE, 0x00, 0x00, 0x00, + 0xFF, 0x80, 0x00, 0x01, 0xFF, 0xF8, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x01, + 0xFF, 0xFF, 0xF0, 0x00, 0xFF, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xFF, 0xC0, + 0x3F, 0xF0, 0x3F, 0xF8, 0x1F, 0xF0, 0x03, 0xFE, 0x07, 0xF0, 0x00, 0x7F, + 0x83, 0xF8, 0x00, 0x0F, 0xF1, 0xFE, 0x00, 0x03, 0xFC, 0x7F, 0x00, 0x00, + 0x7F, 0x3F, 0x80, 0x00, 0x1F, 0xCF, 0xE0, 0x00, 0x07, 0xF7, 0xF0, 0x00, + 0x01, 0xFD, 0xFC, 0x00, 0x00, 0x7F, 0x7F, 0x00, 0x00, 0x1F, 0xDF, 0xC0, + 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x03, 0xFB, 0xF8, 0x00, 0x00, 0xFE, 0xFE, + 0x00, 0x00, 0x3F, 0xBF, 0x80, 0x00, 0x0F, 0xEF, 0xE0, 0x00, 0x07, 0xF3, + 0xF8, 0x00, 0x01, 0xFC, 0xFE, 0x00, 0x00, 0xFE, 0x3F, 0xC0, 0x00, 0x7F, + 0x8F, 0xF0, 0x00, 0x1F, 0xC1, 0xFE, 0x00, 0x0F, 0xE0, 0x7F, 0xC0, 0x0F, + 0xF8, 0x1F, 0xFC, 0x0F, 0xFC, 0x03, 0xFF, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, + 0xFF, 0x00, 0x0F, 0xFF, 0xFF, 0x80, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x1F, + 0xFF, 0x80, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x03, + 0xFF, 0xFF, 0xE0, 0x0F, 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0xE0, 0x3F, + 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xC1, 0xFE, 0x00, 0xFF, 0x83, 0xF8, + 0x00, 0xFF, 0x07, 0xF0, 0x00, 0xFE, 0x0F, 0xE0, 0x01, 0xFC, 0x1F, 0xC0, + 0x03, 0xF8, 0x7F, 0x00, 0x07, 0xF0, 0xFE, 0x00, 0x1F, 0xC1, 0xFC, 0x00, + 0x3F, 0x83, 0xF8, 0x00, 0xFE, 0x07, 0xF0, 0x07, 0xFC, 0x1F, 0xFF, 0xFF, + 0xF0, 0x3F, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xFE, + 0x03, 0xFF, 0xFF, 0xF0, 0x07, 0xFF, 0xFF, 0x80, 0x0F, 0xE0, 0x00, 0x00, + 0x1F, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x0F, + 0xE0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0x80, 0x00, + 0x01, 0xFF, 0xF8, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x01, 0xFF, 0xFF, 0xF0, + 0x00, 0xFF, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xFF, 0xC0, 0x3F, 0xF0, 0x3F, + 0xF0, 0x1F, 0xF0, 0x03, 0xFE, 0x07, 0xF8, 0x00, 0x7F, 0x83, 0xFC, 0x00, + 0x0F, 0xF1, 0xFE, 0x00, 0x03, 0xFC, 0x7F, 0x00, 0x00, 0x7F, 0x3F, 0x80, + 0x00, 0x1F, 0xCF, 0xE0, 0x00, 0x07, 0xF3, 0xF0, 0x00, 0x01, 0xFD, 0xFC, + 0x00, 0x00, 0x7F, 0x7F, 0x00, 0x00, 0x1F, 0xDF, 0x80, 0x00, 0x07, 0xFF, + 0xE0, 0x00, 0x03, 0xFB, 0xF8, 0x00, 0x00, 0xFE, 0xFE, 0x00, 0x00, 0x3F, + 0xBF, 0x80, 0x00, 0x0F, 0xEF, 0xE0, 0x01, 0x87, 0xF3, 0xF8, 0x00, 0xF1, + 0xFC, 0xFE, 0x00, 0x7C, 0xFE, 0x3F, 0xC0, 0x3F, 0xFF, 0x8F, 0xF0, 0x07, + 0xFF, 0xC1, 0xFE, 0x01, 0xFF, 0xE0, 0x7F, 0xC0, 0x3F, 0xF8, 0x1F, 0xFC, + 0x0F, 0xFC, 0x03, 0xFF, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xFF, 0xC0, 0x0F, + 0xFF, 0xFF, 0xF8, 0x01, 0xFF, 0xFF, 0xFF, 0x00, 0x1F, 0xFF, 0x9F, 0x80, + 0x01, 0xFF, 0x03, 0xC0, 0x00, 0x00, 0x00, 0x60, 0x00, 0x01, 0xFF, 0xFF, + 0xF0, 0x00, 0xFF, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, + 0xFF, 0xE0, 0x3F, 0xFF, 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0xFC, 0x0F, 0xE0, + 0x03, 0xFE, 0x0F, 0xF0, 0x00, 0xFF, 0x07, 0xF0, 0x00, 0x3F, 0x83, 0xF8, + 0x00, 0x1F, 0xC1, 0xFC, 0x00, 0x0F, 0xC0, 0xFE, 0x00, 0x07, 0xE0, 0xFE, + 0x00, 0x07, 0xF0, 0x7F, 0x00, 0x07, 0xF0, 0x3F, 0x80, 0x0F, 0xF0, 0x1F, + 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xE0, 0x07, + 0xFF, 0xFF, 0xF0, 0x03, 0xFF, 0xFF, 0xFC, 0x01, 0xFF, 0xFF, 0xFF, 0x01, + 0xFC, 0x00, 0x7F, 0x80, 0xFE, 0x00, 0x1F, 0xC0, 0x7F, 0x00, 0x0F, 0xE0, + 0x3F, 0x80, 0x07, 0xF0, 0x1F, 0xC0, 0x03, 0xF8, 0x1F, 0xC0, 0x01, 0xFC, + 0x0F, 0xE0, 0x01, 0xFC, 0x07, 0xF0, 0x00, 0xFE, 0x03, 0xF8, 0x00, 0x7F, + 0x01, 0xFC, 0x00, 0x3F, 0x81, 0xFC, 0x00, 0x1F, 0xC0, 0xFE, 0x00, 0x0F, + 0xE0, 0x7F, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x7F, + 0xFF, 0x00, 0x07, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0xFC, 0x01, 0xFF, 0xFF, + 0xF8, 0x0F, 0xFF, 0xFF, 0xF0, 0x3F, 0xC0, 0x7F, 0xC1, 0xFE, 0x00, 0xFF, + 0x07, 0xF0, 0x01, 0xFC, 0x3F, 0x80, 0x07, 0xF0, 0xFE, 0x00, 0x1F, 0xC3, + 0xF8, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x00, 0xFF, + 0xE0, 0x00, 0x03, 0xFF, 0xFC, 0x00, 0x07, 0xFF, 0xFF, 0x00, 0x0F, 0xFF, + 0xFE, 0x00, 0x1F, 0xFF, 0xFE, 0x00, 0x0F, 0xFF, 0xF8, 0x00, 0x03, 0xFF, + 0xF0, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x01, 0xFC, + 0x00, 0x00, 0x07, 0xF3, 0xF8, 0x00, 0x1F, 0xCF, 0xE0, 0x00, 0x7E, 0x3F, + 0x80, 0x03, 0xF8, 0xFF, 0x00, 0x1F, 0xE3, 0xFF, 0x01, 0xFF, 0x07, 0xFF, + 0xFF, 0xF8, 0x1F, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, + 0xF0, 0x00, 0x7F, 0xFF, 0x80, 0x00, 0x3F, 0xF0, 0x00, 0x7F, 0xFF, 0xFF, + 0xF7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xFE, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xF8, + 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x07, 0xF0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x0F, 0xE0, 0x00, + 0x01, 0xFC, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xF8, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x7F, 0x00, + 0x00, 0x0F, 0xE0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x7F, + 0x07, 0xF0, 0x00, 0x7F, 0x07, 0xF0, 0x00, 0xFE, 0x0F, 0xE0, 0x00, 0xFE, + 0x0F, 0xE0, 0x00, 0xFE, 0x0F, 0xE0, 0x00, 0xFE, 0x0F, 0xE0, 0x00, 0xFE, + 0x0F, 0xE0, 0x01, 0xFC, 0x1F, 0xC0, 0x01, 0xFC, 0x1F, 0xC0, 0x01, 0xFC, + 0x1F, 0xC0, 0x01, 0xFC, 0x1F, 0xC0, 0x01, 0xFC, 0x3F, 0x80, 0x03, 0xF8, + 0x3F, 0x80, 0x03, 0xF8, 0x3F, 0x80, 0x03, 0xF8, 0x3F, 0x80, 0x03, 0xF8, + 0x3F, 0x80, 0x07, 0xF0, 0x7F, 0x00, 0x07, 0xF0, 0x7F, 0x00, 0x07, 0xF0, + 0x7F, 0x00, 0x07, 0xF0, 0x7F, 0x00, 0x07, 0xF0, 0x7F, 0x00, 0x0F, 0xE0, + 0xFE, 0x00, 0x0F, 0xE0, 0xFE, 0x00, 0x0F, 0xE0, 0xFE, 0x00, 0x0F, 0xE0, + 0xFE, 0x00, 0x1F, 0xC0, 0xFE, 0x00, 0x1F, 0xC0, 0xFF, 0x00, 0x3F, 0x80, + 0xFF, 0xC0, 0xFF, 0x80, 0x7F, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xFE, 0x00, + 0x3F, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0xF8, 0x00, 0x0F, 0xFF, 0xE0, 0x00, + 0x01, 0xFF, 0x00, 0x00, 0xFF, 0x00, 0x03, 0xF9, 0xFC, 0x00, 0x0F, 0xE7, + 0xF0, 0x00, 0x7F, 0x1F, 0xC0, 0x01, 0xFC, 0x7F, 0x00, 0x0F, 0xE1, 0xFC, + 0x00, 0x3F, 0x87, 0xF0, 0x01, 0xFC, 0x1F, 0xC0, 0x07, 0xF0, 0x3F, 0x00, + 0x3F, 0x80, 0xFC, 0x00, 0xFC, 0x03, 0xF0, 0x07, 0xF0, 0x0F, 0xC0, 0x1F, + 0x80, 0x3F, 0x80, 0xFE, 0x00, 0xFE, 0x03, 0xF0, 0x03, 0xF8, 0x1F, 0xC0, + 0x0F, 0xE0, 0x7E, 0x00, 0x1F, 0x83, 0xF8, 0x00, 0x7E, 0x0F, 0xC0, 0x01, + 0xF8, 0x7E, 0x00, 0x07, 0xE1, 0xF8, 0x00, 0x1F, 0x8F, 0xC0, 0x00, 0x7E, + 0x3F, 0x00, 0x01, 0xF9, 0xF8, 0x00, 0x07, 0xE7, 0xE0, 0x00, 0x0F, 0xFF, + 0x00, 0x00, 0x3F, 0xFC, 0x00, 0x00, 0xFF, 0xE0, 0x00, 0x03, 0xFF, 0x00, + 0x00, 0x0F, 0xFC, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x00, 0xFF, 0x80, 0x00, + 0x01, 0xFC, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x00, + 0xFE, 0x00, 0x7F, 0x80, 0x1F, 0xFF, 0xC0, 0x0F, 0xF0, 0x03, 0xFB, 0xF8, + 0x01, 0xFE, 0x00, 0x7F, 0x7F, 0x00, 0x7F, 0xC0, 0x1F, 0xCF, 0xE0, 0x0F, + 0xF8, 0x03, 0xF9, 0xFC, 0x03, 0xFF, 0x00, 0xFE, 0x3F, 0x80, 0x7F, 0xE0, + 0x1F, 0xC7, 0xF0, 0x1F, 0xFC, 0x07, 0xF0, 0x7E, 0x03, 0xFF, 0x80, 0xFE, + 0x0F, 0xC0, 0x7D, 0xF0, 0x1F, 0x81, 0xF8, 0x1F, 0xBE, 0x07, 0xF0, 0x3F, + 0x03, 0xE7, 0xC0, 0xFC, 0x07, 0xE0, 0xFC, 0xF8, 0x3F, 0x80, 0xFC, 0x1F, + 0x1F, 0x07, 0xE0, 0x1F, 0x83, 0xE3, 0xE0, 0xFC, 0x03, 0xF0, 0xFC, 0x7C, + 0x3F, 0x00, 0x7E, 0x1F, 0x0F, 0x87, 0xE0, 0x0F, 0xC7, 0xE1, 0xF1, 0xF8, + 0x01, 0xF8, 0xF8, 0x3E, 0x3F, 0x00, 0x3F, 0x3F, 0x07, 0xCF, 0xC0, 0x07, + 0xE7, 0xC0, 0xF9, 0xF8, 0x00, 0xFC, 0xF8, 0x1F, 0x3E, 0x00, 0x1F, 0xBE, + 0x03, 0xEF, 0xC0, 0x01, 0xF7, 0xC0, 0x7D, 0xF0, 0x00, 0x3F, 0xF8, 0x0F, + 0xFE, 0x00, 0x07, 0xFE, 0x01, 0xFF, 0x80, 0x00, 0xFF, 0xC0, 0x3F, 0xF0, + 0x00, 0x1F, 0xF0, 0x07, 0xFC, 0x00, 0x03, 0xFE, 0x00, 0xFF, 0x80, 0x00, + 0x7F, 0x80, 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x03, 0xFC, 0x00, 0x01, 0xFC, + 0x00, 0x7F, 0x80, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0x01, + 0xFC, 0x00, 0x00, 0x00, 0xFF, 0x00, 0x0F, 0xF0, 0x07, 0xFC, 0x00, 0xFF, + 0x00, 0x1F, 0xE0, 0x07, 0xF8, 0x00, 0xFF, 0x00, 0x7F, 0x80, 0x03, 0xFC, + 0x07, 0xF8, 0x00, 0x1F, 0xE0, 0x7F, 0x80, 0x00, 0xFF, 0x07, 0xF8, 0x00, + 0x03, 0xFC, 0x3F, 0x80, 0x00, 0x1F, 0xE3, 0xF8, 0x00, 0x00, 0x7F, 0x3F, + 0xC0, 0x00, 0x03, 0xFF, 0xFC, 0x00, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x00, + 0x7F, 0xFC, 0x00, 0x00, 0x03, 0xFF, 0xC0, 0x00, 0x00, 0x0F, 0xFC, 0x00, + 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x00, 0x1F, + 0xF0, 0x00, 0x00, 0x01, 0xFF, 0x80, 0x00, 0x00, 0x1F, 0xFE, 0x00, 0x00, + 0x00, 0xFF, 0xF0, 0x00, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x00, 0xFF, 0xFE, + 0x00, 0x00, 0x0F, 0xE7, 0xF0, 0x00, 0x00, 0xFF, 0x3F, 0xC0, 0x00, 0x0F, + 0xF1, 0xFE, 0x00, 0x00, 0xFF, 0x07, 0xF8, 0x00, 0x07, 0xF0, 0x3F, 0xC0, + 0x00, 0x7F, 0x01, 0xFE, 0x00, 0x07, 0xF8, 0x07, 0xF8, 0x00, 0x7F, 0x80, + 0x3F, 0xC0, 0x07, 0xF8, 0x01, 0xFF, 0x00, 0x7F, 0x80, 0x07, 0xF8, 0x07, + 0xFC, 0x00, 0x3F, 0xE0, 0x00, 0xFF, 0x00, 0x07, 0xF7, 0xF8, 0x00, 0x7F, + 0xBF, 0xC0, 0x07, 0xF8, 0xFE, 0x00, 0x3F, 0x87, 0xF8, 0x03, 0xFC, 0x3F, + 0xC0, 0x3F, 0xC0, 0xFE, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x3F, 0xC1, + 0xFE, 0x00, 0xFE, 0x0F, 0xE0, 0x07, 0xF0, 0xFE, 0x00, 0x3F, 0x8F, 0xE0, + 0x00, 0xFE, 0x7F, 0x00, 0x07, 0xF7, 0xF0, 0x00, 0x3F, 0xFF, 0x00, 0x01, + 0xFF, 0xF8, 0x00, 0x07, 0xFF, 0x80, 0x00, 0x3F, 0xF8, 0x00, 0x01, 0xFF, + 0x80, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0x3F, 0x80, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, + 0xFF, 0x80, 0xFF, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, + 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, 0xF8, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xFF, + 0x01, 0xFF, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xFF, 0xC0, 0x7F, 0xFF, 0xFF, + 0xC0, 0x3F, 0xFF, 0xFF, 0xE0, 0x00, 0x00, 0x7F, 0xF8, 0x03, 0xFF, 0x80, + 0x1F, 0xFC, 0x00, 0xFF, 0xE0, 0x0F, 0xFF, 0x00, 0x7E, 0x00, 0x03, 0xF0, + 0x00, 0x1F, 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0x7E, 0x00, 0x03, + 0xF0, 0x00, 0x1F, 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0x7E, 0x00, + 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0x7E, + 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x80, 0x01, 0xF8, 0x00, 0x0F, 0xC0, 0x00, + 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x80, 0x01, 0xF8, 0x00, 0x0F, 0xC0, + 0x00, 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x01, 0xF8, 0x00, 0x0F, + 0xC0, 0x00, 0x7E, 0x00, 0x07, 0xF0, 0x00, 0x3F, 0x00, 0x01, 0xFF, 0xC0, + 0x0F, 0xFE, 0x00, 0x7F, 0xF0, 0x07, 0xFF, 0x80, 0x3F, 0xFC, 0x00, 0x81, + 0xC3, 0xC7, 0x8F, 0x0E, 0x1C, 0x38, 0x70, 0xE1, 0xC3, 0xC7, 0x8F, 0x1E, + 0x1C, 0x38, 0x70, 0xE1, 0xC3, 0x87, 0x8F, 0x1E, 0x3C, 0x38, 0x70, 0xE1, + 0xC3, 0x87, 0x0F, 0x1E, 0x3C, 0x78, 0xF0, 0x00, 0x7F, 0xF8, 0x03, 0xFF, + 0xC0, 0x1F, 0xFC, 0x00, 0xFF, 0xE0, 0x07, 0xFF, 0x00, 0x01, 0xF8, 0x00, + 0x1F, 0xC0, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF8, + 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0x00, 0x03, + 0xF8, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0x00, + 0x03, 0xF8, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x7F, + 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, + 0x7F, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, + 0x00, 0x7F, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x01, 0xFF, + 0xE0, 0x0F, 0xFE, 0x00, 0x7F, 0xF0, 0x03, 0xFF, 0x80, 0x3F, 0xFC, 0x00, + 0x00, 0x1F, 0x80, 0x00, 0xFE, 0x00, 0x0F, 0xF0, 0x00, 0x7F, 0x80, 0x07, + 0xFC, 0x00, 0x7F, 0xE0, 0x03, 0xFF, 0x80, 0x3E, 0xFC, 0x01, 0xF3, 0xE0, + 0x1F, 0x1F, 0x01, 0xF8, 0xF8, 0x0F, 0x87, 0xE0, 0xFC, 0x3F, 0x07, 0xC0, + 0xF8, 0x7C, 0x07, 0xC7, 0xE0, 0x3E, 0x3E, 0x01, 0xFB, 0xF0, 0x0F, 0xDF, + 0x00, 0x3F, 0xF0, 0x01, 0xF0, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFD, 0xFF, 0xFF, 0xFF, 0xE0, 0xF8, 0xF0, 0xF1, 0xE1, + 0xC3, 0xC3, 0x80, 0x00, 0x1F, 0xF0, 0x00, 0x7F, 0xFF, 0x00, 0xFF, 0xFF, + 0xC0, 0xFF, 0xFF, 0xF0, 0x7F, 0xFF, 0xF8, 0x7F, 0x03, 0xFC, 0x3F, 0x00, + 0xFE, 0x1F, 0x80, 0x7E, 0x00, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0x80, 0x1F, + 0xFF, 0xC0, 0x7F, 0xFF, 0xC0, 0xFF, 0xFF, 0xE0, 0xFF, 0xF7, 0xF0, 0xFF, + 0x83, 0xF8, 0xFF, 0x01, 0xF8, 0x7F, 0x00, 0xFC, 0x7F, 0x00, 0xFE, 0x3F, + 0x80, 0x7F, 0x1F, 0xC0, 0x7F, 0x8F, 0xF0, 0xFF, 0x87, 0xFF, 0xFF, 0xC3, + 0xFF, 0xFF, 0xE0, 0xFF, 0xF7, 0xF8, 0x3F, 0xF3, 0xFC, 0x07, 0xE0, 0x00, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xE0, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x3F, 0x80, 0x1F, + 0x9F, 0xFC, 0x03, 0xF7, 0xFF, 0xC0, 0xFF, 0xFF, 0xF8, 0x1F, 0xFF, 0xFF, + 0x83, 0xFF, 0x0F, 0xF0, 0x7F, 0x80, 0xFF, 0x0F, 0xE0, 0x1F, 0xE3, 0xF8, + 0x01, 0xFC, 0x7F, 0x00, 0x3F, 0x8F, 0xC0, 0x07, 0xF1, 0xF8, 0x00, 0xFE, + 0x7F, 0x00, 0x1F, 0xCF, 0xC0, 0x03, 0xF9, 0xF8, 0x00, 0xFE, 0x3F, 0x00, + 0x1F, 0xC7, 0xE0, 0x03, 0xF9, 0xFC, 0x00, 0xFE, 0x3F, 0xC0, 0x3F, 0xC7, + 0xF8, 0x0F, 0xF0, 0xFF, 0x83, 0xFC, 0x1F, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, + 0xC0, 0xFF, 0xFF, 0xF0, 0x1F, 0x9F, 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x00, + 0x00, 0x1F, 0xE0, 0x00, 0x3F, 0xFC, 0x00, 0x7F, 0xFF, 0x80, 0x7F, 0xFF, + 0xE0, 0x7F, 0xFF, 0xF0, 0x7F, 0x83, 0xFC, 0x7F, 0x00, 0xFE, 0x3F, 0x00, + 0x7F, 0x3F, 0x80, 0x3F, 0x9F, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x0F, 0xE0, + 0x00, 0x07, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x01, 0xFC, + 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x7F, 0x3F, 0x80, 0x3F, 0x9F, + 0xE0, 0x3F, 0x87, 0xF8, 0x3F, 0x83, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xC0, + 0x3F, 0xFF, 0xC0, 0x0F, 0xFF, 0x80, 0x01, 0xFE, 0x00, 0x00, 0x00, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x07, + 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x00, 0xFC, 0x00, 0x00, 0x0F, 0xE0, 0x01, 0xFC, 0x7F, 0x00, 0x3F, + 0xF3, 0xF8, 0x03, 0xFF, 0xDF, 0x80, 0x7F, 0xFF, 0xFC, 0x07, 0xFF, 0xFF, + 0xE0, 0x3F, 0xC3, 0xFF, 0x03, 0xFC, 0x0F, 0xF8, 0x3F, 0xC0, 0x3F, 0x81, + 0xFC, 0x01, 0xFC, 0x1F, 0xC0, 0x07, 0xE0, 0xFE, 0x00, 0x3F, 0x07, 0xF0, + 0x03, 0xF8, 0x7F, 0x00, 0x1F, 0x83, 0xF8, 0x00, 0xFC, 0x1F, 0xC0, 0x07, + 0xE0, 0xFE, 0x00, 0x3F, 0x07, 0xF0, 0x03, 0xF0, 0x3F, 0x80, 0x3F, 0x81, + 0xFC, 0x01, 0xFC, 0x0F, 0xF0, 0x1F, 0xE0, 0x3F, 0xC3, 0xFF, 0x01, 0xFF, + 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xFC, 0x00, 0xFF, 0xCF, + 0xE0, 0x01, 0xF8, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0xFC, 0x00, + 0x7F, 0xFF, 0x00, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xF0, 0x7F, 0x87, 0xF8, + 0x7F, 0x01, 0xFE, 0x7F, 0x00, 0x7F, 0x3F, 0x80, 0x3F, 0xBF, 0x80, 0x1F, + 0xDF, 0xC0, 0x0F, 0xEF, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFD, 0xFC, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7F, 0x00, + 0x00, 0x3F, 0x80, 0x3F, 0x9F, 0xE0, 0x3F, 0x87, 0xF8, 0x3F, 0xC3, 0xFF, + 0xFF, 0xC0, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0x80, 0x0F, 0xFF, 0x80, 0x00, + 0xFE, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x1F, 0xF0, 0x0F, 0xF8, 0x07, 0xFE, + 0x01, 0xFF, 0x80, 0xFE, 0x00, 0x3F, 0x80, 0x0F, 0xC0, 0x03, 0xF0, 0x01, + 0xFC, 0x03, 0xFF, 0xF1, 0xFF, 0xF8, 0x7F, 0xFE, 0x1F, 0xFF, 0x80, 0xFE, + 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x03, 0xF0, 0x00, 0xFC, 0x00, 0x7F, 0x00, + 0x1F, 0xC0, 0x07, 0xE0, 0x01, 0xF8, 0x00, 0xFE, 0x00, 0x3F, 0x80, 0x0F, + 0xE0, 0x03, 0xF0, 0x00, 0xFC, 0x00, 0x7F, 0x00, 0x1F, 0xC0, 0x07, 0xF0, + 0x01, 0xF8, 0x00, 0x7E, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x07, 0xC3, 0xF8, + 0x01, 0xFF, 0x9F, 0x80, 0x1F, 0xFE, 0xFC, 0x01, 0xFF, 0xFF, 0xE0, 0x1F, + 0xFF, 0xFF, 0x01, 0xFE, 0x1F, 0xF8, 0x1F, 0xE0, 0x3F, 0x80, 0xFE, 0x01, + 0xFC, 0x0F, 0xE0, 0x0F, 0xE0, 0x7F, 0x00, 0x3F, 0x07, 0xF0, 0x01, 0xF8, + 0x3F, 0x80, 0x0F, 0x81, 0xF8, 0x00, 0x7C, 0x1F, 0xC0, 0x07, 0xE0, 0xFE, + 0x00, 0x3F, 0x07, 0xF0, 0x01, 0xF0, 0x3F, 0x80, 0x1F, 0x81, 0xFC, 0x00, + 0xFC, 0x0F, 0xE0, 0x0F, 0xE0, 0x7F, 0x80, 0xFF, 0x03, 0xFE, 0x1F, 0xF0, + 0x0F, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0xFC, 0x01, 0xFF, 0xF7, 0xE0, 0x07, + 0xFE, 0x7F, 0x00, 0x0F, 0xC3, 0xF0, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x01, + 0xFC, 0x0F, 0xE0, 0x0F, 0xC0, 0x7F, 0x00, 0xFE, 0x03, 0xFC, 0x1F, 0xE0, + 0x1F, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xE0, 0x01, 0xFF, 0xFC, 0x00, 0x01, + 0xFF, 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xE0, + 0x00, 0x00, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xFE, 0x0F, + 0xC0, 0x1F, 0xCF, 0xFE, 0x03, 0xFB, 0xFF, 0xE0, 0x7F, 0xFF, 0xFE, 0x0F, + 0xFF, 0xFF, 0xC3, 0xFF, 0x07, 0xF8, 0x7F, 0x80, 0x7F, 0x0F, 0xE0, 0x0F, + 0xE1, 0xFC, 0x01, 0xFC, 0x7F, 0x00, 0x3F, 0x0F, 0xE0, 0x07, 0xE1, 0xFC, + 0x01, 0xFC, 0x3F, 0x00, 0x3F, 0x87, 0xE0, 0x07, 0xF1, 0xFC, 0x00, 0xFC, + 0x3F, 0x80, 0x1F, 0x87, 0xF0, 0x07, 0xF0, 0xFC, 0x00, 0xFE, 0x1F, 0x80, + 0x1F, 0xC7, 0xF0, 0x03, 0xF0, 0xFE, 0x00, 0x7E, 0x1F, 0xC0, 0x1F, 0xC3, + 0xF0, 0x03, 0xF8, 0xFE, 0x00, 0x7F, 0x1F, 0xC0, 0x0F, 0xC0, 0x01, 0xFC, + 0x07, 0xF0, 0x1F, 0x80, 0x7E, 0x03, 0xF8, 0x0F, 0xE0, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xE0, 0x3F, 0x80, 0xFE, + 0x03, 0xF8, 0x0F, 0xC0, 0x3F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7E, + 0x03, 0xF8, 0x0F, 0xE0, 0x3F, 0x80, 0xFC, 0x03, 0xF0, 0x1F, 0xC0, 0x7F, + 0x01, 0xFC, 0x07, 0xE0, 0x1F, 0x80, 0xFE, 0x03, 0xF8, 0x00, 0x00, 0x0F, + 0xE0, 0x01, 0xFC, 0x00, 0x3F, 0x80, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x3F, + 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xF0, 0x00, 0xFE, + 0x00, 0x1F, 0xC0, 0x03, 0xF8, 0x00, 0x7E, 0x00, 0x1F, 0xC0, 0x03, 0xF8, + 0x00, 0x7F, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x7F, 0x00, 0x0F, 0xE0, + 0x01, 0xFC, 0x00, 0x3F, 0x00, 0x07, 0xE0, 0x01, 0xFC, 0x00, 0x3F, 0x80, + 0x07, 0xF0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x07, 0xF0, 0x00, 0xFE, 0x00, + 0x1F, 0x80, 0x03, 0xF0, 0x00, 0xFE, 0x00, 0x1F, 0xC0, 0x03, 0xF8, 0x00, + 0x7E, 0x00, 0x0F, 0xC0, 0x03, 0xF8, 0x03, 0xFF, 0x00, 0x7F, 0xC0, 0x0F, + 0xF8, 0x03, 0xFE, 0x00, 0x7E, 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x1F, + 0x80, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xF8, 0x00, + 0x00, 0x3F, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0x7F, 0x00, 0xFE, 0x07, 0xE0, 0x3F, 0xC0, 0x7E, 0x07, + 0xF8, 0x0F, 0xE0, 0xFF, 0x00, 0xFE, 0x1F, 0xC0, 0x0F, 0xE3, 0xF8, 0x00, + 0xFC, 0x7F, 0x00, 0x0F, 0xCF, 0xE0, 0x01, 0xFD, 0xFC, 0x00, 0x1F, 0xFF, + 0x80, 0x01, 0xFF, 0xF8, 0x00, 0x1F, 0xFF, 0x80, 0x03, 0xFF, 0xFC, 0x00, + 0x3F, 0xFF, 0xC0, 0x03, 0xFE, 0xFE, 0x00, 0x3F, 0xCF, 0xE0, 0x03, 0xF0, + 0xFE, 0x00, 0x7F, 0x07, 0xF0, 0x07, 0xF0, 0x7F, 0x00, 0x7F, 0x07, 0xF8, + 0x07, 0xE0, 0x3F, 0x80, 0x7E, 0x03, 0xF8, 0x0F, 0xE0, 0x3F, 0xC0, 0xFE, + 0x01, 0xFC, 0x0F, 0xC0, 0x1F, 0xE0, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0x80, + 0x7E, 0x03, 0xF8, 0x0F, 0xE0, 0x3F, 0x80, 0xFC, 0x03, 0xF0, 0x1F, 0xC0, + 0x7F, 0x01, 0xFC, 0x07, 0xE0, 0x3F, 0x80, 0xFE, 0x03, 0xF8, 0x0F, 0xC0, + 0x3F, 0x01, 0xFC, 0x07, 0xF0, 0x1F, 0xC0, 0x7E, 0x03, 0xF8, 0x0F, 0xE0, + 0x3F, 0x80, 0xFC, 0x03, 0xF0, 0x1F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xE0, + 0x1F, 0x80, 0xFE, 0x03, 0xF8, 0x00, 0x07, 0xF0, 0xFC, 0x03, 0xF0, 0x07, + 0xE3, 0xFF, 0x0F, 0xFC, 0x07, 0xEF, 0xFF, 0x3F, 0xFE, 0x0F, 0xFF, 0xFF, + 0xFF, 0xFF, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0x0F, 0xF8, 0x7F, 0xF0, 0xFF, + 0x0F, 0xE0, 0x3F, 0xC0, 0x7F, 0x0F, 0xE0, 0x3F, 0x80, 0x7F, 0x1F, 0xC0, + 0x3F, 0x80, 0x7E, 0x1F, 0xC0, 0x3F, 0x00, 0x7E, 0x1F, 0xC0, 0x3F, 0x00, + 0xFE, 0x1F, 0x80, 0x7F, 0x00, 0xFE, 0x3F, 0x80, 0x7F, 0x00, 0xFC, 0x3F, + 0x80, 0x7F, 0x00, 0xFC, 0x3F, 0x80, 0x7E, 0x01, 0xFC, 0x3F, 0x00, 0x7E, + 0x01, 0xFC, 0x3F, 0x00, 0xFE, 0x01, 0xFC, 0x7F, 0x00, 0xFE, 0x01, 0xF8, + 0x7F, 0x00, 0xFE, 0x01, 0xF8, 0x7F, 0x00, 0xFC, 0x03, 0xF8, 0x7E, 0x01, + 0xFC, 0x03, 0xF8, 0x7E, 0x01, 0xFC, 0x03, 0xF8, 0xFE, 0x01, 0xFC, 0x03, + 0xF0, 0xFE, 0x01, 0xF8, 0x03, 0xF0, 0xFE, 0x01, 0xF8, 0x07, 0xF0, 0x07, + 0xF0, 0xFE, 0x00, 0xFE, 0x7F, 0xF0, 0x1F, 0x9F, 0xFF, 0x03, 0xFF, 0xFF, + 0xF0, 0xFF, 0xFF, 0xFE, 0x1F, 0xF8, 0x3F, 0xC3, 0xFC, 0x03, 0xF8, 0x7F, + 0x00, 0x7F, 0x0F, 0xE0, 0x0F, 0xE3, 0xF8, 0x01, 0xF8, 0x7F, 0x00, 0x3F, + 0x0F, 0xC0, 0x0F, 0xE1, 0xF8, 0x01, 0xFC, 0x7F, 0x00, 0x3F, 0x8F, 0xE0, + 0x07, 0xE1, 0xFC, 0x00, 0xFC, 0x3F, 0x00, 0x3F, 0x87, 0xE0, 0x07, 0xF1, + 0xFC, 0x00, 0xFE, 0x3F, 0x80, 0x1F, 0x87, 0xF0, 0x03, 0xF0, 0xFC, 0x00, + 0xFE, 0x3F, 0x80, 0x1F, 0xC7, 0xF0, 0x03, 0xF8, 0xFE, 0x00, 0x7E, 0x00, + 0x00, 0x1F, 0xE0, 0x00, 0x1F, 0xFF, 0x00, 0x1F, 0xFF, 0xE0, 0x0F, 0xFF, + 0xFC, 0x07, 0xFF, 0xFF, 0x83, 0xFC, 0x1F, 0xE1, 0xFE, 0x03, 0xFC, 0xFF, + 0x00, 0xFF, 0x3F, 0x80, 0x1F, 0xDF, 0xC0, 0x07, 0xF7, 0xF0, 0x01, 0xFD, + 0xFC, 0x00, 0x7F, 0xFE, 0x00, 0x1F, 0xFF, 0x80, 0x07, 0xFF, 0xE0, 0x03, + 0xFB, 0xF8, 0x00, 0xFE, 0xFE, 0x00, 0x3F, 0xBF, 0x80, 0x1F, 0xCF, 0xF0, + 0x0F, 0xF3, 0xFC, 0x07, 0xF8, 0x7F, 0x83, 0xFC, 0x1F, 0xFF, 0xFE, 0x03, + 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0x80, 0x0F, 0xFF, 0x80, 0x00, 0x7F, 0x00, + 0x00, 0x01, 0xFC, 0x3F, 0x00, 0x0F, 0xCF, 0xFE, 0x00, 0x7E, 0xFF, 0xF8, + 0x07, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, 0xFF, 0x01, 0xFF, 0x87, 0xF8, 0x0F, + 0xF0, 0x1F, 0xE0, 0xFF, 0x00, 0xFF, 0x07, 0xF0, 0x03, 0xF8, 0x3F, 0x80, + 0x1F, 0xC1, 0xF8, 0x00, 0xFE, 0x0F, 0xC0, 0x07, 0xF0, 0xFE, 0x00, 0x3F, + 0x87, 0xF0, 0x01, 0xFC, 0x3F, 0x00, 0x1F, 0xC1, 0xF8, 0x00, 0xFE, 0x1F, + 0xC0, 0x07, 0xF0, 0xFE, 0x00, 0x7F, 0x07, 0xF8, 0x07, 0xF8, 0x3F, 0xC0, + 0x7F, 0x81, 0xFF, 0x87, 0xF8, 0x1F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFC, + 0x07, 0xF7, 0xFF, 0xC0, 0x3F, 0x1F, 0xF8, 0x01, 0xF8, 0x7F, 0x00, 0x1F, + 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x3F, 0x00, + 0x00, 0x03, 0xF8, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0x07, 0xE0, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00, 0x00, 0x1F, 0x87, 0xF0, + 0x0F, 0xFE, 0x7F, 0x01, 0xFF, 0xF7, 0xE0, 0x3F, 0xFF, 0x7E, 0x07, 0xFF, + 0xFF, 0xE0, 0xFF, 0x07, 0xFE, 0x1F, 0xE0, 0x3F, 0xE3, 0xFC, 0x03, 0xFC, + 0x3F, 0x80, 0x1F, 0xC7, 0xF0, 0x01, 0xFC, 0x7F, 0x00, 0x1F, 0xC7, 0xF0, + 0x01, 0xF8, 0xFE, 0x00, 0x1F, 0x8F, 0xE0, 0x03, 0xF8, 0xFE, 0x00, 0x3F, + 0x8F, 0xE0, 0x03, 0xF8, 0xFE, 0x00, 0x7F, 0x0F, 0xE0, 0x07, 0xF0, 0xFE, + 0x00, 0xFF, 0x0F, 0xF0, 0x1F, 0xF0, 0x7F, 0x87, 0xFF, 0x07, 0xFF, 0xFF, + 0xE0, 0x3F, 0xFF, 0x7E, 0x03, 0xFF, 0xEF, 0xE0, 0x1F, 0xFC, 0xFE, 0x00, + 0x7F, 0x0F, 0xC0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x1F, 0x80, + 0x00, 0x03, 0xF8, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xF8, 0x00, 0x07, + 0xF0, 0xF0, 0x7F, 0x3F, 0x07, 0xE7, 0xE0, 0x7E, 0xFE, 0x0F, 0xFF, 0xE0, + 0xFF, 0xFE, 0x0F, 0xFC, 0x00, 0xFF, 0x00, 0x0F, 0xE0, 0x01, 0xFC, 0x00, + 0x1F, 0xC0, 0x01, 0xF8, 0x00, 0x1F, 0x80, 0x03, 0xF8, 0x00, 0x3F, 0x80, + 0x03, 0xF8, 0x00, 0x3F, 0x00, 0x03, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xF0, + 0x00, 0x7F, 0x00, 0x07, 0xE0, 0x00, 0xFE, 0x00, 0x0F, 0xE0, 0x00, 0xFE, + 0x00, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0xFF, 0xF8, 0x03, 0xFF, 0xFC, 0x07, + 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0x0F, 0xE0, 0xFF, 0x1F, 0xC0, 0x7F, 0x1F, + 0xC0, 0x7F, 0x1F, 0xE0, 0x00, 0x1F, 0xFC, 0x00, 0x1F, 0xFF, 0xC0, 0x0F, + 0xFF, 0xF0, 0x07, 0xFF, 0xF8, 0x03, 0xFF, 0xFC, 0x00, 0x7F, 0xFE, 0x00, + 0x0F, 0xFE, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFE, 0xFC, 0x00, 0xFE, 0xFE, + 0x00, 0xFE, 0xFF, 0x03, 0xFC, 0x7F, 0xFF, 0xF8, 0x7F, 0xFF, 0xF8, 0x3F, + 0xFF, 0xE0, 0x1F, 0xFF, 0xC0, 0x03, 0xFE, 0x00, 0x03, 0xF0, 0x1F, 0xC0, + 0x7F, 0x01, 0xFC, 0x07, 0xE0, 0x3F, 0x80, 0xFE, 0x1F, 0xFF, 0x7F, 0xFD, + 0xFF, 0xFF, 0xFF, 0xC7, 0xF0, 0x1F, 0xC0, 0x7E, 0x01, 0xF8, 0x0F, 0xE0, + 0x3F, 0x80, 0xFE, 0x03, 0xF0, 0x0F, 0xC0, 0x7F, 0x01, 0xFC, 0x07, 0xE0, + 0x1F, 0x80, 0xFE, 0x03, 0xF8, 0x0F, 0xE0, 0x3F, 0xF0, 0xFF, 0xC3, 0xFF, + 0x07, 0xFC, 0x0F, 0xE0, 0x0F, 0xC0, 0x0F, 0xE1, 0xF8, 0x01, 0xFC, 0x7F, + 0x00, 0x3F, 0x0F, 0xE0, 0x0F, 0xE1, 0xFC, 0x01, 0xFC, 0x3F, 0x00, 0x3F, + 0x87, 0xE0, 0x07, 0xE1, 0xFC, 0x00, 0xFC, 0x3F, 0x80, 0x3F, 0x87, 0xF0, + 0x07, 0xF0, 0xFC, 0x00, 0xFE, 0x1F, 0x80, 0x1F, 0x87, 0xF0, 0x03, 0xF0, + 0xFE, 0x00, 0xFE, 0x1F, 0x80, 0x1F, 0xC3, 0xF0, 0x03, 0xF0, 0xFE, 0x00, + 0x7E, 0x1F, 0xC0, 0x1F, 0xC3, 0xF8, 0x07, 0xF8, 0x7F, 0x01, 0xFF, 0x0F, + 0xF0, 0x7F, 0xC1, 0xFF, 0xFF, 0xF8, 0x3F, 0xFF, 0xFF, 0x03, 0xFF, 0xEF, + 0xE0, 0x3F, 0xF9, 0xFC, 0x01, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x7F, 0x7F, + 0x00, 0x3F, 0xBF, 0x80, 0x3F, 0x8F, 0xC0, 0x1F, 0xC7, 0xE0, 0x1F, 0xC3, + 0xF0, 0x0F, 0xC1, 0xFC, 0x0F, 0xE0, 0xFE, 0x07, 0xE0, 0x7F, 0x07, 0xF0, + 0x3F, 0x83, 0xF0, 0x0F, 0xC3, 0xF8, 0x07, 0xE1, 0xF8, 0x03, 0xF1, 0xFC, + 0x01, 0xF8, 0xFC, 0x00, 0xFC, 0xFC, 0x00, 0x7E, 0x7E, 0x00, 0x3F, 0x7E, + 0x00, 0x0F, 0xBF, 0x00, 0x07, 0xFF, 0x00, 0x03, 0xFF, 0x80, 0x01, 0xFF, + 0x80, 0x00, 0xFF, 0x80, 0x00, 0x7F, 0xC0, 0x00, 0x3F, 0xC0, 0x00, 0x1F, + 0xE0, 0x00, 0x00, 0xFE, 0x03, 0xF8, 0x0F, 0xFF, 0xC0, 0x7F, 0x01, 0xFF, + 0xF8, 0x1F, 0xE0, 0x3F, 0x7F, 0x03, 0xFC, 0x0F, 0xEF, 0xE0, 0xFF, 0x81, + 0xF9, 0xFC, 0x1F, 0xF0, 0x7F, 0x3F, 0x83, 0xFE, 0x0F, 0xC3, 0xF0, 0xFF, + 0xC3, 0xF8, 0x7E, 0x1E, 0xF8, 0x7E, 0x0F, 0xC7, 0xDF, 0x1F, 0xC1, 0xF8, + 0xFB, 0xE3, 0xF0, 0x3F, 0x1E, 0x7C, 0x7E, 0x07, 0xE7, 0xCF, 0x9F, 0x80, + 0xFC, 0xF1, 0xF3, 0xF0, 0x1F, 0xBE, 0x3E, 0xFC, 0x03, 0xF7, 0x87, 0xDF, + 0x80, 0x7E, 0xF0, 0xFF, 0xE0, 0x0F, 0xFE, 0x1F, 0xFC, 0x01, 0xFF, 0x83, + 0xFF, 0x00, 0x3F, 0xF0, 0x7F, 0xE0, 0x07, 0xFC, 0x0F, 0xF8, 0x00, 0x7F, + 0x81, 0xFF, 0x00, 0x0F, 0xF0, 0x3F, 0xC0, 0x01, 0xFC, 0x07, 0xF8, 0x00, + 0x3F, 0x80, 0xFE, 0x00, 0x00, 0x03, 0xFC, 0x07, 0xF8, 0x1F, 0xE0, 0x7F, + 0x80, 0x7F, 0x03, 0xF8, 0x03, 0xF8, 0x3F, 0x80, 0x1F, 0xE3, 0xF8, 0x00, + 0x7F, 0x3F, 0x80, 0x03, 0xF9, 0xFC, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x7F, + 0xFC, 0x00, 0x01, 0xFF, 0xC0, 0x00, 0x0F, 0xFC, 0x00, 0x00, 0x7F, 0xC0, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x01, 0xFF, 0x80, 0x00, + 0x1F, 0xFE, 0x00, 0x01, 0xFF, 0xF0, 0x00, 0x1F, 0xDF, 0xC0, 0x01, 0xFC, + 0xFE, 0x00, 0x1F, 0xE7, 0xF8, 0x00, 0xFE, 0x1F, 0xC0, 0x0F, 0xE0, 0xFE, + 0x00, 0xFF, 0x07, 0xF8, 0x0F, 0xF0, 0x1F, 0xC0, 0xFF, 0x00, 0xFF, 0x00, + 0x0F, 0xE0, 0x03, 0xF0, 0x7F, 0x00, 0x3F, 0x83, 0xF8, 0x01, 0xF8, 0x1F, + 0xC0, 0x1F, 0xC0, 0xFE, 0x00, 0xFC, 0x03, 0xF8, 0x0F, 0xE0, 0x1F, 0xC0, + 0x7E, 0x00, 0xFE, 0x07, 0xE0, 0x07, 0xF0, 0x3F, 0x00, 0x3F, 0x83, 0xF0, + 0x01, 0xFC, 0x1F, 0x80, 0x0F, 0xE1, 0xF8, 0x00, 0x3F, 0x0F, 0xC0, 0x01, + 0xF8, 0xFC, 0x00, 0x0F, 0xC7, 0xC0, 0x00, 0x7F, 0x7E, 0x00, 0x03, 0xFB, + 0xE0, 0x00, 0x1F, 0xFF, 0x00, 0x00, 0xFF, 0xF0, 0x00, 0x03, 0xFF, 0x80, + 0x00, 0x1F, 0xF8, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x07, 0xFC, 0x00, 0x00, + 0x3F, 0xC0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x03, 0xF8, 0x00, + 0x01, 0xFF, 0x80, 0x00, 0x1F, 0xFC, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x07, + 0xF8, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xC0, 0xFF, + 0xFF, 0xF0, 0x3F, 0xFF, 0xF8, 0x1F, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0x80, + 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x07, 0xF8, + 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, + 0x80, 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x07, + 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, + 0x7F, 0xFF, 0xFC, 0x1F, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, + 0xE0, 0xFF, 0xFF, 0xF8, 0x00, 0x00, 0x0F, 0xC0, 0x0F, 0xF0, 0x07, 0xFC, + 0x01, 0xFE, 0x00, 0xFF, 0x80, 0x3E, 0x00, 0x0F, 0x80, 0x07, 0xE0, 0x01, + 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x03, 0xE0, 0x00, 0xF8, + 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x07, 0xE0, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x3F, 0x00, 0x7F, 0x80, 0x1F, 0x80, 0x07, 0xE0, 0x03, 0xFC, 0x00, 0x3F, + 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xC0, + 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x01, + 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xF8, 0x01, 0xFE, 0x00, 0x7F, + 0x80, 0x0F, 0xE0, 0x01, 0xF8, 0x00, 0x00, 0x78, 0x03, 0xC0, 0x1C, 0x01, + 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1C, 0x01, 0xE0, 0x0F, 0x00, 0x78, + 0x03, 0xC0, 0x1C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x3C, 0x01, + 0xE0, 0x0F, 0x00, 0x78, 0x03, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, + 0x03, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0x80, 0x3C, 0x01, + 0xE0, 0x0F, 0x00, 0x70, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x70, + 0x07, 0x80, 0x3C, 0x00, 0x00, 0x7E, 0x00, 0x1F, 0xC0, 0x07, 0xF0, 0x01, + 0xFE, 0x00, 0x7F, 0x80, 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x1F, + 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x0F, 0x80, + 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xF0, 0x00, + 0xFF, 0x00, 0x1F, 0x80, 0x07, 0xE0, 0x07, 0xF8, 0x03, 0xF0, 0x00, 0xF8, + 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x1F, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x1F, + 0x80, 0x07, 0xC0, 0x01, 0xF0, 0x07, 0xFC, 0x01, 0xFE, 0x00, 0xFF, 0x80, + 0x3F, 0xC0, 0x0F, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0xFF, 0x80, 0x07, 0xFF, + 0x03, 0xDF, 0xFE, 0x0F, 0xF0, 0x7F, 0xFB, 0x80, 0xFF, 0xE0, 0x01, 0xFF, + 0x00, 0x03, 0xF0 }; + +const GFXglyph FreeSansBoldOblique24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 13, 0, 1 }, // 0x20 ' ' + { 0, 14, 34, 16, 5, -33 }, // 0x21 '!' + { 60, 18, 12, 22, 8, -33 }, // 0x22 '"' + { 87, 29, 33, 26, 2, -31 }, // 0x23 '#' + { 207, 26, 42, 26, 3, -35 }, // 0x24 '$' + { 344, 36, 34, 42, 6, -32 }, // 0x25 '%' + { 497, 29, 35, 34, 4, -33 }, // 0x26 '&' + { 624, 7, 12, 11, 8, -33 }, // 0x27 ''' + { 635, 17, 44, 16, 4, -33 }, // 0x28 '(' + { 729, 17, 44, 16, 0, -34 }, // 0x29 ')' + { 823, 15, 15, 18, 7, -33 }, // 0x2A '*' + { 852, 24, 22, 27, 4, -21 }, // 0x2B '+' + { 918, 10, 15, 13, 1, -6 }, // 0x2C ',' + { 937, 14, 6, 16, 3, -15 }, // 0x2D '-' + { 948, 8, 7, 13, 3, -6 }, // 0x2E '.' + { 955, 20, 34, 13, 0, -32 }, // 0x2F '/' + { 1040, 25, 35, 26, 4, -33 }, // 0x30 '0' + { 1150, 17, 33, 26, 8, -32 }, // 0x31 '1' + { 1221, 29, 34, 26, 1, -33 }, // 0x32 '2' + { 1345, 26, 35, 26, 3, -33 }, // 0x33 '3' + { 1459, 25, 32, 26, 3, -31 }, // 0x34 '4' + { 1559, 27, 34, 26, 3, -32 }, // 0x35 '5' + { 1674, 25, 35, 26, 4, -33 }, // 0x36 '6' + { 1784, 26, 33, 26, 6, -32 }, // 0x37 '7' + { 1892, 26, 35, 26, 3, -33 }, // 0x38 '8' + { 2006, 25, 35, 26, 4, -33 }, // 0x39 '9' + { 2116, 12, 25, 16, 5, -24 }, // 0x3A ':' + { 2154, 14, 33, 16, 3, -24 }, // 0x3B ';' + { 2212, 26, 23, 27, 4, -22 }, // 0x3C '<' + { 2287, 26, 18, 27, 3, -19 }, // 0x3D '=' + { 2346, 26, 23, 27, 1, -21 }, // 0x3E '>' + { 2421, 24, 35, 29, 8, -34 }, // 0x3F '?' + { 2526, 45, 41, 46, 3, -34 }, // 0x40 '@' + { 2757, 32, 34, 34, 1, -33 }, // 0x41 'A' + { 2893, 32, 34, 34, 4, -33 }, // 0x42 'B' + { 3029, 32, 36, 34, 5, -34 }, // 0x43 'C' + { 3173, 32, 34, 34, 4, -33 }, // 0x44 'D' + { 3309, 32, 34, 31, 4, -33 }, // 0x45 'E' + { 3445, 32, 34, 29, 3, -33 }, // 0x46 'F' + { 3581, 33, 36, 37, 5, -34 }, // 0x47 'G' + { 3730, 35, 34, 34, 3, -33 }, // 0x48 'H' + { 3879, 14, 34, 13, 3, -33 }, // 0x49 'I' + { 3939, 27, 35, 26, 3, -33 }, // 0x4A 'J' + { 4058, 37, 34, 34, 3, -33 }, // 0x4B 'K' + { 4216, 24, 34, 29, 4, -33 }, // 0x4C 'L' + { 4318, 41, 34, 39, 3, -33 }, // 0x4D 'M' + { 4493, 35, 34, 34, 3, -33 }, // 0x4E 'N' + { 4642, 34, 36, 37, 5, -34 }, // 0x4F 'O' + { 4795, 31, 34, 31, 4, -33 }, // 0x50 'P' + { 4927, 34, 37, 37, 5, -34 }, // 0x51 'Q' + { 5085, 33, 34, 34, 4, -33 }, // 0x52 'R' + { 5226, 30, 36, 31, 4, -34 }, // 0x53 'S' + { 5361, 28, 34, 29, 7, -33 }, // 0x54 'T' + { 5480, 32, 35, 34, 6, -33 }, // 0x55 'U' + { 5620, 30, 34, 31, 8, -33 }, // 0x56 'V' + { 5748, 43, 34, 44, 8, -33 }, // 0x57 'W' + { 5931, 37, 34, 31, 1, -33 }, // 0x58 'X' + { 6089, 29, 34, 31, 9, -33 }, // 0x59 'Y' + { 6213, 33, 34, 29, 1, -33 }, // 0x5A 'Z' + { 6354, 21, 43, 16, 1, -33 }, // 0x5B '[' + { 6467, 7, 36, 13, 6, -34 }, // 0x5C '\' + { 6499, 21, 43, 16, -1, -33 }, // 0x5D ']' + { 6612, 21, 20, 27, 6, -32 }, // 0x5E '^' + { 6665, 29, 4, 26, -3, 6 }, // 0x5F '_' + { 6680, 7, 7, 16, 8, -35 }, // 0x60 '`' + { 6687, 25, 26, 26, 2, -24 }, // 0x61 'a' + { 6769, 27, 35, 29, 3, -33 }, // 0x62 'b' + { 6888, 25, 26, 26, 4, -24 }, // 0x63 'c' + { 6970, 29, 35, 29, 4, -33 }, // 0x64 'd' + { 7097, 25, 26, 26, 3, -24 }, // 0x65 'e' + { 7179, 18, 34, 16, 4, -33 }, // 0x66 'f' + { 7256, 29, 35, 29, 2, -24 }, // 0x67 'g' + { 7383, 27, 34, 29, 3, -33 }, // 0x68 'h' + { 7498, 14, 34, 13, 3, -33 }, // 0x69 'i' + { 7558, 19, 44, 13, -2, -33 }, // 0x6A 'j' + { 7663, 28, 34, 26, 3, -33 }, // 0x6B 'k' + { 7782, 14, 34, 13, 3, -33 }, // 0x6C 'l' + { 7842, 40, 25, 42, 3, -24 }, // 0x6D 'm' + { 7967, 27, 25, 29, 3, -24 }, // 0x6E 'n' + { 8052, 26, 26, 29, 4, -24 }, // 0x6F 'o' + { 8137, 29, 35, 29, 1, -24 }, // 0x70 'p' + { 8264, 28, 35, 29, 3, -24 }, // 0x71 'q' + { 8387, 20, 25, 18, 3, -24 }, // 0x72 'r' + { 8450, 24, 26, 26, 3, -24 }, // 0x73 's' + { 8528, 14, 32, 16, 5, -30 }, // 0x74 't' + { 8584, 27, 26, 29, 4, -24 }, // 0x75 'u' + { 8672, 25, 25, 26, 6, -24 }, // 0x76 'v' + { 8751, 35, 25, 37, 6, -24 }, // 0x77 'w' + { 8861, 29, 25, 26, 1, -24 }, // 0x78 'x' + { 8952, 29, 35, 26, 2, -24 }, // 0x79 'y' + { 9079, 26, 25, 23, 1, -24 }, // 0x7A 'z' + { 9161, 18, 43, 18, 4, -33 }, // 0x7B '{' + { 9258, 13, 43, 13, 3, -33 }, // 0x7C '|' + { 9328, 18, 43, 18, 2, -33 }, // 0x7D '}' + { 9425, 22, 8, 27, 5, -14 } }; // 0x7E '~' + +const GFXfont FreeSansBoldOblique24pt7b PROGMEM = { + (uint8_t *)FreeSansBoldOblique24pt7bBitmaps, + (GFXglyph *)FreeSansBoldOblique24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 10119 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique9pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique9pt7b.h new file mode 100644 index 0000000..6250aca --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansBoldOblique9pt7b.h @@ -0,0 +1,227 @@ +const uint8_t FreeSansBoldOblique9pt7bBitmaps[] PROGMEM = { + 0x21, 0x8E, 0x73, 0x18, 0xC6, 0x21, 0x19, 0xCE, 0x00, 0xEF, 0xDF, 0xBE, + 0x68, 0x80, 0x06, 0xC1, 0x99, 0xFF, 0xBF, 0xF1, 0xB0, 0x66, 0x0C, 0xC7, + 0xFC, 0xFF, 0x8C, 0x83, 0x30, 0x64, 0x00, 0x02, 0x00, 0xF0, 0x7F, 0x1D, + 0x73, 0xEE, 0x78, 0x0F, 0x00, 0xF8, 0x0F, 0xC1, 0xBB, 0xA7, 0x74, 0xEF, + 0xF8, 0xFE, 0x04, 0x00, 0x80, 0x3C, 0x11, 0xF8, 0x8E, 0x66, 0x31, 0x90, + 0xCE, 0x83, 0xF4, 0x07, 0xB0, 0x00, 0x9E, 0x04, 0xFC, 0x26, 0x31, 0x98, + 0xC4, 0x7E, 0x20, 0xF0, 0x07, 0x80, 0xFC, 0x1D, 0xC1, 0xDC, 0x1F, 0x80, + 0xE0, 0x3E, 0x37, 0x77, 0xE3, 0xEE, 0x3C, 0xE3, 0xCF, 0xFE, 0x3C, 0xE0, + 0xFF, 0xE8, 0x06, 0x06, 0x0C, 0x18, 0x38, 0x30, 0x70, 0x60, 0xE0, 0xE0, + 0xE0, 0xE0, 0xE0, 0xE0, 0x60, 0x70, 0x30, 0x0C, 0x0E, 0x06, 0x07, 0x07, + 0x07, 0x07, 0x07, 0x07, 0x06, 0x0E, 0x0C, 0x1C, 0x18, 0x30, 0x60, 0x60, + 0x32, 0xBF, 0x9C, 0xD2, 0x40, 0x0C, 0x06, 0x07, 0x1F, 0xFF, 0xF0, 0xC0, + 0xE0, 0x60, 0x77, 0x72, 0x6C, 0xFF, 0xC0, 0xFC, 0x02, 0x02, 0x04, 0x04, + 0x08, 0x08, 0x10, 0x10, 0x20, 0x20, 0x40, 0x40, 0x80, 0x0F, 0x07, 0xE3, + 0x9D, 0xC7, 0x71, 0xDC, 0x7E, 0x1F, 0x8E, 0xE3, 0xB8, 0xEE, 0x73, 0xF8, + 0x3C, 0x00, 0x04, 0x3B, 0xF7, 0xE1, 0xC3, 0x06, 0x1C, 0x38, 0x70, 0xC1, + 0x87, 0x00, 0x0F, 0x87, 0xFC, 0xE3, 0xB8, 0x70, 0x0E, 0x03, 0x80, 0xF0, + 0x38, 0x1E, 0x07, 0x01, 0xC0, 0x7F, 0xCF, 0xF8, 0x0F, 0xC7, 0xFC, 0xE3, + 0xB8, 0x70, 0x1C, 0x0F, 0x03, 0xF0, 0x0E, 0x01, 0xDC, 0x3B, 0x8E, 0x7F, + 0x83, 0xE0, 0x03, 0xC0, 0xE0, 0x58, 0x2E, 0x13, 0x8C, 0xE6, 0x33, 0xFE, + 0xFF, 0x81, 0xC0, 0x60, 0x18, 0x0F, 0xE3, 0xFC, 0x60, 0x0C, 0x03, 0x78, + 0x7F, 0x9C, 0x70, 0x0E, 0x01, 0xDC, 0x33, 0x8E, 0x7F, 0x83, 0xE0, 0x0F, + 0x07, 0xE3, 0x9D, 0xC0, 0x7F, 0x1F, 0xEF, 0x3B, 0x8E, 0xE3, 0xB8, 0xCE, + 0x71, 0xF8, 0x3C, 0x00, 0x7F, 0xDF, 0xF0, 0x18, 0x0C, 0x06, 0x03, 0x81, + 0xC0, 0x60, 0x38, 0x0C, 0x07, 0x01, 0x80, 0x60, 0x00, 0x0F, 0x83, 0xFC, + 0xE3, 0x9C, 0x73, 0x9C, 0x3F, 0x0F, 0xE3, 0x8E, 0xE1, 0xDC, 0x3B, 0x8E, + 0x7F, 0xC3, 0xE0, 0x0F, 0x83, 0xF8, 0xE3, 0xB8, 0x77, 0x0E, 0xE1, 0xDC, + 0x7B, 0xFE, 0x3D, 0xC0, 0x33, 0x8E, 0x7F, 0x87, 0xC0, 0x77, 0x00, 0x00, + 0x0E, 0xE0, 0x39, 0xC0, 0x00, 0x01, 0xCE, 0x71, 0x19, 0x80, 0x00, 0x00, + 0x70, 0xFD, 0xF8, 0x70, 0x3F, 0x03, 0xF8, 0x1E, 0x01, 0x80, 0x7F, 0xDF, + 0xF0, 0x00, 0x00, 0xFF, 0xBF, 0xE0, 0x60, 0x1E, 0x07, 0xF0, 0x3F, 0x03, + 0x87, 0xEF, 0xC3, 0x80, 0x00, 0x00, 0x1F, 0x1F, 0xFE, 0x1F, 0x87, 0x01, + 0xC0, 0xE0, 0x70, 0x78, 0x3C, 0x0E, 0x00, 0x00, 0xE0, 0x38, 0x00, 0x00, + 0xFC, 0x00, 0xFF, 0xC0, 0xF0, 0x78, 0x70, 0x07, 0x38, 0x01, 0xCC, 0x3F, + 0x36, 0x31, 0x8D, 0x98, 0x63, 0xC4, 0x11, 0xF3, 0x0C, 0x6C, 0xC6, 0x73, + 0x3E, 0xF8, 0xE7, 0x3C, 0x1E, 0x00, 0x03, 0xFE, 0x00, 0x3F, 0x00, 0x01, + 0xE0, 0x0F, 0x00, 0xF8, 0x07, 0xC0, 0x6F, 0x03, 0x38, 0x31, 0xC3, 0x8E, + 0x1F, 0xF1, 0xFF, 0x8C, 0x1E, 0xE0, 0x76, 0x03, 0x80, 0x1F, 0xF0, 0xFF, + 0xC6, 0x0E, 0x70, 0x73, 0x87, 0x1F, 0xF0, 0xFF, 0x86, 0x0E, 0x70, 0x73, + 0x83, 0x9C, 0x38, 0xFF, 0xC7, 0xF8, 0x00, 0x07, 0xE0, 0xFF, 0x8F, 0x1E, + 0x70, 0x77, 0x00, 0x30, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x03, 0xBC, + 0x38, 0xFF, 0x83, 0xF0, 0x00, 0x1F, 0xE0, 0xFF, 0x86, 0x1E, 0x70, 0x73, + 0x83, 0x9C, 0x1C, 0xC0, 0xE6, 0x07, 0x70, 0x73, 0x83, 0x9C, 0x38, 0xFF, + 0x8F, 0xF0, 0x00, 0x1F, 0xF8, 0xFF, 0x86, 0x00, 0x70, 0x03, 0x80, 0x1F, + 0xF0, 0xFF, 0x86, 0x00, 0x70, 0x03, 0x80, 0x1C, 0x00, 0xFF, 0xC7, 0xFC, + 0x00, 0x1F, 0xF1, 0xFF, 0x18, 0x03, 0x80, 0x38, 0x03, 0xFC, 0x3F, 0xC7, + 0x00, 0x70, 0x07, 0x00, 0x70, 0x06, 0x00, 0xE0, 0x00, 0x07, 0xC1, 0xFE, + 0x38, 0x77, 0x03, 0x70, 0x0E, 0x00, 0xE1, 0xEE, 0x1E, 0xE0, 0x6E, 0x0E, + 0x70, 0xE7, 0xFC, 0x1F, 0x40, 0x1C, 0x1C, 0x60, 0x63, 0x83, 0x8E, 0x0E, + 0x38, 0x38, 0xFF, 0xC3, 0xFF, 0x1C, 0x1C, 0x70, 0x71, 0xC1, 0xC6, 0x06, + 0x18, 0x38, 0xE0, 0xE0, 0x39, 0xCE, 0x63, 0x39, 0xCE, 0x63, 0x39, 0xCE, + 0x00, 0x00, 0xC0, 0x18, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x00, 0xE0, 0x1C, + 0xE3, 0x9C, 0x73, 0x9C, 0x7F, 0x87, 0xC0, 0x1C, 0x3C, 0x71, 0xC1, 0x8E, + 0x0E, 0x70, 0x3B, 0x80, 0xFC, 0x03, 0xF0, 0x0E, 0xE0, 0x73, 0x81, 0xC7, + 0x07, 0x1C, 0x18, 0x38, 0xE0, 0xF0, 0x1C, 0x07, 0x01, 0x80, 0xE0, 0x38, + 0x0E, 0x03, 0x80, 0xC0, 0x70, 0x1C, 0x07, 0x01, 0xFF, 0x7F, 0x80, 0x1E, + 0x1F, 0x1E, 0x1E, 0x3E, 0x1E, 0x3E, 0x3E, 0x36, 0x3E, 0x36, 0x6E, 0x36, + 0x6C, 0x76, 0xCC, 0x76, 0xDC, 0x67, 0x9C, 0x67, 0x98, 0xE7, 0x18, 0xE7, + 0x18, 0x1C, 0x1C, 0x70, 0x63, 0xE1, 0x8F, 0x8E, 0x3E, 0x38, 0xDC, 0xC3, + 0x33, 0x1C, 0xEC, 0x71, 0xF1, 0xC7, 0xC6, 0x1E, 0x18, 0x38, 0xE0, 0xE0, + 0x07, 0xC0, 0xFF, 0x8E, 0x1E, 0xE0, 0x77, 0x03, 0xF0, 0x1F, 0x80, 0xFC, + 0x07, 0xE0, 0x77, 0x03, 0xBC, 0x38, 0xFF, 0x81, 0xF0, 0x00, 0x1F, 0xF0, + 0xFF, 0xC6, 0x0E, 0x70, 0x73, 0x83, 0x9C, 0x38, 0xFF, 0x87, 0xF8, 0x70, + 0x03, 0x80, 0x1C, 0x00, 0xC0, 0x0E, 0x00, 0x00, 0x07, 0xC0, 0xFF, 0x8F, + 0x1C, 0xE0, 0x77, 0x03, 0xB0, 0x1F, 0x80, 0xFC, 0x06, 0xE1, 0x77, 0x1F, + 0x3C, 0x78, 0xFF, 0xC1, 0xF6, 0x00, 0x20, 0x1F, 0xF0, 0xFF, 0xC6, 0x0E, + 0x70, 0x73, 0x83, 0x9C, 0x38, 0xFF, 0x87, 0xFC, 0x70, 0x73, 0x83, 0x9C, + 0x38, 0xC1, 0xC6, 0x0F, 0x00, 0x07, 0xE0, 0xFF, 0xC7, 0x0E, 0x70, 0x73, + 0x80, 0x1F, 0x80, 0x7F, 0x80, 0x7E, 0x00, 0x77, 0x03, 0xBC, 0x38, 0xFF, + 0xC3, 0xF8, 0x00, 0xFF, 0xDF, 0xF8, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x06, + 0x01, 0xC0, 0x38, 0x07, 0x00, 0xC0, 0x18, 0x07, 0x00, 0x38, 0x31, 0xC1, + 0x8C, 0x1C, 0xE0, 0xE7, 0x07, 0x38, 0x31, 0xC3, 0x9C, 0x1C, 0xE0, 0xE7, + 0x06, 0x38, 0x70, 0xFF, 0x03, 0xE0, 0x00, 0xE0, 0xFC, 0x1D, 0x87, 0x30, + 0xC6, 0x38, 0xC6, 0x19, 0xC3, 0xB0, 0x7E, 0x0F, 0x80, 0xF0, 0x1C, 0x03, + 0x00, 0xE1, 0xC3, 0xF1, 0xE3, 0xB8, 0xF1, 0xDC, 0x78, 0xCE, 0x6C, 0xE7, + 0x36, 0x63, 0xB3, 0x70, 0xD9, 0xB0, 0x7C, 0xD8, 0x3C, 0x78, 0x1E, 0x3C, + 0x0E, 0x1C, 0x07, 0x0E, 0x00, 0x0E, 0x1C, 0x38, 0xE0, 0xE7, 0x01, 0xD8, + 0x07, 0xE0, 0x0F, 0x00, 0x38, 0x01, 0xE0, 0x0F, 0xC0, 0x77, 0x01, 0x8E, + 0x0E, 0x38, 0x70, 0xF0, 0xE0, 0xEE, 0x39, 0xC7, 0x39, 0xC3, 0x70, 0x7C, + 0x0F, 0x80, 0xE0, 0x1C, 0x03, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x3F, 0xF3, + 0xFF, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x3C, 0x07, + 0x80, 0x70, 0x0F, 0xFC, 0xFF, 0xC0, 0x0F, 0x0F, 0x0C, 0x1C, 0x18, 0x18, + 0x18, 0x18, 0x30, 0x30, 0x30, 0x30, 0x60, 0x60, 0x60, 0x78, 0x78, 0x12, + 0x4C, 0x92, 0x49, 0x26, 0xD9, 0x20, 0x1E, 0x1E, 0x06, 0x06, 0x06, 0x0C, + 0x0C, 0x0C, 0x0C, 0x18, 0x18, 0x18, 0x18, 0x38, 0x30, 0xF0, 0xF0, 0x06, + 0x0E, 0x0E, 0x1B, 0x33, 0x33, 0x63, 0x63, 0xFF, 0xE0, 0xCC, 0x1F, 0x8F, + 0xF3, 0x1C, 0x06, 0x1F, 0x9F, 0xEE, 0x3B, 0x9C, 0xFF, 0x1D, 0xC0, 0x18, + 0x03, 0x00, 0xE0, 0x1D, 0xC3, 0xFC, 0x71, 0xDC, 0x3B, 0x87, 0x70, 0xEE, + 0x39, 0xCF, 0x7F, 0xCF, 0xE0, 0x0F, 0x0F, 0xF7, 0x1D, 0xC0, 0xE0, 0x38, + 0x0E, 0x03, 0x8E, 0x7F, 0x0F, 0x80, 0x00, 0x60, 0x06, 0x00, 0x61, 0xEE, + 0x3F, 0xE7, 0x9C, 0x71, 0xCE, 0x1C, 0xE1, 0xCE, 0x1C, 0xE3, 0x87, 0xF8, + 0x7F, 0x80, 0x1F, 0x0F, 0xE7, 0x1D, 0xC7, 0xFF, 0xFF, 0xFE, 0x03, 0x8E, + 0x7F, 0x0F, 0x80, 0x1C, 0xF3, 0x3F, 0xFD, 0xC7, 0x18, 0x63, 0x8E, 0x30, + 0xC0, 0x0F, 0x71, 0xFE, 0x3C, 0xE3, 0x8E, 0x70, 0xE7, 0x0E, 0x70, 0xC7, + 0x1C, 0x3F, 0xC3, 0xFC, 0x01, 0xCE, 0x38, 0x7F, 0x03, 0xE0, 0x18, 0x03, + 0x00, 0xE0, 0x1D, 0xE3, 0xFE, 0x71, 0xCC, 0x3B, 0x86, 0x70, 0xCC, 0x39, + 0x87, 0x30, 0xEE, 0x18, 0x39, 0xC0, 0x63, 0x39, 0xCE, 0x63, 0x39, 0xCE, + 0x00, 0x06, 0x06, 0x00, 0x0E, 0x0E, 0x0C, 0x0C, 0x1C, 0x1C, 0x1C, 0x18, + 0x18, 0x38, 0x38, 0x30, 0x70, 0xE0, 0x18, 0x03, 0x00, 0xE0, 0x1C, 0xE3, + 0x38, 0x6E, 0x1F, 0x83, 0xF0, 0x7E, 0x0E, 0xE1, 0x9C, 0x73, 0x8E, 0x38, + 0x39, 0xCE, 0x63, 0x39, 0xCE, 0x63, 0x39, 0xCE, 0x00, 0x3B, 0x9E, 0x3F, + 0xFF, 0x39, 0xC7, 0x71, 0xC6, 0x71, 0x86, 0x71, 0x8E, 0x63, 0x8E, 0x63, + 0x8C, 0xE3, 0x8C, 0xE3, 0x1C, 0x3B, 0xC7, 0xFC, 0xE3, 0xB8, 0x77, 0x0C, + 0xE1, 0x98, 0x73, 0x0E, 0xE1, 0xDC, 0x30, 0x0F, 0x87, 0xF9, 0xE7, 0xB8, + 0x7E, 0x0F, 0xC1, 0xF8, 0x77, 0x9E, 0x7F, 0x87, 0xC0, 0x1D, 0xE1, 0xFE, + 0x1C, 0x73, 0x87, 0x38, 0x73, 0x87, 0x38, 0xE3, 0x8E, 0x7F, 0xC7, 0xF8, + 0x60, 0x06, 0x00, 0x60, 0x0E, 0x00, 0x1E, 0xE7, 0xFD, 0xE7, 0x38, 0xEE, + 0x1D, 0xC3, 0xB8, 0x77, 0x1C, 0x7F, 0x8F, 0xF0, 0x0E, 0x01, 0x80, 0x30, + 0x06, 0x00, 0x3B, 0x36, 0x38, 0x70, 0x70, 0x70, 0x60, 0x60, 0xE0, 0xE0, + 0x3E, 0x3F, 0xF8, 0xFC, 0x0F, 0xC3, 0xF8, 0x3D, 0x8E, 0xFE, 0x3E, 0x00, + 0x38, 0xCF, 0xFE, 0x71, 0x86, 0x38, 0xE3, 0x8F, 0x3C, 0x31, 0xDC, 0x77, + 0x19, 0x86, 0x63, 0xB8, 0xEE, 0x33, 0x9C, 0xFF, 0x1F, 0xC0, 0xE1, 0x98, + 0xE6, 0x31, 0x9C, 0x66, 0x1B, 0x86, 0xC1, 0xF0, 0x78, 0x0E, 0x00, 0xE7, + 0x1B, 0x9C, 0xEE, 0x73, 0x3B, 0xDC, 0xEB, 0x63, 0xAD, 0x8F, 0xBC, 0x1C, + 0xF0, 0x73, 0xC1, 0xCE, 0x00, 0x1C, 0xE1, 0xCC, 0x0D, 0x80, 0xF8, 0x0F, + 0x00, 0xF0, 0x1F, 0x03, 0xB8, 0x33, 0x87, 0x38, 0x70, 0xCE, 0x38, 0xC6, + 0x19, 0xC3, 0x30, 0x66, 0x0F, 0x81, 0xF0, 0x3C, 0x03, 0x80, 0x60, 0x18, + 0x0F, 0x01, 0xC0, 0x00, 0x1F, 0xCF, 0xF0, 0x38, 0x1C, 0x0E, 0x07, 0x03, + 0x81, 0xC0, 0x7F, 0xBF, 0xE0, 0x0E, 0x38, 0x61, 0x83, 0x06, 0x0C, 0x78, + 0xF0, 0xC1, 0x83, 0x0E, 0x1C, 0x38, 0x78, 0x70, 0x18, 0xC4, 0x21, 0x18, + 0xC4, 0x21, 0x18, 0xC4, 0x23, 0x18, 0x80, 0x1C, 0x3C, 0x38, 0x70, 0xE1, + 0x83, 0x06, 0x1E, 0x5C, 0x60, 0xC1, 0x83, 0x0C, 0x38, 0xE0, 0x71, 0x8E }; + +const GFXglyph FreeSansBoldOblique9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 5, 13, 6, 2, -12 }, // 0x21 '!' + { 9, 7, 5, 9, 3, -12 }, // 0x22 '"' + { 14, 11, 12, 10, 1, -11 }, // 0x23 '#' + { 31, 11, 16, 10, 1, -13 }, // 0x24 '$' + { 53, 14, 13, 16, 2, -12 }, // 0x25 '%' + { 76, 12, 13, 13, 2, -12 }, // 0x26 '&' + { 96, 3, 5, 4, 3, -12 }, // 0x27 ''' + { 98, 8, 17, 6, 2, -12 }, // 0x28 '(' + { 115, 8, 17, 6, -2, -13 }, // 0x29 ')' + { 132, 6, 6, 7, 3, -12 }, // 0x2A '*' + { 137, 9, 8, 11, 2, -7 }, // 0x2B '+' + { 146, 4, 6, 5, 0, -2 }, // 0x2C ',' + { 149, 5, 2, 6, 1, -5 }, // 0x2D '-' + { 151, 3, 2, 5, 1, -1 }, // 0x2E '.' + { 152, 8, 13, 5, 0, -12 }, // 0x2F '/' + { 165, 10, 13, 10, 1, -12 }, // 0x30 '0' + { 182, 7, 13, 10, 3, -12 }, // 0x31 '1' + { 194, 11, 13, 10, 1, -12 }, // 0x32 '2' + { 212, 11, 13, 10, 1, -12 }, // 0x33 '3' + { 230, 10, 12, 10, 1, -11 }, // 0x34 '4' + { 245, 11, 13, 10, 1, -12 }, // 0x35 '5' + { 263, 10, 13, 10, 2, -12 }, // 0x36 '6' + { 280, 10, 13, 10, 2, -12 }, // 0x37 '7' + { 297, 11, 13, 10, 1, -12 }, // 0x38 '8' + { 315, 11, 13, 10, 1, -12 }, // 0x39 '9' + { 333, 4, 9, 6, 2, -8 }, // 0x3A ':' + { 338, 5, 12, 6, 1, -8 }, // 0x3B ';' + { 346, 10, 9, 11, 1, -8 }, // 0x3C '<' + { 358, 10, 6, 11, 1, -6 }, // 0x3D '=' + { 366, 10, 9, 11, 1, -7 }, // 0x3E '>' + { 378, 10, 13, 11, 3, -12 }, // 0x3F '?' + { 395, 18, 16, 18, 1, -13 }, // 0x40 '@' + { 431, 13, 13, 13, 0, -12 }, // 0x41 'A' + { 453, 13, 13, 13, 1, -12 }, // 0x42 'B' + { 475, 13, 13, 13, 2, -12 }, // 0x43 'C' + { 497, 13, 13, 13, 1, -12 }, // 0x44 'D' + { 519, 13, 13, 12, 1, -12 }, // 0x45 'E' + { 541, 12, 13, 11, 1, -12 }, // 0x46 'F' + { 561, 12, 13, 14, 2, -12 }, // 0x47 'G' + { 581, 14, 13, 13, 1, -12 }, // 0x48 'H' + { 604, 5, 13, 5, 1, -12 }, // 0x49 'I' + { 613, 11, 13, 10, 1, -12 }, // 0x4A 'J' + { 631, 14, 13, 13, 1, -12 }, // 0x4B 'K' + { 654, 10, 13, 11, 1, -12 }, // 0x4C 'L' + { 671, 16, 13, 15, 1, -12 }, // 0x4D 'M' + { 697, 14, 13, 13, 1, -12 }, // 0x4E 'N' + { 720, 13, 13, 14, 2, -12 }, // 0x4F 'O' + { 742, 13, 13, 12, 1, -12 }, // 0x50 'P' + { 764, 13, 14, 14, 2, -12 }, // 0x51 'Q' + { 787, 13, 13, 13, 1, -12 }, // 0x52 'R' + { 809, 13, 13, 12, 1, -12 }, // 0x53 'S' + { 831, 11, 13, 11, 3, -12 }, // 0x54 'T' + { 849, 13, 13, 13, 2, -12 }, // 0x55 'U' + { 871, 11, 13, 12, 3, -12 }, // 0x56 'V' + { 889, 17, 13, 17, 3, -12 }, // 0x57 'W' + { 917, 14, 13, 12, 0, -12 }, // 0x58 'X' + { 940, 11, 13, 12, 3, -12 }, // 0x59 'Y' + { 958, 12, 13, 11, 1, -12 }, // 0x5A 'Z' + { 978, 8, 17, 6, 0, -12 }, // 0x5B '[' + { 995, 3, 17, 5, 2, -16 }, // 0x5C '\' + { 1002, 8, 17, 6, 0, -13 }, // 0x5D ']' + { 1019, 8, 8, 11, 2, -12 }, // 0x5E '^' + { 1027, 11, 1, 10, -1, 4 }, // 0x5F '_' + { 1029, 3, 2, 6, 3, -12 }, // 0x60 '`' + { 1030, 10, 10, 10, 1, -9 }, // 0x61 'a' + { 1043, 11, 13, 11, 1, -12 }, // 0x62 'b' + { 1061, 10, 10, 10, 1, -9 }, // 0x63 'c' + { 1074, 12, 13, 11, 1, -12 }, // 0x64 'd' + { 1094, 10, 10, 10, 1, -9 }, // 0x65 'e' + { 1107, 6, 13, 6, 2, -12 }, // 0x66 'f' + { 1117, 12, 14, 11, 0, -9 }, // 0x67 'g' + { 1138, 11, 13, 11, 1, -12 }, // 0x68 'h' + { 1156, 5, 13, 5, 1, -12 }, // 0x69 'i' + { 1165, 8, 17, 5, -1, -12 }, // 0x6A 'j' + { 1182, 11, 13, 10, 1, -12 }, // 0x6B 'k' + { 1200, 5, 13, 5, 1, -12 }, // 0x6C 'l' + { 1209, 16, 10, 16, 1, -9 }, // 0x6D 'm' + { 1229, 11, 10, 11, 1, -9 }, // 0x6E 'n' + { 1243, 11, 10, 11, 1, -9 }, // 0x6F 'o' + { 1257, 12, 14, 11, 0, -9 }, // 0x70 'p' + { 1278, 11, 14, 11, 1, -9 }, // 0x71 'q' + { 1298, 8, 10, 7, 1, -9 }, // 0x72 'r' + { 1308, 9, 10, 10, 2, -9 }, // 0x73 's' + { 1320, 6, 12, 6, 2, -11 }, // 0x74 't' + { 1329, 10, 10, 11, 2, -9 }, // 0x75 'u' + { 1342, 10, 10, 10, 2, -9 }, // 0x76 'v' + { 1355, 14, 10, 14, 2, -9 }, // 0x77 'w' + { 1373, 12, 10, 10, 0, -9 }, // 0x78 'x' + { 1388, 11, 14, 10, 1, -9 }, // 0x79 'y' + { 1408, 10, 10, 9, 0, -9 }, // 0x7A 'z' + { 1421, 7, 17, 7, 2, -12 }, // 0x7B '{' + { 1436, 5, 17, 5, 1, -12 }, // 0x7C '|' + { 1447, 7, 17, 7, 0, -13 }, // 0x7D '}' + { 1462, 8, 2, 11, 2, -4 } }; // 0x7E '~' + +const GFXfont FreeSansBoldOblique9pt7b PROGMEM = { + (uint8_t *)FreeSansBoldOblique9pt7bBitmaps, + (GFXglyph *)FreeSansBoldOblique9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 2136 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansOblique12pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansOblique12pt7b.h new file mode 100644 index 0000000..efdbd8d --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansOblique12pt7b.h @@ -0,0 +1,302 @@ +const uint8_t FreeSansOblique12pt7bBitmaps[] PROGMEM = { + 0x0C, 0x61, 0x86, 0x18, 0x63, 0x0C, 0x30, 0xC2, 0x18, 0x61, 0x00, 0x00, + 0xC3, 0x00, 0xCF, 0x3C, 0xE2, 0x8A, 0x20, 0x01, 0x8C, 0x03, 0x18, 0x06, + 0x60, 0x18, 0xC0, 0x31, 0x83, 0xFF, 0x87, 0xFF, 0x03, 0x18, 0x0C, 0x60, + 0x18, 0xC0, 0x23, 0x03, 0xFF, 0x8F, 0xFF, 0x02, 0x30, 0x0C, 0x60, 0x18, + 0x80, 0x63, 0x00, 0xC6, 0x00, 0x00, 0x80, 0x3F, 0x03, 0xFC, 0x32, 0x73, + 0x91, 0x99, 0x8C, 0xCC, 0x06, 0x60, 0x3E, 0x00, 0x7E, 0x01, 0xFC, 0x0C, + 0xEC, 0x43, 0x62, 0x1B, 0x11, 0x9D, 0x9C, 0x7F, 0xC1, 0xF8, 0x02, 0x00, + 0x10, 0x01, 0x80, 0x00, 0x00, 0x01, 0x83, 0xC0, 0x60, 0xFC, 0x18, 0x30, + 0xC2, 0x0C, 0x18, 0xC1, 0x83, 0x30, 0x38, 0xCC, 0x03, 0xF1, 0x00, 0x3C, + 0x40, 0x00, 0x18, 0xF0, 0x06, 0x3F, 0x01, 0x8C, 0x30, 0x23, 0x06, 0x0C, + 0x60, 0xC3, 0x0E, 0x30, 0xC0, 0xFC, 0x10, 0x0F, 0x00, 0x01, 0xE0, 0x3F, + 0x81, 0x8C, 0x18, 0x60, 0xC3, 0x06, 0x30, 0x1F, 0x00, 0xE0, 0x1F, 0x01, + 0xDC, 0xD8, 0x6D, 0x81, 0xEC, 0x0E, 0x60, 0x73, 0x87, 0xCF, 0xE6, 0x3E, + 0x38, 0xFE, 0xA0, 0x03, 0x06, 0x04, 0x0C, 0x18, 0x18, 0x30, 0x30, 0x60, + 0x60, 0x60, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0x40, 0x60, + 0x60, 0x20, 0x04, 0x06, 0x06, 0x02, 0x03, 0x03, 0x03, 0x03, 0x03, 0x03, + 0x03, 0x03, 0x06, 0x06, 0x06, 0x0C, 0x0C, 0x18, 0x18, 0x30, 0x20, 0x60, + 0xC0, 0x0C, 0x0C, 0x49, 0x7F, 0x3C, 0x3C, 0x6C, 0x00, 0x03, 0x00, 0x30, + 0x03, 0x00, 0x30, 0xFF, 0xFF, 0xFF, 0x06, 0x00, 0x60, 0x06, 0x00, 0xC0, + 0x0C, 0x00, 0x77, 0x22, 0x6C, 0xFF, 0xF0, 0xFC, 0x00, 0x40, 0x30, 0x08, + 0x06, 0x01, 0x00, 0xC0, 0x20, 0x18, 0x04, 0x02, 0x00, 0x80, 0x40, 0x10, + 0x08, 0x02, 0x01, 0x00, 0xC0, 0x20, 0x00, 0x07, 0xC0, 0xFE, 0x1C, 0x73, + 0x83, 0x30, 0x36, 0x03, 0x60, 0x36, 0x03, 0xC0, 0x7C, 0x07, 0xC0, 0x6C, + 0x06, 0xC0, 0xEC, 0x0C, 0xE3, 0x87, 0xF0, 0x3E, 0x00, 0x02, 0x0C, 0x77, + 0xEF, 0xC1, 0x83, 0x0C, 0x18, 0x30, 0x61, 0xC3, 0x06, 0x0C, 0x18, 0x60, + 0x03, 0xF0, 0x1F, 0xE0, 0xE1, 0xC7, 0x03, 0x18, 0x0C, 0x00, 0x30, 0x01, + 0x80, 0x0E, 0x00, 0x70, 0x07, 0x80, 0x78, 0x07, 0x80, 0x38, 0x01, 0xC0, + 0x06, 0x00, 0x1F, 0xFC, 0xFF, 0xE0, 0x07, 0xC0, 0xFE, 0x1C, 0x73, 0x03, + 0x30, 0x30, 0x03, 0x00, 0xE0, 0x7C, 0x07, 0xC0, 0x0E, 0x00, 0x60, 0x06, + 0xC0, 0x6C, 0x0C, 0xE1, 0xC7, 0xF8, 0x3E, 0x00, 0x00, 0x60, 0x06, 0x00, + 0xE0, 0x1E, 0x03, 0xE0, 0x6C, 0x0C, 0xC1, 0x8C, 0x30, 0xC6, 0x1C, 0xC1, + 0x8F, 0xFF, 0xFF, 0xE0, 0x18, 0x03, 0x00, 0x30, 0x03, 0x00, 0x0F, 0xF8, + 0x7F, 0xC6, 0x00, 0x30, 0x01, 0x00, 0x1B, 0xC0, 0xFF, 0x06, 0x1C, 0x60, + 0x60, 0x03, 0x00, 0x18, 0x00, 0xC0, 0x0C, 0x60, 0x63, 0x86, 0x0F, 0xE0, + 0x3E, 0x00, 0x03, 0xC0, 0xFE, 0x1C, 0x73, 0x83, 0x30, 0x06, 0x00, 0x67, + 0x87, 0xFC, 0xF0, 0xEE, 0x06, 0xC0, 0x6C, 0x06, 0xC0, 0x4C, 0x0C, 0xE1, + 0x87, 0xF8, 0x3E, 0x00, 0x3F, 0xFB, 0xFF, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, + 0x00, 0xC0, 0x06, 0x00, 0x60, 0x06, 0x00, 0x70, 0x03, 0x00, 0x30, 0x03, + 0x80, 0x18, 0x01, 0xC0, 0x0C, 0x00, 0xE0, 0x00, 0x07, 0xC0, 0xFE, 0x1C, + 0x73, 0x03, 0x30, 0x33, 0x03, 0x38, 0x61, 0xFC, 0x3F, 0xC7, 0x0E, 0x60, + 0x6C, 0x06, 0xC0, 0x6C, 0x0C, 0xE1, 0xC7, 0xF8, 0x3E, 0x00, 0x07, 0xC1, + 0xFE, 0x38, 0x73, 0x03, 0x60, 0x36, 0x03, 0x60, 0x36, 0x07, 0x70, 0xF3, + 0xFE, 0x1E, 0x60, 0x0E, 0x00, 0xCC, 0x1C, 0xE3, 0x87, 0xF0, 0x3C, 0x00, + 0x39, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x39, 0xC0, 0x1C, 0x70, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x07, 0x1C, 0x20, 0x86, 0x30, 0x00, 0x00, 0x01, 0xC0, + 0x3C, 0x0F, 0x81, 0xE0, 0x7C, 0x03, 0x80, 0x0F, 0x00, 0x1F, 0x00, 0x3E, + 0x00, 0x38, 0x00, 0x40, 0x7F, 0xFB, 0xFF, 0x80, 0x00, 0x00, 0x0F, 0xFF, + 0x7F, 0xF0, 0x20, 0x01, 0xC0, 0x07, 0xC0, 0x0F, 0x80, 0x0F, 0x00, 0x1C, + 0x03, 0xE0, 0x78, 0x1F, 0x03, 0xC0, 0x38, 0x00, 0x00, 0x00, 0x0F, 0x87, + 0xF9, 0xC3, 0xB0, 0x3C, 0x06, 0x00, 0xC0, 0x30, 0x0C, 0x03, 0x01, 0xC0, + 0x30, 0x0C, 0x01, 0x80, 0x00, 0x00, 0x00, 0x00, 0x30, 0x06, 0x00, 0x00, + 0x3F, 0x80, 0x01, 0xFF, 0xE0, 0x0F, 0x01, 0xE0, 0x38, 0x00, 0xE0, 0xE0, + 0x00, 0xC3, 0x87, 0x81, 0xCE, 0x1F, 0xB1, 0x98, 0x71, 0xC3, 0x61, 0x83, + 0x86, 0xC6, 0x06, 0x0F, 0x0C, 0x0C, 0x3E, 0x30, 0x30, 0x6C, 0x60, 0x61, + 0xD8, 0xC1, 0x87, 0x31, 0xC7, 0x1C, 0x61, 0xF7, 0xF0, 0x63, 0xCF, 0x80, + 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xFF, 0xE0, 0x00, 0x7F, 0x00, 0x00, + 0x00, 0x38, 0x00, 0x78, 0x00, 0x7C, 0x00, 0xFC, 0x00, 0xDC, 0x01, 0xCC, + 0x01, 0x8C, 0x03, 0x8C, 0x03, 0x0C, 0x06, 0x0C, 0x0E, 0x0E, 0x0F, 0xFE, + 0x1F, 0xFE, 0x18, 0x06, 0x38, 0x06, 0x30, 0x06, 0x70, 0x06, 0x60, 0x07, + 0x0F, 0xF8, 0x1F, 0xF8, 0x60, 0x38, 0xC0, 0x31, 0x80, 0x63, 0x00, 0xCE, + 0x03, 0x18, 0x0C, 0x3F, 0xF0, 0x7F, 0xF0, 0xC0, 0x73, 0x00, 0x66, 0x00, + 0xCC, 0x01, 0x98, 0x06, 0x70, 0x1C, 0xFF, 0xF1, 0xFF, 0x80, 0x01, 0xF8, + 0x07, 0xFE, 0x0E, 0x0E, 0x1C, 0x03, 0x38, 0x03, 0x30, 0x00, 0x60, 0x00, + 0x60, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x06, + 0xC0, 0x0C, 0xE0, 0x1C, 0x70, 0x78, 0x3F, 0xF0, 0x1F, 0x80, 0x0F, 0xF8, + 0x1F, 0xFC, 0x18, 0x0E, 0x18, 0x07, 0x18, 0x03, 0x18, 0x03, 0x38, 0x03, + 0x30, 0x03, 0x30, 0x03, 0x30, 0x03, 0x70, 0x06, 0x70, 0x06, 0x60, 0x0C, + 0x60, 0x0C, 0x60, 0x18, 0xE0, 0x78, 0xFF, 0xE0, 0xFF, 0x80, 0x0F, 0xFF, + 0x1F, 0xFE, 0x18, 0x00, 0x18, 0x00, 0x18, 0x00, 0x18, 0x00, 0x38, 0x00, + 0x30, 0x00, 0x3F, 0xFC, 0x3F, 0xF8, 0x70, 0x00, 0x70, 0x00, 0x60, 0x00, + 0x60, 0x00, 0x60, 0x00, 0xE0, 0x00, 0xFF, 0xF8, 0xFF, 0xF8, 0x0F, 0xFE, + 0x3F, 0xFC, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x0E, 0x00, 0x18, + 0x00, 0x3F, 0xF0, 0x7F, 0xE1, 0xC0, 0x03, 0x80, 0x06, 0x00, 0x0C, 0x00, + 0x18, 0x00, 0x70, 0x00, 0xC0, 0x01, 0x80, 0x00, 0x01, 0xF8, 0x07, 0xFE, + 0x0E, 0x0F, 0x18, 0x03, 0x30, 0x03, 0x70, 0x00, 0x60, 0x00, 0x60, 0x00, + 0xC0, 0x7F, 0xC0, 0x7E, 0xC0, 0x02, 0xC0, 0x06, 0xC0, 0x06, 0xE0, 0x0E, + 0x60, 0x1E, 0x78, 0x3C, 0x3F, 0xE4, 0x0F, 0x84, 0x0C, 0x01, 0x8E, 0x00, + 0xC6, 0x00, 0xE3, 0x00, 0x61, 0x80, 0x30, 0xC0, 0x18, 0xE0, 0x0C, 0x60, + 0x0E, 0x3F, 0xFE, 0x1F, 0xFF, 0x1C, 0x01, 0x8E, 0x01, 0xC6, 0x00, 0xE3, + 0x00, 0x61, 0x80, 0x31, 0xC0, 0x18, 0xC0, 0x1C, 0x60, 0x0C, 0x00, 0x0C, + 0x71, 0x86, 0x18, 0x63, 0x8C, 0x30, 0xC3, 0x1C, 0x61, 0x86, 0x18, 0xE3, + 0x00, 0x00, 0x18, 0x01, 0x80, 0x0C, 0x00, 0x60, 0x03, 0x00, 0x38, 0x01, + 0x80, 0x0C, 0x00, 0x60, 0x03, 0x00, 0x38, 0x01, 0x8C, 0x0C, 0x60, 0x63, + 0x07, 0x1C, 0x70, 0x7F, 0x01, 0xF0, 0x00, 0x0C, 0x03, 0x87, 0x01, 0xC1, + 0x80, 0xE0, 0x60, 0x60, 0x18, 0x70, 0x06, 0x38, 0x03, 0x9C, 0x00, 0xCE, + 0x00, 0x37, 0x80, 0x0F, 0x70, 0x07, 0x8C, 0x01, 0xC3, 0x80, 0x60, 0x60, + 0x18, 0x1C, 0x06, 0x03, 0x03, 0x80, 0xE0, 0xC0, 0x18, 0x30, 0x07, 0x00, + 0x0C, 0x03, 0x80, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x0E, 0x01, 0x80, 0x30, + 0x06, 0x01, 0xC0, 0x38, 0x06, 0x00, 0xC0, 0x18, 0x07, 0x00, 0xFF, 0xFF, + 0xFC, 0x0E, 0x00, 0x71, 0xE0, 0x0F, 0x1E, 0x00, 0xF1, 0xE0, 0x1E, 0x1E, + 0x01, 0xE1, 0xE0, 0x36, 0x3B, 0x03, 0x63, 0x30, 0x6E, 0x33, 0x0E, 0xC3, + 0x30, 0xCC, 0x33, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x31, 0xC6, 0x33, 0x18, + 0x61, 0xE1, 0x8E, 0x1E, 0x18, 0xC1, 0xC1, 0x8C, 0x1C, 0x38, 0x0C, 0x01, + 0x8F, 0x00, 0xC7, 0x80, 0x63, 0xE0, 0x71, 0xF0, 0x30, 0xD8, 0x18, 0xEE, + 0x0C, 0x63, 0x06, 0x31, 0xC7, 0x18, 0xE3, 0x0C, 0x31, 0x8C, 0x1C, 0xC6, + 0x06, 0x63, 0x03, 0xF1, 0x80, 0xF1, 0xC0, 0x78, 0xC0, 0x3C, 0x60, 0x0E, + 0x00, 0x01, 0xF8, 0x03, 0xFF, 0x03, 0x83, 0xC3, 0x80, 0x63, 0x00, 0x3B, + 0x80, 0x0D, 0x80, 0x06, 0xC0, 0x03, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, + 0xF8, 0x00, 0x6C, 0x00, 0x36, 0x00, 0x31, 0x80, 0x30, 0xF0, 0x78, 0x3F, + 0xF0, 0x07, 0xE0, 0x00, 0x0F, 0xF8, 0x3F, 0xF8, 0x60, 0x38, 0xC0, 0x31, + 0x80, 0x63, 0x00, 0xCE, 0x03, 0x18, 0x0E, 0x3F, 0xF8, 0x7F, 0xE1, 0xC0, + 0x03, 0x80, 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x70, 0x00, 0xC0, 0x01, + 0x80, 0x00, 0x00, 0xFC, 0x01, 0xFF, 0xC0, 0xF0, 0x78, 0x70, 0x06, 0x38, + 0x01, 0xCC, 0x00, 0x36, 0x00, 0x0D, 0x80, 0x03, 0xC0, 0x00, 0xF0, 0x00, + 0x3C, 0x00, 0x1B, 0x00, 0x06, 0xC0, 0x03, 0x38, 0x1D, 0xC6, 0x03, 0xE1, + 0xE0, 0xF0, 0x3F, 0xFE, 0x03, 0xF1, 0xC0, 0x00, 0x20, 0x0F, 0xFC, 0x1F, + 0xFE, 0x18, 0x07, 0x18, 0x03, 0x18, 0x03, 0x18, 0x03, 0x38, 0x06, 0x30, + 0x0C, 0x3F, 0xF8, 0x3F, 0xF8, 0x70, 0x1C, 0x70, 0x0C, 0x60, 0x0C, 0x60, + 0x0C, 0x60, 0x18, 0xE0, 0x18, 0xC0, 0x18, 0xC0, 0x1C, 0x03, 0xF8, 0x1F, + 0xF8, 0x70, 0x38, 0xC0, 0x33, 0x00, 0x66, 0x00, 0x0C, 0x00, 0x1E, 0x00, + 0x1F, 0xC0, 0x0F, 0xF0, 0x01, 0xF0, 0x00, 0xEC, 0x00, 0xD8, 0x01, 0xB0, + 0x06, 0x70, 0x38, 0x7F, 0xE0, 0x3F, 0x00, 0xFF, 0xFF, 0xFF, 0xF0, 0x70, + 0x01, 0xC0, 0x06, 0x00, 0x18, 0x00, 0x60, 0x03, 0x80, 0x0C, 0x00, 0x30, + 0x00, 0xC0, 0x03, 0x00, 0x1C, 0x00, 0x60, 0x01, 0x80, 0x06, 0x00, 0x18, + 0x00, 0xE0, 0x00, 0x18, 0x03, 0x38, 0x03, 0x30, 0x07, 0x30, 0x06, 0x30, + 0x06, 0x70, 0x06, 0x70, 0x0E, 0x60, 0x0C, 0x60, 0x0C, 0x60, 0x0C, 0xE0, + 0x0C, 0xC0, 0x1C, 0xC0, 0x18, 0xC0, 0x18, 0xC0, 0x38, 0xE0, 0x70, 0x7F, + 0xE0, 0x1F, 0x80, 0xC0, 0x0F, 0xC0, 0x1B, 0x80, 0x73, 0x00, 0xC6, 0x03, + 0x0C, 0x06, 0x18, 0x18, 0x30, 0x70, 0x60, 0xC0, 0xE3, 0x81, 0xC6, 0x01, + 0x9C, 0x03, 0x30, 0x06, 0xE0, 0x0D, 0x80, 0x1E, 0x00, 0x3C, 0x00, 0x70, + 0x00, 0xC0, 0x70, 0x1F, 0x01, 0xC0, 0x6C, 0x0F, 0x03, 0xB0, 0x3C, 0x0C, + 0xC1, 0xF0, 0x73, 0x06, 0xC1, 0x8C, 0x3B, 0x06, 0x30, 0xC6, 0x30, 0xC7, + 0x18, 0xC3, 0x18, 0x67, 0x0C, 0xE1, 0x98, 0x33, 0x06, 0xE0, 0xDC, 0x1B, + 0x03, 0x60, 0x6C, 0x07, 0x81, 0xE0, 0x1C, 0x07, 0x80, 0x70, 0x1C, 0x01, + 0x80, 0x70, 0x00, 0x07, 0x00, 0xE0, 0xE0, 0x38, 0x0C, 0x0E, 0x01, 0xC3, + 0x80, 0x18, 0xE0, 0x03, 0x98, 0x00, 0x36, 0x00, 0x07, 0x80, 0x00, 0xF0, + 0x00, 0x1E, 0x00, 0x07, 0xC0, 0x01, 0xDC, 0x00, 0x73, 0x80, 0x1C, 0x30, + 0x03, 0x07, 0x00, 0xC0, 0x60, 0x38, 0x0E, 0x0E, 0x00, 0xC0, 0xE0, 0x06, + 0x60, 0x0C, 0x70, 0x1C, 0x70, 0x38, 0x30, 0x70, 0x38, 0x60, 0x18, 0xC0, + 0x1D, 0xC0, 0x1F, 0x80, 0x0F, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0E, 0x00, + 0x0C, 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x1C, 0x00, 0x18, 0x00, 0x0F, 0xFF, + 0x87, 0xFF, 0x80, 0x01, 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x01, + 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x01, + 0xC0, 0x01, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xFF, 0xF8, 0x7F, 0xFC, + 0x00, 0x07, 0xC1, 0xE0, 0x60, 0x18, 0x0C, 0x03, 0x00, 0xC0, 0x30, 0x1C, + 0x06, 0x01, 0x80, 0x60, 0x18, 0x0E, 0x03, 0x00, 0xC0, 0x30, 0x0C, 0x06, + 0x01, 0x80, 0x60, 0x1E, 0x07, 0x80, 0x93, 0x6C, 0x92, 0x49, 0x24, 0xDB, + 0x24, 0x07, 0x81, 0xE0, 0x18, 0x06, 0x01, 0x80, 0xC0, 0x30, 0x0C, 0x03, + 0x01, 0xC0, 0x60, 0x18, 0x06, 0x01, 0x80, 0xE0, 0x30, 0x0C, 0x03, 0x00, + 0xC0, 0x60, 0x18, 0x1E, 0x0F, 0x80, 0x03, 0x01, 0xC0, 0xD8, 0x36, 0x19, + 0x84, 0x63, 0x19, 0x83, 0x60, 0xC0, 0xFF, 0xFC, 0xE6, 0x23, 0x07, 0xC3, + 0xFC, 0xE3, 0x98, 0x30, 0x06, 0x01, 0x87, 0xF3, 0xC6, 0xC0, 0xD8, 0x3B, + 0x0E, 0x7F, 0x77, 0xCC, 0x0C, 0x00, 0x60, 0x03, 0x00, 0x30, 0x01, 0x80, + 0x0C, 0xF0, 0x7F, 0xC3, 0x87, 0x38, 0x19, 0x80, 0xCC, 0x06, 0x60, 0x32, + 0x03, 0xB0, 0x19, 0xC1, 0xCE, 0x1C, 0x7F, 0xC3, 0x7C, 0x00, 0x0F, 0x83, + 0xF8, 0xE3, 0xB8, 0x36, 0x07, 0xC0, 0x30, 0x06, 0x00, 0xC0, 0x18, 0x1B, + 0x86, 0x3F, 0xC3, 0xE0, 0x00, 0x0C, 0x00, 0x60, 0x01, 0x80, 0x06, 0x00, + 0x18, 0x3E, 0x61, 0xFF, 0x0E, 0x3C, 0x70, 0x71, 0x80, 0xCE, 0x07, 0x30, + 0x18, 0xC0, 0x63, 0x01, 0x8C, 0x0E, 0x38, 0x78, 0x7F, 0xC0, 0xFB, 0x00, + 0x07, 0xC1, 0xFE, 0x38, 0x77, 0x03, 0x60, 0x37, 0xFF, 0xFF, 0xFC, 0x00, + 0xC0, 0x0C, 0x06, 0xE1, 0xC7, 0xF8, 0x3E, 0x00, 0x07, 0x0F, 0x1C, 0x18, + 0x18, 0x7E, 0x7E, 0x30, 0x30, 0x30, 0x30, 0x60, 0x60, 0x60, 0x60, 0x60, + 0xC0, 0xC0, 0x03, 0xCC, 0x3F, 0xA1, 0xC7, 0x8E, 0x0E, 0x30, 0x38, 0xC0, + 0xC6, 0x03, 0x18, 0x0C, 0x60, 0x71, 0x81, 0xC7, 0x0E, 0x0F, 0xF8, 0x1E, + 0x60, 0x03, 0x80, 0x0C, 0x30, 0x70, 0x7F, 0x80, 0xF8, 0x00, 0x0C, 0x00, + 0xC0, 0x0C, 0x01, 0x80, 0x18, 0x01, 0x9E, 0x1F, 0xF1, 0xC7, 0x38, 0x33, + 0x03, 0x30, 0x33, 0x07, 0x30, 0x66, 0x06, 0x60, 0x66, 0x06, 0x60, 0xC6, + 0x0C, 0x18, 0xC0, 0x00, 0x18, 0xC6, 0x33, 0x18, 0xC6, 0x31, 0x98, 0xC6, + 0x00, 0x01, 0x80, 0xC0, 0x00, 0x00, 0x00, 0x18, 0x1C, 0x0C, 0x06, 0x03, + 0x01, 0x81, 0x80, 0xC0, 0x60, 0x30, 0x18, 0x18, 0x0C, 0x06, 0x03, 0x03, + 0x87, 0x83, 0x80, 0x0C, 0x00, 0x60, 0x03, 0x00, 0x30, 0x01, 0x80, 0x0C, + 0x18, 0x61, 0x83, 0x38, 0x33, 0x81, 0xB8, 0x0F, 0xC0, 0x77, 0x03, 0x18, + 0x30, 0xC1, 0x87, 0x0C, 0x18, 0x60, 0xE3, 0x03, 0x00, 0x18, 0xC6, 0x63, + 0x18, 0xC6, 0x33, 0x18, 0xC6, 0x31, 0x98, 0xC6, 0x00, 0x1B, 0xE3, 0xC3, + 0xFD, 0xFC, 0xF1, 0xE1, 0x9C, 0x18, 0x33, 0x03, 0x06, 0x60, 0xC0, 0xCC, + 0x18, 0x3B, 0x83, 0x06, 0x60, 0x60, 0xCC, 0x0C, 0x19, 0x83, 0x03, 0x30, + 0x60, 0xE6, 0x0C, 0x18, 0x1B, 0xE1, 0xFF, 0x3C, 0x73, 0x83, 0x30, 0x33, + 0x03, 0x30, 0x77, 0x06, 0x60, 0x66, 0x06, 0x60, 0x66, 0x0C, 0x60, 0xC0, + 0x07, 0xC1, 0xFE, 0x38, 0x77, 0x03, 0x60, 0x3E, 0x03, 0xC0, 0x3C, 0x06, + 0xC0, 0x6C, 0x0E, 0xE1, 0xC7, 0xF8, 0x3E, 0x00, 0x0C, 0xF0, 0x3F, 0xE0, + 0xE1, 0xC7, 0x03, 0x1C, 0x0C, 0x60, 0x31, 0x80, 0xCE, 0x07, 0x38, 0x18, + 0xE0, 0xE3, 0xC7, 0x0F, 0xF8, 0x77, 0xC1, 0x80, 0x06, 0x00, 0x18, 0x00, + 0x60, 0x03, 0x80, 0x00, 0x0F, 0x98, 0xFF, 0xCE, 0x3C, 0xE0, 0xE6, 0x03, + 0x70, 0x1B, 0x01, 0x98, 0x0C, 0xC0, 0x66, 0x07, 0x38, 0x78, 0xFF, 0x83, + 0xCC, 0x00, 0x60, 0x07, 0x00, 0x38, 0x01, 0x80, 0x0C, 0x00, 0x1B, 0x8F, + 0xCF, 0x07, 0x03, 0x01, 0x80, 0xC0, 0xE0, 0x60, 0x30, 0x18, 0x0C, 0x06, + 0x00, 0x0F, 0xC1, 0xFF, 0x30, 0x76, 0x03, 0x60, 0x07, 0x80, 0x3F, 0x80, + 0x7E, 0x00, 0x6C, 0x06, 0xE0, 0xCF, 0xF8, 0x3E, 0x00, 0x18, 0x30, 0x67, + 0xEF, 0xC6, 0x0C, 0x30, 0x60, 0xC1, 0x83, 0x0C, 0x18, 0x3C, 0x38, 0x30, + 0x33, 0x03, 0x30, 0x37, 0x06, 0x60, 0x66, 0x06, 0x60, 0x66, 0x06, 0xC0, + 0xEC, 0x0C, 0xC3, 0xCF, 0xFC, 0x7C, 0xC0, 0xC0, 0x78, 0x1B, 0x03, 0x60, + 0xC6, 0x18, 0xC6, 0x19, 0xC3, 0x30, 0x6C, 0x0D, 0x81, 0xE0, 0x3C, 0x03, + 0x00, 0xC1, 0xC3, 0xE1, 0xE1, 0xB0, 0xF0, 0xD8, 0x78, 0xCC, 0x6C, 0x66, + 0x36, 0x63, 0x33, 0x30, 0x99, 0xB0, 0x58, 0xD8, 0x2C, 0x78, 0x1C, 0x3C, + 0x0E, 0x1C, 0x06, 0x0E, 0x00, 0x0C, 0x1C, 0x30, 0xE0, 0xE3, 0x01, 0x98, + 0x07, 0xC0, 0x0E, 0x00, 0x30, 0x01, 0xE0, 0x0F, 0x80, 0x73, 0x01, 0x8C, + 0x0C, 0x38, 0x60, 0x60, 0x18, 0x0C, 0x60, 0x61, 0x83, 0x86, 0x0C, 0x1C, + 0x60, 0x31, 0x80, 0xCC, 0x03, 0x30, 0x0D, 0x80, 0x36, 0x00, 0xF0, 0x03, + 0x80, 0x06, 0x00, 0x30, 0x00, 0xC0, 0x06, 0x00, 0xF0, 0x03, 0x80, 0x00, + 0x1F, 0xF1, 0xFF, 0x00, 0x70, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, + 0x18, 0x03, 0x00, 0x60, 0x0F, 0xFC, 0xFF, 0xC0, 0x07, 0x0E, 0x18, 0x18, + 0x18, 0x18, 0x30, 0x30, 0x30, 0x30, 0x60, 0xE0, 0xE0, 0x60, 0x60, 0x60, + 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xF0, 0x60, 0x0C, 0x30, 0x82, 0x08, 0x61, + 0x84, 0x10, 0x43, 0x0C, 0x20, 0x86, 0x18, 0x41, 0x04, 0x30, 0xC2, 0x00, + 0x00, 0x06, 0x07, 0x80, 0xC0, 0x60, 0x30, 0x18, 0x0C, 0x0C, 0x06, 0x03, + 0x01, 0xC0, 0xE0, 0x60, 0x60, 0x30, 0x18, 0x0C, 0x0C, 0x06, 0x03, 0x01, + 0x83, 0x83, 0x80, 0x38, 0x0F, 0x82, 0x38, 0x83, 0xE0, 0x38 }; + +const GFXglyph FreeSansOblique12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 7, 0, 1 }, // 0x20 ' ' + { 0, 6, 18, 7, 3, -17 }, // 0x21 '!' + { 14, 6, 6, 9, 4, -16 }, // 0x22 '"' + { 19, 15, 18, 13, 1, -17 }, // 0x23 '#' + { 53, 13, 21, 13, 2, -17 }, // 0x24 '$' + { 88, 19, 17, 21, 3, -16 }, // 0x25 '%' + { 129, 13, 17, 16, 2, -16 }, // 0x26 '&' + { 157, 2, 6, 5, 4, -16 }, // 0x27 ''' + { 159, 8, 23, 8, 3, -17 }, // 0x28 '(' + { 182, 8, 23, 8, 0, -16 }, // 0x29 ')' + { 205, 8, 8, 9, 4, -17 }, // 0x2A '*' + { 213, 12, 11, 14, 2, -10 }, // 0x2B '+' + { 230, 4, 6, 7, 1, -1 }, // 0x2C ',' + { 233, 6, 2, 8, 2, -7 }, // 0x2D '-' + { 235, 3, 2, 7, 2, -1 }, // 0x2E '.' + { 236, 10, 18, 7, 0, -17 }, // 0x2F '/' + { 259, 12, 17, 13, 2, -16 }, // 0x30 '0' + { 285, 7, 17, 13, 5, -16 }, // 0x31 '1' + { 300, 14, 17, 13, 1, -16 }, // 0x32 '2' + { 330, 12, 17, 13, 2, -16 }, // 0x33 '3' + { 356, 12, 17, 13, 2, -16 }, // 0x34 '4' + { 382, 13, 17, 13, 2, -16 }, // 0x35 '5' + { 410, 12, 17, 13, 2, -16 }, // 0x36 '6' + { 436, 13, 17, 13, 3, -16 }, // 0x37 '7' + { 464, 12, 17, 13, 2, -16 }, // 0x38 '8' + { 490, 12, 17, 13, 2, -16 }, // 0x39 '9' + { 516, 5, 12, 7, 3, -11 }, // 0x3A ':' + { 524, 6, 16, 7, 2, -11 }, // 0x3B ';' + { 536, 13, 12, 14, 2, -11 }, // 0x3C '<' + { 556, 13, 6, 14, 2, -8 }, // 0x3D '=' + { 566, 13, 12, 14, 1, -10 }, // 0x3E '>' + { 586, 11, 18, 13, 4, -17 }, // 0x3F '?' + { 611, 23, 21, 24, 2, -17 }, // 0x40 '@' + { 672, 16, 18, 16, 0, -17 }, // 0x41 'A' + { 708, 15, 18, 16, 2, -17 }, // 0x42 'B' + { 742, 16, 18, 17, 2, -17 }, // 0x43 'C' + { 778, 16, 18, 17, 2, -17 }, // 0x44 'D' + { 814, 16, 18, 16, 2, -17 }, // 0x45 'E' + { 850, 15, 18, 14, 2, -17 }, // 0x46 'F' + { 884, 16, 18, 19, 3, -17 }, // 0x47 'G' + { 920, 17, 18, 17, 2, -17 }, // 0x48 'H' + { 959, 6, 18, 7, 2, -17 }, // 0x49 'I' + { 973, 13, 18, 12, 1, -17 }, // 0x4A 'J' + { 1003, 18, 18, 16, 2, -17 }, // 0x4B 'K' + { 1044, 11, 18, 13, 2, -17 }, // 0x4C 'L' + { 1069, 20, 18, 20, 2, -17 }, // 0x4D 'M' + { 1114, 17, 18, 18, 2, -17 }, // 0x4E 'N' + { 1153, 17, 18, 18, 2, -17 }, // 0x4F 'O' + { 1192, 15, 18, 15, 2, -17 }, // 0x50 'P' + { 1226, 18, 19, 19, 2, -17 }, // 0x51 'Q' + { 1269, 16, 18, 17, 2, -17 }, // 0x52 'R' + { 1305, 15, 18, 16, 2, -17 }, // 0x53 'S' + { 1339, 14, 18, 15, 4, -17 }, // 0x54 'T' + { 1371, 16, 18, 17, 3, -17 }, // 0x55 'U' + { 1407, 15, 18, 15, 4, -17 }, // 0x56 'V' + { 1441, 22, 18, 22, 4, -17 }, // 0x57 'W' + { 1491, 19, 18, 16, 0, -17 }, // 0x58 'X' + { 1534, 16, 18, 16, 4, -17 }, // 0x59 'Y' + { 1570, 17, 18, 15, 1, -17 }, // 0x5A 'Z' + { 1609, 10, 23, 7, 0, -17 }, // 0x5B '[' + { 1638, 3, 18, 7, 4, -17 }, // 0x5C '\' + { 1645, 10, 23, 7, -1, -16 }, // 0x5D ']' + { 1674, 10, 9, 11, 2, -16 }, // 0x5E '^' + { 1686, 14, 1, 13, -1, 4 }, // 0x5F '_' + { 1688, 4, 4, 8, 4, -17 }, // 0x60 '`' + { 1690, 11, 13, 13, 2, -12 }, // 0x61 'a' + { 1708, 13, 18, 13, 1, -17 }, // 0x62 'b' + { 1738, 11, 13, 12, 2, -12 }, // 0x63 'c' + { 1756, 14, 18, 13, 2, -17 }, // 0x64 'd' + { 1788, 12, 13, 13, 2, -12 }, // 0x65 'e' + { 1808, 8, 18, 6, 2, -17 }, // 0x66 'f' + { 1826, 14, 18, 13, 1, -12 }, // 0x67 'g' + { 1858, 12, 18, 13, 1, -17 }, // 0x68 'h' + { 1885, 5, 18, 5, 2, -17 }, // 0x69 'i' + { 1897, 9, 23, 6, -1, -17 }, // 0x6A 'j' + { 1923, 13, 18, 12, 1, -17 }, // 0x6B 'k' + { 1953, 5, 18, 5, 2, -17 }, // 0x6C 'l' + { 1965, 19, 13, 20, 1, -12 }, // 0x6D 'm' + { 1996, 12, 13, 13, 1, -12 }, // 0x6E 'n' + { 2016, 12, 13, 13, 2, -12 }, // 0x6F 'o' + { 2036, 14, 18, 14, 0, -12 }, // 0x70 'p' + { 2068, 13, 18, 13, 2, -12 }, // 0x71 'q' + { 2098, 9, 13, 8, 1, -12 }, // 0x72 'r' + { 2113, 12, 13, 12, 1, -12 }, // 0x73 's' + { 2133, 7, 16, 6, 2, -15 }, // 0x74 't' + { 2147, 12, 13, 13, 2, -12 }, // 0x75 'u' + { 2167, 11, 13, 12, 3, -12 }, // 0x76 'v' + { 2185, 17, 13, 17, 3, -12 }, // 0x77 'w' + { 2213, 14, 13, 12, 0, -12 }, // 0x78 'x' + { 2236, 14, 18, 11, 0, -12 }, // 0x79 'y' + { 2268, 12, 13, 12, 1, -12 }, // 0x7A 'z' + { 2288, 8, 23, 8, 3, -17 }, // 0x7B '{' + { 2311, 6, 23, 6, 1, -17 }, // 0x7C '|' + { 2329, 9, 23, 8, -1, -16 }, // 0x7D '}' + { 2355, 11, 5, 14, 3, -10 } }; // 0x7E '~' + +const GFXfont FreeSansOblique12pt7b PROGMEM = { + (uint8_t *)FreeSansOblique12pt7bBitmaps, + (GFXglyph *)FreeSansOblique12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 3034 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansOblique18pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansOblique18pt7b.h new file mode 100644 index 0000000..2a18a3f --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansOblique18pt7b.h @@ -0,0 +1,518 @@ +const uint8_t FreeSansOblique18pt7bBitmaps[] PROGMEM = { + 0x03, 0x83, 0x81, 0xC0, 0xE0, 0x70, 0x78, 0x38, 0x1C, 0x0E, 0x07, 0x07, + 0x83, 0x81, 0xC0, 0xE0, 0x60, 0x30, 0x30, 0x18, 0x0C, 0x04, 0x00, 0x00, + 0x01, 0xC0, 0xE0, 0x70, 0x78, 0x00, 0x71, 0xDC, 0x7F, 0x3F, 0x8E, 0xE3, + 0xB8, 0xEC, 0x33, 0x0C, 0xC3, 0x00, 0x00, 0x38, 0x70, 0x01, 0xC3, 0x80, + 0x0C, 0x18, 0x00, 0xE1, 0xC0, 0x06, 0x0C, 0x00, 0x70, 0xE0, 0x03, 0x87, + 0x03, 0xFF, 0xFF, 0x1F, 0xFF, 0xF0, 0xFF, 0xFF, 0x80, 0x60, 0xC0, 0x07, + 0x0E, 0x00, 0x30, 0x60, 0x03, 0x87, 0x00, 0x18, 0x30, 0x1F, 0xFF, 0xF8, + 0xFF, 0xFF, 0xC7, 0xFF, 0xFC, 0x07, 0x0E, 0x00, 0x30, 0x70, 0x03, 0x87, + 0x00, 0x1C, 0x38, 0x00, 0xC1, 0x80, 0x0E, 0x1C, 0x00, 0x60, 0xC0, 0x00, + 0x00, 0x0C, 0x00, 0x07, 0xF8, 0x01, 0xFF, 0xC0, 0x3F, 0xFE, 0x07, 0x99, + 0xF0, 0xF1, 0x87, 0x0E, 0x18, 0x71, 0xC1, 0x87, 0x1C, 0x38, 0x01, 0xC3, + 0x00, 0x1C, 0x30, 0x01, 0xE3, 0x00, 0x0F, 0xB0, 0x00, 0xFF, 0x80, 0x03, + 0xFF, 0x00, 0x0F, 0xF8, 0x00, 0x6F, 0xC0, 0x06, 0x3C, 0x00, 0xC1, 0xCE, + 0x0C, 0x1C, 0xE0, 0xC1, 0xCE, 0x0C, 0x38, 0xF1, 0xC3, 0x8F, 0x98, 0xF0, + 0x7F, 0xFE, 0x03, 0xFF, 0xC0, 0x0F, 0xF0, 0x00, 0x30, 0x00, 0x03, 0x00, + 0x00, 0x30, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x07, 0x03, 0xE0, 0x03, + 0x81, 0xFC, 0x00, 0xC0, 0xFF, 0x00, 0x60, 0x70, 0xE0, 0x38, 0x38, 0x18, + 0x1C, 0x0C, 0x06, 0x0E, 0x03, 0x01, 0x83, 0x00, 0xC0, 0xE1, 0x80, 0x38, + 0x70, 0xE0, 0x0F, 0xF8, 0x70, 0x01, 0xFC, 0x18, 0x00, 0x3E, 0x0C, 0x00, + 0x00, 0x06, 0x07, 0x80, 0x03, 0x87, 0xF8, 0x00, 0xC3, 0xFE, 0x00, 0x61, + 0xE1, 0xC0, 0x30, 0x60, 0x30, 0x1C, 0x30, 0x0C, 0x0E, 0x0C, 0x03, 0x03, + 0x03, 0x01, 0x81, 0x80, 0xE1, 0xE0, 0xC0, 0x1F, 0xF0, 0x70, 0x07, 0xF8, + 0x18, 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x07, 0xF8, 0x00, 0xFF, 0xC0, + 0x1E, 0x3C, 0x03, 0xC1, 0xC0, 0x38, 0x1C, 0x03, 0x81, 0xC0, 0x38, 0x38, + 0x03, 0xC7, 0x00, 0x1D, 0xE0, 0x01, 0xFC, 0x00, 0x1F, 0x00, 0x07, 0xF0, + 0x01, 0xF7, 0x87, 0x3C, 0x3C, 0xE7, 0x81, 0xCE, 0x70, 0x1F, 0xCE, 0x00, + 0xFC, 0xE0, 0x07, 0x8E, 0x00, 0x78, 0xF0, 0x1F, 0x8F, 0x87, 0xFC, 0x7F, + 0xF9, 0xC3, 0xFE, 0x1E, 0x1F, 0x80, 0xE0, 0x77, 0xFE, 0xEE, 0xCC, 0xC0, + 0x00, 0x30, 0x06, 0x00, 0xC0, 0x18, 0x03, 0x80, 0x30, 0x06, 0x00, 0xE0, + 0x0C, 0x01, 0xC0, 0x18, 0x03, 0x80, 0x38, 0x07, 0x00, 0x70, 0x07, 0x00, + 0x70, 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x00, + 0xE0, 0x0E, 0x00, 0xE0, 0x06, 0x00, 0x70, 0x07, 0x00, 0x30, 0x03, 0x00, + 0x18, 0x00, 0x01, 0x80, 0x0C, 0x00, 0xC0, 0x0E, 0x00, 0xE0, 0x06, 0x00, + 0x70, 0x07, 0x00, 0x70, 0x07, 0x00, 0x70, 0x07, 0x00, 0x70, 0x07, 0x00, + 0x70, 0x07, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x01, 0xC0, 0x1C, 0x03, + 0x80, 0x38, 0x03, 0x00, 0x70, 0x06, 0x00, 0xC0, 0x1C, 0x01, 0x80, 0x30, + 0x06, 0x00, 0xC0, 0x00, 0x06, 0x01, 0x84, 0x47, 0xF7, 0xFF, 0xCF, 0xC1, + 0xE0, 0xD8, 0x67, 0x18, 0xC0, 0x00, 0x70, 0x00, 0x1C, 0x00, 0x0F, 0x00, + 0x03, 0x80, 0x00, 0xE0, 0x00, 0x38, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xC0, 0x70, 0x00, 0x1C, 0x00, 0x07, 0x00, 0x01, 0xC0, 0x00, 0xE0, + 0x00, 0x38, 0x00, 0x0E, 0x00, 0x3B, 0xDC, 0x21, 0x18, 0x98, 0xFF, 0xFF, + 0xFF, 0xE0, 0x7F, 0xFE, 0x00, 0x06, 0x00, 0x18, 0x00, 0x30, 0x00, 0xC0, + 0x01, 0x80, 0x06, 0x00, 0x0C, 0x00, 0x30, 0x00, 0x60, 0x01, 0x80, 0x03, + 0x00, 0x0C, 0x00, 0x18, 0x00, 0x60, 0x00, 0xC0, 0x03, 0x00, 0x06, 0x00, + 0x18, 0x00, 0x20, 0x00, 0xC0, 0x03, 0x00, 0x06, 0x00, 0x18, 0x00, 0x30, + 0x00, 0xC0, 0x01, 0x80, 0x00, 0x00, 0x7C, 0x00, 0x7F, 0xC0, 0x7F, 0xF8, + 0x3E, 0x1E, 0x0F, 0x03, 0xC7, 0x80, 0x71, 0xC0, 0x1C, 0xE0, 0x07, 0x38, + 0x01, 0xDE, 0x00, 0x77, 0x00, 0x1D, 0xC0, 0x0F, 0x70, 0x03, 0xFC, 0x00, + 0xEE, 0x00, 0x3B, 0x80, 0x0E, 0xE0, 0x07, 0xB8, 0x01, 0xCE, 0x00, 0xF3, + 0x80, 0x38, 0xF0, 0x1E, 0x1E, 0x1F, 0x07, 0xFF, 0x80, 0xFF, 0xC0, 0x0F, + 0x80, 0x00, 0x00, 0xC0, 0x70, 0x3C, 0x3E, 0xFF, 0xBF, 0xEF, 0xF8, 0x1E, + 0x07, 0x01, 0xC0, 0x70, 0x1C, 0x0F, 0x03, 0x80, 0xE0, 0x38, 0x0E, 0x07, + 0x81, 0xC0, 0x70, 0x1C, 0x07, 0x01, 0xC0, 0xE0, 0x38, 0x00, 0x00, 0x3F, + 0x00, 0x0F, 0xFC, 0x03, 0xFF, 0xE0, 0x7C, 0x1E, 0x07, 0x80, 0xF0, 0xF0, + 0x07, 0x0E, 0x00, 0x70, 0xE0, 0x07, 0x00, 0x00, 0x70, 0x00, 0x0E, 0x00, + 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x0F, 0x80, 0x03, 0xF0, 0x00, 0xFC, 0x00, + 0x1F, 0x00, 0x07, 0xC0, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0x80, 0x00, + 0x70, 0x00, 0x07, 0x00, 0x00, 0xFF, 0xFF, 0x8F, 0xFF, 0xF0, 0xFF, 0xFF, + 0x00, 0x00, 0x7E, 0x00, 0x3F, 0xF0, 0x0F, 0xFF, 0x03, 0xC1, 0xF0, 0x70, + 0x0E, 0x1C, 0x01, 0xC3, 0x80, 0x38, 0xE0, 0x07, 0x00, 0x01, 0xC0, 0x00, + 0xF0, 0x03, 0xFC, 0x00, 0x7F, 0x00, 0x0F, 0xF0, 0x00, 0x1F, 0x00, 0x00, + 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x9C, 0x00, 0x73, 0x80, 0x1E, 0x70, 0x03, + 0x8F, 0x00, 0xF1, 0xF0, 0x7C, 0x1F, 0xFF, 0x01, 0xFF, 0xC0, 0x0F, 0xC0, + 0x00, 0x00, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x78, 0x00, 0x3E, 0x00, 0x1F, + 0x80, 0x0F, 0xE0, 0x07, 0xF0, 0x03, 0xDC, 0x01, 0xE7, 0x00, 0x71, 0xC0, + 0x38, 0xF0, 0x1C, 0x38, 0x0E, 0x0E, 0x07, 0x03, 0x83, 0x80, 0xE1, 0xC0, + 0x70, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x70, 0x00, 0x38, + 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x01, 0xFF, + 0xF0, 0x3F, 0xFF, 0x03, 0xFF, 0xE0, 0x78, 0x00, 0x07, 0x00, 0x00, 0x70, + 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0xFC, 0x01, 0xFF, 0xF0, 0x1F, + 0xFF, 0x83, 0xE0, 0x78, 0x3C, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xC0, + 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x18, 0x00, 0x03, 0x8E, 0x00, 0x78, + 0xE0, 0x0F, 0x0F, 0x81, 0xE0, 0x7F, 0xFC, 0x03, 0xFF, 0x80, 0x0F, 0xE0, + 0x00, 0x00, 0x7E, 0x00, 0x3F, 0xF0, 0x0F, 0xFF, 0x03, 0xE1, 0xF0, 0xF0, + 0x0E, 0x1C, 0x01, 0xC7, 0x00, 0x01, 0xE0, 0x00, 0x38, 0x00, 0x07, 0x1F, + 0x01, 0xCF, 0xF8, 0x3B, 0xFF, 0x87, 0xE0, 0xF8, 0xF0, 0x0F, 0x3C, 0x00, + 0xE7, 0x80, 0x1C, 0xE0, 0x03, 0x9C, 0x00, 0x73, 0x80, 0x1C, 0x70, 0x03, + 0x8F, 0x00, 0xE0, 0xF0, 0x78, 0x1F, 0xFF, 0x01, 0xFF, 0x80, 0x0F, 0xC0, + 0x00, 0x3F, 0xFF, 0xCF, 0xFF, 0xF7, 0xFF, 0xFC, 0x00, 0x0E, 0x00, 0x07, + 0x00, 0x03, 0x80, 0x00, 0xC0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, + 0x0E, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x78, 0x00, 0x1C, + 0x00, 0x0E, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xF0, 0x00, 0x38, 0x00, + 0x1E, 0x00, 0x07, 0x00, 0x03, 0xC0, 0x00, 0xE0, 0x00, 0x00, 0x00, 0x7E, + 0x00, 0x3F, 0xF0, 0x1F, 0xFF, 0x07, 0xC1, 0xF0, 0xE0, 0x0E, 0x38, 0x01, + 0xC7, 0x00, 0x38, 0xE0, 0x0E, 0x1C, 0x01, 0xC3, 0xC0, 0xF0, 0x3F, 0xFC, + 0x03, 0xFE, 0x01, 0xFF, 0xF0, 0x7C, 0x1E, 0x1E, 0x01, 0xE3, 0x80, 0x1C, + 0xE0, 0x03, 0x9C, 0x00, 0x73, 0x80, 0x0E, 0x70, 0x03, 0x8F, 0x00, 0xF1, + 0xF0, 0x7C, 0x1F, 0xFF, 0x01, 0xFF, 0xC0, 0x0F, 0xC0, 0x00, 0x00, 0x7E, + 0x00, 0x3F, 0xF0, 0x1F, 0xFF, 0x07, 0xC1, 0xE0, 0xE0, 0x1E, 0x38, 0x01, + 0xC7, 0x00, 0x39, 0xC0, 0x07, 0x38, 0x00, 0xE7, 0x00, 0x3C, 0xE0, 0x07, + 0x9E, 0x01, 0xE3, 0xE0, 0xFC, 0x3F, 0xFB, 0x83, 0xFE, 0xF0, 0x3F, 0x1C, + 0x00, 0x03, 0x80, 0x00, 0xF0, 0x00, 0x1C, 0x70, 0x07, 0x8E, 0x01, 0xE1, + 0xE0, 0xF8, 0x1F, 0xFE, 0x01, 0xFF, 0x80, 0x0F, 0xC0, 0x00, 0x0E, 0x3C, + 0x78, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, + 0xF1, 0xE3, 0x80, 0x07, 0x0F, 0x0F, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x78, 0x70, 0x10, 0x10, + 0x30, 0x20, 0xC0, 0x00, 0x00, 0x20, 0x00, 0x1C, 0x00, 0x1F, 0x80, 0x1F, + 0xC0, 0x0F, 0xC0, 0x0F, 0xE0, 0x07, 0xE0, 0x03, 0xF0, 0x00, 0xF0, 0x00, + 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF8, + 0x00, 0x0F, 0xC0, 0x00, 0x78, 0x00, 0x01, 0x00, 0x7F, 0xFF, 0xDF, 0xFF, + 0xF7, 0xFF, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0xFB, + 0xFF, 0xFE, 0xFF, 0xFF, 0x80, 0x10, 0x00, 0x03, 0xC0, 0x00, 0x7E, 0x00, + 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x3F, + 0x00, 0x01, 0xE0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0xFE, 0x00, 0x7E, 0x00, + 0x7F, 0x00, 0x3F, 0x00, 0x07, 0x00, 0x00, 0x80, 0x00, 0x00, 0x03, 0xF8, + 0x0F, 0xFC, 0x1F, 0xFE, 0x3C, 0x1F, 0x78, 0x07, 0x70, 0x07, 0xE0, 0x07, + 0xE0, 0x07, 0x00, 0x0E, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, + 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0F, 0x00, 0x0E, 0x00, 0x0E, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, + 0x3C, 0x00, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x07, + 0xFF, 0xFE, 0x00, 0x0F, 0xE0, 0x3F, 0x80, 0x0F, 0x80, 0x03, 0xE0, 0x0F, + 0x00, 0x00, 0xF8, 0x0F, 0x00, 0x00, 0x3C, 0x0F, 0x01, 0xF0, 0x0F, 0x0F, + 0x03, 0xFD, 0xC7, 0x8F, 0x03, 0xFE, 0xE1, 0xC7, 0x03, 0xC3, 0x60, 0xE7, + 0x03, 0xC0, 0xF0, 0x77, 0x83, 0xC0, 0x70, 0x3B, 0x83, 0xC0, 0x78, 0x1D, + 0xC1, 0xC0, 0x38, 0x1F, 0xC1, 0xE0, 0x1C, 0x0E, 0xE0, 0xE0, 0x1C, 0x0F, + 0x70, 0x70, 0x0E, 0x07, 0x38, 0x38, 0x0E, 0x07, 0x9C, 0x1C, 0x0F, 0x07, + 0x8E, 0x0F, 0x0F, 0x8F, 0x87, 0x03, 0xFD, 0xFF, 0x83, 0xC1, 0xFC, 0xFF, + 0x80, 0xE0, 0x7C, 0x3F, 0x00, 0x78, 0x00, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x00, 0x07, 0x80, 0x00, 0x00, 0x01, 0xF8, 0x07, 0x00, 0x00, 0x7F, 0xFF, + 0x80, 0x00, 0x1F, 0xFF, 0xC0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x00, 0x01, + 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x80, 0x00, 0xFF, + 0x00, 0x01, 0xDE, 0x00, 0x07, 0x9C, 0x00, 0x0E, 0x38, 0x00, 0x3C, 0x70, + 0x00, 0x70, 0xF0, 0x01, 0xC1, 0xE0, 0x07, 0x83, 0xC0, 0x0E, 0x07, 0x80, + 0x38, 0x07, 0x00, 0x70, 0x0E, 0x01, 0xFF, 0xFC, 0x03, 0xFF, 0xFC, 0x0F, + 0xFF, 0xF8, 0x1C, 0x00, 0xF0, 0x70, 0x01, 0xE1, 0xE0, 0x01, 0xC3, 0x80, + 0x03, 0x8F, 0x00, 0x07, 0x1C, 0x00, 0x0E, 0x78, 0x00, 0x1E, 0xE0, 0x00, + 0x3C, 0x07, 0xFF, 0xC0, 0x3F, 0xFF, 0x81, 0xFF, 0xFC, 0x0E, 0x00, 0xF0, + 0xF0, 0x03, 0x87, 0x00, 0x1C, 0x38, 0x00, 0xE1, 0xC0, 0x07, 0x0E, 0x00, + 0x70, 0xF0, 0x03, 0x87, 0x00, 0x78, 0x3F, 0xFF, 0x81, 0xFF, 0xF8, 0x0F, + 0xFF, 0xF0, 0xE0, 0x03, 0xC7, 0x00, 0x0E, 0x38, 0x00, 0x71, 0xC0, 0x03, + 0x9E, 0x00, 0x1C, 0xE0, 0x00, 0xE7, 0x00, 0x0E, 0x38, 0x00, 0xF1, 0xC0, + 0x0F, 0x1F, 0xFF, 0xF0, 0xFF, 0xFF, 0x07, 0xFF, 0xE0, 0x00, 0x00, 0x1F, + 0x80, 0x03, 0xFF, 0x80, 0x1F, 0xFF, 0x01, 0xF8, 0x3E, 0x07, 0x80, 0x38, + 0x38, 0x00, 0xF1, 0xC0, 0x01, 0xCF, 0x00, 0x07, 0x38, 0x00, 0x01, 0xE0, + 0x00, 0x07, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x70, 0x00, 0x03, 0x80, 0x00, + 0x0E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x7B, 0x80, 0x01, 0xCE, + 0x00, 0x0F, 0x3C, 0x00, 0x38, 0x70, 0x01, 0xE1, 0xE0, 0x0F, 0x07, 0xC0, + 0xF8, 0x0F, 0xFF, 0xC0, 0x1F, 0xFC, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xFF, + 0xC0, 0x0F, 0xFF, 0xE0, 0x1F, 0xFF, 0xE0, 0x38, 0x03, 0xE0, 0xF0, 0x03, + 0xC1, 0xC0, 0x03, 0x83, 0x80, 0x03, 0x87, 0x00, 0x07, 0x1E, 0x00, 0x0E, + 0x3C, 0x00, 0x1C, 0x70, 0x00, 0x38, 0xE0, 0x00, 0x71, 0xC0, 0x00, 0xE7, + 0x80, 0x03, 0x8F, 0x00, 0x07, 0x1C, 0x00, 0x0E, 0x38, 0x00, 0x3C, 0x70, + 0x00, 0x71, 0xE0, 0x01, 0xE3, 0x80, 0x03, 0x87, 0x00, 0x0E, 0x0E, 0x00, + 0x3C, 0x1C, 0x01, 0xF0, 0x7F, 0xFF, 0xC0, 0xFF, 0xFE, 0x01, 0xFF, 0xF0, + 0x00, 0x07, 0xFF, 0xFE, 0x0F, 0xFF, 0xFC, 0x1F, 0xFF, 0xF0, 0x38, 0x00, + 0x00, 0xF0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x70, 0x00, 0x00, 0xFF, 0xFF, 0x81, + 0xFF, 0xFF, 0x07, 0xFF, 0xFE, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, + 0x00, 0x00, 0x70, 0x00, 0x01, 0xE0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, + 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x7F, 0xFF, 0xF0, 0xFF, 0xFF, + 0xC1, 0xFF, 0xFF, 0x80, 0x07, 0xFF, 0xFC, 0x1F, 0xFF, 0xF0, 0x7F, 0xFF, + 0xC1, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x03, + 0x80, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xC0, 0x00, 0x07, 0xFF, + 0xF0, 0x1F, 0xFF, 0xC0, 0xFF, 0xFF, 0x03, 0x80, 0x00, 0x0E, 0x00, 0x00, + 0x38, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1C, 0x00, 0x00, 0x70, + 0x00, 0x01, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xE0, 0x00, + 0x03, 0x80, 0x00, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x7F, 0xF8, 0x01, 0xFF, + 0xFC, 0x03, 0xE0, 0x3E, 0x07, 0x80, 0x0E, 0x0F, 0x00, 0x0F, 0x1E, 0x00, + 0x07, 0x1C, 0x00, 0x07, 0x38, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, + 0x00, 0x70, 0x00, 0x00, 0xF0, 0x07, 0xFE, 0xE0, 0x07, 0xFE, 0xE0, 0x07, + 0xFE, 0xE0, 0x00, 0x0E, 0xE0, 0x00, 0x0E, 0xE0, 0x00, 0x0E, 0xE0, 0x00, + 0x1C, 0xF0, 0x00, 0x3C, 0x70, 0x00, 0x7C, 0x78, 0x00, 0xFC, 0x3E, 0x03, + 0xDC, 0x1F, 0xFF, 0x98, 0x0F, 0xFE, 0x18, 0x03, 0xF8, 0x18, 0x07, 0x00, + 0x07, 0x83, 0x80, 0x03, 0xC1, 0xC0, 0x01, 0xC0, 0xE0, 0x00, 0xE0, 0xF0, + 0x00, 0x70, 0x70, 0x00, 0x78, 0x38, 0x00, 0x3C, 0x1C, 0x00, 0x1C, 0x1E, + 0x00, 0x0E, 0x0F, 0x00, 0x07, 0x07, 0x00, 0x07, 0x83, 0xFF, 0xFF, 0x81, + 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, 0xE0, 0xE0, 0x00, 0x70, 0x70, 0x00, 0x78, + 0x38, 0x00, 0x38, 0x1C, 0x00, 0x1C, 0x1E, 0x00, 0x0E, 0x0E, 0x00, 0x0F, + 0x07, 0x00, 0x07, 0x83, 0x80, 0x03, 0x81, 0xC0, 0x01, 0xC1, 0xE0, 0x00, + 0xE0, 0xE0, 0x00, 0xF0, 0x70, 0x00, 0x78, 0x00, 0x07, 0x0F, 0x0F, 0x0E, + 0x0E, 0x0E, 0x0E, 0x1E, 0x1C, 0x1C, 0x1C, 0x1C, 0x3C, 0x3C, 0x38, 0x38, + 0x38, 0x38, 0x78, 0x70, 0x70, 0x70, 0x70, 0xF0, 0xF0, 0xE0, 0x00, 0x01, + 0xC0, 0x00, 0x70, 0x00, 0x3C, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, + 0x00, 0x38, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x01, 0xC0, 0x00, 0x70, 0x00, + 0x1C, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x1E, + 0x1C, 0x07, 0x0E, 0x01, 0xC3, 0x80, 0x70, 0xE0, 0x3C, 0x38, 0x0E, 0x0F, + 0x0F, 0x81, 0xFF, 0xC0, 0x7F, 0xE0, 0x07, 0xE0, 0x00, 0x07, 0x00, 0x07, + 0x83, 0x80, 0x07, 0x81, 0xC0, 0x0F, 0x00, 0xE0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0x70, 0x0F, 0x00, 0x38, 0x0F, 0x00, 0x1C, 0x1F, 0x00, 0x1E, 0x1E, + 0x00, 0x0F, 0x1E, 0x00, 0x07, 0x1E, 0x00, 0x03, 0x9F, 0x00, 0x01, 0xDF, + 0xC0, 0x01, 0xFC, 0xE0, 0x00, 0xFC, 0x78, 0x00, 0x7C, 0x1C, 0x00, 0x3C, + 0x0F, 0x00, 0x1C, 0x07, 0x80, 0x1E, 0x01, 0xE0, 0x0E, 0x00, 0xF0, 0x07, + 0x00, 0x38, 0x03, 0x80, 0x1E, 0x01, 0xC0, 0x07, 0x01, 0xE0, 0x03, 0xC0, + 0xE0, 0x00, 0xE0, 0x70, 0x00, 0x78, 0x00, 0x07, 0x00, 0x07, 0x00, 0x07, + 0x00, 0x07, 0x00, 0x0F, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x1E, + 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x3C, 0x00, 0x38, + 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x78, 0x00, 0x70, 0x00, 0x70, + 0x00, 0x70, 0x00, 0x70, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x07, + 0xC0, 0x00, 0xF8, 0x3E, 0x00, 0x07, 0xC1, 0xF0, 0x00, 0x7E, 0x0F, 0x80, + 0x03, 0xF0, 0xFC, 0x00, 0x3F, 0x07, 0x70, 0x01, 0xF8, 0x3B, 0x80, 0x1D, + 0xC1, 0xDC, 0x00, 0xEE, 0x0E, 0xE0, 0x0E, 0xE0, 0xE7, 0x00, 0x77, 0x07, + 0x38, 0x07, 0x38, 0x39, 0xC0, 0x31, 0xC1, 0xCE, 0x03, 0x9E, 0x1E, 0x38, + 0x38, 0xE0, 0xE1, 0xC1, 0xC7, 0x07, 0x0E, 0x1C, 0x38, 0x38, 0x70, 0xE1, + 0xC1, 0xC3, 0x8E, 0x1E, 0x1E, 0x1C, 0x70, 0xE0, 0xE0, 0xE7, 0x07, 0x07, + 0x07, 0x38, 0x38, 0x38, 0x1F, 0x81, 0xC1, 0xC0, 0xF8, 0x1E, 0x1C, 0x07, + 0xC0, 0xE0, 0xE0, 0x3C, 0x07, 0x07, 0x01, 0xE0, 0x38, 0x00, 0x07, 0x80, + 0x03, 0x83, 0xE0, 0x01, 0xC1, 0xF0, 0x00, 0xE0, 0xF8, 0x00, 0xE0, 0xFE, + 0x00, 0x70, 0x7F, 0x00, 0x38, 0x3B, 0xC0, 0x1C, 0x1D, 0xE0, 0x1E, 0x0E, + 0x70, 0x0E, 0x0E, 0x3C, 0x07, 0x07, 0x0E, 0x03, 0x83, 0x87, 0x81, 0xC1, + 0xC3, 0xC1, 0xE1, 0xE0, 0xE0, 0xE0, 0xE0, 0x78, 0x70, 0x70, 0x1C, 0x38, + 0x38, 0x0F, 0x1C, 0x1C, 0x07, 0x9E, 0x1E, 0x01, 0xCE, 0x0E, 0x00, 0xF7, + 0x07, 0x00, 0x3B, 0x83, 0x80, 0x1F, 0xC1, 0xC0, 0x07, 0xC1, 0xC0, 0x03, + 0xE0, 0xE0, 0x01, 0xF0, 0x70, 0x00, 0x78, 0x00, 0x00, 0x1F, 0xC0, 0x00, + 0xFF, 0xF0, 0x01, 0xFF, 0xF8, 0x03, 0xE0, 0x7C, 0x07, 0x80, 0x1E, 0x0F, + 0x00, 0x0E, 0x1C, 0x00, 0x0F, 0x3C, 0x00, 0x07, 0x38, 0x00, 0x07, 0x70, + 0x00, 0x07, 0x70, 0x00, 0x07, 0x70, 0x00, 0x07, 0xE0, 0x00, 0x07, 0xE0, + 0x00, 0x0F, 0xE0, 0x00, 0x0E, 0xE0, 0x00, 0x0E, 0xE0, 0x00, 0x0E, 0xE0, + 0x00, 0x1C, 0xE0, 0x00, 0x1C, 0xF0, 0x00, 0x38, 0x70, 0x00, 0x78, 0x78, + 0x00, 0xF0, 0x3E, 0x07, 0xE0, 0x1F, 0xFF, 0xC0, 0x0F, 0xFF, 0x00, 0x03, + 0xF8, 0x00, 0x07, 0xFF, 0xE0, 0x1F, 0xFF, 0xC0, 0x7F, 0xFF, 0x81, 0xC0, + 0x1F, 0x0F, 0x00, 0x3C, 0x38, 0x00, 0x70, 0xE0, 0x01, 0xC3, 0x80, 0x07, + 0x1E, 0x00, 0x1C, 0x78, 0x00, 0xE1, 0xC0, 0x07, 0x87, 0x00, 0x3C, 0x1F, + 0xFF, 0xE0, 0xFF, 0xFF, 0x03, 0xFF, 0xF0, 0x0E, 0x00, 0x00, 0x38, 0x00, + 0x00, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1C, 0x00, 0x00, 0x70, 0x00, 0x01, + 0xC0, 0x00, 0x07, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xE0, 0x00, 0x03, 0x80, + 0x00, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x3F, 0xFC, 0x00, 0x7F, 0xFF, 0x00, + 0x7C, 0x07, 0xC0, 0x78, 0x00, 0xF0, 0x78, 0x00, 0x38, 0x78, 0x00, 0x1E, + 0x78, 0x00, 0x07, 0x38, 0x00, 0x03, 0xBC, 0x00, 0x01, 0xDC, 0x00, 0x00, + 0xEE, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0x80, 0x00, + 0x1D, 0xC0, 0x00, 0x0E, 0xE0, 0x00, 0x0F, 0x70, 0x00, 0x07, 0x38, 0x00, + 0x87, 0x9E, 0x00, 0xE7, 0x87, 0x00, 0x7F, 0x83, 0xC0, 0x1F, 0x80, 0xF8, + 0x1F, 0x80, 0x3F, 0xFF, 0xE0, 0x0F, 0xFF, 0x78, 0x01, 0xFE, 0x1E, 0x00, + 0x00, 0x07, 0x00, 0x00, 0x02, 0x00, 0x07, 0xFF, 0xF0, 0x0F, 0xFF, 0xF8, + 0x1F, 0xFF, 0xF0, 0x38, 0x00, 0xF0, 0xF0, 0x00, 0xE1, 0xC0, 0x01, 0xC3, + 0x80, 0x03, 0x87, 0x00, 0x07, 0x1E, 0x00, 0x0E, 0x3C, 0x00, 0x38, 0x70, + 0x00, 0xF0, 0xE0, 0x03, 0xC1, 0xFF, 0xFE, 0x07, 0xFF, 0xF8, 0x0F, 0xFF, + 0xF8, 0x1C, 0x00, 0x78, 0x38, 0x00, 0x70, 0x70, 0x00, 0xE1, 0xE0, 0x01, + 0xC3, 0x80, 0x03, 0x87, 0x00, 0x06, 0x0E, 0x00, 0x1C, 0x1C, 0x00, 0x38, + 0x78, 0x00, 0x70, 0xE0, 0x00, 0xE1, 0xC0, 0x01, 0xE0, 0x00, 0x3F, 0xC0, + 0x07, 0xFF, 0xC0, 0x3F, 0xFF, 0x81, 0xF0, 0x1E, 0x0F, 0x00, 0x3C, 0x38, + 0x00, 0x71, 0xC0, 0x01, 0xC7, 0x00, 0x07, 0x1C, 0x00, 0x00, 0x78, 0x00, + 0x01, 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x07, 0xFE, 0x00, 0x07, 0xFF, 0x00, + 0x03, 0xFE, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xF3, 0x80, 0x01, 0xCE, 0x00, + 0x07, 0x38, 0x00, 0x18, 0xE0, 0x00, 0xE3, 0xC0, 0x07, 0x07, 0x80, 0x7C, + 0x1F, 0xFF, 0xE0, 0x3F, 0xFE, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x1E, 0x00, + 0x01, 0xE0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x03, 0xC0, + 0x00, 0x38, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x03, 0x80, 0x00, 0x78, + 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0xF0, 0x00, 0x0F, + 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x1E, 0x00, 0x01, + 0xE0, 0x00, 0x0E, 0x00, 0x0F, 0x0E, 0x00, 0x0F, 0x0E, 0x00, 0x0E, 0x0E, + 0x00, 0x0E, 0x1E, 0x00, 0x0E, 0x1C, 0x00, 0x1E, 0x1C, 0x00, 0x1C, 0x1C, + 0x00, 0x1C, 0x3C, 0x00, 0x1C, 0x3C, 0x00, 0x1C, 0x38, 0x00, 0x3C, 0x38, + 0x00, 0x38, 0x38, 0x00, 0x38, 0x78, 0x00, 0x38, 0x70, 0x00, 0x78, 0x70, + 0x00, 0x78, 0x70, 0x00, 0x70, 0xF0, 0x00, 0x70, 0xF0, 0x00, 0x70, 0xE0, + 0x00, 0xF0, 0xE0, 0x00, 0xE0, 0xF0, 0x03, 0xE0, 0x78, 0x0F, 0xC0, 0x7F, + 0xFF, 0x80, 0x1F, 0xFE, 0x00, 0x07, 0xF0, 0x00, 0xE0, 0x00, 0x3F, 0x80, + 0x03, 0xFC, 0x00, 0x1D, 0xE0, 0x01, 0xE7, 0x00, 0x0E, 0x38, 0x00, 0xE1, + 0xC0, 0x07, 0x0E, 0x00, 0x70, 0x70, 0x07, 0x83, 0xC0, 0x38, 0x1E, 0x03, + 0xC0, 0xF0, 0x1C, 0x03, 0x81, 0xE0, 0x1C, 0x0E, 0x00, 0xE0, 0xF0, 0x07, + 0x07, 0x00, 0x3C, 0x70, 0x01, 0xE3, 0x80, 0x0F, 0x38, 0x00, 0x39, 0xC0, + 0x01, 0xDC, 0x00, 0x0E, 0xE0, 0x00, 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x1F, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0xE0, 0x03, 0x80, 0x0E, 0xE0, 0x07, 0x80, + 0x1E, 0xE0, 0x07, 0xC0, 0x1E, 0xE0, 0x0F, 0xC0, 0x1C, 0xE0, 0x0F, 0xC0, + 0x3C, 0xE0, 0x1F, 0xC0, 0x38, 0xE0, 0x1D, 0xC0, 0x78, 0xE0, 0x3D, 0xC0, + 0x70, 0xE0, 0x39, 0xC0, 0xF0, 0xE0, 0x79, 0xC0, 0xE0, 0xE0, 0x71, 0xC0, + 0xE0, 0xE0, 0xF1, 0xC1, 0xC0, 0xE0, 0xE1, 0xC1, 0xC0, 0xE1, 0xE1, 0xC3, + 0xC0, 0x61, 0xC1, 0xC3, 0x80, 0x63, 0xC1, 0xC7, 0x80, 0x63, 0x80, 0xE7, + 0x00, 0x67, 0x80, 0xEF, 0x00, 0x67, 0x00, 0xEE, 0x00, 0x7F, 0x00, 0xEE, + 0x00, 0x7E, 0x00, 0xFC, 0x00, 0x7E, 0x00, 0xFC, 0x00, 0x7C, 0x00, 0xF8, + 0x00, 0x7C, 0x00, 0xF8, 0x00, 0x78, 0x00, 0xF8, 0x00, 0x78, 0x00, 0xF0, + 0x00, 0x03, 0xC0, 0x03, 0xC0, 0x78, 0x00, 0xF0, 0x07, 0x80, 0x1C, 0x00, + 0xF0, 0x07, 0x80, 0x0F, 0x01, 0xE0, 0x01, 0xE0, 0x78, 0x00, 0x1C, 0x1E, + 0x00, 0x03, 0xC7, 0x80, 0x00, 0x39, 0xE0, 0x00, 0x07, 0xB8, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x3E, 0x00, + 0x00, 0x0F, 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xF3, 0x80, 0x00, 0x3C, + 0x78, 0x00, 0x0F, 0x0F, 0x00, 0x03, 0xC0, 0xF0, 0x00, 0x70, 0x1E, 0x00, + 0x1E, 0x01, 0xE0, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x03, 0xC0, 0x78, 0x00, + 0x78, 0x1E, 0x00, 0x0F, 0x00, 0xF0, 0x00, 0x3C, 0xE0, 0x00, 0x71, 0xE0, + 0x01, 0xE3, 0xC0, 0x07, 0x83, 0xC0, 0x1E, 0x07, 0x80, 0x78, 0x07, 0x00, + 0xE0, 0x0F, 0x03, 0xC0, 0x1E, 0x0F, 0x00, 0x1C, 0x3C, 0x00, 0x3C, 0xF0, + 0x00, 0x39, 0xC0, 0x00, 0x7F, 0x80, 0x00, 0xFE, 0x00, 0x00, 0xF8, 0x00, + 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, + 0x1C, 0x00, 0x00, 0x78, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xC0, 0x00, 0x03, + 0x80, 0x00, 0x07, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0x81, + 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0xFF, 0xFF, 0xE0, 0xFF, + 0xFF, 0xF0, 0x7F, 0xFF, 0xF8, 0x00, 0x01, 0xF8, 0x1F, 0xC0, 0xFE, 0x07, + 0x00, 0x38, 0x03, 0xC0, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x03, 0xC0, + 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, + 0x00, 0x38, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x78, 0x03, 0x80, + 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x70, 0x03, 0xF8, 0x1F, 0xC0, 0xFE, 0x00, + 0xCC, 0xCC, 0xCC, 0x46, 0x66, 0x66, 0x66, 0x66, 0x66, 0x62, 0x33, 0x33, + 0x33, 0x03, 0xF8, 0x1F, 0xC0, 0xFE, 0x00, 0x70, 0x07, 0x00, 0x38, 0x01, + 0xC0, 0x0E, 0x00, 0xF0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x0E, 0x00, 0xE0, + 0x07, 0x00, 0x38, 0x01, 0xC0, 0x0E, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, + 0xC0, 0x1E, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x1E, 0x00, 0xE0, + 0x07, 0x03, 0xF8, 0x1F, 0xC0, 0xFC, 0x00, 0x00, 0xF0, 0x03, 0xC0, 0x1F, + 0x00, 0x7C, 0x03, 0xB8, 0x1C, 0xE0, 0x63, 0x83, 0x8E, 0x1C, 0x38, 0x60, + 0x73, 0x81, 0xCC, 0x07, 0x70, 0x1F, 0x80, 0x70, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xC0, 0xF1, 0xC3, 0x86, 0x0C, 0x00, 0xFE, 0x01, 0xFF, 0xE0, 0xFF, + 0xFC, 0x3C, 0x0F, 0x1C, 0x01, 0xC0, 0x00, 0x70, 0x00, 0x1C, 0x00, 0x0E, + 0x00, 0x1F, 0x83, 0xFF, 0xE3, 0xFE, 0x39, 0xF0, 0x1E, 0xF0, 0x07, 0x38, + 0x01, 0xCE, 0x00, 0xF3, 0xC0, 0xFC, 0xFF, 0xF7, 0x9F, 0xF1, 0xE1, 0xF0, + 0x38, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0xF0, + 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x71, 0xF0, 0x0E, 0xFF, 0x83, 0xFF, + 0xF8, 0x7F, 0x0F, 0x0F, 0x80, 0xF1, 0xE0, 0x0E, 0x38, 0x01, 0xCF, 0x00, + 0x39, 0xE0, 0x07, 0x38, 0x00, 0xE7, 0x00, 0x38, 0xE0, 0x07, 0x3C, 0x00, + 0xE7, 0x80, 0x38, 0xF8, 0x0F, 0x1F, 0x87, 0xC3, 0xFF, 0xF0, 0xE7, 0xFC, + 0x1C, 0x7E, 0x00, 0x01, 0xF8, 0x07, 0xFC, 0x0F, 0xFE, 0x1E, 0x0F, 0x3C, + 0x07, 0x78, 0x07, 0x70, 0x07, 0x70, 0x00, 0xF0, 0x00, 0xE0, 0x00, 0xE0, + 0x00, 0xE0, 0x00, 0xE0, 0x0E, 0xE0, 0x1C, 0xF0, 0x3C, 0x78, 0x78, 0x7F, + 0xF0, 0x3F, 0xE0, 0x0F, 0x80, 0x00, 0x00, 0x70, 0x00, 0x0F, 0x00, 0x00, + 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x01, 0xE0, 0x1F, + 0x1C, 0x07, 0xFD, 0xC0, 0xFF, 0xDC, 0x1E, 0x0F, 0xC3, 0xC0, 0x7C, 0x38, + 0x07, 0x87, 0x00, 0x38, 0x70, 0x03, 0x8F, 0x00, 0x38, 0xE0, 0x07, 0x8E, + 0x00, 0x70, 0xE0, 0x07, 0x0E, 0x00, 0xF0, 0xE0, 0x0F, 0x0F, 0x01, 0xF0, + 0x78, 0x7E, 0x07, 0xFF, 0xE0, 0x3F, 0xEE, 0x01, 0xF8, 0xE0, 0x01, 0xF8, + 0x03, 0xFF, 0x03, 0xFF, 0xC3, 0xC1, 0xF3, 0xC0, 0x79, 0xC0, 0x1D, 0xC0, + 0x0E, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0xFF, 0xF8, 0x00, 0x1C, 0x00, 0x0E, + 0x00, 0x07, 0x00, 0x73, 0xC0, 0x78, 0xF0, 0x78, 0x7F, 0xF8, 0x1F, 0xF8, + 0x03, 0xF0, 0x00, 0x01, 0xE0, 0x7C, 0x1F, 0x83, 0x80, 0x70, 0x1C, 0x03, + 0x83, 0xFC, 0x7F, 0x8F, 0xF0, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x0F, 0x01, + 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, + 0xE0, 0x1C, 0x00, 0x00, 0xFC, 0x60, 0x7F, 0xCC, 0x1F, 0xFF, 0x87, 0xC3, + 0xF1, 0xE0, 0x3E, 0x38, 0x03, 0x8E, 0x00, 0x71, 0xC0, 0x0E, 0x38, 0x01, + 0xCE, 0x00, 0x79, 0xC0, 0x0E, 0x38, 0x01, 0xC7, 0x00, 0x78, 0xE0, 0x0F, + 0x1E, 0x03, 0xC1, 0xE1, 0xF8, 0x3F, 0xFF, 0x03, 0xFE, 0xE0, 0x1F, 0x1C, + 0x00, 0x03, 0x00, 0x00, 0xE0, 0x00, 0x18, 0x38, 0x07, 0x07, 0x83, 0xC0, + 0x7F, 0xF8, 0x0F, 0xFC, 0x00, 0x7E, 0x00, 0x00, 0x07, 0x00, 0x01, 0xC0, + 0x00, 0x70, 0x00, 0x1C, 0x00, 0x0F, 0x00, 0x03, 0x80, 0x00, 0xE0, 0x00, + 0x38, 0xFC, 0x0E, 0xFF, 0x87, 0xFF, 0xF1, 0xF8, 0x3C, 0x7C, 0x07, 0x1E, + 0x01, 0xC7, 0x00, 0x73, 0xC0, 0x1C, 0xE0, 0x0F, 0x38, 0x03, 0x8E, 0x00, + 0xE3, 0x80, 0x39, 0xE0, 0x0E, 0x70, 0x07, 0x9C, 0x01, 0xC7, 0x00, 0x71, + 0xC0, 0x1C, 0xE0, 0x07, 0x38, 0x03, 0x80, 0x07, 0x07, 0x0F, 0x0E, 0x00, + 0x00, 0x00, 0x1E, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x38, 0x38, 0x38, 0x38, + 0x38, 0x78, 0x70, 0x70, 0x70, 0x70, 0xF0, 0xE0, 0xE0, 0x00, 0x3C, 0x00, + 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1C, 0x00, + 0x70, 0x01, 0xC0, 0x0E, 0x00, 0x38, 0x00, 0xE0, 0x03, 0x80, 0x1E, 0x00, + 0x70, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, 0xE0, 0x03, 0x80, 0x0E, 0x00, + 0x38, 0x00, 0xE0, 0x07, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xC0, 0x0F, 0x00, + 0x38, 0x00, 0xE0, 0x1F, 0x80, 0x7C, 0x03, 0xE0, 0x00, 0x07, 0x00, 0x00, + 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0xF0, 0x00, 0x1C, 0x00, 0x03, + 0x80, 0x00, 0x70, 0x1E, 0x0E, 0x07, 0x83, 0xC1, 0xE0, 0x70, 0x70, 0x0E, + 0x1C, 0x01, 0xCF, 0x00, 0x3B, 0xC0, 0x0F, 0xF8, 0x01, 0xFF, 0x80, 0x3E, + 0x70, 0x07, 0x8E, 0x00, 0xE0, 0xE0, 0x38, 0x1C, 0x07, 0x03, 0xC0, 0xE0, + 0x38, 0x1C, 0x07, 0x03, 0x80, 0xF0, 0xE0, 0x0E, 0x1C, 0x01, 0xE0, 0x07, + 0x07, 0x0F, 0x0E, 0x0E, 0x0E, 0x0E, 0x1E, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, + 0x38, 0x38, 0x38, 0x38, 0x38, 0x78, 0x70, 0x70, 0x70, 0x70, 0xF0, 0xE0, + 0xE0, 0x1E, 0x7C, 0x0F, 0x83, 0xBF, 0xE7, 0xF8, 0x7F, 0xFD, 0xFF, 0x8F, + 0xC3, 0xF0, 0xF1, 0xE0, 0x3C, 0x0E, 0x38, 0x07, 0x01, 0xCF, 0x01, 0xE0, + 0x39, 0xC0, 0x38, 0x07, 0x38, 0x07, 0x00, 0xE7, 0x00, 0xE0, 0x1C, 0xE0, + 0x1C, 0x07, 0x3C, 0x07, 0x00, 0xE7, 0x00, 0xE0, 0x1C, 0xE0, 0x1C, 0x03, + 0x9C, 0x03, 0x80, 0xF3, 0x80, 0x70, 0x1C, 0x70, 0x1C, 0x03, 0x9C, 0x03, + 0x80, 0x73, 0x80, 0x70, 0x0E, 0x00, 0x1E, 0x3E, 0x07, 0x7F, 0xE1, 0xFF, + 0xF8, 0x7E, 0x0F, 0x1F, 0x01, 0xC7, 0x80, 0x73, 0xC0, 0x1C, 0xE0, 0x07, + 0x38, 0x03, 0xCE, 0x00, 0xE3, 0x80, 0x39, 0xE0, 0x0E, 0x70, 0x03, 0x9C, + 0x01, 0xC7, 0x00, 0x71, 0xC0, 0x1C, 0x70, 0x07, 0x38, 0x01, 0xCE, 0x00, + 0xE0, 0x01, 0xF8, 0x03, 0xFF, 0x03, 0xFF, 0xC3, 0xE1, 0xE3, 0xC0, 0x79, + 0xC0, 0x1D, 0xC0, 0x0E, 0xE0, 0x07, 0x70, 0x03, 0xF0, 0x01, 0xF8, 0x01, + 0xDC, 0x00, 0xEE, 0x00, 0x77, 0x00, 0x73, 0xC0, 0x78, 0xF0, 0xF8, 0x7F, + 0xF8, 0x1F, 0xF8, 0x03, 0xF0, 0x00, 0x03, 0x8F, 0x80, 0x1D, 0xFF, 0x01, + 0xFF, 0xFC, 0x0F, 0xC1, 0xE0, 0x7C, 0x07, 0x83, 0xC0, 0x1C, 0x1C, 0x00, + 0xE1, 0xE0, 0x07, 0x0E, 0x00, 0x38, 0x70, 0x01, 0xC3, 0x80, 0x1E, 0x1C, + 0x00, 0xE1, 0xE0, 0x07, 0x0F, 0x00, 0x70, 0x78, 0x07, 0x83, 0xF0, 0xF8, + 0x3F, 0xFF, 0x81, 0xDF, 0xF8, 0x0E, 0x3F, 0x00, 0x70, 0x00, 0x03, 0x80, + 0x00, 0x3C, 0x00, 0x01, 0xC0, 0x00, 0x0E, 0x00, 0x00, 0x70, 0x00, 0x03, + 0x80, 0x00, 0x00, 0x00, 0xF8, 0xF0, 0x7F, 0xEE, 0x0F, 0xFF, 0xE1, 0xF0, + 0xFE, 0x3C, 0x07, 0xE3, 0x80, 0x3E, 0x70, 0x03, 0xC7, 0x00, 0x3C, 0x70, + 0x03, 0xCE, 0x00, 0x3C, 0xE0, 0x07, 0x8E, 0x00, 0x78, 0xE0, 0x07, 0x8E, + 0x00, 0xF8, 0xF0, 0x1F, 0x87, 0x87, 0xF0, 0x7F, 0xF7, 0x03, 0xFE, 0x70, + 0x0F, 0x8F, 0x00, 0x00, 0xF0, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x0E, + 0x00, 0x01, 0xE0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x04, 0x00, 0x1E, + 0x78, 0xE7, 0xC7, 0x7C, 0x3F, 0x01, 0xF0, 0x0F, 0x00, 0xF0, 0x07, 0x00, + 0x38, 0x01, 0xC0, 0x0E, 0x00, 0xF0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x0E, + 0x00, 0x70, 0x07, 0x00, 0x38, 0x00, 0x01, 0xF8, 0x07, 0xFE, 0x0F, 0xFF, + 0x1E, 0x0F, 0x3C, 0x07, 0x38, 0x07, 0x38, 0x00, 0x3C, 0x00, 0x3F, 0x80, + 0x1F, 0xF8, 0x07, 0xFC, 0x00, 0x7E, 0x00, 0x0E, 0xE0, 0x0E, 0xE0, 0x1E, + 0xF0, 0x3C, 0x7F, 0xF8, 0x7F, 0xF0, 0x1F, 0xC0, 0x0E, 0x03, 0x80, 0xE0, + 0x38, 0x7F, 0xDF, 0xEF, 0xF8, 0x70, 0x1C, 0x0E, 0x03, 0x80, 0xE0, 0x38, + 0x1E, 0x07, 0x01, 0xC0, 0x70, 0x1C, 0x0F, 0x03, 0x80, 0xFC, 0x3F, 0x07, + 0x80, 0x1C, 0x03, 0xC7, 0x00, 0xE1, 0xC0, 0x38, 0xF0, 0x0E, 0x38, 0x03, + 0x8E, 0x00, 0xE3, 0x80, 0x70, 0xE0, 0x1C, 0x78, 0x07, 0x1C, 0x01, 0xC7, + 0x00, 0x71, 0xC0, 0x3C, 0x70, 0x0E, 0x38, 0x07, 0x8E, 0x03, 0xE3, 0x81, + 0xF8, 0xFF, 0xFE, 0x1F, 0xFF, 0x03, 0xF1, 0xC0, 0xE0, 0x07, 0xE0, 0x0F, + 0xE0, 0x0E, 0xE0, 0x1C, 0x70, 0x1C, 0x70, 0x38, 0x70, 0x38, 0x70, 0x70, + 0x70, 0xF0, 0x70, 0xE0, 0x71, 0xC0, 0x71, 0xC0, 0x33, 0x80, 0x3B, 0x80, + 0x3F, 0x00, 0x3F, 0x00, 0x3E, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0xE0, 0x1C, + 0x07, 0xE0, 0x3C, 0x0E, 0xE0, 0x3C, 0x0E, 0xE0, 0x7C, 0x1C, 0xE0, 0x7C, + 0x1C, 0xE0, 0xEC, 0x38, 0xE0, 0xEC, 0x38, 0x61, 0xCC, 0x70, 0x61, 0xCC, + 0x70, 0x63, 0x8C, 0xE0, 0x73, 0x8C, 0xE0, 0x77, 0x0C, 0xC0, 0x77, 0x0D, + 0xC0, 0x7E, 0x0D, 0x80, 0x7E, 0x0F, 0x80, 0x7C, 0x0F, 0x80, 0x7C, 0x0F, + 0x00, 0x78, 0x0F, 0x00, 0x78, 0x0E, 0x00, 0x0E, 0x00, 0xE1, 0xE0, 0x38, + 0x1C, 0x0E, 0x03, 0xC3, 0x80, 0x38, 0xE0, 0x07, 0xBC, 0x00, 0x77, 0x00, + 0x0F, 0xC0, 0x00, 0xF0, 0x00, 0x1C, 0x00, 0x07, 0xC0, 0x01, 0xF8, 0x00, + 0x77, 0x80, 0x1E, 0x70, 0x07, 0x8F, 0x00, 0xE0, 0xE0, 0x38, 0x1C, 0x0E, + 0x01, 0xC3, 0x80, 0x38, 0x00, 0x0E, 0x00, 0x70, 0xF0, 0x0F, 0x07, 0x00, + 0xE0, 0x70, 0x1C, 0x07, 0x01, 0xC0, 0x70, 0x38, 0x07, 0x03, 0x80, 0x70, + 0x70, 0x07, 0x07, 0x00, 0x70, 0xE0, 0x03, 0x9E, 0x00, 0x39, 0xC0, 0x03, + 0xB8, 0x00, 0x3B, 0x80, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xE0, 0x00, + 0x1E, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, + 0x07, 0x00, 0x00, 0xE0, 0x00, 0xFE, 0x00, 0x0F, 0xC0, 0x00, 0xF0, 0x00, + 0x00, 0x07, 0xFF, 0xC0, 0xFF, 0xF8, 0x3F, 0xFF, 0x00, 0x01, 0xC0, 0x00, + 0x70, 0x00, 0x1C, 0x00, 0x07, 0x00, 0x01, 0xC0, 0x00, 0x70, 0x00, 0x1C, + 0x00, 0x07, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, + 0x03, 0xC0, 0x00, 0x7F, 0xFE, 0x1F, 0xFF, 0xC3, 0xFF, 0xF8, 0x00, 0x00, + 0x70, 0x1F, 0x01, 0xF0, 0x3C, 0x03, 0x80, 0x38, 0x07, 0x00, 0x70, 0x07, + 0x00, 0x70, 0x07, 0x00, 0xE0, 0x0E, 0x01, 0xE0, 0x3C, 0x0F, 0x80, 0xE0, + 0x0F, 0x00, 0x78, 0x03, 0x80, 0x38, 0x03, 0x80, 0x38, 0x03, 0x80, 0x38, + 0x07, 0x00, 0x70, 0x07, 0x00, 0x70, 0x0E, 0x00, 0xF8, 0x0F, 0x80, 0x78, + 0x00, 0x01, 0x80, 0xC0, 0xC0, 0x60, 0x30, 0x18, 0x0C, 0x0C, 0x06, 0x03, + 0x01, 0x81, 0xC0, 0xC0, 0x60, 0x30, 0x18, 0x18, 0x0C, 0x06, 0x03, 0x01, + 0x81, 0x80, 0xC0, 0x60, 0x30, 0x38, 0x18, 0x0C, 0x06, 0x03, 0x03, 0x01, + 0x80, 0xC0, 0x00, 0x01, 0xE0, 0x1F, 0x01, 0xF0, 0x07, 0x00, 0xE0, 0x0E, + 0x00, 0xE0, 0x0E, 0x01, 0xC0, 0x1C, 0x01, 0xC0, 0x1C, 0x01, 0xC0, 0x1C, + 0x01, 0xE0, 0x0F, 0x00, 0x70, 0x1F, 0x03, 0xC0, 0x78, 0x07, 0x00, 0x70, + 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x01, 0xC0, 0x1C, 0x03, 0xC0, + 0xF8, 0x0F, 0x80, 0xE0, 0x00, 0x1C, 0x00, 0x3F, 0x00, 0x7F, 0x83, 0x63, + 0xC7, 0xC1, 0xFE, 0x00, 0xFC, 0x00, 0x78 }; + +const GFXglyph FreeSansOblique18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 10, 0, 1 }, // 0x20 ' ' + { 0, 9, 26, 10, 4, -25 }, // 0x21 '!' + { 30, 10, 9, 12, 6, -24 }, // 0x22 '"' + { 42, 21, 25, 19, 2, -24 }, // 0x23 '#' + { 108, 20, 31, 19, 2, -26 }, // 0x24 '$' + { 186, 26, 25, 31, 5, -24 }, // 0x25 '%' + { 268, 20, 25, 23, 3, -24 }, // 0x26 '&' + { 331, 4, 9, 7, 6, -24 }, // 0x27 ''' + { 336, 12, 33, 12, 4, -25 }, // 0x28 '(' + { 386, 12, 33, 12, -1, -24 }, // 0x29 ')' + { 436, 10, 10, 14, 6, -25 }, // 0x2A '*' + { 449, 18, 16, 20, 3, -15 }, // 0x2B '+' + { 485, 5, 8, 10, 2, -2 }, // 0x2C ',' + { 490, 9, 3, 12, 3, -10 }, // 0x2D '-' + { 494, 4, 4, 10, 3, -3 }, // 0x2E '.' + { 496, 15, 26, 10, 0, -25 }, // 0x2F '/' + { 545, 18, 25, 19, 3, -24 }, // 0x30 '0' + { 602, 10, 25, 19, 7, -24 }, // 0x31 '1' + { 634, 20, 25, 19, 2, -24 }, // 0x32 '2' + { 697, 19, 25, 19, 2, -24 }, // 0x33 '3' + { 757, 18, 25, 19, 2, -24 }, // 0x34 '4' + { 814, 20, 25, 19, 2, -24 }, // 0x35 '5' + { 877, 19, 25, 19, 3, -24 }, // 0x36 '6' + { 937, 18, 25, 19, 5, -24 }, // 0x37 '7' + { 994, 19, 25, 19, 3, -24 }, // 0x38 '8' + { 1054, 19, 25, 19, 2, -24 }, // 0x39 '9' + { 1114, 7, 19, 10, 4, -18 }, // 0x3A ':' + { 1131, 8, 24, 10, 3, -18 }, // 0x3B ';' + { 1155, 19, 17, 20, 3, -16 }, // 0x3C '<' + { 1196, 18, 9, 20, 3, -12 }, // 0x3D '=' + { 1217, 19, 17, 20, 2, -15 }, // 0x3E '>' + { 1258, 16, 26, 19, 6, -25 }, // 0x3F '?' + { 1310, 33, 31, 36, 3, -25 }, // 0x40 '@' + { 1438, 23, 26, 23, 0, -25 }, // 0x41 'A' + { 1513, 21, 26, 23, 3, -25 }, // 0x42 'B' + { 1582, 22, 26, 25, 4, -25 }, // 0x43 'C' + { 1654, 23, 26, 25, 3, -25 }, // 0x44 'D' + { 1729, 23, 26, 23, 3, -25 }, // 0x45 'E' + { 1804, 22, 26, 21, 3, -25 }, // 0x46 'F' + { 1876, 24, 26, 27, 4, -25 }, // 0x47 'G' + { 1954, 25, 26, 25, 3, -25 }, // 0x48 'H' + { 2036, 8, 26, 10, 4, -25 }, // 0x49 'I' + { 2062, 18, 26, 18, 2, -25 }, // 0x4A 'J' + { 2121, 25, 26, 23, 3, -25 }, // 0x4B 'K' + { 2203, 16, 26, 19, 3, -25 }, // 0x4C 'L' + { 2255, 29, 26, 30, 3, -25 }, // 0x4D 'M' + { 2350, 25, 26, 26, 3, -25 }, // 0x4E 'N' + { 2432, 24, 26, 27, 4, -25 }, // 0x4F 'O' + { 2510, 22, 26, 23, 3, -25 }, // 0x50 'P' + { 2582, 25, 28, 27, 4, -25 }, // 0x51 'Q' + { 2670, 23, 26, 25, 3, -25 }, // 0x52 'R' + { 2745, 22, 26, 23, 3, -25 }, // 0x53 'S' + { 2817, 20, 26, 21, 6, -25 }, // 0x54 'T' + { 2882, 24, 26, 25, 4, -25 }, // 0x55 'U' + { 2960, 21, 26, 23, 6, -25 }, // 0x56 'V' + { 3029, 32, 26, 33, 6, -25 }, // 0x57 'W' + { 3133, 27, 26, 23, 1, -25 }, // 0x58 'X' + { 3221, 23, 26, 24, 6, -25 }, // 0x59 'Y' + { 3296, 25, 26, 21, 1, -25 }, // 0x5A 'Z' + { 3378, 13, 33, 10, 1, -25 }, // 0x5B '[' + { 3432, 4, 26, 10, 5, -25 }, // 0x5C '\' + { 3445, 13, 33, 10, -1, -24 }, // 0x5D ']' + { 3499, 14, 14, 16, 3, -24 }, // 0x5E '^' + { 3524, 21, 2, 19, -2, 5 }, // 0x5F '_' + { 3530, 6, 5, 12, 6, -25 }, // 0x60 '`' + { 3534, 18, 19, 19, 2, -18 }, // 0x61 'a' + { 3577, 19, 26, 20, 2, -25 }, // 0x62 'b' + { 3639, 16, 19, 18, 3, -18 }, // 0x63 'c' + { 3677, 20, 26, 20, 3, -25 }, // 0x64 'd' + { 3742, 17, 19, 19, 3, -18 }, // 0x65 'e' + { 3783, 11, 26, 9, 2, -25 }, // 0x66 'f' + { 3819, 19, 27, 19, 2, -18 }, // 0x67 'g' + { 3884, 18, 26, 19, 2, -25 }, // 0x68 'h' + { 3943, 8, 26, 8, 2, -25 }, // 0x69 'i' + { 3969, 14, 34, 8, -2, -25 }, // 0x6A 'j' + { 4029, 19, 26, 18, 2, -25 }, // 0x6B 'k' + { 4091, 8, 26, 8, 2, -25 }, // 0x6C 'l' + { 4117, 27, 19, 29, 2, -18 }, // 0x6D 'm' + { 4182, 18, 19, 19, 2, -18 }, // 0x6E 'n' + { 4225, 17, 19, 19, 3, -18 }, // 0x6F 'o' + { 4266, 21, 26, 20, 0, -18 }, // 0x70 'p' + { 4335, 20, 27, 19, 2, -18 }, // 0x71 'q' + { 4403, 13, 19, 11, 2, -18 }, // 0x72 'r' + { 4434, 16, 19, 18, 2, -18 }, // 0x73 's' + { 4472, 10, 23, 9, 3, -22 }, // 0x74 't' + { 4501, 18, 19, 19, 3, -18 }, // 0x75 'u' + { 4544, 16, 19, 17, 4, -18 }, // 0x76 'v' + { 4582, 24, 19, 25, 4, -18 }, // 0x77 'w' + { 4639, 19, 19, 17, 1, -18 }, // 0x78 'x' + { 4685, 20, 27, 17, 0, -18 }, // 0x79 'y' + { 4753, 19, 19, 17, 1, -18 }, // 0x7A 'z' + { 4799, 12, 33, 12, 3, -25 }, // 0x7B '{' + { 4849, 9, 33, 9, 2, -25 }, // 0x7C '|' + { 4887, 12, 33, 12, 0, -24 }, // 0x7D '}' + { 4937, 16, 7, 20, 5, -15 } }; // 0x7E '~' + +const GFXfont FreeSansOblique18pt7b PROGMEM = { + (uint8_t *)FreeSansOblique18pt7bBitmaps, + (GFXglyph *)FreeSansOblique18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 5623 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansOblique24pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansOblique24pt7b.h new file mode 100644 index 0000000..4c8c8ab --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansOblique24pt7b.h @@ -0,0 +1,840 @@ +const uint8_t FreeSansOblique24pt7bBitmaps[] PROGMEM = { + 0x01, 0xE0, 0x3C, 0x0F, 0x81, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x3C, 0x07, + 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x03, + 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x38, 0x07, 0x00, 0xE0, 0x18, 0x03, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xF0, 0x1E, 0x07, 0x80, 0xF0, 0x1E, 0x00, 0x78, + 0x7B, 0xC3, 0xDE, 0x1F, 0xE1, 0xEF, 0x0F, 0x78, 0x7B, 0xC3, 0xDC, 0x1C, + 0xE0, 0xE7, 0x07, 0x30, 0x31, 0x81, 0x80, 0x00, 0x07, 0x81, 0xC0, 0x00, + 0x78, 0x3C, 0x00, 0x07, 0x03, 0xC0, 0x00, 0xF0, 0x38, 0x00, 0x0E, 0x07, + 0x80, 0x01, 0xE0, 0x70, 0x00, 0x1E, 0x0F, 0x00, 0x01, 0xC0, 0xF0, 0x00, + 0x3C, 0x0E, 0x00, 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, + 0xFE, 0x00, 0x70, 0x3C, 0x00, 0x0F, 0x03, 0x80, 0x00, 0xF0, 0x78, 0x00, + 0x0E, 0x07, 0x80, 0x01, 0xE0, 0x70, 0x00, 0x1C, 0x0F, 0x00, 0x03, 0xC0, + 0xE0, 0x00, 0x3C, 0x1E, 0x00, 0x03, 0x81, 0xE0, 0x0F, 0xFF, 0xFF, 0xE0, + 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0xE0, 0x0F, 0x03, 0x80, 0x00, 0xE0, + 0x78, 0x00, 0x1E, 0x07, 0x00, 0x01, 0xC0, 0xF0, 0x00, 0x1C, 0x0F, 0x00, + 0x03, 0xC0, 0xE0, 0x00, 0x38, 0x1E, 0x00, 0x07, 0x81, 0xC0, 0x00, 0x78, + 0x3C, 0x00, 0x07, 0x03, 0xC0, 0x00, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x30, + 0x00, 0x00, 0x7F, 0x80, 0x00, 0xFF, 0xF8, 0x00, 0x7F, 0xFF, 0x00, 0x7F, + 0xFF, 0xE0, 0x1F, 0x18, 0xF8, 0x0F, 0x8E, 0x1F, 0x07, 0xC3, 0x83, 0xC1, + 0xE0, 0xE0, 0xF0, 0x70, 0x38, 0x3C, 0x3C, 0x0C, 0x0F, 0x0F, 0x07, 0x00, + 0x03, 0xC1, 0xC0, 0x00, 0xF0, 0x70, 0x00, 0x3E, 0x1C, 0x00, 0x0F, 0xE6, + 0x00, 0x01, 0xFF, 0xC0, 0x00, 0x3F, 0xFE, 0x00, 0x03, 0xFF, 0xE0, 0x00, + 0x3F, 0xFC, 0x00, 0x03, 0xFF, 0x80, 0x01, 0xC7, 0xF0, 0x00, 0x70, 0x7C, + 0x00, 0x1C, 0x0F, 0x00, 0x06, 0x03, 0xCF, 0x03, 0x80, 0xF3, 0xC0, 0xE0, + 0x3C, 0xF0, 0x38, 0x0E, 0x3C, 0x0E, 0x07, 0x8F, 0x03, 0x01, 0xE3, 0xE1, + 0xC0, 0xF0, 0xF8, 0x70, 0x78, 0x1F, 0x9C, 0xFC, 0x03, 0xFF, 0xFE, 0x00, + 0x7F, 0xFF, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x38, 0x00, 0x00, 0x0E, 0x00, + 0x00, 0x03, 0x00, 0x00, 0x01, 0xC0, 0x00, 0x00, 0x70, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x07, 0x80, 0x1F, 0x00, 0x00, 0x70, 0x07, 0xFC, 0x00, 0x0E, + 0x00, 0xFF, 0xE0, 0x01, 0xC0, 0x1E, 0x1E, 0x00, 0x3C, 0x03, 0x80, 0xF0, + 0x03, 0x80, 0x70, 0x07, 0x00, 0x70, 0x07, 0x00, 0x70, 0x0E, 0x00, 0xE0, + 0x07, 0x01, 0xC0, 0x0E, 0x00, 0x70, 0x3C, 0x00, 0xE0, 0x0E, 0x03, 0x80, + 0x0E, 0x00, 0xE0, 0x70, 0x00, 0xF0, 0x1C, 0x0E, 0x00, 0x07, 0x87, 0xC1, + 0xE0, 0x00, 0x7F, 0xF8, 0x1C, 0x00, 0x03, 0xFE, 0x03, 0x80, 0x00, 0x0F, + 0x80, 0x70, 0x00, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x00, 0x01, 0xE0, 0x1F, + 0x00, 0x00, 0x1C, 0x07, 0xFC, 0x00, 0x03, 0x80, 0xFF, 0xE0, 0x00, 0x70, + 0x1E, 0x1E, 0x00, 0x0F, 0x03, 0x80, 0xF0, 0x00, 0xE0, 0x70, 0x07, 0x00, + 0x1C, 0x07, 0x00, 0x70, 0x03, 0x80, 0xE0, 0x07, 0x00, 0x70, 0x0E, 0x00, + 0x70, 0x0F, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x1C, 0x00, + 0xF0, 0x1C, 0x03, 0x80, 0x07, 0x87, 0xC0, 0x70, 0x00, 0x7F, 0xF8, 0x07, + 0x00, 0x03, 0xFE, 0x00, 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF8, 0x00, + 0x03, 0xFF, 0x00, 0x01, 0xFF, 0xE0, 0x00, 0xF8, 0x7C, 0x00, 0x78, 0x0F, + 0x00, 0x1E, 0x03, 0xC0, 0x0F, 0x00, 0xF0, 0x03, 0xC0, 0x3C, 0x00, 0xF0, + 0x1E, 0x00, 0x3C, 0x07, 0x80, 0x0F, 0x87, 0xC0, 0x01, 0xE3, 0xE0, 0x00, + 0x7F, 0xF0, 0x00, 0x0F, 0xF8, 0x00, 0x03, 0xF8, 0x00, 0x03, 0xFC, 0x00, + 0x03, 0xFF, 0x00, 0x01, 0xFB, 0xE0, 0x70, 0xF8, 0x7C, 0x1C, 0x7C, 0x1F, + 0x0E, 0x3C, 0x03, 0xE3, 0x9E, 0x00, 0x79, 0xE7, 0x80, 0x1F, 0xF3, 0xC0, + 0x03, 0xF8, 0xF0, 0x00, 0xFE, 0x3C, 0x00, 0x1F, 0x0F, 0x00, 0x07, 0xC3, + 0xE0, 0x03, 0xF8, 0xF8, 0x03, 0xFE, 0x3F, 0x83, 0xF7, 0xC7, 0xFF, 0xF8, + 0xF0, 0xFF, 0xFC, 0x3E, 0x1F, 0xFC, 0x07, 0x81, 0xFC, 0x00, 0x00, 0x7B, + 0xDF, 0xEF, 0x7B, 0xDC, 0xE7, 0x31, 0x80, 0x00, 0x0E, 0x00, 0x38, 0x00, + 0xE0, 0x03, 0x80, 0x07, 0x00, 0x1C, 0x00, 0x70, 0x01, 0xE0, 0x03, 0x80, + 0x0F, 0x00, 0x1C, 0x00, 0x78, 0x00, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x0E, + 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, + 0x1C, 0x00, 0x78, 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, + 0x00, 0x1C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, + 0x07, 0x00, 0x06, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x30, 0x00, + 0x70, 0x00, 0xE0, 0x00, 0xC0, 0x00, 0x00, 0x30, 0x00, 0x70, 0x00, 0xE0, + 0x00, 0xC0, 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x0E, 0x00, + 0x1C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, 0x07, + 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x70, 0x01, 0xE0, 0x03, 0x80, + 0x07, 0x00, 0x0E, 0x00, 0x3C, 0x00, 0x70, 0x00, 0xE0, 0x01, 0xC0, 0x07, + 0x00, 0x0E, 0x00, 0x3C, 0x00, 0x70, 0x01, 0xE0, 0x03, 0x80, 0x0F, 0x00, + 0x1C, 0x00, 0x78, 0x00, 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x1C, 0x00, 0x70, + 0x01, 0xC0, 0x07, 0x00, 0x00, 0x01, 0xC0, 0x07, 0x00, 0x38, 0x18, 0xE3, + 0x7B, 0xBF, 0xFF, 0xF3, 0xFF, 0x01, 0xE0, 0x1F, 0xC0, 0xF7, 0x07, 0x9E, + 0x1C, 0x38, 0x20, 0xC0, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x78, + 0x00, 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, + 0x00, 0x1C, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xE0, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, + 0x78, 0x00, 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, + 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, 0x00, 0x3E, 0x7C, 0xF9, 0xE7, + 0xC1, 0x83, 0x0C, 0x18, 0x63, 0xC6, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFE, 0x7D, 0xF7, 0xBE, 0xF8, 0x00, 0x00, 0x18, 0x00, 0x01, 0xC0, 0x00, + 0x1C, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x00, 0x70, 0x00, 0x07, 0x00, + 0x00, 0x30, 0x00, 0x03, 0x80, 0x00, 0x18, 0x00, 0x01, 0xC0, 0x00, 0x0C, + 0x00, 0x00, 0xE0, 0x00, 0x06, 0x00, 0x00, 0x70, 0x00, 0x03, 0x00, 0x00, + 0x38, 0x00, 0x01, 0x80, 0x00, 0x1C, 0x00, 0x00, 0xC0, 0x00, 0x0E, 0x00, + 0x00, 0x60, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x03, 0x80, 0x00, 0x38, + 0x00, 0x01, 0x80, 0x00, 0x1C, 0x00, 0x00, 0xC0, 0x00, 0x0E, 0x00, 0x00, + 0x60, 0x00, 0x07, 0x00, 0x00, 0x30, 0x00, 0x03, 0x80, 0x00, 0x18, 0x00, + 0x00, 0x00, 0x0F, 0xC0, 0x00, 0xFF, 0xE0, 0x03, 0xFF, 0xE0, 0x0F, 0xFF, + 0xE0, 0x3F, 0x0F, 0xC0, 0xF8, 0x07, 0x81, 0xE0, 0x0F, 0x87, 0x80, 0x0F, + 0x1F, 0x00, 0x1E, 0x3C, 0x00, 0x3C, 0x78, 0x00, 0x79, 0xE0, 0x00, 0xF3, + 0xC0, 0x01, 0xE7, 0x80, 0x07, 0xDE, 0x00, 0x0F, 0xBC, 0x00, 0x1E, 0x78, + 0x00, 0x3C, 0xF0, 0x00, 0x79, 0xE0, 0x00, 0xF7, 0x80, 0x03, 0xEF, 0x00, + 0x07, 0xDE, 0x00, 0x0F, 0x3C, 0x00, 0x1E, 0x78, 0x00, 0x7C, 0xF0, 0x00, + 0xF1, 0xE0, 0x03, 0xE3, 0xC0, 0x07, 0x87, 0xC0, 0x1F, 0x0F, 0x80, 0x7C, + 0x0F, 0xC3, 0xF0, 0x1F, 0xFF, 0xC0, 0x1F, 0xFF, 0x00, 0x1F, 0xFC, 0x00, + 0x0F, 0xC0, 0x00, 0x00, 0x18, 0x01, 0xC0, 0x1C, 0x01, 0xE0, 0x1F, 0x0F, + 0xFB, 0xFF, 0xDF, 0xFC, 0xFF, 0xE0, 0x0F, 0x00, 0x78, 0x07, 0xC0, 0x3C, + 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x07, 0xC0, 0x3C, 0x01, 0xE0, 0x0F, 0x00, + 0x78, 0x07, 0xC0, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x07, 0xC0, 0x3C, + 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x07, 0xC0, 0x3C, 0x00, 0x00, 0x03, 0xFC, + 0x00, 0x03, 0xFF, 0xE0, 0x00, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0xE0, 0x0F, + 0xC0, 0xFC, 0x03, 0xE0, 0x07, 0xC0, 0xF8, 0x00, 0xF8, 0x1F, 0x00, 0x0F, + 0x03, 0xC0, 0x01, 0xE0, 0xF8, 0x00, 0x3C, 0x1E, 0x00, 0x07, 0x80, 0x00, + 0x01, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x1F, + 0xC0, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0xFC, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0xFF, + 0xFF, 0xFC, 0x3F, 0xFF, 0xFF, 0x07, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFC, + 0x00, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xFE, 0x00, 0x3F, 0xFF, 0x80, 0x3F, + 0xFF, 0xE0, 0x1F, 0x81, 0xF8, 0x1F, 0x00, 0x7C, 0x1F, 0x00, 0x1E, 0x0F, + 0x00, 0x0F, 0x0F, 0x80, 0x07, 0x87, 0x80, 0x03, 0xC0, 0x00, 0x03, 0xC0, + 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x7F, 0xE0, + 0x00, 0x3F, 0xE0, 0x00, 0x1F, 0xF8, 0x00, 0x1F, 0xFE, 0x00, 0x00, 0x3F, + 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, + 0x79, 0xE0, 0x00, 0x3C, 0xF0, 0x00, 0x1E, 0x78, 0x00, 0x1E, 0x3C, 0x00, + 0x0F, 0x1E, 0x00, 0x0F, 0x0F, 0x80, 0x1F, 0x83, 0xF0, 0x3F, 0x81, 0xFF, + 0xFF, 0x80, 0x7F, 0xFF, 0x80, 0x1F, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x00, + 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7E, + 0x00, 0x00, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x03, 0xFC, 0x00, 0x07, 0xBC, + 0x00, 0x0F, 0xBC, 0x00, 0x1F, 0x7C, 0x00, 0x3E, 0x78, 0x00, 0x7C, 0x78, + 0x00, 0xF8, 0x78, 0x00, 0xF0, 0x78, 0x01, 0xE0, 0xF0, 0x03, 0xC0, 0xF0, + 0x07, 0x80, 0xF0, 0x0F, 0x00, 0xF0, 0x1E, 0x01, 0xF0, 0x3C, 0x01, 0xE0, + 0x78, 0x01, 0xE0, 0x7F, 0xFF, 0xFF, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, + 0xFF, 0xFF, 0xFE, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, + 0x00, 0x07, 0x80, 0x00, 0x07, 0x80, 0x00, 0x07, 0x80, 0x00, 0x07, 0x80, + 0x00, 0x0F, 0x80, 0x00, 0x7F, 0xFF, 0xC0, 0x1F, 0xFF, 0xF8, 0x03, 0xFF, + 0xFF, 0x00, 0x7F, 0xFF, 0xE0, 0x1E, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, + 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x78, 0x00, + 0x00, 0x1E, 0x00, 0x00, 0x03, 0xC7, 0xE0, 0x00, 0xF7, 0xFF, 0x80, 0x1F, + 0xFF, 0xF8, 0x03, 0xFF, 0xFF, 0x80, 0xFE, 0x03, 0xF0, 0x1F, 0x00, 0x3F, + 0x03, 0xC0, 0x03, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x07, 0x80, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x70, + 0x00, 0x00, 0x1E, 0x1E, 0x00, 0x03, 0xC3, 0xC0, 0x00, 0xF0, 0x7C, 0x00, + 0x3C, 0x0F, 0x80, 0x0F, 0x80, 0xFC, 0x07, 0xE0, 0x1F, 0xFF, 0xF8, 0x01, + 0xFF, 0xFE, 0x00, 0x1F, 0xFF, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x07, + 0xE0, 0x00, 0x3F, 0xF8, 0x00, 0x7F, 0xFC, 0x00, 0xFF, 0xFE, 0x01, 0xF8, + 0x3E, 0x03, 0xE0, 0x1F, 0x07, 0xC0, 0x1F, 0x0F, 0x80, 0x0F, 0x0F, 0x00, + 0x0F, 0x1F, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x3C, 0x1F, + 0x80, 0x3C, 0x7F, 0xE0, 0x3D, 0xFF, 0xF0, 0x7B, 0xFF, 0xF8, 0x7F, 0xC1, + 0xF8, 0x7F, 0x00, 0x7C, 0x7E, 0x00, 0x7C, 0xFC, 0x00, 0x3C, 0xF8, 0x00, + 0x3C, 0xF8, 0x00, 0x3C, 0xF0, 0x00, 0x3C, 0xF0, 0x00, 0x38, 0xF0, 0x00, + 0x78, 0xF0, 0x00, 0x78, 0xF0, 0x00, 0xF0, 0xF8, 0x01, 0xF0, 0x7C, 0x03, + 0xE0, 0x7E, 0x0F, 0xC0, 0x3F, 0xFF, 0xC0, 0x3F, 0xFF, 0x80, 0x0F, 0xFE, + 0x00, 0x03, 0xF8, 0x00, 0x1F, 0xFF, 0xFF, 0x87, 0xFF, 0xFF, 0xE1, 0xFF, + 0xFF, 0xF8, 0xFF, 0xFF, 0xFE, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0x80, + 0x00, 0x03, 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0x80, 0x00, 0x03, + 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xC0, 0x00, 0x01, 0xE0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0x80, + 0x00, 0x03, 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, + 0x00, 0x00, 0x0F, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x01, 0xF0, 0x00, 0x00, + 0x78, 0x00, 0x00, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xFE, 0x00, 0x1F, + 0xFF, 0x80, 0x1F, 0xFF, 0xE0, 0x1F, 0x81, 0xF8, 0x1F, 0x00, 0x7C, 0x0F, + 0x00, 0x1E, 0x0F, 0x00, 0x0F, 0x07, 0x80, 0x07, 0x83, 0xC0, 0x03, 0xC1, + 0xE0, 0x03, 0xC0, 0xF8, 0x03, 0xC0, 0x7E, 0x07, 0xC0, 0x1F, 0xFF, 0xC0, + 0x07, 0xFF, 0xC0, 0x03, 0xFF, 0xE0, 0x07, 0xFF, 0xF8, 0x07, 0xE0, 0x7E, + 0x07, 0xC0, 0x0F, 0x07, 0x80, 0x07, 0xC7, 0xC0, 0x01, 0xE3, 0xC0, 0x00, + 0xF3, 0xC0, 0x00, 0x79, 0xE0, 0x00, 0x3C, 0xF0, 0x00, 0x1C, 0x78, 0x00, + 0x1E, 0x3C, 0x00, 0x0F, 0x1F, 0x00, 0x0F, 0x0F, 0xC0, 0x0F, 0x83, 0xF0, + 0x3F, 0x81, 0xFF, 0xFF, 0x80, 0x7F, 0xFF, 0x80, 0x0F, 0xFF, 0x00, 0x01, + 0xFE, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x7F, 0xF0, 0x01, 0xFF, 0xFC, + 0x03, 0xFF, 0xFC, 0x07, 0xF0, 0x7E, 0x07, 0xC0, 0x3E, 0x0F, 0x80, 0x1F, + 0x0F, 0x00, 0x0F, 0x1E, 0x00, 0x0F, 0x1E, 0x00, 0x0F, 0x3C, 0x00, 0x0F, + 0x3C, 0x00, 0x0F, 0x3C, 0x00, 0x1F, 0x3C, 0x00, 0x1F, 0x3C, 0x00, 0x3F, + 0x3E, 0x00, 0x7E, 0x3E, 0x00, 0xFE, 0x1F, 0x83, 0xFE, 0x1F, 0xFF, 0xFE, + 0x0F, 0xFF, 0xBC, 0x07, 0xFE, 0x3C, 0x01, 0xF8, 0x7C, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x78, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF0, 0xF0, 0x01, 0xF0, + 0xF0, 0x03, 0xE0, 0xF8, 0x07, 0xC0, 0xFC, 0x1F, 0xC0, 0x7F, 0xFF, 0x80, + 0x3F, 0xFE, 0x00, 0x1F, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xC1, 0xF0, + 0x78, 0x3E, 0x0F, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7C, 0x1F, + 0x07, 0x83, 0xE0, 0xF8, 0x00, 0x03, 0xE0, 0x7C, 0x0F, 0x03, 0xE0, 0x7C, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xE0, 0x7C, 0x0F, + 0x81, 0xE0, 0x7C, 0x01, 0x80, 0x30, 0x0C, 0x01, 0x80, 0x60, 0x3C, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x70, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0xFE, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xFE, 0x00, 0x03, 0xFE, 0x00, + 0x07, 0xFC, 0x00, 0x07, 0xFC, 0x00, 0x0F, 0xF8, 0x00, 0x07, 0xF0, 0x00, + 0x03, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x1F, 0xF0, 0x00, + 0x01, 0xFF, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x0E, + 0x00, 0x00, 0x00, 0x80, 0x1F, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0xE3, 0xFF, + 0xFF, 0xF8, 0xFF, 0xFF, 0xFE, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xFF, 0x1F, 0xFF, 0xFF, + 0xC7, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xF8, 0x04, 0x00, 0x00, 0x01, 0xC0, + 0x00, 0x00, 0xFC, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x03, 0xFE, 0x00, 0x00, + 0x3F, 0xE0, 0x00, 0x03, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x00, 0x00, + 0x3F, 0x80, 0x00, 0x7F, 0xC0, 0x00, 0xFF, 0x80, 0x00, 0xFF, 0x80, 0x01, + 0xFF, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0x38, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0xFE, + 0x00, 0x3F, 0xF8, 0x0F, 0xFF, 0xC1, 0xFF, 0xFE, 0x1F, 0x03, 0xE3, 0xE0, + 0x1F, 0x7C, 0x00, 0xF7, 0x80, 0x0F, 0x78, 0x00, 0xFF, 0x00, 0x0F, 0xF0, + 0x01, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, + 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x1F, 0x00, + 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0x80, 0x00, 0x78, 0x00, 0x0F, 0x80, + 0x00, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x1E, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xE0, 0x00, 0x3E, + 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0x80, 0x00, 0x00, 0x00, 0xFF, 0xFF, + 0x80, 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFE, + 0x00, 0x00, 0x7F, 0xE0, 0x0F, 0xF8, 0x00, 0x0F, 0xF0, 0x00, 0x1F, 0xE0, + 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x0F, 0xC0, 0x00, 0x00, 0xFC, 0x00, + 0xFC, 0x00, 0x00, 0x01, 0xF0, 0x0F, 0xC0, 0x00, 0x00, 0x0F, 0x80, 0xF8, + 0x00, 0xFC, 0x00, 0x3E, 0x0F, 0x80, 0x1F, 0xF9, 0xE1, 0xF0, 0x78, 0x03, + 0xFF, 0xCF, 0x07, 0x87, 0xC0, 0x3F, 0x0F, 0xF0, 0x3C, 0x7C, 0x03, 0xE0, + 0x3F, 0x01, 0xE3, 0xC0, 0x3E, 0x01, 0xF8, 0x0F, 0x3E, 0x03, 0xE0, 0x0F, + 0x80, 0x79, 0xE0, 0x1E, 0x00, 0x7C, 0x03, 0xDF, 0x01, 0xE0, 0x03, 0xC0, + 0x3E, 0xF0, 0x1F, 0x00, 0x3E, 0x01, 0xE7, 0x80, 0xF0, 0x01, 0xE0, 0x0F, + 0x38, 0x07, 0x80, 0x0F, 0x00, 0xFB, 0xC0, 0x78, 0x00, 0xF0, 0x07, 0x9E, + 0x03, 0xC0, 0x07, 0x80, 0x7C, 0xF0, 0x1E, 0x00, 0x78, 0x07, 0xC7, 0x80, + 0xF0, 0x07, 0xC0, 0x7E, 0x3C, 0x07, 0x80, 0x7C, 0x07, 0xE1, 0xE0, 0x3E, + 0x07, 0xE0, 0x7E, 0x0F, 0x00, 0xF8, 0x7F, 0x8F, 0xC0, 0x7C, 0x07, 0xFF, + 0x7F, 0xFC, 0x01, 0xE0, 0x1F, 0xF1, 0xFF, 0x80, 0x0F, 0x00, 0x7E, 0x0F, + 0xF0, 0x00, 0x7C, 0x00, 0x00, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x00, + 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x00, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFE, 0x00, 0xF8, 0x00, 0x00, + 0x0F, 0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x1F, 0xFF, 0xFF, 0x00, 0x00, 0x00, + 0x3F, 0xFF, 0xE0, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x1F, 0x80, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0x1F, 0xE0, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x03, 0xDF, 0x00, 0x00, 0x1E, + 0x7C, 0x00, 0x00, 0x79, 0xF0, 0x00, 0x03, 0xC7, 0xC0, 0x00, 0x0F, 0x1F, + 0x00, 0x00, 0x78, 0x3C, 0x00, 0x03, 0xE0, 0xF0, 0x00, 0x0F, 0x03, 0xE0, + 0x00, 0x78, 0x0F, 0x80, 0x01, 0xE0, 0x3E, 0x00, 0x0F, 0x00, 0xF8, 0x00, + 0x3C, 0x03, 0xE0, 0x01, 0xE0, 0x0F, 0x80, 0x0F, 0x80, 0x1E, 0x00, 0x3C, + 0x00, 0x7C, 0x01, 0xFF, 0xFF, 0xF0, 0x07, 0xFF, 0xFF, 0xC0, 0x3F, 0xFF, + 0xFF, 0x00, 0xFF, 0xFF, 0xFC, 0x07, 0xC0, 0x01, 0xF0, 0x3E, 0x00, 0x03, + 0xC0, 0xF8, 0x00, 0x0F, 0x87, 0xC0, 0x00, 0x3E, 0x1E, 0x00, 0x00, 0xF8, + 0xF8, 0x00, 0x03, 0xE3, 0xC0, 0x00, 0x0F, 0x9F, 0x00, 0x00, 0x3E, 0xF8, + 0x00, 0x00, 0x7B, 0xE0, 0x00, 0x01, 0xF0, 0x01, 0xFF, 0xFF, 0x00, 0x0F, + 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xFC, 0x03, 0xFF, 0xFF, 0xE0, 0x3E, 0x00, + 0x1F, 0x81, 0xE0, 0x00, 0x7C, 0x0F, 0x00, 0x01, 0xE0, 0x78, 0x00, 0x0F, + 0x03, 0xC0, 0x00, 0x78, 0x3C, 0x00, 0x03, 0xC1, 0xE0, 0x00, 0x3C, 0x0F, + 0x00, 0x01, 0xE0, 0x78, 0x00, 0x1E, 0x07, 0xC0, 0x03, 0xE0, 0x3F, 0xFF, + 0xFC, 0x01, 0xFF, 0xFF, 0xC0, 0x0F, 0xFF, 0xFF, 0x00, 0xFF, 0xFF, 0xFE, + 0x07, 0x80, 0x01, 0xF0, 0x3C, 0x00, 0x07, 0xC1, 0xE0, 0x00, 0x1E, 0x0F, + 0x00, 0x00, 0xF0, 0xF0, 0x00, 0x07, 0x87, 0x80, 0x00, 0x3C, 0x3C, 0x00, + 0x01, 0xE1, 0xE0, 0x00, 0x1E, 0x1F, 0x00, 0x00, 0xF0, 0xF0, 0x00, 0x0F, + 0x87, 0x80, 0x00, 0xF8, 0x3C, 0x00, 0x1F, 0x81, 0xFF, 0xFF, 0xF8, 0x1F, + 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0x00, 0x00, 0x00, + 0x01, 0xFE, 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x1F, + 0xFF, 0xFC, 0x00, 0xFE, 0x03, 0xF0, 0x07, 0xE0, 0x03, 0xE0, 0x3E, 0x00, + 0x07, 0x81, 0xF0, 0x00, 0x1E, 0x07, 0x80, 0x00, 0x3C, 0x3C, 0x00, 0x00, + 0xF1, 0xF0, 0x00, 0x03, 0xC7, 0x80, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x00, + 0xF0, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x0F, 0x00, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0x3C, 0xF0, 0x00, 0x01, 0xF3, 0xC0, 0x00, 0x07, + 0x8F, 0x80, 0x00, 0x3E, 0x3E, 0x00, 0x00, 0xF0, 0x7C, 0x00, 0x07, 0xC1, + 0xF0, 0x00, 0x3E, 0x03, 0xE0, 0x03, 0xF0, 0x0F, 0xE0, 0x3F, 0x80, 0x1F, + 0xFF, 0xFC, 0x00, 0x3F, 0xFF, 0xE0, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x3F, + 0xC0, 0x00, 0x01, 0xFF, 0xFF, 0x00, 0x03, 0xFF, 0xFF, 0x80, 0x07, 0xFF, + 0xFF, 0x80, 0x1F, 0xFF, 0xFF, 0x80, 0x3E, 0x00, 0x3F, 0x80, 0x78, 0x00, + 0x1F, 0x80, 0xF0, 0x00, 0x1F, 0x03, 0xE0, 0x00, 0x1E, 0x07, 0xC0, 0x00, + 0x3E, 0x0F, 0x00, 0x00, 0x3C, 0x1E, 0x00, 0x00, 0x78, 0x3C, 0x00, 0x00, + 0xF0, 0xF8, 0x00, 0x01, 0xE1, 0xF0, 0x00, 0x03, 0xC3, 0xC0, 0x00, 0x07, + 0x87, 0x80, 0x00, 0x0F, 0x0F, 0x00, 0x00, 0x3C, 0x3E, 0x00, 0x00, 0x78, + 0x7C, 0x00, 0x00, 0xF0, 0xF0, 0x00, 0x01, 0xE1, 0xE0, 0x00, 0x07, 0x87, + 0xC0, 0x00, 0x0F, 0x0F, 0x80, 0x00, 0x3E, 0x1E, 0x00, 0x00, 0x78, 0x3C, + 0x00, 0x01, 0xF0, 0x78, 0x00, 0x03, 0xC1, 0xF0, 0x00, 0x0F, 0x03, 0xE0, + 0x00, 0x3E, 0x07, 0x80, 0x01, 0xF8, 0x0F, 0x00, 0x0F, 0xE0, 0x1F, 0xFF, + 0xFF, 0x80, 0x7F, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0xF0, 0x01, 0xFF, 0xFF, + 0x00, 0x00, 0x01, 0xFF, 0xFF, 0xFE, 0x03, 0xFF, 0xFF, 0xFC, 0x07, 0xFF, + 0xFF, 0xF0, 0x1F, 0xFF, 0xFF, 0xE0, 0x3E, 0x00, 0x00, 0x00, 0x78, 0x00, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x07, 0xC0, 0x00, + 0x00, 0x0F, 0x00, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, + 0x07, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xE0, 0x3F, 0xFF, 0xFF, 0x80, + 0x7F, 0xFF, 0xFF, 0x00, 0xF0, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x07, + 0xC0, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x1F, 0xFF, + 0xFF, 0xE0, 0x7F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFF, 0x81, 0xFF, 0xFF, + 0xFE, 0x00, 0x01, 0xFF, 0xFF, 0xFC, 0x07, 0xFF, 0xFF, 0xF0, 0x1F, 0xFF, + 0xFF, 0xC0, 0xFF, 0xFF, 0xFE, 0x03, 0xE0, 0x00, 0x00, 0x0F, 0x00, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x0F, + 0x80, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x03, 0xFF, + 0xFF, 0xC0, 0x0F, 0xFF, 0xFF, 0x00, 0x7F, 0xFF, 0xFC, 0x01, 0xFF, 0xFF, + 0xF0, 0x07, 0x80, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, + 0x03, 0xE0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x00, + 0xF0, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x3E, 0x00, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x7F, 0xC0, 0x00, 0x01, 0xFF, 0xF8, 0x00, 0x07, 0xFF, 0xFF, 0x00, 0x07, + 0xFF, 0xFF, 0xC0, 0x07, 0xF0, 0x0F, 0xF0, 0x0F, 0xC0, 0x00, 0xF8, 0x0F, + 0xC0, 0x00, 0x3E, 0x07, 0x80, 0x00, 0x1F, 0x07, 0x80, 0x00, 0x07, 0x87, + 0xC0, 0x00, 0x03, 0xC3, 0xC0, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x03, + 0xE0, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x00, + 0xF0, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x00, 0x3C, 0x00, 0x1F, 0xFF, + 0xBC, 0x00, 0x0F, 0xFF, 0xDE, 0x00, 0x0F, 0xFF, 0xEF, 0x00, 0x07, 0xFF, + 0xF7, 0x80, 0x00, 0x00, 0x73, 0xC0, 0x00, 0x00, 0x39, 0xE0, 0x00, 0x00, + 0x3C, 0xF0, 0x00, 0x00, 0x1E, 0x78, 0x00, 0x00, 0x1F, 0x3E, 0x00, 0x00, + 0x0F, 0x8F, 0x00, 0x00, 0x0F, 0x87, 0xC0, 0x00, 0x0F, 0xC3, 0xF0, 0x00, + 0x0F, 0xE0, 0xFC, 0x00, 0x1F, 0xF0, 0x7F, 0x80, 0x7F, 0x78, 0x1F, 0xFF, + 0xFE, 0x38, 0x03, 0xFF, 0xFE, 0x1C, 0x00, 0xFF, 0xFC, 0x0E, 0x00, 0x0F, + 0xF0, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0xF0, 0x00, 0x03, 0xC0, + 0x78, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x01, 0xF0, 0x3E, 0x00, 0x00, 0xF0, + 0x1E, 0x00, 0x00, 0x78, 0x0F, 0x00, 0x00, 0x3C, 0x0F, 0x80, 0x00, 0x3E, + 0x07, 0xC0, 0x00, 0x1F, 0x03, 0xC0, 0x00, 0x0F, 0x01, 0xE0, 0x00, 0x07, + 0x80, 0xF0, 0x00, 0x03, 0xC0, 0xF8, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x01, + 0xF0, 0x3C, 0x00, 0x00, 0xF0, 0x1F, 0xFF, 0xFF, 0xF8, 0x0F, 0xFF, 0xFF, + 0xFC, 0x0F, 0xFF, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xFE, 0x03, 0xC0, 0x00, + 0x0F, 0x01, 0xE0, 0x00, 0x07, 0x81, 0xF0, 0x00, 0x07, 0xC0, 0xF8, 0x00, + 0x03, 0xE0, 0x78, 0x00, 0x01, 0xE0, 0x3C, 0x00, 0x00, 0xF0, 0x1E, 0x00, + 0x00, 0x78, 0x1F, 0x00, 0x00, 0x7C, 0x0F, 0x80, 0x00, 0x3C, 0x07, 0x80, + 0x00, 0x1E, 0x03, 0xC0, 0x00, 0x0F, 0x01, 0xE0, 0x00, 0x0F, 0x81, 0xF0, + 0x00, 0x07, 0xC0, 0xF0, 0x00, 0x03, 0xC0, 0x78, 0x00, 0x01, 0xE0, 0x00, + 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xE0, 0x3C, 0x07, 0x81, 0xF0, 0x3E, 0x07, + 0x80, 0xF0, 0x1E, 0x07, 0xC0, 0xF8, 0x1E, 0x03, 0xC0, 0x78, 0x1F, 0x03, + 0xE0, 0x78, 0x0F, 0x01, 0xE0, 0x7C, 0x0F, 0x81, 0xE0, 0x3C, 0x07, 0x81, + 0xF0, 0x3E, 0x07, 0x80, 0xF0, 0x1E, 0x07, 0xC0, 0xF8, 0x1E, 0x00, 0x00, + 0x00, 0x07, 0x80, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x01, 0xE0, + 0x00, 0x00, 0xF0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0x80, 0x00, 0x07, + 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, + 0x78, 0x00, 0x00, 0x78, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x0F, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0x80, 0x00, 0x03, 0xC0, 0xF0, + 0x01, 0xE0, 0x78, 0x00, 0xF0, 0x78, 0x00, 0xF8, 0x3C, 0x00, 0x78, 0x1E, + 0x00, 0x3C, 0x0F, 0x00, 0x3E, 0x07, 0xC0, 0x3E, 0x03, 0xF0, 0x7E, 0x00, + 0xFF, 0xFF, 0x00, 0x3F, 0xFF, 0x00, 0x0F, 0xFE, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x01, 0xE0, 0x00, 0x0F, 0xC0, 0x78, 0x00, 0x07, 0xC0, 0x1E, 0x00, + 0x03, 0xE0, 0x0F, 0x80, 0x03, 0xF0, 0x03, 0xE0, 0x01, 0xF8, 0x00, 0xF0, + 0x00, 0xFC, 0x00, 0x3C, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x3E, 0x00, 0x07, + 0xC0, 0x3F, 0x00, 0x01, 0xE0, 0x1F, 0x80, 0x00, 0x78, 0x0F, 0x80, 0x00, + 0x1E, 0x07, 0xC0, 0x00, 0x0F, 0x83, 0xE0, 0x00, 0x03, 0xE3, 0xF0, 0x00, + 0x00, 0xF1, 0xFC, 0x00, 0x00, 0x3C, 0xFF, 0x00, 0x00, 0x0F, 0x7F, 0xE0, + 0x00, 0x07, 0xFE, 0xF8, 0x00, 0x01, 0xFE, 0x1E, 0x00, 0x00, 0x7F, 0x07, + 0xC0, 0x00, 0x1F, 0x80, 0xF0, 0x00, 0x0F, 0xC0, 0x3E, 0x00, 0x03, 0xE0, + 0x07, 0x80, 0x00, 0xF0, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x7C, 0x00, 0x0F, + 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x78, 0x00, 0x1F, 0x00, 0x1E, 0x00, 0x03, 0xE0, 0x07, 0x80, 0x00, 0xF8, + 0x03, 0xE0, 0x00, 0x1F, 0x00, 0xF0, 0x00, 0x07, 0xC0, 0x3C, 0x00, 0x00, + 0xF8, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, 0xF8, + 0x00, 0x03, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, 0x01, 0xF0, 0x00, + 0x07, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x0F, + 0x80, 0x00, 0x3E, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, + 0x00, 0x7C, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, + 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x3C, 0x00, 0x00, 0xF0, + 0x00, 0x07, 0xC0, 0x00, 0x1F, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, + 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, 0xE0, + 0x01, 0xF8, 0x00, 0x00, 0x7E, 0x03, 0xF8, 0x00, 0x01, 0xFC, 0x0F, 0xF0, + 0x00, 0x03, 0xF8, 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x3F, 0xC0, 0x00, 0x1F, + 0xC0, 0x7F, 0x80, 0x00, 0x7F, 0x80, 0xFF, 0x00, 0x00, 0xEF, 0x03, 0xFE, + 0x00, 0x03, 0xFE, 0x07, 0xBC, 0x00, 0x0F, 0x78, 0x0F, 0x3C, 0x00, 0x1E, + 0xF0, 0x1E, 0x78, 0x00, 0x79, 0xE0, 0x3C, 0xF0, 0x00, 0xF3, 0xC0, 0xF9, + 0xE0, 0x03, 0xCF, 0x81, 0xE3, 0xC0, 0x07, 0x9E, 0x03, 0xC7, 0x80, 0x1E, + 0x3C, 0x07, 0x8F, 0x00, 0x38, 0x78, 0x1F, 0x1E, 0x00, 0xF0, 0xF0, 0x3C, + 0x1E, 0x03, 0xC3, 0xE0, 0x78, 0x3C, 0x07, 0x87, 0x80, 0xF0, 0x78, 0x1E, + 0x0F, 0x01, 0xE0, 0xF0, 0x3C, 0x1E, 0x07, 0xC1, 0xE0, 0xF0, 0x7C, 0x0F, + 0x03, 0xC1, 0xE0, 0xF0, 0x1E, 0x07, 0x87, 0x81, 0xE0, 0x3C, 0x0F, 0x0E, + 0x03, 0xC0, 0x78, 0x0F, 0x3C, 0x07, 0x81, 0xF0, 0x1E, 0x70, 0x1F, 0x03, + 0xC0, 0x3D, 0xE0, 0x3C, 0x07, 0x80, 0x7F, 0x80, 0x78, 0x0F, 0x00, 0xFF, + 0x00, 0xF0, 0x3E, 0x01, 0xFC, 0x01, 0xE0, 0x78, 0x03, 0xF8, 0x07, 0xC0, + 0xF0, 0x07, 0xE0, 0x0F, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x01, 0xF0, + 0x00, 0x03, 0xC0, 0x7E, 0x00, 0x01, 0xF0, 0x3F, 0x80, 0x00, 0x78, 0x0F, + 0xE0, 0x00, 0x1E, 0x03, 0xFC, 0x00, 0x07, 0x80, 0xFF, 0x00, 0x03, 0xE0, + 0x3F, 0xE0, 0x00, 0xF0, 0x1F, 0xF8, 0x00, 0x3C, 0x07, 0x9E, 0x00, 0x0F, + 0x01, 0xE7, 0xC0, 0x03, 0xC0, 0x78, 0xF0, 0x01, 0xF0, 0x1E, 0x3E, 0x00, + 0x78, 0x0F, 0x87, 0x80, 0x1E, 0x03, 0xC1, 0xF0, 0x07, 0x80, 0xF0, 0x7C, + 0x01, 0xE0, 0x3C, 0x0F, 0x00, 0xF8, 0x1F, 0x03, 0xE0, 0x3C, 0x07, 0x80, + 0x78, 0x0F, 0x01, 0xE0, 0x1F, 0x03, 0xC0, 0x78, 0x07, 0xC1, 0xF0, 0x1E, + 0x00, 0xF8, 0x78, 0x0F, 0x80, 0x3E, 0x1E, 0x03, 0xC0, 0x07, 0x87, 0x80, + 0xF0, 0x01, 0xF1, 0xE0, 0x3C, 0x00, 0x3C, 0xF8, 0x0F, 0x00, 0x0F, 0xBC, + 0x07, 0xC0, 0x03, 0xEF, 0x01, 0xE0, 0x00, 0x7F, 0xC0, 0x78, 0x00, 0x1F, + 0xF0, 0x1E, 0x00, 0x03, 0xFC, 0x0F, 0x80, 0x00, 0xFE, 0x03, 0xC0, 0x00, + 0x1F, 0x80, 0xF0, 0x00, 0x07, 0xE0, 0x3C, 0x00, 0x01, 0xF8, 0x00, 0x00, + 0x00, 0xFF, 0x00, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xFC, 0x00, + 0x0F, 0xFF, 0xFF, 0x80, 0x0F, 0xF0, 0x1F, 0xC0, 0x0F, 0xC0, 0x03, 0xF0, + 0x0F, 0x80, 0x00, 0xFC, 0x0F, 0x80, 0x00, 0x3E, 0x0F, 0x80, 0x00, 0x0F, + 0x07, 0x80, 0x00, 0x07, 0xC7, 0xC0, 0x00, 0x01, 0xE3, 0xC0, 0x00, 0x00, + 0xF3, 0xC0, 0x00, 0x00, 0x79, 0xE0, 0x00, 0x00, 0x3D, 0xE0, 0x00, 0x00, + 0x1E, 0xF0, 0x00, 0x00, 0x0F, 0x78, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, + 0x07, 0xFC, 0x00, 0x00, 0x03, 0xDE, 0x00, 0x00, 0x01, 0xEF, 0x00, 0x00, + 0x00, 0xF7, 0x80, 0x00, 0x00, 0xFB, 0xC0, 0x00, 0x00, 0x79, 0xE0, 0x00, + 0x00, 0x3C, 0xF0, 0x00, 0x00, 0x3E, 0x78, 0x00, 0x00, 0x1E, 0x3E, 0x00, + 0x00, 0x1F, 0x0F, 0x00, 0x00, 0x1F, 0x07, 0xC0, 0x00, 0x1F, 0x03, 0xF0, + 0x00, 0x1F, 0x00, 0xFC, 0x00, 0x3F, 0x80, 0x3F, 0x80, 0x7F, 0x80, 0x1F, + 0xFF, 0xFF, 0x00, 0x03, 0xFF, 0xFF, 0x00, 0x00, 0xFF, 0xFE, 0x00, 0x00, + 0x0F, 0xF8, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0x00, 0x0F, 0xFF, 0xFE, 0x00, + 0x7F, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0xE0, 0x3E, 0x00, 0x3F, 0x81, 0xE0, + 0x00, 0x7C, 0x0F, 0x00, 0x01, 0xE0, 0xF8, 0x00, 0x0F, 0x07, 0xC0, 0x00, + 0x78, 0x3C, 0x00, 0x03, 0xC1, 0xE0, 0x00, 0x1E, 0x0F, 0x00, 0x01, 0xE0, + 0xF8, 0x00, 0x0F, 0x07, 0xC0, 0x00, 0xF8, 0x3C, 0x00, 0x0F, 0x81, 0xE0, + 0x01, 0xF8, 0x0F, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xFC, 0x07, 0xFF, 0xFF, + 0x80, 0x3F, 0xFF, 0xF0, 0x01, 0xE0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x01, 0xE0, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x07, 0x80, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, + 0xF0, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0x00, + 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xFC, 0x00, 0x0F, 0xFF, 0xFF, + 0x80, 0x0F, 0xF0, 0x1F, 0xC0, 0x0F, 0xC0, 0x03, 0xF0, 0x0F, 0xC0, 0x00, + 0xFC, 0x0F, 0x80, 0x00, 0x3E, 0x0F, 0x80, 0x00, 0x0F, 0x07, 0x80, 0x00, + 0x07, 0xC7, 0xC0, 0x00, 0x01, 0xE3, 0xC0, 0x00, 0x00, 0xF3, 0xC0, 0x00, + 0x00, 0x79, 0xE0, 0x00, 0x00, 0x3D, 0xE0, 0x00, 0x00, 0x1E, 0xF0, 0x00, + 0x00, 0x0F, 0x78, 0x00, 0x00, 0x07, 0xB8, 0x00, 0x00, 0x03, 0xFC, 0x00, + 0x00, 0x03, 0xDE, 0x00, 0x00, 0x01, 0xEF, 0x00, 0x00, 0x00, 0xF7, 0x80, + 0x00, 0x00, 0x7B, 0xC0, 0x00, 0x00, 0x79, 0xE0, 0x00, 0x00, 0x3C, 0xF0, + 0x00, 0x00, 0x3C, 0x78, 0x00, 0x08, 0x3E, 0x3E, 0x00, 0x0E, 0x1E, 0x0F, + 0x00, 0x0F, 0x9F, 0x07, 0xC0, 0x07, 0xFF, 0x03, 0xF0, 0x01, 0xFF, 0x00, + 0xFC, 0x00, 0x7F, 0x00, 0x3F, 0x80, 0xFF, 0x80, 0x1F, 0xFF, 0xFF, 0xE0, + 0x03, 0xFF, 0xFF, 0xF8, 0x00, 0xFF, 0xFC, 0x7E, 0x00, 0x0F, 0xF0, 0x1F, + 0x00, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0xFF, + 0xC0, 0x07, 0xFF, 0xFF, 0xC0, 0x1F, 0xFF, 0xFF, 0x80, 0xFF, 0xFF, 0xFE, + 0x03, 0xE0, 0x00, 0xFC, 0x0F, 0x00, 0x01, 0xF0, 0x3C, 0x00, 0x03, 0xC1, + 0xF0, 0x00, 0x0F, 0x07, 0xC0, 0x00, 0x3C, 0x1E, 0x00, 0x00, 0xF0, 0x78, + 0x00, 0x03, 0xC1, 0xE0, 0x00, 0x1E, 0x0F, 0x80, 0x00, 0x78, 0x3E, 0x00, + 0x03, 0xE0, 0xF0, 0x00, 0x1F, 0x03, 0xC0, 0x01, 0xF8, 0x0F, 0xFF, 0xFF, + 0xC0, 0x7F, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, 0xF8, 0x07, 0xFF, 0xFF, 0xF0, + 0x1E, 0x00, 0x07, 0xE0, 0xF8, 0x00, 0x0F, 0x83, 0xE0, 0x00, 0x1E, 0x0F, + 0x00, 0x00, 0x78, 0x3C, 0x00, 0x01, 0xE0, 0xF0, 0x00, 0x07, 0x87, 0xC0, + 0x00, 0x1E, 0x1F, 0x00, 0x00, 0xF0, 0x78, 0x00, 0x03, 0xC1, 0xE0, 0x00, + 0x0F, 0x07, 0x80, 0x00, 0x3C, 0x3E, 0x00, 0x00, 0xF0, 0xF0, 0x00, 0x03, + 0xC3, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFF, 0xFC, + 0x00, 0x1F, 0xFF, 0xF8, 0x01, 0xFF, 0xFF, 0xC0, 0x1F, 0xC0, 0x7F, 0x01, + 0xF0, 0x00, 0xFC, 0x0F, 0x00, 0x03, 0xE0, 0xF0, 0x00, 0x0F, 0x07, 0x00, + 0x00, 0x78, 0x78, 0x00, 0x03, 0xC3, 0xC0, 0x00, 0x1E, 0x1E, 0x00, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, + 0xFF, 0xE0, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x0F, 0xFF, 0xF0, 0x00, 0x0F, + 0xFF, 0xC0, 0x00, 0x07, 0xFF, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x07, + 0xF0, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x3C, 0xF0, 0x00, 0x01, 0xE7, + 0x80, 0x00, 0x0F, 0x3C, 0x00, 0x00, 0x71, 0xE0, 0x00, 0x07, 0x8F, 0x00, + 0x00, 0x3C, 0x7C, 0x00, 0x03, 0xC1, 0xF0, 0x00, 0x7C, 0x0F, 0xE0, 0x1F, + 0xC0, 0x3F, 0xFF, 0xFC, 0x00, 0xFF, 0xFF, 0xC0, 0x03, 0xFF, 0xF8, 0x00, + 0x03, 0xFE, 0x00, 0x00, 0x7F, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0x7F, + 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFE, 0x00, 0x0F, 0x00, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x01, 0xE0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, 0x00, + 0x00, 0x78, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0x78, 0x00, 0x00, 0x0F, + 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0x0F, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x01, + 0xE0, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x3E, 0x00, + 0x00, 0x03, 0xC0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x0F, 0x00, 0x00, 0x3C, 0x1E, + 0x00, 0x00, 0xF8, 0x7C, 0x00, 0x01, 0xF0, 0xF8, 0x00, 0x03, 0xC1, 0xE0, + 0x00, 0x07, 0x83, 0xC0, 0x00, 0x0F, 0x0F, 0x80, 0x00, 0x3E, 0x1F, 0x00, + 0x00, 0x7C, 0x3C, 0x00, 0x00, 0xF0, 0x78, 0x00, 0x01, 0xE0, 0xF0, 0x00, + 0x03, 0xC3, 0xE0, 0x00, 0x0F, 0x87, 0xC0, 0x00, 0x1F, 0x0F, 0x00, 0x00, + 0x3C, 0x1E, 0x00, 0x00, 0x78, 0x3C, 0x00, 0x01, 0xF0, 0xF8, 0x00, 0x03, + 0xE1, 0xF0, 0x00, 0x07, 0x83, 0xC0, 0x00, 0x0F, 0x07, 0x80, 0x00, 0x1E, + 0x1F, 0x00, 0x00, 0x7C, 0x3E, 0x00, 0x00, 0xF8, 0x78, 0x00, 0x01, 0xE0, + 0xF0, 0x00, 0x03, 0xC1, 0xE0, 0x00, 0x0F, 0x83, 0xC0, 0x00, 0x1E, 0x07, + 0x80, 0x00, 0x7C, 0x0F, 0x80, 0x01, 0xF0, 0x0F, 0x80, 0x07, 0xE0, 0x1F, + 0xC0, 0x7F, 0x80, 0x1F, 0xFF, 0xFE, 0x00, 0x1F, 0xFF, 0xF0, 0x00, 0x1F, + 0xFF, 0xC0, 0x00, 0x07, 0xFC, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFF, 0xC0, + 0x00, 0x0F, 0xBE, 0x00, 0x00, 0x79, 0xF0, 0x00, 0x07, 0xC7, 0x80, 0x00, + 0x3C, 0x3C, 0x00, 0x03, 0xE1, 0xE0, 0x00, 0x1E, 0x0F, 0x80, 0x01, 0xF0, + 0x7C, 0x00, 0x0F, 0x03, 0xE0, 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0x80, 0x78, + 0x00, 0x78, 0x03, 0xC0, 0x07, 0xC0, 0x1E, 0x00, 0x3C, 0x00, 0xF0, 0x03, + 0xE0, 0x07, 0xC0, 0x1E, 0x00, 0x3E, 0x01, 0xF0, 0x01, 0xF0, 0x0F, 0x00, + 0x07, 0x80, 0xF0, 0x00, 0x3C, 0x07, 0x80, 0x01, 0xE0, 0x78, 0x00, 0x0F, + 0x07, 0xC0, 0x00, 0x7C, 0x3C, 0x00, 0x03, 0xE3, 0xE0, 0x00, 0x1F, 0x1E, + 0x00, 0x00, 0xF9, 0xF0, 0x00, 0x03, 0xCF, 0x00, 0x00, 0x1E, 0xF0, 0x00, + 0x00, 0xF7, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0xF0, + 0x00, 0x1F, 0x00, 0x03, 0xDE, 0x00, 0x07, 0xE0, 0x00, 0xFB, 0xC0, 0x00, + 0xFC, 0x00, 0x1E, 0x78, 0x00, 0x3F, 0x80, 0x07, 0xCF, 0x00, 0x07, 0xF0, + 0x00, 0xF9, 0xE0, 0x01, 0xFE, 0x00, 0x3E, 0x3C, 0x00, 0x7F, 0xC0, 0x07, + 0xC7, 0x80, 0x0F, 0x78, 0x01, 0xF0, 0xF0, 0x03, 0xEF, 0x00, 0x3E, 0x1E, + 0x00, 0x79, 0xE0, 0x0F, 0x83, 0xC0, 0x1F, 0x3C, 0x01, 0xF0, 0x78, 0x03, + 0xC7, 0x80, 0x3C, 0x0F, 0x00, 0xF8, 0xF0, 0x0F, 0x80, 0xE0, 0x1E, 0x1E, + 0x01, 0xE0, 0x1C, 0x07, 0xC1, 0xC0, 0x7C, 0x03, 0x80, 0xF0, 0x3C, 0x0F, + 0x00, 0x70, 0x3E, 0x07, 0x83, 0xE0, 0x0E, 0x07, 0x80, 0xF0, 0x78, 0x01, + 0xC1, 0xF0, 0x1E, 0x1F, 0x00, 0x3C, 0x3C, 0x03, 0xC3, 0xE0, 0x07, 0x8F, + 0x80, 0x78, 0x78, 0x00, 0xF1, 0xE0, 0x0F, 0x1F, 0x00, 0x1E, 0x7C, 0x01, + 0xE3, 0xC0, 0x03, 0xCF, 0x00, 0x3C, 0xF8, 0x00, 0x7B, 0xE0, 0x07, 0x9E, + 0x00, 0x0F, 0x78, 0x00, 0xF7, 0xC0, 0x01, 0xFF, 0x00, 0x1E, 0xF0, 0x00, + 0x3F, 0xC0, 0x03, 0xFE, 0x00, 0x07, 0xF8, 0x00, 0x7F, 0x80, 0x00, 0xFE, + 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0xFC, 0x00, 0x03, 0xF0, 0x00, + 0x1F, 0x80, 0x00, 0x7E, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x7C, + 0x00, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xF0, 0x07, 0xC0, 0x00, 0x3E, 0x00, + 0x7C, 0x00, 0x07, 0xC0, 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x1F, + 0x00, 0x01, 0xF0, 0x03, 0xE0, 0x00, 0x1F, 0x00, 0x7C, 0x00, 0x00, 0xF8, + 0x0F, 0x80, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0x00, 0x7C, 0x1F, 0x00, 0x00, + 0x07, 0xC3, 0xE0, 0x00, 0x00, 0x7C, 0x7C, 0x00, 0x00, 0x03, 0xEF, 0x80, + 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, + 0x03, 0xFC, 0x00, 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x00, 0x0F, 0xBE, 0x00, + 0x00, 0x01, 0xF3, 0xE0, 0x00, 0x00, 0x3E, 0x1F, 0x00, 0x00, 0x03, 0xE1, + 0xF0, 0x00, 0x00, 0x7C, 0x0F, 0x80, 0x00, 0x0F, 0x80, 0xF8, 0x00, 0x01, + 0xF0, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x03, 0xE0, + 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x03, 0xF0, 0x03, 0xF0, 0x00, + 0x1F, 0x00, 0x7E, 0x00, 0x01, 0xF8, 0x0F, 0xC0, 0x00, 0x0F, 0x80, 0xF8, + 0x00, 0x00, 0x7D, 0xF0, 0x00, 0x03, 0xE7, 0xC0, 0x00, 0x1F, 0x1F, 0x80, + 0x00, 0xF8, 0x3E, 0x00, 0x03, 0xE0, 0xF8, 0x00, 0x1F, 0x01, 0xF0, 0x00, + 0xF8, 0x07, 0xC0, 0x07, 0xC0, 0x0F, 0x00, 0x3E, 0x00, 0x3E, 0x01, 0xF0, + 0x00, 0xF8, 0x07, 0xC0, 0x01, 0xF0, 0x3E, 0x00, 0x07, 0xC1, 0xF0, 0x00, + 0x0F, 0x0F, 0x80, 0x00, 0x3E, 0x7C, 0x00, 0x00, 0x79, 0xE0, 0x00, 0x01, + 0xFF, 0x80, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x3F, + 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x0F, 0x80, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x03, 0xC0, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, + 0x07, 0x80, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x03, + 0xE0, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x00, 0x7F, 0xFF, 0xFF, 0xC0, + 0x1F, 0xFF, 0xFF, 0xE0, 0x07, 0xFF, 0xFF, 0xF8, 0x03, 0xFF, 0xFF, 0xFE, + 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x07, + 0xC0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, + 0x03, 0xE0, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x01, 0xF0, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x0F, 0x80, + 0x00, 0x00, 0x07, 0xFF, 0xFF, 0xFE, 0x01, 0xFF, 0xFF, 0xFF, 0x80, 0x7F, + 0xFF, 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0xF8, 0x00, 0x00, 0x7F, 0xC0, 0x1F, + 0xF0, 0x07, 0xFC, 0x01, 0xFE, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, + 0x03, 0xC0, 0x01, 0xF0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, + 0xE0, 0x00, 0xF8, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, + 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0xF8, 0x00, + 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x7C, 0x00, 0x1E, + 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x0F, 0x00, + 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x7C, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, + 0xE0, 0x00, 0x7F, 0xC0, 0x3F, 0xE0, 0x0F, 0xF8, 0x03, 0xFE, 0x00, 0xE3, + 0x8E, 0x38, 0xE1, 0x86, 0x18, 0x61, 0x87, 0x1C, 0x71, 0xC7, 0x0C, 0x30, + 0xC3, 0x0C, 0x38, 0xE3, 0x8E, 0x38, 0x61, 0x86, 0x18, 0x61, 0xC7, 0x1C, + 0x71, 0xC0, 0x00, 0x7F, 0xC0, 0x1F, 0xF0, 0x07, 0xFC, 0x03, 0xFE, 0x00, + 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x03, + 0xC0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, + 0x00, 0x78, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, + 0x3C, 0x00, 0x1F, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, + 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, 0x00, + 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x0F, 0x80, 0x03, + 0xC0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x7F, 0x80, 0x3F, 0xE0, + 0x0F, 0xF8, 0x03, 0xFE, 0x00, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x1F, 0x00, + 0x1F, 0xC0, 0x0E, 0xE0, 0x0E, 0x70, 0x0F, 0x38, 0x07, 0x1C, 0x07, 0x0E, + 0x03, 0x83, 0x83, 0x81, 0xC3, 0xC0, 0xE1, 0xC0, 0x71, 0xC0, 0x39, 0xE0, + 0x0E, 0xE0, 0x07, 0xF0, 0x03, 0xF0, 0x01, 0xC0, 0x7F, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xC0, 0xF8, 0x78, 0x3C, 0x1C, 0x0E, 0x0E, 0x07, 0x00, + 0x1F, 0xE0, 0x01, 0xFF, 0xF0, 0x07, 0xFF, 0xF0, 0x1F, 0xFF, 0xF0, 0x7E, + 0x07, 0xE1, 0xF0, 0x07, 0xC3, 0xC0, 0x07, 0x80, 0x00, 0x0F, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xF0, 0x00, 0x07, 0xE0, 0x0F, 0xFF, + 0xC0, 0xFF, 0xFF, 0x07, 0xFF, 0x9E, 0x1F, 0xC0, 0x3C, 0x7C, 0x00, 0x78, + 0xF0, 0x00, 0xF3, 0xC0, 0x03, 0xC7, 0x80, 0x07, 0x8F, 0x00, 0x1F, 0x1E, + 0x00, 0x7E, 0x3F, 0x07, 0xFC, 0x3F, 0xFF, 0x7E, 0x7F, 0xFC, 0xFC, 0x7F, + 0xF0, 0xF8, 0x3F, 0x00, 0xF0, 0x01, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x78, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x0F, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0x83, 0xE0, 0x03, 0xC7, 0xFC, + 0x01, 0xEF, 0xFF, 0x00, 0xFF, 0xFF, 0xC0, 0xF7, 0x83, 0xF0, 0x7F, 0x00, + 0xF8, 0x3F, 0x00, 0x3E, 0x1F, 0x00, 0x0F, 0x1F, 0x80, 0x07, 0x8F, 0x80, + 0x03, 0xC7, 0x80, 0x01, 0xE3, 0xC0, 0x00, 0xF1, 0xE0, 0x00, 0x79, 0xF0, + 0x00, 0x3C, 0xF0, 0x00, 0x3C, 0x78, 0x00, 0x1E, 0x3C, 0x00, 0x0F, 0x1E, + 0x00, 0x0F, 0x9F, 0x00, 0x07, 0x8F, 0xC0, 0x07, 0xC7, 0xE0, 0x07, 0xC3, + 0xF8, 0x07, 0xC1, 0xFE, 0x0F, 0xC1, 0xEF, 0xFF, 0xE0, 0xF3, 0xFF, 0xC0, + 0x78, 0xFF, 0xC0, 0x00, 0x1F, 0x80, 0x00, 0x00, 0x3F, 0x80, 0x03, 0xFF, + 0x80, 0x3F, 0xFF, 0x01, 0xFF, 0xFE, 0x0F, 0xE0, 0xF8, 0x7E, 0x01, 0xF1, + 0xF0, 0x03, 0xCF, 0x80, 0x0F, 0x3C, 0x00, 0x3D, 0xF0, 0x00, 0x07, 0x80, + 0x00, 0x1E, 0x00, 0x00, 0xF8, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x0F, 0x3C, + 0x00, 0x3C, 0xF8, 0x01, 0xE1, 0xF0, 0x0F, 0x87, 0xE0, 0xFC, 0x0F, 0xFF, + 0xE0, 0x3F, 0xFF, 0x00, 0x7F, 0xF8, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x00, + 0x03, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x01, 0xE0, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, + 0x3C, 0x00, 0x3F, 0x07, 0x80, 0x1F, 0xF8, 0xF0, 0x0F, 0xFF, 0x3E, 0x03, + 0xFF, 0xF7, 0x80, 0xFC, 0x1F, 0xF0, 0x3F, 0x00, 0xFE, 0x07, 0xC0, 0x0F, + 0xC1, 0xF0, 0x01, 0xF0, 0x3C, 0x00, 0x3E, 0x0F, 0x80, 0x07, 0xC1, 0xE0, + 0x00, 0x78, 0x3C, 0x00, 0x1F, 0x0F, 0x80, 0x03, 0xC1, 0xE0, 0x00, 0x78, + 0x3C, 0x00, 0x0F, 0x07, 0x80, 0x01, 0xE0, 0xF0, 0x00, 0x7C, 0x1E, 0x00, + 0x0F, 0x03, 0xC0, 0x03, 0xE0, 0x78, 0x00, 0x7C, 0x0F, 0x80, 0x1F, 0x80, + 0xF8, 0x07, 0xF0, 0x1F, 0x83, 0xFC, 0x03, 0xFF, 0xFF, 0x80, 0x3F, 0xFE, + 0xF0, 0x03, 0xFF, 0x1E, 0x00, 0x1F, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x80, + 0x01, 0xFF, 0xC0, 0x07, 0xFF, 0xE0, 0x3F, 0xFF, 0xC0, 0xFE, 0x0F, 0xC1, + 0xF0, 0x07, 0xC7, 0xC0, 0x0F, 0x8F, 0x00, 0x0F, 0x3C, 0x00, 0x1E, 0x78, + 0x00, 0x3D, 0xE0, 0x00, 0x7B, 0xFF, 0xFF, 0xF7, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xBF, 0xFF, 0xFF, 0x78, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, + 0x03, 0xC0, 0x00, 0x07, 0x80, 0x03, 0xCF, 0x80, 0x0F, 0x0F, 0x80, 0x3E, + 0x1F, 0x81, 0xF8, 0x1F, 0xFF, 0xE0, 0x1F, 0xFF, 0x80, 0x1F, 0xFC, 0x00, + 0x0F, 0xE0, 0x00, 0x00, 0x3E, 0x01, 0xFC, 0x07, 0xF8, 0x0F, 0xE0, 0x3E, + 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x07, 0xC0, 0x7F, 0xF0, 0xFF, 0xE3, + 0xFF, 0xC0, 0x78, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x3E, + 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x0F, 0x80, 0x1E, 0x00, + 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x03, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1E, + 0x00, 0x3C, 0x00, 0xF0, 0x01, 0xE0, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x07, + 0xFE, 0x3C, 0x01, 0xFF, 0xE7, 0x00, 0xFF, 0xFE, 0xE0, 0x1F, 0x83, 0xFC, + 0x07, 0xC0, 0x3F, 0x81, 0xF0, 0x03, 0xF0, 0x3C, 0x00, 0x7C, 0x0F, 0x00, + 0x0F, 0x81, 0xE0, 0x01, 0xF0, 0x78, 0x00, 0x3E, 0x0F, 0x00, 0x07, 0xC1, + 0xE0, 0x00, 0xF0, 0x38, 0x00, 0x1E, 0x0F, 0x00, 0x03, 0xC1, 0xE0, 0x00, + 0xF8, 0x3C, 0x00, 0x1F, 0x07, 0x80, 0x03, 0xC0, 0xF0, 0x00, 0xF8, 0x1E, + 0x00, 0x3F, 0x03, 0xE0, 0x07, 0xE0, 0x3E, 0x01, 0xF8, 0x07, 0xE0, 0xFF, + 0x00, 0x7F, 0xFD, 0xE0, 0x0F, 0xFF, 0x3C, 0x00, 0xFF, 0xCF, 0x00, 0x07, + 0xE1, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x0F, 0x01, 0xE0, 0x03, 0xE0, + 0x3C, 0x00, 0xF8, 0x07, 0xE0, 0x7F, 0x00, 0x7F, 0xFF, 0xC0, 0x0F, 0xFF, + 0xF0, 0x00, 0x7F, 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x01, 0xE0, 0x00, + 0x03, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x78, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x83, 0xF0, 0x0F, + 0x1F, 0xF0, 0x1E, 0xFF, 0xF0, 0x3F, 0xFF, 0xE0, 0xFF, 0x87, 0xE1, 0xFC, + 0x07, 0xC3, 0xF0, 0x07, 0x87, 0xC0, 0x0F, 0x1F, 0x00, 0x1E, 0x3E, 0x00, + 0x3C, 0x78, 0x00, 0x78, 0xF0, 0x01, 0xE1, 0xE0, 0x03, 0xC7, 0xC0, 0x07, + 0x8F, 0x00, 0x0F, 0x1E, 0x00, 0x1E, 0x3C, 0x00, 0x78, 0x78, 0x00, 0xF1, + 0xE0, 0x01, 0xE3, 0xC0, 0x03, 0xC7, 0x80, 0x0F, 0x8F, 0x00, 0x1E, 0x1E, + 0x00, 0x3C, 0x78, 0x00, 0x78, 0xF0, 0x00, 0xF1, 0xE0, 0x03, 0xC0, 0x01, + 0xE0, 0x3C, 0x0F, 0x01, 0xE0, 0x3C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xF0, 0x1E, 0x03, 0xC0, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x03, 0xC0, + 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, + 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0xF0, 0x1E, 0x00, 0x00, 0x07, + 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xC0, 0x01, 0xE0, 0x00, + 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x3C, + 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, + 0x07, 0x80, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, + 0xC0, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, + 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x01, 0xF0, 0x00, + 0x78, 0x00, 0x3E, 0x00, 0x7F, 0x80, 0x3F, 0xC0, 0x0F, 0xE0, 0x03, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x0F, + 0x00, 0x00, 0x07, 0x80, 0x00, 0x03, 0xC0, 0x0F, 0x81, 0xE0, 0x0F, 0x80, + 0xF0, 0x0F, 0x80, 0xF0, 0x1F, 0x00, 0x78, 0x1F, 0x00, 0x3C, 0x1F, 0x00, + 0x1E, 0x1F, 0x00, 0x1F, 0x1F, 0x00, 0x0F, 0x1E, 0x00, 0x07, 0xBF, 0x80, + 0x03, 0xFF, 0xC0, 0x01, 0xFD, 0xE0, 0x01, 0xFC, 0xF8, 0x00, 0xFC, 0x3C, + 0x00, 0x7C, 0x1F, 0x00, 0x3C, 0x07, 0x80, 0x1E, 0x03, 0xC0, 0x1F, 0x01, + 0xF0, 0x0F, 0x00, 0x78, 0x07, 0x80, 0x3E, 0x03, 0xC0, 0x0F, 0x01, 0xE0, + 0x07, 0x81, 0xE0, 0x03, 0xE0, 0xF0, 0x00, 0xF0, 0x78, 0x00, 0x7C, 0x00, + 0x01, 0xE0, 0x3C, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x3C, 0x07, + 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x03, + 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, + 0xF0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0xF0, 0x1E, 0x00, 0x00, + 0x07, 0xE0, 0x1F, 0x80, 0xF9, 0xFF, 0x07, 0xFC, 0x0F, 0x3F, 0xF8, 0xFF, + 0xE0, 0xF7, 0xFF, 0x9F, 0xFF, 0x0F, 0xF0, 0xFF, 0xC3, 0xF0, 0xFC, 0x07, + 0xF8, 0x1F, 0x1F, 0x80, 0x3F, 0x00, 0xF1, 0xF0, 0x03, 0xE0, 0x0F, 0x1E, + 0x00, 0x3C, 0x00, 0xF1, 0xE0, 0x03, 0xC0, 0x0F, 0x1E, 0x00, 0x3C, 0x00, + 0xF1, 0xE0, 0x07, 0x80, 0x0F, 0x3C, 0x00, 0x78, 0x01, 0xF3, 0xC0, 0x07, + 0x80, 0x1E, 0x3C, 0x00, 0x78, 0x01, 0xE3, 0xC0, 0x0F, 0x80, 0x1E, 0x3C, + 0x00, 0xF0, 0x01, 0xE7, 0xC0, 0x0F, 0x00, 0x3C, 0x78, 0x00, 0xF0, 0x03, + 0xC7, 0x80, 0x0F, 0x00, 0x3C, 0x78, 0x01, 0xE0, 0x03, 0xC7, 0x80, 0x1E, + 0x00, 0x3C, 0xF8, 0x01, 0xE0, 0x07, 0x8F, 0x00, 0x1E, 0x00, 0x78, 0xF0, + 0x01, 0xE0, 0x07, 0x8F, 0x00, 0x3C, 0x00, 0x78, 0x00, 0x07, 0xE0, 0x1F, + 0x3F, 0xF0, 0x3C, 0xFF, 0xF0, 0x7B, 0xFF, 0xE0, 0xFF, 0x07, 0xE1, 0xF8, + 0x07, 0xC7, 0xE0, 0x07, 0x8F, 0x80, 0x0F, 0x1F, 0x00, 0x1E, 0x3C, 0x00, + 0x3C, 0x78, 0x00, 0x78, 0xF0, 0x01, 0xE3, 0xC0, 0x03, 0xC7, 0x80, 0x07, + 0x8F, 0x00, 0x0F, 0x1E, 0x00, 0x3E, 0x3C, 0x00, 0x78, 0xF0, 0x00, 0xF1, + 0xE0, 0x01, 0xE3, 0xC0, 0x03, 0xC7, 0x80, 0x0F, 0x8F, 0x00, 0x1E, 0x3E, + 0x00, 0x3C, 0x78, 0x00, 0x78, 0xF0, 0x00, 0xF1, 0xE0, 0x03, 0xC0, 0x00, + 0x1F, 0x80, 0x01, 0xFF, 0xC0, 0x0F, 0xFF, 0xE0, 0x3F, 0xFF, 0xC0, 0xFE, + 0x0F, 0xC1, 0xF0, 0x0F, 0x87, 0xC0, 0x0F, 0x8F, 0x00, 0x0F, 0x3C, 0x00, + 0x1E, 0x78, 0x00, 0x3D, 0xE0, 0x00, 0x7B, 0xC0, 0x00, 0xF7, 0x80, 0x01, + 0xFE, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0x78, 0x00, 0x1E, 0xF0, 0x00, 0x3D, + 0xE0, 0x00, 0xF3, 0xC0, 0x01, 0xE7, 0x80, 0x07, 0x8F, 0x80, 0x1F, 0x0F, + 0x80, 0x7C, 0x1F, 0x83, 0xF8, 0x1F, 0xFF, 0xE0, 0x3F, 0xFF, 0x00, 0x1F, + 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x00, 0xFC, 0x00, 0x3C, 0x7F, 0xE0, + 0x07, 0xBF, 0xFE, 0x01, 0xFF, 0xFF, 0xC0, 0x3D, 0xE0, 0xFC, 0x07, 0xF0, + 0x0F, 0x80, 0xFC, 0x00, 0xF8, 0x1F, 0x00, 0x0F, 0x07, 0xC0, 0x01, 0xE0, + 0xF8, 0x00, 0x3C, 0x1F, 0x00, 0x07, 0x83, 0xC0, 0x00, 0xF0, 0x78, 0x00, + 0x1E, 0x1F, 0x00, 0x03, 0xC3, 0xC0, 0x00, 0xF0, 0x78, 0x00, 0x1E, 0x0F, + 0x00, 0x03, 0xC3, 0xE0, 0x00, 0xF8, 0x7C, 0x00, 0x1E, 0x0F, 0x80, 0x07, + 0xC1, 0xF8, 0x01, 0xF0, 0x3F, 0x80, 0x7C, 0x0F, 0xF8, 0x3F, 0x81, 0xEF, + 0xFF, 0xE0, 0x3C, 0xFF, 0xF8, 0x07, 0x8F, 0xFC, 0x00, 0xF0, 0xFE, 0x00, + 0x3E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0x03, 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x03, + 0xC0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x3F, + 0xF8, 0xF0, 0x1F, 0xFF, 0x3C, 0x0F, 0xFF, 0xDF, 0x07, 0xE0, 0xFF, 0x83, + 0xE0, 0x1F, 0xE1, 0xF0, 0x03, 0xF8, 0x78, 0x00, 0xFE, 0x3C, 0x00, 0x1F, + 0x8F, 0x00, 0x07, 0xC7, 0x80, 0x01, 0xF1, 0xE0, 0x00, 0x7C, 0x78, 0x00, + 0x1F, 0x3C, 0x00, 0x0F, 0x8F, 0x00, 0x03, 0xE3, 0xC0, 0x00, 0xF8, 0xF0, + 0x00, 0x3E, 0x3C, 0x00, 0x1F, 0x8F, 0x00, 0x0F, 0xC3, 0xC0, 0x03, 0xF0, + 0xF8, 0x01, 0xFC, 0x1F, 0x00, 0xFF, 0x07, 0xE0, 0xFF, 0xC0, 0xFF, 0xFD, + 0xE0, 0x1F, 0xFE, 0x78, 0x03, 0xFF, 0x3E, 0x00, 0x3F, 0x0F, 0x80, 0x00, + 0x03, 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x1F, 0x00, + 0x00, 0x07, 0xC0, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x0F, 0x80, 0x00, 0x07, 0x87, 0xCF, 0xC3, 0xCF, 0xE1, 0xEF, + 0xE0, 0xFF, 0x80, 0x7F, 0x00, 0x7E, 0x00, 0x3F, 0x00, 0x1F, 0x00, 0x0F, + 0x00, 0x07, 0x80, 0x03, 0xC0, 0x03, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, + 0x78, 0x00, 0x3C, 0x00, 0x3E, 0x00, 0x1E, 0x00, 0x0F, 0x00, 0x07, 0x80, + 0x03, 0xC0, 0x03, 0xE0, 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x00, + 0x00, 0x3F, 0x80, 0x07, 0xFF, 0x00, 0xFF, 0xFC, 0x0F, 0xFF, 0xE0, 0xFC, + 0x1F, 0x87, 0x80, 0x3C, 0x7C, 0x01, 0xE3, 0xC0, 0x0F, 0x1E, 0x00, 0x00, + 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0xE0, 0x03, 0xFF, + 0xC0, 0x07, 0xFF, 0x80, 0x07, 0xFE, 0x00, 0x03, 0xF0, 0x00, 0x07, 0xBC, + 0x00, 0x3D, 0xE0, 0x01, 0xEF, 0x00, 0x1F, 0x7C, 0x01, 0xF3, 0xF0, 0x1F, + 0x8F, 0xFF, 0xF8, 0x7F, 0xFF, 0x80, 0xFF, 0xF0, 0x01, 0xFE, 0x00, 0x03, + 0xC0, 0x1E, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC1, 0xFF, 0xEF, 0xFF, + 0x7F, 0xF0, 0x78, 0x03, 0xC0, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, + 0xC0, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x3C, 0x01, 0xE0, + 0x0F, 0x00, 0x78, 0x07, 0xC0, 0x3C, 0x01, 0xE0, 0x0F, 0xF0, 0x7F, 0x81, + 0xF8, 0x07, 0xC0, 0x0F, 0x00, 0x0F, 0x0F, 0x00, 0x1E, 0x0F, 0x00, 0x1E, + 0x1F, 0x00, 0x1E, 0x1E, 0x00, 0x1E, 0x1E, 0x00, 0x1E, 0x1E, 0x00, 0x3C, + 0x1E, 0x00, 0x3C, 0x3E, 0x00, 0x3C, 0x3C, 0x00, 0x3C, 0x3C, 0x00, 0x3C, + 0x3C, 0x00, 0x7C, 0x3C, 0x00, 0x78, 0x78, 0x00, 0x78, 0x78, 0x00, 0x78, + 0x78, 0x00, 0x78, 0x78, 0x00, 0xF8, 0x78, 0x00, 0xF0, 0xF0, 0x01, 0xF0, + 0xF0, 0x03, 0xF0, 0xF0, 0x07, 0xF0, 0xF8, 0x1F, 0xF0, 0xFF, 0xFF, 0xE0, + 0x7F, 0xFD, 0xE0, 0x3F, 0xF1, 0xE0, 0x1F, 0xC0, 0x00, 0xF0, 0x00, 0x7F, + 0xC0, 0x01, 0xEF, 0x00, 0x0F, 0xBC, 0x00, 0x3C, 0x78, 0x01, 0xE1, 0xE0, + 0x07, 0x87, 0x80, 0x3C, 0x1E, 0x01, 0xF0, 0x78, 0x07, 0x81, 0xE0, 0x3E, + 0x07, 0x80, 0xF0, 0x1E, 0x07, 0x80, 0x38, 0x1E, 0x00, 0xF0, 0xF0, 0x03, + 0xC7, 0xC0, 0x0F, 0x1E, 0x00, 0x3C, 0xF0, 0x00, 0xF3, 0xC0, 0x03, 0xDE, + 0x00, 0x07, 0x78, 0x00, 0x1F, 0xC0, 0x00, 0x7E, 0x00, 0x01, 0xF8, 0x00, + 0x07, 0xC0, 0x00, 0x1F, 0x00, 0x00, 0xF0, 0x07, 0xC0, 0x0F, 0x78, 0x03, + 0xE0, 0x0F, 0xBC, 0x03, 0xF0, 0x07, 0x9E, 0x01, 0xF8, 0x03, 0xCF, 0x00, + 0xFC, 0x03, 0xC7, 0x80, 0xFE, 0x01, 0xE3, 0xC0, 0x77, 0x01, 0xE0, 0xE0, + 0x7B, 0x80, 0xF0, 0x70, 0x39, 0xC0, 0xF0, 0x38, 0x3C, 0xE0, 0x78, 0x1C, + 0x1E, 0x78, 0x78, 0x0F, 0x1E, 0x3C, 0x3C, 0x07, 0x8F, 0x1E, 0x3C, 0x03, + 0xC7, 0x0F, 0x1E, 0x01, 0xE7, 0x87, 0x9E, 0x00, 0xF3, 0x81, 0xCF, 0x00, + 0x7B, 0xC0, 0xEF, 0x00, 0x3D, 0xC0, 0x77, 0x80, 0x1F, 0xE0, 0x3F, 0x80, + 0x0F, 0xF0, 0x1F, 0xC0, 0x07, 0xF0, 0x0F, 0xC0, 0x01, 0xF8, 0x07, 0xE0, + 0x00, 0xF8, 0x03, 0xE0, 0x00, 0x7C, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0xF0, + 0x00, 0x00, 0x03, 0xC0, 0x07, 0xC0, 0xF8, 0x01, 0xE0, 0x1E, 0x00, 0xF0, + 0x07, 0x80, 0x78, 0x00, 0xF0, 0x3C, 0x00, 0x3C, 0x1F, 0x00, 0x0F, 0x8F, + 0x80, 0x01, 0xE7, 0xC0, 0x00, 0x7D, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x03, + 0xF8, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, 0xC0, 0x00, + 0x07, 0xF0, 0x00, 0x03, 0xFE, 0x00, 0x01, 0xF7, 0x80, 0x00, 0xF9, 0xF0, + 0x00, 0x3C, 0x3C, 0x00, 0x1E, 0x0F, 0x80, 0x0F, 0x01, 0xE0, 0x07, 0x80, + 0x7C, 0x03, 0xE0, 0x0F, 0x01, 0xF0, 0x03, 0xE0, 0xF8, 0x00, 0x78, 0x00, + 0x03, 0xC0, 0x01, 0xE0, 0x78, 0x00, 0x78, 0x0F, 0x00, 0x0F, 0x01, 0xE0, + 0x03, 0xC0, 0x3C, 0x00, 0x78, 0x07, 0xC0, 0x1E, 0x00, 0x78, 0x07, 0xC0, + 0x0F, 0x00, 0xF0, 0x01, 0xE0, 0x3C, 0x00, 0x3C, 0x07, 0x80, 0x07, 0x81, + 0xE0, 0x00, 0xF0, 0x3C, 0x00, 0x1E, 0x0F, 0x00, 0x03, 0xC1, 0xC0, 0x00, + 0x3C, 0x78, 0x00, 0x07, 0x9E, 0x00, 0x00, 0xF3, 0xC0, 0x00, 0x1E, 0xF0, + 0x00, 0x03, 0xDE, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x0F, 0xE0, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x78, 0x00, + 0x00, 0x0F, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x1E, + 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x00, 0x01, + 0xFF, 0xFF, 0x81, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xE0, 0x7F, 0xFF, 0xE0, + 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, + 0x00, 0x01, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x01, 0xE0, + 0x00, 0x01, 0xE0, 0x00, 0x03, 0xE0, 0x00, 0x03, 0xE0, 0x00, 0x03, 0xE0, + 0x00, 0x03, 0xE0, 0x00, 0x03, 0xE0, 0x00, 0x03, 0xE0, 0x00, 0x03, 0xE0, + 0x00, 0x03, 0xC0, 0x00, 0x03, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, 0xE0, 0xFF, + 0xFF, 0xF0, 0x7F, 0xFF, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x7E, 0x00, 0xFE, + 0x00, 0xF0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x07, 0xC0, 0x07, 0x80, 0x07, 0x80, 0x07, 0x80, + 0x07, 0x80, 0x0F, 0x00, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0xF8, 0x00, + 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, + 0x38, 0x00, 0x38, 0x00, 0x3C, 0x00, 0x7C, 0x00, 0x78, 0x00, 0x78, 0x00, + 0x78, 0x00, 0x78, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xE0, 0x00, + 0xE0, 0x00, 0xF0, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0x7C, 0x00, 0x00, 0x70, + 0x07, 0x00, 0x60, 0x06, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0C, 0x01, 0xC0, + 0x1C, 0x01, 0xC0, 0x1C, 0x01, 0x80, 0x38, 0x03, 0x80, 0x38, 0x03, 0x00, + 0x30, 0x07, 0x00, 0x70, 0x07, 0x00, 0x60, 0x0E, 0x00, 0xE0, 0x0E, 0x00, + 0xE0, 0x0C, 0x01, 0xC0, 0x1C, 0x01, 0xC0, 0x1C, 0x01, 0x80, 0x38, 0x03, + 0x80, 0x38, 0x03, 0x00, 0x70, 0x07, 0x00, 0x70, 0x07, 0x00, 0x60, 0x0E, + 0x00, 0xE0, 0x06, 0x00, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x3F, 0x00, 0x0F, + 0x00, 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x1E, + 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x3E, 0x00, 0x3C, 0x00, 0x1C, + 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1E, 0x00, 0x0F, + 0x00, 0x07, 0x00, 0x1F, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x00, 0xF0, + 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x03, 0xE0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x07, 0x80, 0x07, 0x80, 0x07, 0x80, + 0x0F, 0x00, 0x7F, 0x00, 0x7E, 0x00, 0xF8, 0x00, 0x0F, 0x00, 0x01, 0xFE, + 0x00, 0xCF, 0xFC, 0x0E, 0xE3, 0xF0, 0xE6, 0x07, 0xFF, 0x60, 0x0F, 0xF0, + 0x00, 0x1E, 0x00 }; + +const GFXglyph FreeSansOblique24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 13, 0, 1 }, // 0x20 ' ' + { 0, 11, 34, 13, 6, -33 }, // 0x21 '!' + { 47, 13, 12, 17, 8, -32 }, // 0x22 '"' + { 67, 28, 34, 26, 3, -32 }, // 0x23 '#' + { 186, 26, 42, 26, 3, -35 }, // 0x24 '$' + { 323, 36, 34, 42, 6, -32 }, // 0x25 '%' + { 476, 26, 34, 31, 4, -32 }, // 0x26 '&' + { 587, 5, 12, 9, 8, -32 }, // 0x27 ''' + { 595, 15, 44, 16, 5, -33 }, // 0x28 '(' + { 678, 15, 44, 16, 1, -33 }, // 0x29 ')' + { 761, 14, 13, 18, 8, -33 }, // 0x2A '*' + { 784, 23, 22, 27, 5, -20 }, // 0x2B '+' + { 848, 7, 12, 13, 3, -4 }, // 0x2C ',' + { 859, 12, 4, 16, 5, -14 }, // 0x2D '-' + { 865, 6, 5, 13, 4, -4 }, // 0x2E '.' + { 869, 21, 35, 13, -1, -33 }, // 0x2F '/' + { 961, 23, 34, 26, 5, -32 }, // 0x30 '0' + { 1059, 13, 33, 26, 10, -32 }, // 0x31 '1' + { 1113, 27, 33, 26, 2, -32 }, // 0x32 '2' + { 1225, 25, 34, 26, 3, -32 }, // 0x33 '3' + { 1332, 24, 33, 26, 3, -32 }, // 0x34 '4' + { 1431, 27, 34, 26, 3, -32 }, // 0x35 '5' + { 1546, 24, 34, 26, 4, -32 }, // 0x36 '6' + { 1648, 26, 33, 26, 6, -32 }, // 0x37 '7' + { 1756, 25, 34, 26, 3, -32 }, // 0x38 '8' + { 1863, 24, 34, 26, 4, -32 }, // 0x39 '9' + { 1965, 10, 25, 13, 5, -24 }, // 0x3A ':' + { 1997, 11, 32, 13, 4, -24 }, // 0x3B ';' + { 2041, 26, 23, 27, 4, -22 }, // 0x3C '<' + { 2116, 26, 12, 27, 3, -16 }, // 0x3D '=' + { 2155, 26, 23, 27, 2, -21 }, // 0x3E '>' + { 2230, 20, 35, 26, 9, -34 }, // 0x3F '?' + { 2318, 45, 42, 48, 4, -34 }, // 0x40 '@' + { 2555, 30, 34, 31, 1, -33 }, // 0x41 'A' + { 2683, 29, 34, 31, 4, -33 }, // 0x42 'B' + { 2807, 30, 36, 33, 5, -34 }, // 0x43 'C' + { 2942, 31, 34, 33, 4, -33 }, // 0x44 'D' + { 3074, 31, 34, 31, 4, -33 }, // 0x45 'E' + { 3206, 30, 34, 28, 4, -33 }, // 0x46 'F' + { 3334, 33, 36, 37, 5, -34 }, // 0x47 'G' + { 3483, 33, 34, 34, 4, -33 }, // 0x48 'H' + { 3624, 11, 34, 13, 5, -33 }, // 0x49 'I' + { 3671, 25, 35, 24, 2, -33 }, // 0x4A 'J' + { 3781, 34, 34, 31, 4, -33 }, // 0x4B 'K' + { 3926, 22, 34, 26, 4, -33 }, // 0x4C 'L' + { 4020, 39, 34, 40, 4, -33 }, // 0x4D 'M' + { 4186, 34, 34, 34, 4, -33 }, // 0x4E 'N' + { 4331, 33, 36, 36, 5, -34 }, // 0x4F 'O' + { 4480, 29, 34, 30, 4, -33 }, // 0x50 'P' + { 4604, 33, 38, 36, 5, -34 }, // 0x51 'Q' + { 4761, 30, 34, 33, 4, -33 }, // 0x52 'R' + { 4889, 29, 36, 31, 4, -34 }, // 0x53 'S' + { 5020, 28, 34, 29, 7, -33 }, // 0x54 'T' + { 5139, 31, 35, 34, 6, -33 }, // 0x55 'U' + { 5275, 29, 34, 30, 8, -33 }, // 0x56 'V' + { 5399, 43, 34, 44, 8, -33 }, // 0x57 'W' + { 5582, 36, 34, 31, 1, -33 }, // 0x58 'X' + { 5735, 30, 34, 32, 8, -33 }, // 0x59 'Y' + { 5863, 34, 34, 29, 1, -33 }, // 0x5A 'Z' + { 6008, 18, 44, 13, 1, -33 }, // 0x5B '[' + { 6107, 6, 35, 13, 7, -33 }, // 0x5C '\' + { 6134, 18, 44, 13, -1, -33 }, // 0x5D ']' + { 6233, 17, 18, 22, 6, -32 }, // 0x5E '^' + { 6272, 29, 2, 26, -3, 7 }, // 0x5F '_' + { 6280, 8, 7, 16, 8, -34 }, // 0x60 '`' + { 6287, 23, 27, 26, 3, -25 }, // 0x61 'a' + { 6365, 25, 35, 26, 3, -33 }, // 0x62 'b' + { 6475, 22, 27, 24, 4, -25 }, // 0x63 'c' + { 6550, 27, 35, 26, 4, -33 }, // 0x64 'd' + { 6669, 23, 27, 26, 4, -25 }, // 0x65 'e' + { 6747, 15, 34, 12, 3, -33 }, // 0x66 'f' + { 6811, 27, 36, 26, 2, -25 }, // 0x67 'g' + { 6933, 23, 34, 25, 3, -33 }, // 0x68 'h' + { 7031, 11, 34, 10, 3, -33 }, // 0x69 'i' + { 7078, 18, 44, 11, -2, -33 }, // 0x6A 'j' + { 7177, 25, 34, 24, 3, -33 }, // 0x6B 'k' + { 7284, 11, 34, 10, 3, -33 }, // 0x6C 'l' + { 7331, 36, 26, 38, 3, -25 }, // 0x6D 'm' + { 7448, 23, 26, 25, 3, -25 }, // 0x6E 'n' + { 7523, 23, 27, 26, 4, -25 }, // 0x6F 'o' + { 7601, 27, 36, 26, 1, -25 }, // 0x70 'p' + { 7723, 26, 36, 26, 3, -25 }, // 0x71 'q' + { 7840, 17, 26, 15, 3, -25 }, // 0x72 'r' + { 7896, 21, 27, 24, 3, -25 }, // 0x73 's' + { 7967, 13, 32, 12, 4, -30 }, // 0x74 't' + { 8019, 24, 26, 25, 4, -24 }, // 0x75 'u' + { 8097, 22, 25, 23, 6, -24 }, // 0x76 'v' + { 8166, 33, 25, 34, 6, -24 }, // 0x77 'w' + { 8270, 26, 25, 23, 1, -24 }, // 0x78 'x' + { 8352, 27, 35, 23, 0, -24 }, // 0x79 'y' + { 8471, 25, 25, 23, 1, -24 }, // 0x7A 'z' + { 8550, 16, 44, 16, 5, -33 }, // 0x7B '{' + { 8638, 12, 44, 12, 3, -33 }, // 0x7C '|' + { 8704, 16, 44, 16, -1, -33 }, // 0x7D '}' + { 8792, 21, 7, 27, 6, -19 } }; // 0x7E '~' + +const GFXfont FreeSansOblique24pt7b PROGMEM = { + (uint8_t *)FreeSansOblique24pt7bBitmaps, + (GFXglyph *)FreeSansOblique24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 9483 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansOblique9pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansOblique9pt7b.h new file mode 100644 index 0000000..18a6cbe --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSansOblique9pt7b.h @@ -0,0 +1,220 @@ +const uint8_t FreeSansOblique9pt7bBitmaps[] PROGMEM = { + 0x10, 0x84, 0x22, 0x10, 0x84, 0x42, 0x10, 0x08, 0x00, 0xDE, 0xE5, 0x20, + 0x06, 0x40, 0x88, 0x13, 0x06, 0x43, 0xFE, 0x32, 0x04, 0x40, 0x98, 0x32, + 0x1F, 0xF0, 0x98, 0x22, 0x04, 0xC0, 0x02, 0x01, 0xF8, 0x6B, 0x99, 0x33, + 0x40, 0x68, 0x0F, 0x00, 0xF8, 0x07, 0xC1, 0x1B, 0x23, 0x64, 0x4E, 0x98, + 0xFC, 0x04, 0x00, 0x80, 0x3C, 0x08, 0xCC, 0x23, 0x18, 0x86, 0x32, 0x0C, + 0x64, 0x19, 0x90, 0x1E, 0x40, 0x01, 0x1E, 0x02, 0x66, 0x09, 0x8C, 0x23, + 0x18, 0x86, 0x62, 0x07, 0x80, 0x0F, 0x06, 0x63, 0x18, 0xC6, 0x3F, 0x07, + 0x03, 0xC1, 0xB3, 0xC7, 0xB0, 0xCC, 0x33, 0x3E, 0x79, 0x80, 0xFA, 0x04, + 0x10, 0x60, 0x83, 0x04, 0x18, 0x30, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x10, + 0x30, 0x20, 0x08, 0x18, 0x10, 0x30, 0x60, 0xC1, 0x83, 0x06, 0x18, 0x30, + 0x41, 0x82, 0x0C, 0x10, 0x40, 0x19, 0x73, 0x16, 0x48, 0x04, 0x04, 0x02, + 0x1F, 0xF0, 0x80, 0x80, 0x40, 0x20, 0x6D, 0x28, 0xF0, 0xC0, 0x01, 0x02, + 0x04, 0x04, 0x08, 0x08, 0x10, 0x10, 0x20, 0x20, 0x40, 0x40, 0x80, 0x0F, + 0x19, 0xC8, 0x6C, 0x36, 0x1A, 0x0F, 0x05, 0x86, 0xC3, 0x61, 0xB1, 0x9C, + 0x87, 0x80, 0x08, 0xCD, 0xE3, 0x18, 0xC4, 0x23, 0x18, 0xC4, 0x00, 0x07, + 0x83, 0x1C, 0x41, 0x98, 0x30, 0x06, 0x01, 0x80, 0x60, 0x38, 0x1C, 0x06, + 0x01, 0x80, 0x20, 0x0F, 0xF8, 0x0F, 0x86, 0x73, 0x0C, 0x83, 0x00, 0xC0, + 0x60, 0xE0, 0x06, 0x01, 0xB0, 0x6C, 0x13, 0x8C, 0x7C, 0x00, 0x00, 0x80, + 0xC0, 0xE0, 0xA0, 0x90, 0x98, 0x8C, 0x86, 0xFF, 0x81, 0x01, 0x80, 0xC0, + 0x60, 0x0F, 0xC3, 0x00, 0x40, 0x08, 0x03, 0x00, 0x7F, 0x1C, 0x70, 0x06, + 0x00, 0xC0, 0x1B, 0x06, 0x71, 0x87, 0xE0, 0x0F, 0x86, 0x73, 0x0D, 0x80, + 0x60, 0x1F, 0xCF, 0x3B, 0x86, 0xC1, 0xB0, 0x6C, 0x33, 0x98, 0x3C, 0x00, + 0x7F, 0xC0, 0x20, 0x10, 0x0C, 0x06, 0x01, 0x00, 0x80, 0x60, 0x10, 0x0C, + 0x02, 0x01, 0x80, 0x40, 0x00, 0x0F, 0x86, 0x73, 0x0C, 0xC3, 0x30, 0xCC, + 0x61, 0xE1, 0x86, 0x41, 0xB0, 0x6C, 0x13, 0x8C, 0x3E, 0x00, 0x0F, 0x06, + 0x73, 0x0D, 0x83, 0x60, 0xD8, 0x77, 0x3C, 0xFE, 0x01, 0x80, 0x6C, 0x33, + 0x98, 0x7C, 0x00, 0x30, 0x00, 0x00, 0x00, 0xC0, 0x18, 0x00, 0x00, 0x00, + 0x0C, 0x62, 0x11, 0x00, 0x00, 0x01, 0xC3, 0x8F, 0x0C, 0x07, 0x00, 0xE0, + 0x1E, 0x01, 0x00, 0x7F, 0xC0, 0x00, 0x03, 0xFE, 0x40, 0x3C, 0x03, 0x80, + 0x70, 0x18, 0x78, 0xE1, 0xC0, 0x00, 0x00, 0x1F, 0x30, 0xD0, 0x78, 0x30, + 0x30, 0x30, 0x30, 0x30, 0x30, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0xFE, + 0x00, 0xC0, 0xE0, 0xC0, 0x18, 0x61, 0xD3, 0x31, 0x9C, 0xD8, 0xC2, 0x36, + 0x31, 0x8F, 0x18, 0x67, 0xC6, 0x11, 0xB1, 0x8C, 0xCC, 0x67, 0x63, 0x0E, + 0xF0, 0x60, 0x00, 0x1C, 0x00, 0x01, 0x81, 0x00, 0x1F, 0xC0, 0x01, 0xC0, + 0x1C, 0x03, 0xC0, 0x24, 0x06, 0x60, 0x46, 0x0C, 0x61, 0x86, 0x1F, 0xE3, + 0x06, 0x20, 0x26, 0x03, 0x40, 0x30, 0x1F, 0xE1, 0x87, 0x30, 0x33, 0x03, + 0x30, 0x23, 0x06, 0x3F, 0xC6, 0x06, 0x60, 0x66, 0x06, 0x60, 0x66, 0x0C, + 0x7F, 0x80, 0x07, 0xC1, 0x86, 0x30, 0x32, 0x03, 0x60, 0x04, 0x00, 0xC0, + 0x0C, 0x00, 0xC0, 0x6C, 0x06, 0xC0, 0xC6, 0x18, 0x3E, 0x00, 0x1F, 0xE0, + 0xC1, 0x84, 0x06, 0x60, 0x33, 0x01, 0x98, 0x0C, 0x80, 0x64, 0x02, 0x60, + 0x33, 0x01, 0x98, 0x18, 0x81, 0x87, 0xF0, 0x00, 0x1F, 0xF1, 0x80, 0x10, + 0x03, 0x00, 0x30, 0x03, 0x00, 0x3F, 0xE2, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x04, 0x00, 0x7F, 0xC0, 0x1F, 0xF1, 0x80, 0x10, 0x03, 0x00, 0x30, 0x03, + 0x00, 0x3F, 0xC2, 0x00, 0x60, 0x06, 0x00, 0x60, 0x04, 0x00, 0x40, 0x00, + 0x07, 0xE0, 0xE1, 0x8C, 0x06, 0xC0, 0x36, 0x00, 0x60, 0x03, 0x07, 0xF8, + 0x02, 0xC0, 0x36, 0x01, 0x98, 0x1C, 0xE1, 0xC1, 0xF2, 0x00, 0x18, 0x08, + 0xC0, 0xC4, 0x06, 0x60, 0x33, 0x01, 0x18, 0x18, 0xFF, 0xC4, 0x06, 0x60, + 0x23, 0x01, 0x18, 0x18, 0x80, 0xC4, 0x06, 0x00, 0x33, 0x32, 0x26, 0x66, + 0x44, 0xCC, 0xC0, 0x00, 0xC0, 0x60, 0x18, 0x06, 0x01, 0x80, 0x60, 0x30, + 0x0C, 0x03, 0x30, 0xCC, 0x63, 0x18, 0x7C, 0x00, 0x18, 0x18, 0x60, 0xC1, + 0x0E, 0x0C, 0x60, 0x33, 0x00, 0xD8, 0x03, 0xF0, 0x0C, 0xC0, 0x61, 0x81, + 0x86, 0x06, 0x0C, 0x10, 0x30, 0x40, 0x60, 0x18, 0x0C, 0x04, 0x06, 0x03, + 0x01, 0x80, 0xC0, 0x40, 0x60, 0x30, 0x18, 0x08, 0x07, 0xF8, 0x18, 0x06, + 0x18, 0x0E, 0x18, 0x0E, 0x34, 0x1E, 0x34, 0x36, 0x34, 0x34, 0x24, 0x64, + 0x24, 0x6C, 0x64, 0xCC, 0x64, 0x8C, 0x65, 0x88, 0x43, 0x08, 0x43, 0x18, + 0x18, 0x08, 0xE0, 0x47, 0x06, 0x6C, 0x33, 0x61, 0x99, 0x08, 0x8C, 0xC4, + 0x66, 0x61, 0xB3, 0x0D, 0x18, 0x38, 0x81, 0xC4, 0x06, 0x00, 0x07, 0xC0, + 0xC3, 0x8C, 0x0E, 0xC0, 0x36, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, + 0x36, 0x01, 0xB8, 0x18, 0xE1, 0x81, 0xF0, 0x00, 0x1F, 0xE1, 0x83, 0x10, + 0x33, 0x03, 0x30, 0x33, 0x06, 0x3F, 0xC2, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x04, 0x00, 0x40, 0x00, 0x07, 0xC0, 0xC3, 0x8C, 0x0E, 0xC0, 0x36, 0x01, + 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x36, 0x09, 0xB8, 0x78, 0xE3, 0x81, + 0xF6, 0x00, 0x10, 0x1F, 0xF0, 0xC0, 0xC4, 0x06, 0x60, 0x33, 0x01, 0x18, + 0x18, 0xFF, 0x04, 0x0C, 0x60, 0x63, 0x03, 0x18, 0x18, 0x80, 0xC4, 0x06, + 0x00, 0x07, 0xC1, 0x87, 0x30, 0x33, 0x03, 0x30, 0x03, 0xC0, 0x0F, 0xC0, + 0x1E, 0x00, 0x6C, 0x06, 0xC0, 0x46, 0x0C, 0x3F, 0x00, 0xFF, 0xC3, 0x00, + 0xC0, 0x20, 0x18, 0x06, 0x01, 0x80, 0x60, 0x10, 0x0C, 0x03, 0x00, 0xC0, + 0x20, 0x00, 0x30, 0x13, 0x03, 0x20, 0x36, 0x03, 0x60, 0x26, 0x06, 0x60, + 0x64, 0x06, 0xC0, 0x6C, 0x04, 0xC0, 0xCE, 0x18, 0x3E, 0x00, 0xC0, 0x78, + 0x0B, 0x03, 0x20, 0xC4, 0x18, 0xC6, 0x18, 0x83, 0x30, 0x64, 0x0D, 0x80, + 0xA0, 0x1C, 0x03, 0x00, 0xC1, 0x83, 0xC1, 0x83, 0xC3, 0x86, 0xC2, 0x86, + 0xC6, 0x84, 0xC4, 0x8C, 0xCC, 0xC8, 0xC8, 0xD8, 0xD8, 0xD0, 0xD0, 0xF0, + 0x70, 0xE0, 0x60, 0xE0, 0x60, 0xE0, 0x0C, 0x0C, 0x30, 0x60, 0x63, 0x01, + 0x98, 0x02, 0xC0, 0x0E, 0x00, 0x38, 0x01, 0xE0, 0x0C, 0x80, 0x33, 0x01, + 0x8C, 0x0C, 0x18, 0x60, 0x60, 0xC0, 0x66, 0x0C, 0x60, 0xC2, 0x18, 0x33, + 0x03, 0x60, 0x1C, 0x01, 0x80, 0x18, 0x01, 0x80, 0x18, 0x01, 0x00, 0x30, + 0x00, 0x1F, 0xF0, 0x07, 0x00, 0xE0, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, + 0xC0, 0x18, 0x03, 0x00, 0x60, 0x0C, 0x00, 0xFF, 0xC0, 0x0E, 0x10, 0x20, + 0x41, 0x02, 0x04, 0x08, 0x20, 0x40, 0x81, 0x04, 0x08, 0x10, 0x20, 0xE0, + 0xAA, 0xA9, 0x55, 0x40, 0x0E, 0x08, 0x10, 0x20, 0x41, 0x02, 0x04, 0x08, + 0x20, 0x40, 0x81, 0x04, 0x08, 0x10, 0xE0, 0x0C, 0x18, 0x51, 0xA2, 0x4C, + 0x50, 0x80, 0xFF, 0xE0, 0xC8, 0x80, 0x0F, 0x86, 0x33, 0x0C, 0x03, 0x03, + 0xDF, 0xEE, 0x0B, 0x02, 0xC1, 0x9F, 0xE0, 0x10, 0x04, 0x01, 0x00, 0xDC, + 0x39, 0x88, 0x32, 0x0D, 0x83, 0x40, 0xD0, 0x64, 0x1B, 0x8C, 0xBC, 0x00, + 0x1F, 0x18, 0xD8, 0x6C, 0x0C, 0x06, 0x03, 0x01, 0x86, 0x66, 0x3E, 0x00, + 0x00, 0x20, 0x08, 0x01, 0x0F, 0x23, 0x14, 0xC1, 0x18, 0x26, 0x04, 0xC0, + 0x98, 0x23, 0x04, 0x71, 0x87, 0xD0, 0x0F, 0x0C, 0x76, 0x0D, 0x83, 0xFF, + 0xF0, 0x0C, 0x03, 0x06, 0x63, 0x0F, 0x80, 0x1C, 0xC2, 0x1E, 0x20, 0x84, + 0x10, 0x41, 0x04, 0x20, 0x80, 0x0F, 0x46, 0x33, 0x0C, 0xC1, 0x60, 0xD8, + 0x26, 0x09, 0x86, 0x71, 0x8F, 0xE0, 0x10, 0x04, 0xC2, 0x1F, 0x00, 0x10, + 0x04, 0x01, 0x00, 0x9F, 0x39, 0x88, 0x22, 0x09, 0x02, 0x40, 0x90, 0x44, + 0x12, 0x04, 0x81, 0x00, 0x10, 0x02, 0x22, 0x64, 0x44, 0x48, 0x80, 0x04, + 0x00, 0x01, 0x08, 0x20, 0x82, 0x08, 0x41, 0x04, 0x10, 0x42, 0x08, 0xE0, + 0x10, 0x08, 0x04, 0x04, 0x32, 0x31, 0x20, 0xA0, 0xB8, 0x6C, 0x22, 0x11, + 0x90, 0xC8, 0x30, 0x11, 0x22, 0x22, 0x64, 0x44, 0x48, 0x80, 0x2F, 0x3C, + 0x63, 0x8C, 0x86, 0x19, 0x08, 0x44, 0x10, 0x88, 0x21, 0x10, 0x82, 0x21, + 0x04, 0x82, 0x11, 0x04, 0x20, 0x00, 0x0B, 0xF3, 0x18, 0x82, 0x20, 0x90, + 0x24, 0x09, 0x04, 0x41, 0x20, 0x48, 0x10, 0x0F, 0x0C, 0x76, 0x0D, 0x83, + 0xC0, 0xF0, 0x3C, 0x1B, 0x06, 0xE3, 0x0F, 0x00, 0x17, 0xC3, 0x1C, 0x41, + 0x98, 0x32, 0x06, 0x40, 0xC8, 0x33, 0x06, 0x71, 0x8B, 0xC1, 0x00, 0x20, + 0x08, 0x01, 0x00, 0x00, 0x1E, 0xCC, 0x66, 0x09, 0x82, 0xC0, 0xB0, 0x4C, + 0x13, 0x04, 0x63, 0x0F, 0xC0, 0x20, 0x08, 0x02, 0x00, 0x80, 0x2C, 0x60, + 0x81, 0x04, 0x08, 0x10, 0x20, 0x81, 0x00, 0x1E, 0x33, 0x63, 0x60, 0x70, + 0x1E, 0x03, 0xC3, 0xC6, 0x7C, 0x22, 0xF2, 0x44, 0x44, 0xCC, 0xCE, 0x21, + 0x20, 0x90, 0x48, 0x24, 0x12, 0x13, 0x09, 0x84, 0xE6, 0x3E, 0x00, 0xC1, + 0xE1, 0xB0, 0xC8, 0xC4, 0x43, 0x61, 0xA0, 0xF0, 0x70, 0x18, 0x00, 0xC7, + 0x1E, 0x38, 0xB3, 0xCD, 0x96, 0x4C, 0xB6, 0x6D, 0xB1, 0x4D, 0x0E, 0x78, + 0x63, 0x83, 0x1C, 0x00, 0x10, 0xC3, 0x10, 0x24, 0x07, 0x80, 0xE0, 0x1C, + 0x07, 0x81, 0x90, 0x23, 0x08, 0x20, 0x30, 0x46, 0x18, 0x42, 0x08, 0xC1, + 0x10, 0x24, 0x07, 0x80, 0xE0, 0x1C, 0x03, 0x00, 0x60, 0x08, 0x03, 0x01, + 0xC0, 0x00, 0x3F, 0x80, 0x80, 0x80, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, + 0x7F, 0x00, 0x18, 0x88, 0x42, 0x10, 0x88, 0xC3, 0x18, 0x88, 0x42, 0x18, + 0xE0, 0x11, 0x22, 0x22, 0x24, 0x44, 0x4C, 0x88, 0x88, 0x00, 0x38, 0xC2, + 0x10, 0x88, 0xC6, 0x18, 0x88, 0x42, 0x10, 0x88, 0xC0, 0x70, 0x4E, 0x41, + 0xC0 }; + +const GFXglyph FreeSansOblique9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 5, 13, 5, 2, -12 }, // 0x21 '!' + { 9, 5, 4, 6, 3, -12 }, // 0x22 '"' + { 12, 11, 13, 10, 1, -12 }, // 0x23 '#' + { 30, 11, 16, 10, 1, -13 }, // 0x24 '$' + { 52, 15, 13, 16, 2, -12 }, // 0x25 '%' + { 77, 10, 13, 12, 2, -12 }, // 0x26 '&' + { 94, 2, 4, 3, 3, -12 }, // 0x27 ''' + { 95, 7, 17, 6, 2, -12 }, // 0x28 '(' + { 110, 7, 17, 6, -1, -12 }, // 0x29 ')' + { 125, 6, 5, 7, 3, -12 }, // 0x2A '*' + { 129, 9, 8, 11, 2, -7 }, // 0x2B '+' + { 138, 3, 5, 5, 1, -1 }, // 0x2C ',' + { 140, 4, 1, 6, 2, -4 }, // 0x2D '-' + { 141, 2, 1, 5, 2, 0 }, // 0x2E '.' + { 142, 8, 13, 5, 0, -12 }, // 0x2F '/' + { 155, 9, 13, 10, 2, -12 }, // 0x30 '0' + { 170, 5, 13, 10, 4, -12 }, // 0x31 '1' + { 179, 11, 13, 10, 1, -12 }, // 0x32 '2' + { 197, 10, 13, 10, 1, -12 }, // 0x33 '3' + { 214, 9, 13, 10, 1, -12 }, // 0x34 '4' + { 229, 11, 13, 10, 1, -12 }, // 0x35 '5' + { 247, 10, 13, 10, 2, -12 }, // 0x36 '6' + { 264, 10, 13, 10, 2, -12 }, // 0x37 '7' + { 281, 10, 13, 10, 1, -12 }, // 0x38 '8' + { 298, 10, 13, 10, 1, -12 }, // 0x39 '9' + { 315, 4, 9, 5, 2, -8 }, // 0x3A ':' + { 320, 5, 12, 5, 1, -8 }, // 0x3B ';' + { 328, 9, 9, 11, 2, -8 }, // 0x3C '<' + { 339, 10, 4, 11, 1, -5 }, // 0x3D '=' + { 344, 9, 9, 11, 1, -7 }, // 0x3E '>' + { 355, 9, 13, 10, 3, -12 }, // 0x3F '?' + { 370, 18, 16, 18, 1, -12 }, // 0x40 '@' + { 406, 12, 13, 12, 0, -12 }, // 0x41 'A' + { 426, 12, 13, 12, 1, -12 }, // 0x42 'B' + { 446, 12, 13, 13, 2, -12 }, // 0x43 'C' + { 466, 13, 13, 13, 1, -12 }, // 0x44 'D' + { 488, 12, 13, 12, 1, -12 }, // 0x45 'E' + { 508, 12, 13, 11, 1, -12 }, // 0x46 'F' + { 528, 13, 13, 14, 2, -12 }, // 0x47 'G' + { 550, 13, 13, 13, 1, -12 }, // 0x48 'H' + { 572, 4, 13, 5, 2, -12 }, // 0x49 'I' + { 579, 10, 13, 9, 1, -12 }, // 0x4A 'J' + { 596, 14, 13, 12, 1, -12 }, // 0x4B 'K' + { 619, 9, 13, 10, 1, -12 }, // 0x4C 'L' + { 634, 16, 13, 15, 1, -12 }, // 0x4D 'M' + { 660, 13, 13, 13, 1, -12 }, // 0x4E 'N' + { 682, 13, 13, 14, 2, -12 }, // 0x4F 'O' + { 704, 12, 13, 12, 1, -12 }, // 0x50 'P' + { 724, 13, 14, 14, 2, -12 }, // 0x51 'Q' + { 747, 13, 13, 13, 1, -12 }, // 0x52 'R' + { 769, 12, 13, 12, 1, -12 }, // 0x53 'S' + { 789, 10, 13, 11, 3, -12 }, // 0x54 'T' + { 806, 12, 13, 13, 2, -12 }, // 0x55 'U' + { 826, 11, 13, 12, 3, -12 }, // 0x56 'V' + { 844, 16, 13, 17, 3, -12 }, // 0x57 'W' + { 870, 14, 13, 12, 0, -12 }, // 0x58 'X' + { 893, 12, 13, 12, 3, -12 }, // 0x59 'Y' + { 913, 12, 13, 11, 1, -12 }, // 0x5A 'Z' + { 933, 7, 17, 5, 0, -12 }, // 0x5B '[' + { 948, 2, 13, 5, 3, -12 }, // 0x5C '\' + { 952, 7, 17, 5, 0, -12 }, // 0x5D ']' + { 967, 7, 7, 8, 2, -12 }, // 0x5E '^' + { 974, 11, 1, 10, -1, 3 }, // 0x5F '_' + { 976, 3, 3, 6, 3, -12 }, // 0x60 '`' + { 978, 10, 10, 10, 1, -9 }, // 0x61 'a' + { 991, 10, 13, 10, 1, -12 }, // 0x62 'b' + { 1008, 9, 10, 9, 1, -9 }, // 0x63 'c' + { 1020, 11, 13, 10, 1, -12 }, // 0x64 'd' + { 1038, 10, 10, 10, 1, -9 }, // 0x65 'e' + { 1051, 6, 13, 5, 1, -12 }, // 0x66 'f' + { 1061, 10, 14, 10, 0, -9 }, // 0x67 'g' + { 1079, 10, 13, 10, 1, -12 }, // 0x68 'h' + { 1096, 4, 13, 4, 1, -12 }, // 0x69 'i' + { 1103, 6, 17, 4, -1, -12 }, // 0x6A 'j' + { 1116, 9, 13, 9, 1, -12 }, // 0x6B 'k' + { 1131, 4, 13, 4, 1, -12 }, // 0x6C 'l' + { 1138, 15, 10, 15, 1, -9 }, // 0x6D 'm' + { 1157, 10, 11, 10, 1, -10 }, // 0x6E 'n' + { 1171, 10, 10, 10, 1, -9 }, // 0x6F 'o' + { 1184, 11, 14, 10, 0, -9 }, // 0x70 'p' + { 1204, 10, 14, 10, 1, -9 }, // 0x71 'q' + { 1222, 7, 10, 6, 1, -9 }, // 0x72 'r' + { 1231, 8, 10, 9, 1, -9 }, // 0x73 's' + { 1241, 4, 12, 5, 2, -11 }, // 0x74 't' + { 1247, 9, 10, 10, 2, -9 }, // 0x75 'u' + { 1259, 9, 10, 9, 2, -9 }, // 0x76 'v' + { 1271, 13, 10, 13, 2, -9 }, // 0x77 'w' + { 1288, 11, 10, 9, 0, -9 }, // 0x78 'x' + { 1302, 11, 14, 9, 0, -9 }, // 0x79 'y' + { 1322, 9, 10, 9, 1, -9 }, // 0x7A 'z' + { 1334, 5, 17, 6, 2, -12 }, // 0x7B '{' + { 1345, 4, 17, 5, 1, -12 }, // 0x7C '|' + { 1354, 5, 17, 6, 0, -12 }, // 0x7D '}' + { 1365, 9, 3, 11, 2, -7 } }; // 0x7E '~' + +const GFXfont FreeSansOblique9pt7b PROGMEM = { + (uint8_t *)FreeSansOblique9pt7bBitmaps, + (GFXglyph *)FreeSansOblique9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 2041 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerif12pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerif12pt7b.h new file mode 100644 index 0000000..48ad3da --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerif12pt7b.h @@ -0,0 +1,259 @@ +const uint8_t FreeSerif12pt7bBitmaps[] PROGMEM = { + 0xFF, 0xFE, 0xA8, 0x3F, 0xCF, 0x3C, 0xF3, 0x8A, 0x20, 0x0C, 0x40, 0xC4, + 0x08, 0x40, 0x8C, 0x08, 0xC7, 0xFF, 0x18, 0x81, 0x88, 0x10, 0x81, 0x08, + 0xFF, 0xE1, 0x18, 0x31, 0x03, 0x10, 0x31, 0x02, 0x10, 0x04, 0x07, 0xC6, + 0x5B, 0x12, 0xC4, 0xB1, 0x0F, 0x41, 0xF0, 0x1E, 0x01, 0xE0, 0x58, 0x13, + 0x84, 0xE1, 0x3C, 0x4F, 0x96, 0x3F, 0x01, 0x00, 0x00, 0x04, 0x03, 0x83, + 0x03, 0x9F, 0x81, 0xC2, 0x20, 0x60, 0x90, 0x38, 0x24, 0x0C, 0x12, 0x03, + 0x0D, 0x00, 0xC6, 0x47, 0x9E, 0x23, 0x10, 0x09, 0x84, 0x04, 0xE1, 0x03, + 0x30, 0x40, 0x8C, 0x20, 0x43, 0x08, 0x10, 0xC4, 0x08, 0x1E, 0x00, 0x03, + 0xC0, 0x02, 0x30, 0x03, 0x08, 0x01, 0x84, 0x00, 0xC4, 0x00, 0x7C, 0xF8, + 0x1C, 0x38, 0x1E, 0x08, 0x33, 0x0C, 0x31, 0xC4, 0x10, 0x74, 0x18, 0x3A, + 0x0C, 0x0E, 0x07, 0x03, 0x83, 0xC3, 0xE2, 0x7E, 0x3E, 0xFF, 0xA0, 0x04, + 0x21, 0x08, 0x61, 0x0C, 0x30, 0xC3, 0x0C, 0x30, 0xC1, 0x04, 0x18, 0x20, + 0x40, 0x81, 0x81, 0x02, 0x04, 0x18, 0x20, 0x83, 0x0C, 0x30, 0xC3, 0x0C, + 0x30, 0x86, 0x10, 0x84, 0x20, 0x30, 0xB3, 0xD7, 0x54, 0x38, 0x7C, 0xD3, + 0x30, 0x30, 0x10, 0x04, 0x00, 0x80, 0x10, 0x02, 0x00, 0x41, 0xFF, 0xC1, + 0x00, 0x20, 0x04, 0x00, 0x80, 0x10, 0x00, 0xDF, 0x95, 0x00, 0xFC, 0xFC, + 0x06, 0x0C, 0x10, 0x60, 0xC1, 0x06, 0x0C, 0x10, 0x60, 0xC1, 0x06, 0x0C, + 0x10, 0x60, 0xC0, 0x1E, 0x0C, 0xC6, 0x19, 0x86, 0xC0, 0xB0, 0x3C, 0x0F, + 0x03, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0xC0, 0xD8, 0x66, 0x18, 0xCC, 0x1E, + 0x00, 0x11, 0xC3, 0x0C, 0x30, 0xC3, 0x0C, 0x30, 0xC3, 0x0C, 0x30, 0xC3, + 0x0C, 0xFC, 0x1E, 0x18, 0xC4, 0x1A, 0x06, 0x01, 0x80, 0x60, 0x10, 0x0C, + 0x02, 0x01, 0x00, 0xC0, 0x60, 0x30, 0x18, 0x1F, 0xF8, 0x1E, 0x18, 0xE8, + 0x18, 0x06, 0x01, 0x00, 0x80, 0xF0, 0x7E, 0x03, 0xC0, 0x70, 0x0C, 0x03, + 0x00, 0xC0, 0x6E, 0x11, 0xF8, 0x01, 0x00, 0xC0, 0x70, 0x2C, 0x0B, 0x04, + 0xC2, 0x30, 0x8C, 0x43, 0x20, 0xC8, 0x33, 0xFF, 0x03, 0x00, 0xC0, 0x30, + 0x0C, 0x00, 0x03, 0xF1, 0x00, 0x40, 0x18, 0x0F, 0x80, 0xF8, 0x0E, 0x01, + 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x20, 0x1B, 0x8C, 0x7C, 0x00, 0x01, + 0xC3, 0xC1, 0xC0, 0xC0, 0x70, 0x18, 0x0E, 0xF3, 0xCE, 0xC1, 0xF0, 0x3C, + 0x0F, 0x03, 0xC0, 0xD8, 0x36, 0x08, 0xC6, 0x1E, 0x00, 0x3F, 0xD0, 0x38, + 0x08, 0x06, 0x01, 0x80, 0x40, 0x10, 0x0C, 0x02, 0x00, 0x80, 0x20, 0x10, + 0x04, 0x01, 0x00, 0x80, 0x20, 0x1F, 0x18, 0x6C, 0x0F, 0x03, 0xC0, 0xF8, + 0x67, 0x30, 0xF0, 0x1E, 0x09, 0xE6, 0x3B, 0x07, 0xC0, 0xF0, 0x3C, 0x0D, + 0x86, 0x1F, 0x00, 0x1E, 0x08, 0xC6, 0x1B, 0x02, 0xC0, 0xF0, 0x3C, 0x0F, + 0x03, 0xE0, 0xDC, 0x73, 0xEC, 0x06, 0x01, 0x80, 0xC0, 0x70, 0x38, 0x38, + 0x18, 0x00, 0xFC, 0x00, 0x3F, 0xCC, 0xC0, 0x00, 0x00, 0x06, 0x77, 0x12, + 0x40, 0x00, 0x00, 0x07, 0x01, 0xE0, 0x78, 0x1E, 0x07, 0x00, 0xC0, 0x0F, + 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x07, 0x00, 0x10, 0xFF, 0xF0, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0x80, 0x0E, 0x00, 0x3C, 0x00, 0xF0, + 0x03, 0xC0, 0x0F, 0x00, 0x30, 0x0E, 0x07, 0x81, 0xE0, 0x78, 0x0E, 0x00, + 0x00, 0x00, 0x7C, 0x86, 0x83, 0xC3, 0x03, 0x03, 0x06, 0x0C, 0x08, 0x08, + 0x10, 0x10, 0x00, 0x00, 0x30, 0x30, 0x30, 0x03, 0xF0, 0x06, 0x06, 0x06, + 0x00, 0x86, 0x00, 0x26, 0x0E, 0xD3, 0x0C, 0xC7, 0x0C, 0x63, 0x84, 0x31, + 0xC6, 0x18, 0xE3, 0x08, 0x71, 0x8C, 0x4C, 0xC6, 0x46, 0x3D, 0xC1, 0x80, + 0x00, 0x30, 0x10, 0x07, 0xF0, 0x00, 0x80, 0x00, 0x60, 0x00, 0x70, 0x00, + 0x38, 0x00, 0x2E, 0x00, 0x13, 0x00, 0x19, 0xC0, 0x08, 0x60, 0x04, 0x38, + 0x04, 0x0C, 0x03, 0xFF, 0x03, 0x03, 0x81, 0x00, 0xE1, 0x80, 0x70, 0xC0, + 0x3D, 0xF0, 0x3F, 0xFF, 0x83, 0x0C, 0x30, 0x63, 0x06, 0x30, 0x63, 0x06, + 0x30, 0xC3, 0xF0, 0x30, 0xE3, 0x06, 0x30, 0x33, 0x03, 0x30, 0x33, 0x07, + 0x30, 0xEF, 0xFC, 0x07, 0xE2, 0x38, 0x3C, 0xC0, 0x3B, 0x00, 0x36, 0x00, + 0x38, 0x00, 0x30, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x03, + 0x00, 0x06, 0x00, 0x06, 0x00, 0x47, 0x03, 0x03, 0xF8, 0xFF, 0xC0, 0x30, + 0x78, 0x30, 0x1C, 0x30, 0x0E, 0x30, 0x06, 0x30, 0x03, 0x30, 0x03, 0x30, + 0x03, 0x30, 0x03, 0x30, 0x03, 0x30, 0x03, 0x30, 0x06, 0x30, 0x06, 0x30, + 0x0C, 0x30, 0x78, 0xFF, 0xC0, 0xFF, 0xFC, 0xC0, 0x33, 0x00, 0x4C, 0x00, + 0x30, 0x00, 0xC0, 0x43, 0x03, 0x0F, 0xFC, 0x30, 0x30, 0xC0, 0x43, 0x00, + 0x0C, 0x00, 0x30, 0x08, 0xC0, 0x23, 0x03, 0xBF, 0xFE, 0xFF, 0xFC, 0xC0, + 0x33, 0x00, 0x4C, 0x00, 0x30, 0x00, 0xC0, 0x43, 0x03, 0x0F, 0xFC, 0x30, + 0x30, 0xC0, 0x43, 0x00, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x03, 0x00, 0x3F, + 0x00, 0x07, 0xE4, 0x1C, 0x3C, 0x30, 0x0C, 0x60, 0x0C, 0x60, 0x04, 0xC0, + 0x00, 0xC0, 0x00, 0xC0, 0x3F, 0xC0, 0x0C, 0xC0, 0x0C, 0xC0, 0x0C, 0x60, + 0x0C, 0x60, 0x0C, 0x30, 0x0C, 0x1C, 0x1C, 0x07, 0xE0, 0xFC, 0x3F, 0x30, + 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x3F, + 0xFC, 0x30, 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x30, 0x0C, 0x30, + 0x0C, 0x30, 0x0C, 0xFC, 0x3F, 0xFC, 0xC3, 0x0C, 0x30, 0xC3, 0x0C, 0x30, + 0xC3, 0x0C, 0x30, 0xC3, 0x3F, 0x3F, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, + 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0x0C, 0xC8, 0xF0, 0xFC, 0xFE, 0x30, + 0x38, 0x30, 0x20, 0x30, 0x40, 0x30, 0x80, 0x33, 0x00, 0x36, 0x00, 0x3E, + 0x00, 0x37, 0x00, 0x33, 0x80, 0x31, 0xC0, 0x30, 0xE0, 0x30, 0x70, 0x30, + 0x38, 0x30, 0x3C, 0xFC, 0x7F, 0xFC, 0x00, 0x60, 0x00, 0xC0, 0x01, 0x80, + 0x03, 0x00, 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, 0x00, + 0xC0, 0x01, 0x80, 0x03, 0x00, 0x26, 0x00, 0x8C, 0x07, 0x7F, 0xFE, 0xF8, + 0x01, 0xE7, 0x00, 0x70, 0xE0, 0x0E, 0x1E, 0x03, 0xC2, 0xC0, 0x58, 0x5C, + 0x1B, 0x09, 0x82, 0x61, 0x38, 0x4C, 0x27, 0x11, 0x84, 0x72, 0x30, 0x8E, + 0xC6, 0x10, 0xD0, 0xC2, 0x1E, 0x18, 0x41, 0x83, 0x1C, 0x30, 0x67, 0xC4, + 0x3F, 0xF0, 0x1F, 0x78, 0x0E, 0x3C, 0x04, 0x3E, 0x04, 0x2E, 0x04, 0x27, + 0x04, 0x23, 0x84, 0x23, 0xC4, 0x21, 0xE4, 0x20, 0xE4, 0x20, 0x74, 0x20, + 0x3C, 0x20, 0x1C, 0x20, 0x0C, 0x70, 0x0C, 0xF8, 0x04, 0x07, 0xC0, 0x30, + 0x60, 0xC0, 0x63, 0x00, 0x66, 0x00, 0xD8, 0x00, 0xF0, 0x01, 0xE0, 0x03, + 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1B, 0x00, 0x66, 0x00, 0xC6, 0x03, 0x06, + 0x0C, 0x03, 0xE0, 0xFF, 0x83, 0x0E, 0x30, 0x73, 0x03, 0x30, 0x33, 0x03, + 0x30, 0x63, 0x0E, 0x3F, 0x83, 0x00, 0x30, 0x03, 0x00, 0x30, 0x03, 0x00, + 0x30, 0x0F, 0xC0, 0x0F, 0xE0, 0x18, 0x30, 0x30, 0x18, 0x60, 0x0C, 0x60, + 0x0C, 0xC0, 0x06, 0xC0, 0x06, 0xC0, 0x06, 0xC0, 0x06, 0xC0, 0x06, 0xC0, + 0x06, 0x60, 0x0C, 0x60, 0x0C, 0x30, 0x18, 0x18, 0x30, 0x07, 0xC0, 0x03, + 0xC0, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1F, 0xFF, 0x80, 0x61, 0xC0, 0xC1, + 0xC1, 0x81, 0x83, 0x03, 0x06, 0x06, 0x0C, 0x1C, 0x18, 0x70, 0x3F, 0x80, + 0x67, 0x00, 0xC7, 0x01, 0x8F, 0x03, 0x0F, 0x06, 0x0E, 0x0C, 0x0E, 0x7E, + 0x0F, 0x1F, 0x46, 0x19, 0x81, 0x30, 0x27, 0x02, 0xF0, 0x0F, 0x00, 0xF8, + 0x07, 0xC0, 0x38, 0x03, 0xC0, 0x34, 0x06, 0x80, 0xDC, 0x32, 0x7C, 0xFF, + 0xFF, 0x86, 0x0E, 0x0C, 0x1C, 0x18, 0x10, 0x30, 0x00, 0x60, 0x00, 0xC0, + 0x01, 0x80, 0x03, 0x00, 0x06, 0x00, 0x0C, 0x00, 0x18, 0x00, 0x30, 0x00, + 0x60, 0x00, 0xC0, 0x07, 0xE0, 0xFC, 0x1F, 0x30, 0x0E, 0x30, 0x04, 0x30, + 0x04, 0x30, 0x04, 0x30, 0x04, 0x30, 0x04, 0x30, 0x04, 0x30, 0x04, 0x30, + 0x04, 0x30, 0x04, 0x30, 0x04, 0x30, 0x04, 0x18, 0x08, 0x1C, 0x18, 0x07, + 0xE0, 0xFE, 0x0F, 0x9C, 0x03, 0x0E, 0x01, 0x83, 0x00, 0x81, 0xC0, 0x40, + 0x60, 0x40, 0x38, 0x20, 0x0C, 0x30, 0x07, 0x10, 0x01, 0x98, 0x00, 0xE8, + 0x00, 0x34, 0x00, 0x1E, 0x00, 0x06, 0x00, 0x03, 0x00, 0x01, 0x00, 0xFC, + 0xFC, 0x3D, 0xE1, 0xC0, 0x63, 0x83, 0x01, 0x86, 0x0E, 0x04, 0x1C, 0x18, + 0x10, 0x70, 0x70, 0x80, 0xC3, 0xC2, 0x03, 0x8B, 0x08, 0x06, 0x6E, 0x40, + 0x1D, 0x19, 0x00, 0x74, 0x78, 0x00, 0xE1, 0xE0, 0x03, 0x83, 0x80, 0x0E, + 0x0C, 0x00, 0x10, 0x10, 0x00, 0x40, 0x40, 0x7F, 0x1F, 0x9E, 0x03, 0x07, + 0x03, 0x01, 0xC3, 0x00, 0x71, 0x00, 0x19, 0x00, 0x0F, 0x00, 0x03, 0x80, + 0x01, 0xE0, 0x01, 0xB0, 0x01, 0x9C, 0x00, 0x87, 0x00, 0x81, 0xC0, 0x80, + 0xE0, 0xC0, 0x79, 0xF8, 0x7F, 0xFE, 0x1F, 0x78, 0x0C, 0x38, 0x08, 0x1C, + 0x18, 0x0E, 0x10, 0x06, 0x20, 0x07, 0x60, 0x03, 0xC0, 0x01, 0x80, 0x01, + 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x07, + 0xE0, 0x7F, 0xFB, 0x00, 0xC8, 0x07, 0x20, 0x38, 0x01, 0xC0, 0x07, 0x00, + 0x38, 0x01, 0xC0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x0E, 0x00, 0x38, 0x05, + 0xC0, 0x3E, 0x01, 0xBF, 0xFE, 0xFE, 0x31, 0x8C, 0x63, 0x18, 0xC6, 0x31, + 0x8C, 0x63, 0x18, 0xC6, 0x31, 0xF0, 0xC1, 0x81, 0x03, 0x06, 0x04, 0x0C, + 0x18, 0x10, 0x30, 0x60, 0x40, 0xC1, 0x81, 0x03, 0x06, 0xF8, 0xC6, 0x31, + 0x8C, 0x63, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0xC7, 0xF0, 0x0C, 0x07, + 0x01, 0x60, 0xD8, 0x23, 0x18, 0xC4, 0x1B, 0x06, 0x80, 0xC0, 0xFF, 0xF0, + 0xC7, 0x0C, 0x30, 0x3E, 0x31, 0x8C, 0x30, 0x0C, 0x03, 0x07, 0xC6, 0x33, + 0x0C, 0xC3, 0x31, 0xC7, 0xB8, 0x20, 0x38, 0x06, 0x01, 0x80, 0x60, 0x18, + 0x06, 0xF1, 0xC6, 0x61, 0xD8, 0x36, 0x0D, 0x83, 0x60, 0xD8, 0x26, 0x19, + 0x84, 0x3E, 0x00, 0x1E, 0x23, 0x63, 0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xE1, + 0x72, 0x3C, 0x00, 0x80, 0xE0, 0x18, 0x06, 0x01, 0x80, 0x61, 0xD8, 0x8E, + 0x61, 0xB0, 0x6C, 0x1B, 0x06, 0xC1, 0xB0, 0x6E, 0x19, 0xCE, 0x3D, 0xC0, + 0x1E, 0x08, 0xE4, 0x1B, 0xFE, 0xC0, 0x30, 0x0C, 0x03, 0x81, 0x60, 0x9C, + 0x41, 0xE0, 0x0F, 0x08, 0xC4, 0x06, 0x03, 0x01, 0x81, 0xF0, 0x60, 0x30, + 0x18, 0x0C, 0x06, 0x03, 0x01, 0x80, 0xC0, 0x60, 0xFC, 0x00, 0x1F, 0x03, + 0x1F, 0x60, 0xC6, 0x0C, 0x60, 0xC3, 0x18, 0x1F, 0x02, 0x00, 0x40, 0x07, + 0xFC, 0x40, 0x24, 0x02, 0xC0, 0x2C, 0x04, 0xE0, 0x83, 0xF0, 0x30, 0x1E, + 0x00, 0xC0, 0x18, 0x03, 0x00, 0x60, 0x0D, 0xE1, 0xCE, 0x30, 0xC6, 0x18, + 0xC3, 0x18, 0x63, 0x0C, 0x61, 0x8C, 0x31, 0x86, 0x79, 0xE0, 0x31, 0x80, + 0x00, 0x09, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0xDF, 0x0C, 0x30, 0x00, 0x00, + 0x31, 0xC3, 0x0C, 0x30, 0xC3, 0x0C, 0x30, 0xC3, 0x0C, 0x30, 0xF2, 0xF0, + 0x20, 0x1C, 0x01, 0x80, 0x30, 0x06, 0x00, 0xC0, 0x18, 0xFB, 0x08, 0x62, + 0x0C, 0x81, 0xE0, 0x3E, 0x06, 0xE0, 0xCE, 0x18, 0xC3, 0x0E, 0xF3, 0xE0, + 0x13, 0x8C, 0x63, 0x18, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0xC6, 0xF8, 0xF7, + 0x8F, 0x0E, 0x3C, 0xE3, 0x0C, 0x18, 0xC3, 0x06, 0x30, 0xC1, 0x8C, 0x30, + 0x63, 0x0C, 0x18, 0xC3, 0x06, 0x30, 0xC1, 0x8C, 0x30, 0x67, 0x9E, 0x3C, + 0xF7, 0x87, 0x18, 0xC3, 0x18, 0x63, 0x0C, 0x61, 0x8C, 0x31, 0x86, 0x30, + 0xC6, 0x19, 0xE7, 0x80, 0x1E, 0x18, 0xE4, 0x1B, 0x03, 0xC0, 0xF0, 0x3C, + 0x0F, 0x03, 0x60, 0x9C, 0x41, 0xE0, 0x77, 0x87, 0x18, 0xC3, 0x98, 0x33, + 0x06, 0x60, 0xCC, 0x19, 0x83, 0x30, 0xC7, 0x10, 0xDC, 0x18, 0x03, 0x00, + 0x60, 0x0C, 0x07, 0xE0, 0x1E, 0x8C, 0xE6, 0x1B, 0x06, 0xC1, 0xB0, 0x6C, + 0x1B, 0x06, 0xE1, 0x98, 0xE3, 0xD8, 0x06, 0x01, 0x80, 0x60, 0x18, 0x1F, + 0x37, 0x7B, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x30, 0x7C, 0x7B, + 0x0E, 0x1C, 0x1E, 0x0F, 0x07, 0xC3, 0x87, 0x8A, 0xE0, 0x21, 0x8F, 0x98, + 0x61, 0x86, 0x18, 0x61, 0x86, 0x19, 0x38, 0xE3, 0x98, 0x66, 0x19, 0x86, + 0x61, 0x98, 0x66, 0x19, 0x86, 0x61, 0x9C, 0xE3, 0xDC, 0xF8, 0xEE, 0x08, + 0xC1, 0x18, 0x41, 0x88, 0x32, 0x03, 0x40, 0x68, 0x06, 0x00, 0xC0, 0x10, + 0x00, 0xF3, 0xE7, 0x61, 0x83, 0x70, 0xC2, 0x30, 0xC2, 0x30, 0xC4, 0x19, + 0x64, 0x19, 0x68, 0x0E, 0x38, 0x0E, 0x38, 0x0C, 0x30, 0x04, 0x10, 0xFB, + 0xC6, 0x30, 0x64, 0x0F, 0x00, 0xC0, 0x0C, 0x03, 0xC0, 0x98, 0x21, 0x8C, + 0x3B, 0xCF, 0x80, 0xF8, 0xEE, 0x08, 0xC1, 0x18, 0x41, 0x88, 0x31, 0x03, + 0x40, 0x68, 0x06, 0x00, 0xC0, 0x08, 0x02, 0x00, 0x40, 0x10, 0x1E, 0x03, + 0x80, 0x7F, 0x90, 0xE0, 0x30, 0x18, 0x0E, 0x03, 0x01, 0xC0, 0xE0, 0x30, + 0x5C, 0x3F, 0xF8, 0x19, 0x8C, 0x63, 0x18, 0xC6, 0x31, 0xB0, 0x63, 0x18, + 0xC6, 0x31, 0x8C, 0x61, 0x80, 0xFF, 0xFF, 0x80, 0xC3, 0x18, 0xC6, 0x31, + 0x8C, 0x63, 0x06, 0xC6, 0x31, 0x8C, 0x63, 0x18, 0xCC, 0x00, 0x38, 0x06, + 0x62, 0x41, 0xC0 }; + +const GFXglyph FreeSerif12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 6, 0, 1 }, // 0x20 ' ' + { 0, 2, 16, 8, 3, -15 }, // 0x21 '!' + { 4, 6, 6, 10, 1, -15 }, // 0x22 '"' + { 9, 12, 16, 12, 0, -15 }, // 0x23 '#' + { 33, 10, 18, 12, 1, -16 }, // 0x24 '$' + { 56, 18, 17, 20, 1, -16 }, // 0x25 '%' + { 95, 17, 16, 19, 1, -15 }, // 0x26 '&' + { 129, 2, 6, 5, 1, -15 }, // 0x27 ''' + { 131, 6, 20, 8, 1, -15 }, // 0x28 '(' + { 146, 6, 20, 8, 1, -15 }, // 0x29 ')' + { 161, 8, 10, 12, 3, -14 }, // 0x2A '*' + { 171, 11, 11, 14, 1, -10 }, // 0x2B '+' + { 187, 3, 6, 6, 2, -2 }, // 0x2C ',' + { 190, 6, 1, 8, 1, -5 }, // 0x2D '-' + { 191, 2, 3, 6, 2, -2 }, // 0x2E '.' + { 192, 7, 17, 7, 0, -16 }, // 0x2F '/' + { 207, 10, 17, 12, 1, -16 }, // 0x30 '0' + { 229, 6, 17, 12, 3, -16 }, // 0x31 '1' + { 242, 10, 15, 12, 1, -14 }, // 0x32 '2' + { 261, 10, 16, 12, 1, -15 }, // 0x33 '3' + { 281, 10, 16, 12, 1, -15 }, // 0x34 '4' + { 301, 10, 17, 12, 1, -16 }, // 0x35 '5' + { 323, 10, 17, 12, 1, -16 }, // 0x36 '6' + { 345, 10, 16, 12, 0, -15 }, // 0x37 '7' + { 365, 10, 17, 12, 1, -16 }, // 0x38 '8' + { 387, 10, 18, 12, 1, -16 }, // 0x39 '9' + { 410, 2, 12, 6, 2, -11 }, // 0x3A ':' + { 413, 4, 15, 6, 2, -11 }, // 0x3B ';' + { 421, 12, 13, 14, 1, -12 }, // 0x3C '<' + { 441, 12, 6, 14, 1, -8 }, // 0x3D '=' + { 450, 12, 13, 14, 1, -11 }, // 0x3E '>' + { 470, 8, 17, 11, 2, -16 }, // 0x3F '?' + { 487, 17, 16, 21, 2, -15 }, // 0x40 '@' + { 521, 17, 16, 17, 0, -15 }, // 0x41 'A' + { 555, 12, 16, 15, 1, -15 }, // 0x42 'B' + { 579, 15, 16, 16, 1, -15 }, // 0x43 'C' + { 609, 16, 16, 17, 0, -15 }, // 0x44 'D' + { 641, 14, 16, 15, 0, -15 }, // 0x45 'E' + { 669, 14, 16, 14, 0, -15 }, // 0x46 'F' + { 697, 16, 16, 17, 1, -15 }, // 0x47 'G' + { 729, 16, 16, 17, 0, -15 }, // 0x48 'H' + { 761, 6, 16, 8, 1, -15 }, // 0x49 'I' + { 773, 8, 16, 9, 0, -15 }, // 0x4A 'J' + { 789, 16, 16, 17, 1, -15 }, // 0x4B 'K' + { 821, 15, 16, 15, 0, -15 }, // 0x4C 'L' + { 851, 19, 16, 21, 1, -15 }, // 0x4D 'M' + { 889, 16, 16, 17, 1, -15 }, // 0x4E 'N' + { 921, 15, 16, 17, 1, -15 }, // 0x4F 'O' + { 951, 12, 16, 14, 0, -15 }, // 0x50 'P' + { 975, 16, 20, 17, 1, -15 }, // 0x51 'Q' + { 1015, 15, 16, 16, 0, -15 }, // 0x52 'R' + { 1045, 11, 16, 13, 0, -15 }, // 0x53 'S' + { 1067, 15, 16, 15, 0, -15 }, // 0x54 'T' + { 1097, 16, 16, 17, 1, -15 }, // 0x55 'U' + { 1129, 17, 16, 17, 0, -15 }, // 0x56 'V' + { 1163, 22, 16, 23, 0, -15 }, // 0x57 'W' + { 1207, 17, 16, 17, 0, -15 }, // 0x58 'X' + { 1241, 16, 16, 17, 0, -15 }, // 0x59 'Y' + { 1273, 14, 16, 15, 1, -15 }, // 0x5A 'Z' + { 1301, 5, 20, 8, 2, -15 }, // 0x5B '[' + { 1314, 7, 17, 7, 0, -16 }, // 0x5C '\' + { 1329, 5, 20, 8, 1, -15 }, // 0x5D ']' + { 1342, 10, 9, 11, 1, -15 }, // 0x5E '^' + { 1354, 12, 1, 12, 0, 3 }, // 0x5F '_' + { 1356, 5, 4, 6, 0, -15 }, // 0x60 '`' + { 1359, 10, 11, 10, 1, -10 }, // 0x61 'a' + { 1373, 10, 17, 12, 1, -16 }, // 0x62 'b' + { 1395, 8, 11, 11, 1, -10 }, // 0x63 'c' + { 1406, 10, 17, 12, 1, -16 }, // 0x64 'd' + { 1428, 10, 11, 11, 1, -10 }, // 0x65 'e' + { 1442, 9, 17, 9, 0, -16 }, // 0x66 'f' + { 1462, 12, 16, 11, 0, -10 }, // 0x67 'g' + { 1486, 11, 17, 12, 0, -16 }, // 0x68 'h' + { 1510, 5, 16, 7, 0, -15 }, // 0x69 'i' + { 1520, 6, 21, 8, 0, -15 }, // 0x6A 'j' + { 1536, 11, 17, 12, 1, -16 }, // 0x6B 'k' + { 1560, 5, 17, 6, 0, -16 }, // 0x6C 'l' + { 1571, 18, 11, 19, 0, -10 }, // 0x6D 'm' + { 1596, 11, 11, 12, 0, -10 }, // 0x6E 'n' + { 1612, 10, 11, 12, 1, -10 }, // 0x6F 'o' + { 1626, 11, 16, 12, 0, -10 }, // 0x70 'p' + { 1648, 10, 16, 12, 1, -10 }, // 0x71 'q' + { 1668, 8, 11, 8, 0, -10 }, // 0x72 'r' + { 1679, 7, 11, 9, 1, -10 }, // 0x73 's' + { 1689, 6, 13, 7, 1, -12 }, // 0x74 't' + { 1699, 10, 11, 12, 1, -10 }, // 0x75 'u' + { 1713, 11, 11, 11, 0, -10 }, // 0x76 'v' + { 1729, 16, 11, 16, 0, -10 }, // 0x77 'w' + { 1751, 11, 11, 12, 0, -10 }, // 0x78 'x' + { 1767, 11, 16, 11, 0, -10 }, // 0x79 'y' + { 1789, 10, 11, 10, 0, -10 }, // 0x7A 'z' + { 1803, 5, 21, 12, 2, -16 }, // 0x7B '{' + { 1817, 1, 17, 5, 2, -16 }, // 0x7C '|' + { 1820, 5, 21, 12, 5, -15 }, // 0x7D '}' + { 1834, 12, 3, 12, 0, -6 } }; // 0x7E '~' + +const GFXfont FreeSerif12pt7b PROGMEM = { + (uint8_t *)FreeSerif12pt7bBitmaps, + (GFXglyph *)FreeSerif12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 2511 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerif18pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerif18pt7b.h new file mode 100644 index 0000000..7d19dd1 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerif18pt7b.h @@ -0,0 +1,429 @@ +const uint8_t FreeSerif18pt7bBitmaps[] PROGMEM = { + 0x6F, 0xFF, 0xFF, 0xFE, 0x66, 0x66, 0x66, 0x64, 0x40, 0x00, 0x6F, 0xF6, + 0xE7, 0xE7, 0xE7, 0xE7, 0xE7, 0x46, 0x42, 0x42, 0x42, 0x03, 0x06, 0x01, + 0x83, 0x00, 0xC1, 0x80, 0x61, 0xC0, 0x30, 0xC0, 0x38, 0x60, 0x18, 0x30, + 0xFF, 0xFF, 0x7F, 0xFF, 0x83, 0x06, 0x01, 0x86, 0x00, 0xC3, 0x00, 0xC1, + 0x87, 0xFF, 0xFF, 0xFF, 0xFE, 0x18, 0x30, 0x0C, 0x18, 0x06, 0x18, 0x06, + 0x0C, 0x03, 0x06, 0x01, 0x83, 0x00, 0xC1, 0x80, 0x60, 0xC0, 0x02, 0x00, + 0x10, 0x03, 0xE0, 0x64, 0xE6, 0x23, 0x61, 0x1B, 0x08, 0x58, 0x42, 0xE2, + 0x03, 0x90, 0x1F, 0x80, 0x7E, 0x00, 0xFC, 0x01, 0xF0, 0x0F, 0xC0, 0x4E, + 0x02, 0x38, 0x10, 0xE0, 0x87, 0x04, 0x3C, 0x21, 0xE1, 0x1B, 0xC9, 0xCF, + 0xFC, 0x1F, 0x80, 0x10, 0x00, 0x80, 0x07, 0x80, 0x20, 0x0F, 0xF0, 0x70, + 0x0F, 0x07, 0xD0, 0x0F, 0x02, 0x18, 0x07, 0x01, 0x18, 0x07, 0x00, 0x8C, + 0x03, 0x80, 0x4C, 0x01, 0x80, 0x44, 0x00, 0xC0, 0x26, 0x00, 0x60, 0x22, + 0x0F, 0x30, 0x33, 0x1F, 0xCC, 0x73, 0x1E, 0x37, 0xF1, 0x8E, 0x19, 0xE1, + 0x8E, 0x04, 0x00, 0x86, 0x02, 0x00, 0xC7, 0x01, 0x00, 0xC3, 0x80, 0x80, + 0x61, 0x80, 0x80, 0x60, 0xC0, 0x40, 0x30, 0x60, 0x40, 0x30, 0x38, 0xE0, + 0x30, 0x0F, 0xE0, 0x18, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x00, 0x7E, 0x00, + 0x00, 0x61, 0x80, 0x00, 0x60, 0x60, 0x00, 0x30, 0x30, 0x00, 0x18, 0x18, + 0x00, 0x0C, 0x0C, 0x00, 0x06, 0x0C, 0x00, 0x03, 0x8E, 0x00, 0x01, 0xCE, + 0x00, 0x00, 0x7C, 0x3F, 0xC0, 0x38, 0x07, 0x80, 0x3E, 0x03, 0x80, 0x77, + 0x01, 0x80, 0x73, 0xC0, 0x80, 0xF0, 0xF0, 0xC0, 0x70, 0x7C, 0xC0, 0x78, + 0x1E, 0x40, 0x3C, 0x07, 0xC0, 0x1E, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x0F, + 0xC0, 0xFF, 0x0D, 0xF0, 0xC7, 0xFC, 0x7F, 0xC1, 0xFC, 0x1F, 0x80, 0x3C, + 0x00, 0xFF, 0xFE, 0x92, 0x40, 0x00, 0x80, 0x80, 0x80, 0x80, 0x80, 0xC0, + 0xC0, 0x60, 0x70, 0x30, 0x18, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, + 0x70, 0x38, 0x0C, 0x06, 0x03, 0x80, 0xC0, 0x60, 0x18, 0x0C, 0x03, 0x00, + 0xC0, 0x30, 0x0C, 0x80, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0x60, 0x18, 0x0C, + 0x07, 0x01, 0x80, 0xC0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, + 0xE0, 0x60, 0x30, 0x38, 0x18, 0x0C, 0x0C, 0x04, 0x04, 0x04, 0x04, 0x04, + 0x00, 0x0C, 0x00, 0xC0, 0x0C, 0x0C, 0x46, 0xE4, 0xF7, 0x5E, 0x1F, 0x00, + 0xC0, 0x17, 0x8E, 0x4E, 0xE4, 0xFC, 0xC6, 0x0C, 0x00, 0xC0, 0x01, 0x80, + 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, + 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, + 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x6F, 0xFF, + 0x11, 0x24, 0x80, 0xFF, 0xFF, 0x6F, 0xF6, 0x00, 0xC0, 0x60, 0x18, 0x06, + 0x03, 0x80, 0xC0, 0x30, 0x1C, 0x06, 0x01, 0x80, 0xE0, 0x30, 0x0C, 0x07, + 0x01, 0x80, 0x60, 0x38, 0x0C, 0x03, 0x01, 0xC0, 0x60, 0x18, 0x0E, 0x03, + 0x00, 0x03, 0xE0, 0x0E, 0x70, 0x1C, 0x38, 0x38, 0x1C, 0x38, 0x1C, 0x78, + 0x1E, 0x70, 0x0E, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, + 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0x70, 0x0E, 0x70, + 0x0E, 0x78, 0x1E, 0x38, 0x1C, 0x38, 0x1C, 0x1C, 0x38, 0x0C, 0x30, 0x03, + 0xC0, 0x06, 0x03, 0x83, 0xE3, 0x38, 0x0E, 0x03, 0x80, 0xE0, 0x38, 0x0E, + 0x03, 0x80, 0xE0, 0x38, 0x0E, 0x03, 0x80, 0xE0, 0x38, 0x0E, 0x03, 0x80, + 0xE0, 0x38, 0x0E, 0x03, 0x81, 0xE1, 0xFF, 0x07, 0xC0, 0x1F, 0xF0, 0x3F, + 0xF8, 0x70, 0xF8, 0x60, 0x3C, 0xC0, 0x3C, 0x80, 0x1C, 0x00, 0x1C, 0x00, + 0x1C, 0x00, 0x18, 0x00, 0x18, 0x00, 0x30, 0x00, 0x30, 0x00, 0x60, 0x00, + 0xC0, 0x00, 0x80, 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x08, 0x01, 0x10, + 0x02, 0x3F, 0xFE, 0x7F, 0xFC, 0xFF, 0xFC, 0x0F, 0xC0, 0xFF, 0x0C, 0x3C, + 0x80, 0xE4, 0x03, 0x00, 0x18, 0x00, 0xC0, 0x04, 0x00, 0x40, 0x04, 0x00, + 0xF8, 0x1F, 0xE0, 0x0F, 0x00, 0x1C, 0x00, 0xE0, 0x03, 0x00, 0x18, 0x00, + 0xC0, 0x06, 0x00, 0x60, 0x03, 0x78, 0x73, 0xFF, 0x0F, 0xC0, 0x00, 0x30, + 0x00, 0x30, 0x00, 0x70, 0x00, 0xF0, 0x00, 0xB0, 0x01, 0x30, 0x03, 0x30, + 0x06, 0x30, 0x04, 0x30, 0x08, 0x30, 0x18, 0x30, 0x10, 0x30, 0x20, 0x30, + 0x60, 0x30, 0xC0, 0x30, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x30, 0x00, 0x30, + 0x00, 0x30, 0x00, 0x30, 0x00, 0x30, 0x00, 0x30, 0x00, 0x00, 0x7F, 0xC3, + 0xFE, 0x1F, 0xE1, 0x80, 0x08, 0x00, 0xC0, 0x07, 0xC0, 0x7F, 0x81, 0xFF, + 0x00, 0xFC, 0x01, 0xE0, 0x07, 0x80, 0x1C, 0x00, 0x60, 0x03, 0x00, 0x18, + 0x00, 0xC0, 0x06, 0x00, 0x60, 0x07, 0x78, 0x73, 0xFF, 0x0F, 0xC0, 0x00, + 0x0E, 0x00, 0xF8, 0x03, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x3C, + 0x00, 0x7C, 0x00, 0x79, 0xF0, 0x7F, 0xFC, 0xF8, 0x3C, 0xF0, 0x1E, 0xF0, + 0x1F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0x70, 0x0F, 0x78, + 0x0F, 0x78, 0x0E, 0x3C, 0x1E, 0x1E, 0x3C, 0x0F, 0xF8, 0x07, 0xE0, 0x3F, + 0xFD, 0xFF, 0xF7, 0xFF, 0xF0, 0x06, 0x80, 0x18, 0x00, 0x60, 0x03, 0x00, + 0x0C, 0x00, 0x30, 0x01, 0x80, 0x06, 0x00, 0x18, 0x00, 0xE0, 0x03, 0x00, + 0x0C, 0x00, 0x70, 0x01, 0x80, 0x06, 0x00, 0x38, 0x00, 0xC0, 0x03, 0x00, + 0x1C, 0x00, 0x60, 0x00, 0x0F, 0x83, 0xFC, 0x70, 0xE6, 0x07, 0xC0, 0x3C, + 0x03, 0xC0, 0x3E, 0x03, 0x70, 0x67, 0x8C, 0x3D, 0x81, 0xF0, 0x0F, 0x81, + 0x7C, 0x21, 0xE6, 0x0E, 0xC0, 0x7C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x36, + 0x06, 0x70, 0xE3, 0xFC, 0x0F, 0x80, 0x07, 0xC0, 0x1F, 0xF0, 0x3C, 0x78, + 0x38, 0x3C, 0x78, 0x1E, 0x70, 0x1E, 0xF0, 0x0E, 0xF0, 0x0F, 0xF0, 0x0F, + 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF8, 0x0F, 0x78, 0x0F, 0x3C, 0x3F, + 0x1F, 0xEE, 0x0F, 0x9E, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x38, 0x00, 0x78, + 0x00, 0xF0, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x70, 0x00, 0x6F, 0xF6, + 0x00, 0x00, 0x00, 0x00, 0x06, 0xFF, 0x60, 0x67, 0xBC, 0xC0, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x19, 0xEF, 0x78, 0x42, 0x22, 0x20, 0x00, 0x00, 0xC0, + 0x00, 0xF0, 0x01, 0xF8, 0x01, 0xF8, 0x01, 0xF8, 0x01, 0xF0, 0x03, 0xF0, + 0x03, 0xF0, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, + 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xC0, + 0x00, 0x10, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x80, + 0x00, 0x3C, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x07, 0xC0, 0x00, 0x7C, + 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x07, 0xC0, 0x00, 0xF0, 0x00, 0xFC, + 0x00, 0xFC, 0x00, 0xF8, 0x01, 0xF8, 0x01, 0xF8, 0x01, 0xF8, 0x00, 0xF0, + 0x00, 0x30, 0x00, 0x00, 0x1F, 0x81, 0xFF, 0x18, 0x7D, 0x81, 0xEC, 0x07, + 0xF0, 0x3F, 0x81, 0xE0, 0x0F, 0x00, 0x70, 0x03, 0x80, 0x38, 0x01, 0x80, + 0x08, 0x00, 0xC0, 0x04, 0x00, 0x20, 0x02, 0x00, 0x10, 0x00, 0x80, 0x00, + 0x00, 0x00, 0x03, 0x00, 0x3C, 0x01, 0xE0, 0x07, 0x00, 0x00, 0x7F, 0x00, + 0x01, 0xFF, 0xC0, 0x07, 0x80, 0xF0, 0x0F, 0x00, 0x38, 0x1C, 0x00, 0x1C, + 0x38, 0x00, 0x0C, 0x38, 0x00, 0x06, 0x70, 0x1E, 0x02, 0x70, 0x3F, 0xE3, + 0xF0, 0x71, 0xE1, 0xE0, 0xE0, 0xC1, 0xE0, 0xC0, 0xC1, 0xE0, 0xC1, 0xC1, + 0xE1, 0x81, 0xC1, 0xE1, 0x81, 0x83, 0xE1, 0x83, 0x82, 0xE1, 0x83, 0x86, + 0x71, 0xC7, 0x8C, 0x70, 0xF9, 0xF8, 0x38, 0xF0, 0xF0, 0x3C, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x07, 0x80, 0x70, 0x03, 0xFF, 0xE0, 0x00, 0x7F, 0x00, + 0x00, 0x10, 0x00, 0x00, 0x38, 0x00, 0x00, 0x38, 0x00, 0x00, 0x38, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x5C, 0x00, 0x00, 0xDE, 0x00, 0x00, 0x8E, 0x00, + 0x01, 0x8F, 0x00, 0x01, 0x87, 0x00, 0x03, 0x07, 0x80, 0x03, 0x03, 0x80, + 0x02, 0x03, 0xC0, 0x06, 0x03, 0xC0, 0x07, 0xFF, 0xC0, 0x0F, 0xFF, 0xE0, + 0x0C, 0x01, 0xE0, 0x18, 0x00, 0xF0, 0x18, 0x00, 0xF0, 0x30, 0x00, 0x78, + 0x30, 0x00, 0x78, 0x70, 0x00, 0x7C, 0xFC, 0x01, 0xFF, 0xFF, 0xFC, 0x03, + 0xFF, 0xF8, 0x1E, 0x0F, 0xC1, 0xE0, 0x3C, 0x1E, 0x01, 0xE1, 0xE0, 0x1E, + 0x1E, 0x01, 0xE1, 0xE0, 0x1E, 0x1E, 0x03, 0xC1, 0xE0, 0x78, 0x1F, 0xFE, + 0x01, 0xFF, 0xF0, 0x1E, 0x07, 0xC1, 0xE0, 0x1E, 0x1E, 0x00, 0xF1, 0xE0, + 0x0F, 0x1E, 0x00, 0xF1, 0xE0, 0x0F, 0x1E, 0x00, 0xF1, 0xE0, 0x1E, 0x1E, + 0x07, 0xE3, 0xFF, 0xF8, 0xFF, 0xFE, 0x00, 0x00, 0xFE, 0x08, 0x0F, 0xFF, + 0x60, 0xFC, 0x1F, 0x87, 0xC0, 0x1E, 0x3C, 0x00, 0x38, 0xF0, 0x00, 0x67, + 0x80, 0x01, 0x9E, 0x00, 0x02, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x0F, + 0x00, 0x02, 0x1F, 0x00, 0x38, 0x3F, 0x03, 0x80, 0x7F, 0xFC, 0x00, 0x3F, + 0x80, 0xFF, 0xFC, 0x00, 0x7F, 0xFF, 0x00, 0x78, 0x3F, 0x80, 0xF0, 0x0F, + 0x81, 0xE0, 0x0F, 0x83, 0xC0, 0x0F, 0x07, 0x80, 0x0F, 0x0F, 0x00, 0x1E, + 0x1E, 0x00, 0x1E, 0x3C, 0x00, 0x3C, 0x78, 0x00, 0x78, 0xF0, 0x00, 0xF1, + 0xE0, 0x01, 0xE3, 0xC0, 0x03, 0xC7, 0x80, 0x07, 0x8F, 0x00, 0x1E, 0x1E, + 0x00, 0x3C, 0x3C, 0x00, 0xF0, 0x78, 0x01, 0xE0, 0xF0, 0x0F, 0x81, 0xE0, + 0x7E, 0x07, 0xFF, 0xF0, 0x3F, 0xFF, 0x00, 0x00, 0xFF, 0xFF, 0x87, 0xFF, + 0xF8, 0x3C, 0x01, 0x83, 0xC0, 0x08, 0x3C, 0x00, 0x83, 0xC0, 0x00, 0x3C, + 0x00, 0x03, 0xC0, 0x00, 0x3C, 0x02, 0x03, 0xC0, 0x60, 0x3F, 0xFE, 0x03, + 0xFF, 0xE0, 0x3C, 0x06, 0x03, 0xC0, 0x20, 0x3C, 0x00, 0x03, 0xC0, 0x00, + 0x3C, 0x00, 0x03, 0xC0, 0x01, 0x3C, 0x00, 0x23, 0xC0, 0x06, 0x3C, 0x01, + 0xE7, 0xFF, 0xFE, 0xFF, 0xFF, 0xC0, 0xFF, 0xFF, 0xBF, 0xFF, 0xCF, 0x00, + 0x67, 0x80, 0x13, 0xC0, 0x09, 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, + 0x02, 0x1E, 0x03, 0x0F, 0xFF, 0x87, 0xFF, 0xC3, 0xC0, 0x61, 0xE0, 0x10, + 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x0F, 0x00, 0x07, 0x80, + 0x03, 0xC0, 0x03, 0xF0, 0x03, 0xFC, 0x00, 0x00, 0xFE, 0x04, 0x07, 0xFF, + 0xB8, 0x1F, 0x03, 0xF0, 0xF8, 0x01, 0xE3, 0xE0, 0x01, 0xC7, 0x80, 0x01, + 0x9E, 0x00, 0x01, 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x03, + 0xC0, 0x00, 0x07, 0x80, 0x07, 0xFF, 0x00, 0x07, 0xDE, 0x00, 0x07, 0xBC, + 0x00, 0x0F, 0x78, 0x00, 0x1E, 0x78, 0x00, 0x3C, 0xF0, 0x00, 0x78, 0xF0, + 0x00, 0xF1, 0xF0, 0x01, 0xE1, 0xF0, 0x03, 0xC1, 0xF8, 0x1F, 0x00, 0xFF, + 0xFC, 0x00, 0x3F, 0x80, 0xFF, 0x03, 0xFD, 0xF8, 0x07, 0xE3, 0xC0, 0x0F, + 0x0F, 0x00, 0x3C, 0x3C, 0x00, 0xF0, 0xF0, 0x03, 0xC3, 0xC0, 0x0F, 0x0F, + 0x00, 0x3C, 0x3C, 0x00, 0xF0, 0xF0, 0x03, 0xC3, 0xFF, 0xFF, 0x0F, 0xFF, + 0xFC, 0x3C, 0x00, 0xF0, 0xF0, 0x03, 0xC3, 0xC0, 0x0F, 0x0F, 0x00, 0x3C, + 0x3C, 0x00, 0xF0, 0xF0, 0x03, 0xC3, 0xC0, 0x0F, 0x0F, 0x00, 0x3C, 0x3C, + 0x00, 0xF1, 0xF8, 0x07, 0xEF, 0xF0, 0x3F, 0xC0, 0xFF, 0xBF, 0x0F, 0x07, + 0x83, 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, 0xC1, 0xE0, + 0xF0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, 0xC3, 0xF3, 0xFE, 0x0F, 0xF0, + 0x7E, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, + 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, + 0x3C, 0x03, 0xC6, 0x38, 0xF3, 0x8F, 0xF0, 0x7C, 0x00, 0xFF, 0x07, 0xFC, + 0xFC, 0x03, 0xC0, 0xF0, 0x07, 0x01, 0xE0, 0x1C, 0x03, 0xC0, 0x60, 0x07, + 0x81, 0x80, 0x0F, 0x06, 0x00, 0x1E, 0x18, 0x00, 0x3C, 0x60, 0x00, 0x79, + 0x80, 0x00, 0xFF, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xDF, 0x00, 0x07, 0x8F, + 0x00, 0x0F, 0x0F, 0x00, 0x1E, 0x0F, 0x00, 0x3C, 0x0F, 0x00, 0x78, 0x0F, + 0x00, 0xF0, 0x1F, 0x01, 0xE0, 0x1F, 0x03, 0xC0, 0x1F, 0x0F, 0xC0, 0x3F, + 0x3F, 0xC1, 0xFF, 0x80, 0xFF, 0x00, 0x0F, 0xC0, 0x00, 0xF0, 0x00, 0x1E, + 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, + 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, 0x00, 0x78, + 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x07, 0x80, 0x04, 0xF0, + 0x01, 0x1E, 0x00, 0x63, 0xC0, 0x3C, 0xFF, 0xFF, 0xBF, 0xFF, 0xE0, 0xFC, + 0x00, 0x03, 0xF9, 0xF0, 0x00, 0x1F, 0x87, 0x80, 0x01, 0xF8, 0x3E, 0x00, + 0x0F, 0xC1, 0xF0, 0x00, 0x5E, 0x0B, 0xC0, 0x06, 0xF0, 0x5E, 0x00, 0x37, + 0x82, 0x78, 0x03, 0x3C, 0x13, 0xC0, 0x19, 0xE0, 0x8F, 0x01, 0x8F, 0x04, + 0x78, 0x0C, 0x78, 0x21, 0xE0, 0xC3, 0xC1, 0x0F, 0x06, 0x1E, 0x08, 0x3C, + 0x60, 0xF0, 0x41, 0xE3, 0x07, 0x82, 0x07, 0xB0, 0x3C, 0x10, 0x3D, 0x81, + 0xE0, 0x81, 0xF8, 0x0F, 0x04, 0x07, 0xC0, 0x78, 0x20, 0x3C, 0x03, 0xC1, + 0x00, 0xE0, 0x1E, 0x1C, 0x06, 0x01, 0xFB, 0xF8, 0x10, 0x1F, 0xE0, 0xFC, + 0x00, 0xFE, 0x78, 0x00, 0x70, 0x78, 0x00, 0x40, 0xF8, 0x00, 0x81, 0xF8, + 0x01, 0x02, 0xF8, 0x02, 0x04, 0xF8, 0x04, 0x08, 0xF0, 0x08, 0x11, 0xF0, + 0x10, 0x21, 0xF0, 0x20, 0x41, 0xF0, 0x40, 0x81, 0xF0, 0x81, 0x01, 0xF1, + 0x02, 0x01, 0xE2, 0x04, 0x03, 0xE4, 0x08, 0x03, 0xE8, 0x10, 0x03, 0xF0, + 0x20, 0x03, 0xE0, 0x40, 0x03, 0xC0, 0x80, 0x03, 0x81, 0x00, 0x07, 0x07, + 0x00, 0x06, 0x3F, 0x80, 0x04, 0x00, 0x00, 0xFE, 0x00, 0x07, 0xFF, 0x00, + 0x3E, 0x0F, 0x80, 0xF0, 0x07, 0x83, 0xC0, 0x07, 0x87, 0x80, 0x07, 0x1E, + 0x00, 0x0F, 0x3C, 0x00, 0x1E, 0xF0, 0x00, 0x1F, 0xE0, 0x00, 0x3F, 0xC0, + 0x00, 0x7F, 0x80, 0x00, 0xFF, 0x00, 0x01, 0xFE, 0x00, 0x03, 0xFC, 0x00, + 0x07, 0xF8, 0x00, 0x0F, 0x78, 0x00, 0x3C, 0xF0, 0x00, 0x78, 0xE0, 0x01, + 0xE1, 0xE0, 0x03, 0xC1, 0xE0, 0x0F, 0x01, 0xF0, 0x7C, 0x00, 0xFF, 0xE0, + 0x00, 0x7F, 0x00, 0xFF, 0xF8, 0x1F, 0xFF, 0x83, 0xC1, 0xF0, 0xF0, 0x1E, + 0x3C, 0x07, 0xCF, 0x00, 0xF3, 0xC0, 0x3C, 0xF0, 0x0F, 0x3C, 0x03, 0xCF, + 0x01, 0xF3, 0xC0, 0x78, 0xF0, 0x7C, 0x3F, 0xFE, 0x0F, 0xFE, 0x03, 0xC0, + 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, + 0x3C, 0x00, 0x1F, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x07, 0xFF, + 0x00, 0x3E, 0x0F, 0x80, 0xF0, 0x07, 0x83, 0xC0, 0x07, 0x87, 0x80, 0x0F, + 0x1E, 0x00, 0x0F, 0x3C, 0x00, 0x1E, 0xF0, 0x00, 0x1D, 0xE0, 0x00, 0x3F, + 0xC0, 0x00, 0x7F, 0x80, 0x00, 0xFF, 0x00, 0x01, 0xFE, 0x00, 0x03, 0xFC, + 0x00, 0x07, 0xF8, 0x00, 0x0F, 0x70, 0x00, 0x1C, 0xF0, 0x00, 0x79, 0xE0, + 0x00, 0xF1, 0xE0, 0x03, 0xC1, 0xC0, 0x07, 0x01, 0xC0, 0x1C, 0x01, 0xE0, + 0xF0, 0x00, 0x7F, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x7E, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x0F, 0xC0, 0xFF, 0xF0, + 0x03, 0xFF, 0xF0, 0x0F, 0x07, 0xC0, 0x78, 0x1E, 0x03, 0xC0, 0x78, 0x1E, + 0x03, 0xC0, 0xF0, 0x1E, 0x07, 0x80, 0xF0, 0x3C, 0x07, 0x81, 0xE0, 0x78, + 0x0F, 0x0F, 0x80, 0x7F, 0xF8, 0x03, 0xFE, 0x00, 0x1E, 0x78, 0x00, 0xF1, + 0xE0, 0x07, 0x87, 0x80, 0x3C, 0x3C, 0x01, 0xE0, 0xF0, 0x0F, 0x03, 0xC0, + 0x78, 0x0F, 0x03, 0xC0, 0x7C, 0x3F, 0x01, 0xF3, 0xFC, 0x07, 0xE0, 0x07, + 0x84, 0x1F, 0xFC, 0x3C, 0x3E, 0x30, 0x0E, 0x70, 0x06, 0x70, 0x06, 0x70, + 0x02, 0x78, 0x00, 0x7C, 0x00, 0x3F, 0x00, 0x1F, 0xC0, 0x0F, 0xE0, 0x03, + 0xF8, 0x00, 0xFC, 0x00, 0x3E, 0x00, 0x1F, 0x80, 0x0F, 0x80, 0x0F, 0xC0, + 0x0F, 0xE0, 0x0F, 0x70, 0x1E, 0x78, 0x3C, 0x4F, 0xF8, 0x43, 0xF0, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xF0, 0x7C, 0x0F, 0x03, 0x80, 0xF0, 0x10, + 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, + 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, + 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x0F, + 0x00, 0x00, 0xF0, 0x00, 0x1F, 0x80, 0x03, 0xFC, 0x00, 0xFF, 0x01, 0xFD, + 0xF8, 0x01, 0xC3, 0xC0, 0x02, 0x0F, 0x00, 0x08, 0x3C, 0x00, 0x20, 0xF0, + 0x00, 0x83, 0xC0, 0x02, 0x0F, 0x00, 0x08, 0x3C, 0x00, 0x20, 0xF0, 0x00, + 0x83, 0xC0, 0x02, 0x0F, 0x00, 0x08, 0x3C, 0x00, 0x20, 0xF0, 0x00, 0x83, + 0xC0, 0x02, 0x0F, 0x00, 0x08, 0x3C, 0x00, 0x20, 0xF0, 0x00, 0x81, 0xE0, + 0x04, 0x07, 0x80, 0x30, 0x0F, 0x81, 0x80, 0x1F, 0xFC, 0x00, 0x1F, 0xC0, + 0x00, 0xFF, 0xC0, 0x7F, 0x3E, 0x00, 0x1E, 0x1E, 0x00, 0x0C, 0x0E, 0x00, + 0x18, 0x0F, 0x00, 0x18, 0x07, 0x00, 0x10, 0x07, 0x80, 0x30, 0x07, 0x80, + 0x30, 0x03, 0xC0, 0x60, 0x03, 0xC0, 0x60, 0x01, 0xE0, 0x40, 0x01, 0xE0, + 0xC0, 0x00, 0xF0, 0xC0, 0x00, 0xF1, 0x80, 0x00, 0x71, 0x80, 0x00, 0x7B, + 0x00, 0x00, 0x3B, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x1E, + 0x00, 0x00, 0x0C, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x08, 0x00, 0xFF, 0x9F, + 0xF0, 0x3F, 0x9F, 0x03, 0xE0, 0x07, 0x07, 0x80, 0xF0, 0x03, 0x03, 0xC0, + 0x78, 0x01, 0x80, 0xE0, 0x1E, 0x00, 0x80, 0x78, 0x0F, 0x00, 0xC0, 0x1C, + 0x03, 0x80, 0x60, 0x0F, 0x01, 0xE0, 0x20, 0x07, 0x81, 0xF0, 0x30, 0x01, + 0xC0, 0xBC, 0x18, 0x00, 0xF0, 0xDE, 0x08, 0x00, 0x78, 0x67, 0x0C, 0x00, + 0x1E, 0x23, 0xC4, 0x00, 0x0F, 0x31, 0xE6, 0x00, 0x03, 0x90, 0x7B, 0x00, + 0x01, 0xF8, 0x3D, 0x00, 0x00, 0xFC, 0x0F, 0x80, 0x00, 0x3C, 0x07, 0xC0, + 0x00, 0x1E, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0xE0, 0x00, 0x03, 0x00, 0x70, + 0x00, 0x01, 0x80, 0x10, 0x00, 0x00, 0x80, 0x08, 0x00, 0x7F, 0xE0, 0xFF, + 0x0F, 0xC0, 0x1E, 0x03, 0xE0, 0x0E, 0x00, 0xF0, 0x06, 0x00, 0x3C, 0x06, + 0x00, 0x0F, 0x06, 0x00, 0x07, 0x86, 0x00, 0x01, 0xE6, 0x00, 0x00, 0x7B, + 0x00, 0x00, 0x3F, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x03, + 0xF0, 0x00, 0x03, 0x78, 0x00, 0x01, 0x9E, 0x00, 0x01, 0x87, 0x80, 0x01, + 0x83, 0xE0, 0x01, 0x80, 0xF0, 0x01, 0x80, 0x3C, 0x01, 0x80, 0x1F, 0x01, + 0xC0, 0x07, 0xC1, 0xE0, 0x03, 0xF3, 0xFE, 0x0F, 0xFE, 0xFF, 0xC0, 0xFF, + 0x7E, 0x00, 0x1C, 0x1E, 0x00, 0x18, 0x1F, 0x00, 0x30, 0x0F, 0x00, 0x60, + 0x07, 0x80, 0x60, 0x03, 0xC0, 0xC0, 0x03, 0xE1, 0x80, 0x01, 0xE1, 0x80, + 0x00, 0xF3, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, + 0x00, 0x7E, 0x00, 0x01, 0xFF, 0x80, 0x3F, 0xFF, 0xF1, 0xFF, 0xFF, 0x9C, + 0x00, 0x78, 0xC0, 0x07, 0x84, 0x00, 0x38, 0x00, 0x03, 0xC0, 0x00, 0x3C, + 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, + 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, + 0x07, 0x00, 0x00, 0x78, 0x00, 0x47, 0x80, 0x06, 0x78, 0x00, 0x33, 0x80, + 0x07, 0x3F, 0xFF, 0xFB, 0xFF, 0xFF, 0xC0, 0xFF, 0x83, 0x06, 0x0C, 0x18, + 0x30, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x06, + 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x07, 0xF0, 0xC0, 0x18, 0x06, 0x01, + 0x80, 0x70, 0x0C, 0x03, 0x00, 0xE0, 0x18, 0x06, 0x01, 0xC0, 0x30, 0x0C, + 0x03, 0x80, 0x60, 0x18, 0x07, 0x00, 0xC0, 0x30, 0x0E, 0x01, 0x80, 0x60, + 0x1C, 0x03, 0xFE, 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x18, + 0x30, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x06, + 0x0C, 0x1F, 0xF0, 0x03, 0x80, 0x0F, 0x00, 0x1F, 0x00, 0x76, 0x00, 0xCE, + 0x03, 0x8C, 0x06, 0x1C, 0x1C, 0x18, 0x30, 0x30, 0xE0, 0x31, 0x80, 0x67, + 0x00, 0x6C, 0x00, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0xC0, 0xE0, 0x70, + 0x18, 0x0C, 0x03, 0x1F, 0x03, 0x8C, 0x38, 0x31, 0xC1, 0x8E, 0x0C, 0x00, + 0x60, 0x0F, 0x01, 0x98, 0x30, 0xC3, 0x86, 0x38, 0x31, 0xC1, 0x8E, 0x0C, + 0x78, 0xE5, 0xFB, 0xCF, 0x0C, 0x00, 0x00, 0x38, 0x00, 0xF8, 0x00, 0x38, + 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x39, + 0xF0, 0x3B, 0xFC, 0x3C, 0x3E, 0x38, 0x0E, 0x38, 0x0F, 0x38, 0x07, 0x38, + 0x07, 0x38, 0x07, 0x38, 0x07, 0x38, 0x07, 0x38, 0x06, 0x38, 0x0E, 0x38, + 0x0C, 0x3C, 0x1C, 0x1F, 0xF0, 0x07, 0xE0, 0x07, 0xE0, 0x7F, 0xE3, 0x87, + 0xD8, 0x0F, 0x60, 0x1B, 0x00, 0x0C, 0x00, 0x30, 0x00, 0xC0, 0x03, 0x00, + 0x0E, 0x00, 0x3C, 0x01, 0x78, 0x19, 0xFF, 0xC3, 0xFE, 0x03, 0xE0, 0x00, + 0x00, 0x00, 0x1C, 0x00, 0x7C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, + 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x07, 0x9C, 0x1F, 0xDC, 0x38, 0x7C, 0x70, + 0x3C, 0x70, 0x1C, 0x60, 0x1C, 0xE0, 0x1C, 0xE0, 0x1C, 0xE0, 0x1C, 0xE0, + 0x1C, 0xE0, 0x1C, 0xF0, 0x1C, 0x70, 0x1C, 0x7C, 0x3E, 0x3F, 0xDF, 0x0F, + 0x90, 0x0F, 0x81, 0xFF, 0x08, 0x3C, 0x80, 0xE7, 0xFF, 0x7F, 0xFF, 0x00, + 0x18, 0x00, 0xC0, 0x07, 0x00, 0x38, 0x03, 0xE0, 0x37, 0x83, 0x3F, 0xF0, + 0xFF, 0x03, 0xF0, 0x01, 0xF0, 0x3F, 0xC3, 0x8E, 0x18, 0x00, 0xC0, 0x0E, + 0x00, 0x70, 0x03, 0x80, 0x1C, 0x03, 0xFE, 0x1F, 0xF0, 0x38, 0x01, 0xC0, + 0x0E, 0x00, 0x70, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, + 0xC0, 0x0E, 0x00, 0x70, 0x07, 0xC0, 0xFF, 0x80, 0x0F, 0xC0, 0x1F, 0xFF, + 0x38, 0xFF, 0x70, 0x70, 0x70, 0x70, 0x70, 0x30, 0x70, 0x30, 0x70, 0x30, + 0x38, 0x20, 0x1C, 0x60, 0x0F, 0x80, 0x10, 0x00, 0x20, 0x00, 0x60, 0x00, + 0x7F, 0xE0, 0x3F, 0xFC, 0x1F, 0xFE, 0x20, 0x06, 0x40, 0x02, 0xC0, 0x02, + 0xC0, 0x04, 0xF0, 0x18, 0x7F, 0xF0, 0x1F, 0x80, 0x00, 0x00, 0x38, 0x00, + 0xF8, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, + 0x38, 0x00, 0x38, 0xF0, 0x3B, 0xF8, 0x3E, 0x3C, 0x3C, 0x1C, 0x38, 0x1C, + 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, + 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x7C, 0x3E, 0xFE, 0x7F, 0x18, 0x3C, + 0x3C, 0x18, 0x00, 0x00, 0x00, 0x00, 0x04, 0x3C, 0x7C, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x3C, 0xFF, 0x03, 0x03, + 0xC1, 0xE0, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x83, 0xC3, 0xE0, 0x70, + 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, + 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x37, 0x3B, 0xF8, 0xF8, 0x00, 0x00, + 0x1C, 0x00, 0x3E, 0x00, 0x07, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, + 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x3F, 0x8E, 0x0F, 0x07, 0x06, 0x03, + 0x86, 0x01, 0xC4, 0x00, 0xE4, 0x00, 0x7E, 0x00, 0x3F, 0x80, 0x1D, 0xC0, + 0x0E, 0x70, 0x07, 0x1C, 0x03, 0x8F, 0x01, 0xC3, 0xC0, 0xE0, 0xF0, 0xF8, + 0x3C, 0xFE, 0x7F, 0x80, 0x00, 0x1C, 0x7C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1C, 0x1C, 0x3C, 0xFF, 0x38, 0xF0, 0x7C, 0x3E, 0xFE, 0x7F, 0x83, + 0xE3, 0xF0, 0xE0, 0xE0, 0x70, 0x1C, 0x38, 0x1C, 0x07, 0x0E, 0x07, 0x01, + 0xC3, 0x81, 0xC0, 0x70, 0xE0, 0x70, 0x1C, 0x38, 0x1C, 0x07, 0x0E, 0x07, + 0x01, 0xC3, 0x81, 0xC0, 0x70, 0xE0, 0x70, 0x1C, 0x38, 0x1C, 0x07, 0x0E, + 0x07, 0x01, 0xC3, 0x81, 0xE0, 0x73, 0xF9, 0xFC, 0x7F, 0x38, 0xF0, 0xFB, + 0xF8, 0x3E, 0x3C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, + 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, + 0x1C, 0x78, 0x3C, 0xFE, 0x7F, 0x07, 0xE0, 0x1F, 0xF8, 0x3C, 0x7C, 0x78, + 0x3E, 0x70, 0x1E, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, 0xF0, + 0x0F, 0xF8, 0x0F, 0x78, 0x0E, 0x7C, 0x1C, 0x3E, 0x3C, 0x0F, 0xF0, 0x07, + 0xC0, 0x18, 0xF0, 0xFB, 0xFC, 0x3E, 0x1E, 0x38, 0x0E, 0x38, 0x0F, 0x38, + 0x07, 0x38, 0x07, 0x38, 0x07, 0x38, 0x07, 0x38, 0x07, 0x38, 0x06, 0x38, + 0x0E, 0x38, 0x0C, 0x3E, 0x1C, 0x3B, 0xF8, 0x39, 0xE0, 0x38, 0x00, 0x38, + 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, 0x00, 0x7C, 0x00, 0xFF, + 0x00, 0x07, 0xC4, 0x1F, 0xEC, 0x3C, 0x3C, 0x70, 0x1C, 0x70, 0x1C, 0x60, + 0x1C, 0xE0, 0x1C, 0xE0, 0x1C, 0xE0, 0x1C, 0xE0, 0x1C, 0xE0, 0x1C, 0xF0, + 0x1C, 0x70, 0x1C, 0x78, 0x3C, 0x3F, 0xDC, 0x1F, 0x1C, 0x00, 0x1C, 0x00, + 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x3E, 0x00, + 0xFF, 0x19, 0xFF, 0x7C, 0xF3, 0x9C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, + 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x1F, 0x07, 0xF0, 0x3E, + 0x58, 0x7C, 0x0F, 0x03, 0xC0, 0x7C, 0x07, 0x80, 0xF8, 0x1F, 0x81, 0xF8, + 0x1E, 0x03, 0xC0, 0xF0, 0x3E, 0x1A, 0x7C, 0x10, 0x30, 0x70, 0xFE, 0xFE, + 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0x79, + 0x7E, 0x3C, 0xF8, 0x7C, 0x38, 0x3C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, + 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, 0x38, 0x1C, + 0x38, 0x1C, 0x38, 0x1C, 0x3C, 0x7C, 0x1F, 0xDF, 0x0F, 0x18, 0xFE, 0x1F, + 0x7C, 0x06, 0x38, 0x04, 0x1C, 0x04, 0x1C, 0x0C, 0x0E, 0x08, 0x0E, 0x18, + 0x07, 0x10, 0x07, 0x10, 0x07, 0x20, 0x03, 0xA0, 0x03, 0xE0, 0x01, 0xC0, + 0x01, 0xC0, 0x00, 0x80, 0x00, 0x80, 0xFC, 0x7F, 0x1F, 0x78, 0x3C, 0x06, + 0x38, 0x1C, 0x04, 0x38, 0x1C, 0x04, 0x1C, 0x1C, 0x0C, 0x1C, 0x0E, 0x08, + 0x1C, 0x1E, 0x18, 0x0E, 0x17, 0x10, 0x0E, 0x37, 0x10, 0x07, 0x23, 0x30, + 0x07, 0x63, 0xA0, 0x07, 0x43, 0xE0, 0x03, 0xC1, 0xC0, 0x03, 0x81, 0xC0, + 0x01, 0x80, 0x80, 0x01, 0x00, 0x80, 0x7F, 0x7E, 0x1E, 0x0C, 0x07, 0x8C, + 0x01, 0xC4, 0x00, 0x76, 0x00, 0x3E, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x03, + 0xE0, 0x01, 0x70, 0x01, 0x1C, 0x01, 0x8F, 0x01, 0x83, 0x80, 0x80, 0xE0, + 0xC0, 0x79, 0xF0, 0xFF, 0xFE, 0x0F, 0x7C, 0x06, 0x38, 0x06, 0x1C, 0x04, + 0x1C, 0x0C, 0x0E, 0x0C, 0x0E, 0x08, 0x0F, 0x18, 0x07, 0x10, 0x07, 0x90, + 0x03, 0xB0, 0x03, 0xA0, 0x01, 0xE0, 0x01, 0xE0, 0x00, 0xC0, 0x00, 0xC0, + 0x00, 0x80, 0x00, 0x80, 0x01, 0x80, 0x01, 0x00, 0x03, 0x00, 0x7E, 0x00, + 0x7C, 0x00, 0x78, 0x00, 0x7F, 0xF9, 0xFF, 0xE6, 0x07, 0x10, 0x38, 0x00, + 0xE0, 0x07, 0x00, 0x38, 0x01, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xE0, 0x07, + 0x01, 0x38, 0x0D, 0xC0, 0x3F, 0xFF, 0xBF, 0xFE, 0x07, 0x0E, 0x1C, 0x18, + 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x30, 0x60, 0x60, + 0x10, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x1C, + 0x0E, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x70, 0x38, 0x18, + 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x08, 0x06, 0x06, + 0x08, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x38, + 0x70, 0xE0, 0x3E, 0x00, 0x7F, 0x87, 0xE3, 0xFE, 0x00, 0x7C }; + +const GFXglyph FreeSerif18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 9, 0, 1 }, // 0x20 ' ' + { 0, 4, 24, 12, 5, -23 }, // 0x21 '!' + { 12, 8, 9, 14, 3, -23 }, // 0x22 '"' + { 21, 17, 23, 17, 0, -22 }, // 0x23 '#' + { 70, 13, 27, 17, 2, -24 }, // 0x24 '$' + { 114, 25, 23, 29, 2, -22 }, // 0x25 '%' + { 186, 25, 25, 27, 1, -24 }, // 0x26 '&' + { 265, 3, 9, 7, 2, -23 }, // 0x27 ''' + { 269, 9, 30, 12, 2, -23 }, // 0x28 '(' + { 303, 9, 30, 12, 1, -22 }, // 0x29 ')' + { 337, 12, 14, 18, 3, -23 }, // 0x2A '*' + { 358, 16, 18, 20, 2, -17 }, // 0x2B '+' + { 394, 4, 9, 9, 2, -3 }, // 0x2C ',' + { 399, 8, 2, 12, 1, -8 }, // 0x2D '-' + { 401, 4, 4, 9, 2, -3 }, // 0x2E '.' + { 403, 10, 24, 10, 0, -23 }, // 0x2F '/' + { 433, 16, 24, 18, 1, -23 }, // 0x30 '0' + { 481, 10, 24, 18, 3, -23 }, // 0x31 '1' + { 511, 16, 24, 17, 1, -23 }, // 0x32 '2' + { 559, 13, 24, 17, 2, -23 }, // 0x33 '3' + { 598, 16, 23, 18, 0, -22 }, // 0x34 '4' + { 644, 13, 24, 17, 2, -23 }, // 0x35 '5' + { 683, 16, 24, 18, 1, -23 }, // 0x36 '6' + { 731, 14, 23, 18, 1, -22 }, // 0x37 '7' + { 772, 12, 25, 18, 2, -24 }, // 0x38 '8' + { 810, 16, 26, 17, 1, -24 }, // 0x39 '9' + { 862, 4, 17, 9, 2, -16 }, // 0x3A ':' + { 871, 5, 22, 9, 2, -16 }, // 0x3B ';' + { 885, 18, 18, 20, 1, -17 }, // 0x3C '<' + { 926, 18, 9, 20, 1, -12 }, // 0x3D '=' + { 947, 18, 18, 20, 1, -17 }, // 0x3E '>' + { 988, 13, 25, 16, 2, -24 }, // 0x3F '?' + { 1029, 24, 25, 30, 3, -24 }, // 0x40 '@' + { 1104, 24, 23, 25, 1, -22 }, // 0x41 'A' + { 1173, 20, 23, 22, 1, -22 }, // 0x42 'B' + { 1231, 22, 24, 23, 1, -23 }, // 0x43 'C' + { 1297, 23, 23, 25, 1, -22 }, // 0x44 'D' + { 1364, 20, 23, 21, 2, -22 }, // 0x45 'E' + { 1422, 17, 23, 20, 2, -22 }, // 0x46 'F' + { 1471, 23, 24, 25, 1, -23 }, // 0x47 'G' + { 1540, 22, 23, 25, 2, -22 }, // 0x48 'H' + { 1604, 9, 23, 11, 2, -22 }, // 0x49 'I' + { 1630, 12, 23, 13, 0, -22 }, // 0x4A 'J' + { 1665, 23, 23, 25, 2, -22 }, // 0x4B 'K' + { 1732, 19, 23, 21, 2, -22 }, // 0x4C 'L' + { 1787, 29, 23, 31, 1, -22 }, // 0x4D 'M' + { 1871, 23, 23, 25, 1, -22 }, // 0x4E 'N' + { 1938, 23, 24, 25, 1, -23 }, // 0x4F 'O' + { 2007, 18, 23, 20, 1, -22 }, // 0x50 'P' + { 2059, 23, 30, 25, 1, -23 }, // 0x51 'Q' + { 2146, 21, 23, 23, 2, -22 }, // 0x52 'R' + { 2207, 16, 24, 19, 1, -23 }, // 0x53 'S' + { 2255, 20, 23, 21, 1, -22 }, // 0x54 'T' + { 2313, 22, 23, 25, 2, -22 }, // 0x55 'U' + { 2377, 24, 23, 25, 0, -22 }, // 0x56 'V' + { 2446, 33, 23, 33, 0, -22 }, // 0x57 'W' + { 2541, 25, 23, 25, 0, -22 }, // 0x58 'X' + { 2613, 24, 23, 25, 1, -22 }, // 0x59 'Y' + { 2682, 21, 23, 21, 0, -22 }, // 0x5A 'Z' + { 2743, 7, 28, 12, 3, -22 }, // 0x5B '[' + { 2768, 10, 24, 10, 0, -23 }, // 0x5C '\' + { 2798, 7, 28, 12, 2, -22 }, // 0x5D ']' + { 2823, 15, 13, 16, 1, -22 }, // 0x5E '^' + { 2848, 18, 2, 17, 0, 3 }, // 0x5F '_' + { 2853, 8, 6, 9, 1, -23 }, // 0x60 '`' + { 2859, 13, 16, 15, 2, -15 }, // 0x61 'a' + { 2885, 16, 25, 17, 1, -24 }, // 0x62 'b' + { 2935, 14, 16, 16, 1, -15 }, // 0x63 'c' + { 2963, 16, 25, 17, 1, -24 }, // 0x64 'd' + { 3013, 13, 16, 16, 1, -15 }, // 0x65 'e' + { 3039, 13, 25, 13, 0, -24 }, // 0x66 'f' + { 3080, 16, 24, 16, 1, -15 }, // 0x67 'g' + { 3128, 16, 25, 17, 1, -24 }, // 0x68 'h' + { 3178, 8, 24, 10, 0, -23 }, // 0x69 'i' + { 3202, 9, 32, 12, 0, -23 }, // 0x6A 'j' + { 3238, 17, 25, 18, 1, -24 }, // 0x6B 'k' + { 3292, 8, 25, 9, 0, -24 }, // 0x6C 'l' + { 3317, 26, 16, 27, 1, -15 }, // 0x6D 'm' + { 3369, 16, 16, 17, 1, -15 }, // 0x6E 'n' + { 3401, 16, 16, 17, 1, -15 }, // 0x6F 'o' + { 3433, 16, 24, 17, 1, -15 }, // 0x70 'p' + { 3481, 16, 24, 17, 1, -15 }, // 0x71 'q' + { 3529, 11, 16, 12, 1, -15 }, // 0x72 'r' + { 3551, 10, 16, 13, 1, -15 }, // 0x73 's' + { 3571, 8, 19, 10, 2, -18 }, // 0x74 't' + { 3590, 16, 16, 17, 1, -15 }, // 0x75 'u' + { 3622, 16, 16, 16, 0, -15 }, // 0x76 'v' + { 3654, 24, 16, 24, 0, -15 }, // 0x77 'w' + { 3702, 17, 16, 17, 0, -15 }, // 0x78 'x' + { 3736, 16, 24, 16, 0, -15 }, // 0x79 'y' + { 3784, 14, 16, 15, 0, -15 }, // 0x7A 'z' + { 3812, 8, 30, 17, 3, -23 }, // 0x7B '{' + { 3842, 2, 24, 7, 2, -23 }, // 0x7C '|' + { 3848, 8, 30, 17, 6, -22 }, // 0x7D '}' + { 3878, 16, 4, 17, 1, -10 } }; // 0x7E '~' + +const GFXfont FreeSerif18pt7b PROGMEM = { + (uint8_t *)FreeSerif18pt7bBitmaps, + (GFXglyph *)FreeSerif18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 4558 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerif24pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerif24pt7b.h new file mode 100644 index 0000000..99ff3f4 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerif24pt7b.h @@ -0,0 +1,690 @@ +const uint8_t FreeSerif24pt7bBitmaps[] PROGMEM = { + 0x77, 0xBF, 0xFF, 0xFF, 0xFF, 0xFB, 0x9C, 0xE7, 0x39, 0xCE, 0x61, 0x08, + 0x42, 0x10, 0x84, 0x00, 0x00, 0xEF, 0xFF, 0xEE, 0x60, 0x6F, 0x0F, 0xF0, + 0xFF, 0x0F, 0xF0, 0xFF, 0x0F, 0x60, 0x66, 0x06, 0x60, 0x66, 0x06, 0x60, + 0x66, 0x06, 0x00, 0xE0, 0x70, 0x01, 0xC0, 0xE0, 0x03, 0x81, 0xC0, 0x07, + 0x03, 0x80, 0x0E, 0x06, 0x00, 0x18, 0x0C, 0x00, 0x30, 0x38, 0x00, 0xE0, + 0x70, 0x01, 0xC0, 0xE0, 0x03, 0x81, 0xC1, 0xFF, 0xFF, 0xFB, 0xFF, 0xFF, + 0xF0, 0x18, 0x0C, 0x00, 0x70, 0x38, 0x00, 0xE0, 0x70, 0x01, 0xC0, 0xE0, + 0x03, 0x81, 0xC0, 0x07, 0x03, 0x80, 0x0C, 0x06, 0x07, 0xFF, 0xFF, 0xEF, + 0xFF, 0xFF, 0xC0, 0xE0, 0x70, 0x01, 0xC0, 0xE0, 0x03, 0x81, 0xC0, 0x06, + 0x03, 0x80, 0x0C, 0x06, 0x00, 0x38, 0x1C, 0x00, 0x70, 0x38, 0x00, 0xE0, + 0x70, 0x01, 0xC0, 0xE0, 0x03, 0x81, 0xC0, 0x00, 0x00, 0x40, 0x00, 0x08, + 0x00, 0x01, 0x00, 0x01, 0xFC, 0x01, 0xE4, 0xF8, 0x70, 0x87, 0x9C, 0x10, + 0x77, 0x02, 0x06, 0xE0, 0x40, 0xDC, 0x08, 0x0B, 0x81, 0x00, 0x78, 0x20, + 0x07, 0x84, 0x00, 0xFC, 0x80, 0x0F, 0xF0, 0x00, 0xFE, 0x00, 0x07, 0xF0, + 0x00, 0x7F, 0x80, 0x03, 0xFC, 0x00, 0x3F, 0xC0, 0x05, 0xFC, 0x00, 0x8F, + 0x80, 0x10, 0xF8, 0x02, 0x0F, 0x00, 0x40, 0xF0, 0x08, 0x1E, 0x01, 0x03, + 0xE0, 0x20, 0x7C, 0x04, 0x0F, 0xC0, 0x83, 0xBC, 0x10, 0xE3, 0xE2, 0x78, + 0x3F, 0xFE, 0x00, 0xFE, 0x00, 0x01, 0x00, 0x00, 0x20, 0x00, 0x04, 0x00, + 0x01, 0xF0, 0x00, 0xC0, 0x03, 0xFC, 0x01, 0xE0, 0x03, 0xC7, 0x81, 0xE0, + 0x03, 0xC0, 0x7F, 0x60, 0x03, 0xC0, 0x20, 0x70, 0x01, 0xE0, 0x10, 0x30, + 0x01, 0xE0, 0x08, 0x38, 0x00, 0xE0, 0x04, 0x18, 0x00, 0xF0, 0x02, 0x1C, + 0x00, 0x78, 0x02, 0x0C, 0x00, 0x38, 0x01, 0x0E, 0x00, 0x1C, 0x01, 0x86, + 0x00, 0x0E, 0x00, 0x86, 0x00, 0x07, 0x00, 0x87, 0x03, 0xE1, 0x80, 0xC3, + 0x07, 0xFC, 0xE1, 0xC3, 0x87, 0xC6, 0x3F, 0xC1, 0x87, 0x81, 0x8F, 0x81, + 0xC7, 0x80, 0x40, 0x00, 0xC3, 0xC0, 0x20, 0x00, 0xE3, 0xC0, 0x10, 0x00, + 0x61, 0xC0, 0x08, 0x00, 0x61, 0xE0, 0x04, 0x00, 0x70, 0xF0, 0x06, 0x00, + 0x30, 0x70, 0x02, 0x00, 0x38, 0x38, 0x03, 0x00, 0x18, 0x1C, 0x01, 0x00, + 0x1C, 0x0E, 0x01, 0x80, 0x0C, 0x07, 0x01, 0x80, 0x0E, 0x01, 0xC3, 0x80, + 0x06, 0x00, 0x7F, 0x80, 0x06, 0x00, 0x1F, 0x00, 0x07, 0x00, 0x00, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x00, 0x70, 0xE0, 0x00, + 0x00, 0xE0, 0x60, 0x00, 0x00, 0xC0, 0x30, 0x00, 0x01, 0xC0, 0x30, 0x00, + 0x01, 0xC0, 0x30, 0x00, 0x01, 0xC0, 0x30, 0x00, 0x01, 0xC0, 0x70, 0x00, + 0x01, 0xE0, 0xE0, 0x00, 0x01, 0xE1, 0xC0, 0x00, 0x00, 0xF3, 0x80, 0x00, + 0x00, 0xFF, 0x0F, 0xFC, 0x00, 0xFC, 0x03, 0xF0, 0x00, 0xF8, 0x01, 0xE0, + 0x01, 0xFC, 0x01, 0xC0, 0x07, 0x7C, 0x01, 0xC0, 0x0F, 0x3E, 0x01, 0x80, + 0x1E, 0x3E, 0x03, 0x00, 0x3C, 0x1F, 0x03, 0x00, 0x7C, 0x1F, 0x06, 0x00, + 0x78, 0x0F, 0x86, 0x00, 0x78, 0x07, 0xCC, 0x00, 0xF8, 0x07, 0xE8, 0x00, + 0xF8, 0x03, 0xF8, 0x00, 0xF8, 0x01, 0xF0, 0x00, 0xF8, 0x01, 0xF8, 0x00, + 0xFC, 0x00, 0xFC, 0x01, 0xFC, 0x01, 0xFE, 0x01, 0x7E, 0x03, 0xBF, 0x86, + 0x7F, 0x0F, 0x1F, 0xFE, 0x3F, 0xFC, 0x0F, 0xF8, 0x0F, 0xE0, 0x03, 0xF0, + 0x6F, 0xFF, 0xFF, 0x66, 0x66, 0x66, 0x00, 0x10, 0x02, 0x00, 0xC0, 0x18, + 0x03, 0x00, 0x60, 0x0E, 0x00, 0xC0, 0x1C, 0x03, 0x80, 0x38, 0x03, 0x80, + 0x78, 0x07, 0x00, 0x70, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, + 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x07, 0x00, 0x70, 0x07, 0x80, + 0x38, 0x03, 0x80, 0x38, 0x01, 0xC0, 0x0C, 0x00, 0xC0, 0x06, 0x00, 0x30, + 0x01, 0x80, 0x0C, 0x00, 0x60, 0x03, 0xC0, 0x06, 0x00, 0x30, 0x01, 0x80, + 0x0C, 0x00, 0x60, 0x07, 0x00, 0x30, 0x03, 0x80, 0x1C, 0x01, 0xC0, 0x1C, + 0x01, 0xE0, 0x0E, 0x00, 0xE0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0E, 0x00, 0xE0, 0x1E, + 0x01, 0xC0, 0x1C, 0x01, 0xC0, 0x38, 0x03, 0x00, 0x70, 0x0E, 0x00, 0xC0, + 0x18, 0x03, 0x00, 0x40, 0x08, 0x00, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, + 0x43, 0x86, 0xE1, 0x0F, 0xF1, 0x1F, 0xF9, 0x3E, 0x3D, 0x78, 0x07, 0xC0, + 0x01, 0x00, 0x07, 0xC0, 0x19, 0x30, 0xF9, 0x1E, 0xF1, 0x0F, 0xE1, 0x07, + 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0x00, 0x38, 0x00, 0x00, + 0x70, 0x00, 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, + 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, + 0x00, 0x00, 0xE0, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0x07, 0x00, + 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, + 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, + 0x0E, 0x00, 0x00, 0x73, 0xEF, 0xFF, 0x7C, 0x10, 0x42, 0x08, 0xC6, 0x00, + 0xFF, 0xFF, 0xFC, 0x77, 0xFF, 0xF7, 0x00, 0x00, 0x1C, 0x00, 0xE0, 0x03, + 0x80, 0x0E, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, 0x38, 0x00, 0xE0, 0x03, + 0x80, 0x1C, 0x00, 0x70, 0x01, 0xC0, 0x0E, 0x00, 0x38, 0x01, 0xE0, 0x07, + 0x00, 0x1C, 0x00, 0xF0, 0x03, 0x80, 0x0E, 0x00, 0x78, 0x01, 0xC0, 0x07, + 0x00, 0x3C, 0x00, 0xE0, 0x03, 0x80, 0x1E, 0x00, 0x70, 0x01, 0xC0, 0x0F, + 0x00, 0x38, 0x00, 0x00, 0xFC, 0x00, 0x0E, 0x1C, 0x00, 0x70, 0x38, 0x03, + 0x80, 0x70, 0x1E, 0x01, 0xE0, 0xF0, 0x03, 0x83, 0xC0, 0x0F, 0x0F, 0x00, + 0x3C, 0x7C, 0x00, 0xF9, 0xE0, 0x01, 0xE7, 0x80, 0x07, 0xBE, 0x00, 0x1F, + 0xF8, 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0x80, 0x07, 0xFE, 0x00, 0x1F, 0xF8, + 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0x80, 0x07, 0xFE, 0x00, 0x1F, 0xF8, 0x00, + 0x7F, 0xE0, 0x01, 0xF7, 0x80, 0x07, 0x9E, 0x00, 0x1E, 0x7C, 0x00, 0xF8, + 0xF0, 0x03, 0xC3, 0xC0, 0x0F, 0x07, 0x00, 0x38, 0x1E, 0x01, 0xE0, 0x38, + 0x07, 0x00, 0x70, 0x38, 0x00, 0xE1, 0xC0, 0x00, 0xFC, 0x00, 0x00, 0x80, + 0x1C, 0x03, 0xE0, 0x7F, 0x0C, 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xF0, 0x07, + 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1E, 0x00, 0xF0, + 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x1E, 0x00, + 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x3F, + 0x0F, 0xFF, 0x01, 0xF8, 0x00, 0x3F, 0xF0, 0x07, 0xFF, 0xE0, 0x70, 0x3F, + 0x83, 0x00, 0x7C, 0x30, 0x01, 0xF1, 0x00, 0x0F, 0x98, 0x00, 0x3C, 0x80, + 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0x80, 0x00, 0x1C, + 0x00, 0x01, 0xC0, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00, + 0x70, 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, + 0x03, 0x00, 0x00, 0x30, 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, 0x43, 0x00, + 0x02, 0x30, 0x00, 0x23, 0xFF, 0xFF, 0x3F, 0xFF, 0xF3, 0xFF, 0xFF, 0x80, + 0x03, 0xF8, 0x03, 0xFF, 0x01, 0x83, 0xE0, 0x80, 0x3C, 0x40, 0x0F, 0x10, + 0x01, 0xC8, 0x00, 0x70, 0x00, 0x1C, 0x00, 0x06, 0x00, 0x03, 0x00, 0x00, + 0x80, 0x00, 0xC0, 0x00, 0x78, 0x00, 0x7F, 0x80, 0x7F, 0xF0, 0x01, 0xFE, + 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x01, 0xC0, + 0x00, 0x70, 0x00, 0x1C, 0x00, 0x07, 0x00, 0x01, 0x80, 0x00, 0x60, 0x00, + 0x30, 0x00, 0x0C, 0x70, 0x06, 0x3F, 0x07, 0x0F, 0xFF, 0x00, 0xFF, 0x00, + 0x00, 0x03, 0x00, 0x00, 0x38, 0x00, 0x01, 0xC0, 0x00, 0x1E, 0x00, 0x01, + 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xDC, 0x00, 0x0C, 0xE0, 0x00, 0x47, 0x00, + 0x06, 0x38, 0x00, 0x61, 0xC0, 0x06, 0x0E, 0x00, 0x30, 0x70, 0x03, 0x03, + 0x80, 0x30, 0x1C, 0x01, 0x80, 0xE0, 0x18, 0x07, 0x01, 0x80, 0x38, 0x08, + 0x01, 0xC0, 0xC0, 0x0E, 0x0C, 0x00, 0x70, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, + 0xE0, 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00, 0x38, 0x00, 0x01, 0xC0, 0x00, + 0x0E, 0x00, 0x00, 0x70, 0x00, 0x03, 0x80, 0x00, 0x1C, 0x00, 0x00, 0x00, + 0x40, 0x7F, 0xF8, 0x1F, 0xFE, 0x03, 0xFF, 0xC0, 0xC0, 0x00, 0x18, 0x00, + 0x06, 0x00, 0x00, 0xC0, 0x00, 0x1C, 0x00, 0x07, 0xF8, 0x00, 0xFF, 0xC0, + 0x3F, 0xFE, 0x00, 0xFF, 0xE0, 0x01, 0xFE, 0x00, 0x0F, 0xE0, 0x00, 0x7C, + 0x00, 0x07, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x1C, + 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x30, + 0x00, 0x0E, 0x00, 0x01, 0x80, 0x00, 0x71, 0xE0, 0x1C, 0x3F, 0x07, 0x07, + 0xFF, 0x80, 0x3F, 0x80, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x0F, + 0x80, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, + 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, + 0x07, 0xC7, 0xE0, 0x3E, 0xFF, 0xC3, 0xF8, 0x3F, 0x1F, 0x80, 0x7C, 0xF8, + 0x03, 0xF7, 0xC0, 0x0F, 0xBE, 0x00, 0x7F, 0xF0, 0x01, 0xFF, 0x80, 0x0F, + 0xFC, 0x00, 0x7F, 0xE0, 0x03, 0xFF, 0x00, 0x1F, 0x78, 0x00, 0xFB, 0xE0, + 0x07, 0x9F, 0x00, 0x3C, 0x78, 0x03, 0xE3, 0xE0, 0x1E, 0x0F, 0x81, 0xE0, + 0x3E, 0x1E, 0x00, 0xFF, 0xE0, 0x00, 0xFC, 0x00, 0x3F, 0xFF, 0xF3, 0xFF, + 0xFF, 0x3F, 0xFF, 0xE7, 0x00, 0x0E, 0x40, 0x00, 0xEC, 0x00, 0x1C, 0x80, + 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x03, 0x80, + 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x00, 0xE0, + 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x38, + 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x07, + 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x1E, 0x00, 0x01, + 0xC0, 0x00, 0x03, 0xF0, 0x03, 0xFF, 0x03, 0xC1, 0xE0, 0xC0, 0x1C, 0x70, + 0x07, 0x18, 0x00, 0xEE, 0x00, 0x3B, 0x80, 0x0E, 0xF0, 0x03, 0xBC, 0x00, + 0xE7, 0x80, 0x71, 0xF0, 0x38, 0x3E, 0x1C, 0x07, 0xEE, 0x00, 0xFE, 0x00, + 0x1F, 0xC0, 0x03, 0xF8, 0x03, 0xFF, 0x01, 0xC7, 0xE0, 0xE0, 0xFC, 0x70, + 0x0F, 0x98, 0x01, 0xEE, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x01, 0xF8, 0x00, + 0x7E, 0x00, 0x1F, 0xC0, 0x07, 0x70, 0x03, 0x9E, 0x00, 0xE3, 0xE0, 0xF0, + 0x7F, 0xF0, 0x07, 0xF0, 0x00, 0x01, 0xF8, 0x00, 0x3F, 0xF0, 0x03, 0xC3, + 0xE0, 0x3C, 0x0F, 0x83, 0xC0, 0x3C, 0x3E, 0x00, 0xF1, 0xE0, 0x07, 0xCF, + 0x00, 0x3E, 0xF8, 0x00, 0xF7, 0xC0, 0x07, 0xFE, 0x00, 0x3F, 0xF0, 0x01, + 0xFF, 0x80, 0x0F, 0xFC, 0x00, 0x7F, 0xF0, 0x03, 0xEF, 0x80, 0x1F, 0x7C, + 0x00, 0xF9, 0xF0, 0x0F, 0xC7, 0xE1, 0xFC, 0x1F, 0xF9, 0xE0, 0x3F, 0x1F, + 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x78, 0x00, 0x07, 0xC0, 0x00, + 0x7C, 0x00, 0x03, 0xC0, 0x00, 0x3C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, + 0x0F, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x00, 0x77, 0xFF, 0xF7, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xBF, 0xFF, 0xB8, 0x39, 0xF7, + 0xDF, 0x38, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x73, 0xEF, + 0xFF, 0x7C, 0x10, 0x42, 0x08, 0xC6, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x07, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x07, + 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xE0, + 0x00, 0x3F, 0x80, 0x00, 0xFE, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xF8, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0x3F, 0x80, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0x00, 0x00, 0x01, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, 0xE0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x07, + 0xF8, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x3F, 0xC0, 0x00, 0xFF, + 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFE, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0xE0, + 0x0F, 0xFE, 0x0C, 0x1F, 0x88, 0x03, 0xEC, 0x01, 0xF7, 0x00, 0x7F, 0xC0, + 0x3F, 0xE0, 0x1F, 0x70, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xC0, 0x01, 0xE0, + 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x70, 0x00, 0x70, 0x00, 0x30, 0x00, 0x10, + 0x00, 0x18, 0x00, 0x08, 0x00, 0x04, 0x00, 0x06, 0x00, 0x02, 0x00, 0x01, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x38, 0x00, 0x3E, 0x00, + 0x1F, 0x00, 0x0F, 0x80, 0x03, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x3F, + 0xFF, 0x00, 0x00, 0xFC, 0x07, 0xC0, 0x01, 0xE0, 0x00, 0xE0, 0x07, 0xC0, + 0x00, 0x30, 0x0F, 0x00, 0x00, 0x18, 0x1E, 0x00, 0x00, 0x0C, 0x1E, 0x00, + 0x00, 0x04, 0x3C, 0x00, 0xF8, 0x06, 0x3C, 0x01, 0xFD, 0xC2, 0x78, 0x03, + 0xC7, 0xC3, 0x78, 0x07, 0x07, 0x81, 0xF0, 0x0E, 0x03, 0x81, 0xF0, 0x0E, + 0x03, 0x81, 0xF0, 0x1C, 0x07, 0x81, 0xF0, 0x1C, 0x07, 0x01, 0xF0, 0x38, + 0x07, 0x01, 0xF0, 0x38, 0x07, 0x03, 0xF0, 0x38, 0x0F, 0x02, 0xF0, 0x38, + 0x0E, 0x02, 0xF0, 0x38, 0x1E, 0x04, 0x78, 0x38, 0x1E, 0x0C, 0x78, 0x1C, + 0x6E, 0x18, 0x38, 0x1F, 0xC7, 0xF0, 0x3C, 0x0F, 0x03, 0xE0, 0x1E, 0x00, + 0x00, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x07, 0xC0, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x60, 0x00, 0xFC, 0x03, 0xE0, 0x00, 0x3F, + 0xFF, 0x80, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x01, + 0x80, 0x00, 0x00, 0x03, 0x80, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x07, + 0xC0, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x0D, + 0xF0, 0x00, 0x00, 0x0D, 0xF0, 0x00, 0x00, 0x18, 0xF0, 0x00, 0x00, 0x18, + 0xF8, 0x00, 0x00, 0x38, 0x78, 0x00, 0x00, 0x30, 0x7C, 0x00, 0x00, 0x30, + 0x7C, 0x00, 0x00, 0x60, 0x3E, 0x00, 0x00, 0x60, 0x3E, 0x00, 0x00, 0xE0, + 0x1E, 0x00, 0x00, 0xC0, 0x1F, 0x00, 0x00, 0xC0, 0x1F, 0x00, 0x01, 0x80, + 0x0F, 0x80, 0x01, 0xFF, 0xFF, 0x80, 0x03, 0xFF, 0xFF, 0xC0, 0x03, 0x00, + 0x07, 0xC0, 0x07, 0x00, 0x07, 0xC0, 0x06, 0x00, 0x03, 0xE0, 0x06, 0x00, + 0x03, 0xE0, 0x0E, 0x00, 0x01, 0xF0, 0x0C, 0x00, 0x01, 0xF0, 0x1C, 0x00, + 0x01, 0xF8, 0x3C, 0x00, 0x01, 0xF8, 0x7E, 0x00, 0x01, 0xFC, 0xFF, 0x80, + 0x0F, 0xFF, 0xFF, 0xFF, 0xE0, 0x03, 0xFF, 0xFF, 0x80, 0x1F, 0x01, 0xF8, + 0x03, 0xE0, 0x0F, 0x80, 0x7C, 0x00, 0xF8, 0x0F, 0x80, 0x1F, 0x81, 0xF0, + 0x01, 0xF0, 0x3E, 0x00, 0x3E, 0x07, 0xC0, 0x07, 0xC0, 0xF8, 0x00, 0xF8, + 0x1F, 0x00, 0x1F, 0x03, 0xE0, 0x07, 0xC0, 0x7C, 0x01, 0xF0, 0x0F, 0x80, + 0xFC, 0x01, 0xFF, 0xFE, 0x00, 0x3F, 0xFF, 0xC0, 0x07, 0xC0, 0x7F, 0x00, + 0xF8, 0x01, 0xF0, 0x1F, 0x00, 0x1F, 0x03, 0xE0, 0x03, 0xE0, 0x7C, 0x00, + 0x3E, 0x0F, 0x80, 0x07, 0xC1, 0xF0, 0x00, 0xF8, 0x3E, 0x00, 0x1F, 0x07, + 0xC0, 0x03, 0xE0, 0xF8, 0x00, 0xF8, 0x1F, 0x00, 0x1F, 0x03, 0xE0, 0x07, + 0xC0, 0x7C, 0x07, 0xF0, 0x1F, 0xFF, 0xFC, 0x3F, 0xFF, 0xFC, 0x00, 0x00, + 0x1F, 0xF0, 0x20, 0x07, 0xFF, 0xEE, 0x01, 0xF8, 0x1F, 0xE0, 0x3E, 0x00, + 0x7E, 0x07, 0x80, 0x01, 0xE0, 0xF0, 0x00, 0x1E, 0x1F, 0x00, 0x00, 0xE3, + 0xE0, 0x00, 0x06, 0x3C, 0x00, 0x00, 0x67, 0xC0, 0x00, 0x02, 0x7C, 0x00, + 0x00, 0x27, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x80, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x01, 0xF0, 0x00, + 0x02, 0x0F, 0x80, 0x00, 0xE0, 0x7E, 0x00, 0x1C, 0x03, 0xF8, 0x0F, 0x00, + 0x0F, 0xFF, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0xFF, 0xFF, 0xC0, 0x00, 0x7F, + 0xFF, 0xF8, 0x00, 0x3E, 0x03, 0xFC, 0x00, 0x7C, 0x00, 0xFC, 0x00, 0xF8, + 0x00, 0x7E, 0x01, 0xF0, 0x00, 0x7E, 0x03, 0xE0, 0x00, 0x7C, 0x07, 0xC0, + 0x00, 0x7C, 0x0F, 0x80, 0x00, 0xF8, 0x1F, 0x00, 0x00, 0xF8, 0x3E, 0x00, + 0x01, 0xF0, 0x7C, 0x00, 0x03, 0xF0, 0xF8, 0x00, 0x03, 0xE1, 0xF0, 0x00, + 0x07, 0xC3, 0xE0, 0x00, 0x0F, 0x87, 0xC0, 0x00, 0x1F, 0x0F, 0x80, 0x00, + 0x3E, 0x1F, 0x00, 0x00, 0x7C, 0x3E, 0x00, 0x00, 0xF8, 0x7C, 0x00, 0x01, + 0xF0, 0xF8, 0x00, 0x07, 0xC1, 0xF0, 0x00, 0x0F, 0x83, 0xE0, 0x00, 0x1E, + 0x07, 0xC0, 0x00, 0x7C, 0x0F, 0x80, 0x01, 0xF0, 0x1F, 0x00, 0x03, 0xE0, + 0x3E, 0x00, 0x1F, 0x80, 0x7C, 0x00, 0x7C, 0x00, 0xF8, 0x0F, 0xF0, 0x07, + 0xFF, 0xFF, 0x80, 0x3F, 0xFF, 0xF0, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0x07, + 0xFF, 0xFF, 0xE0, 0x7C, 0x00, 0x1C, 0x0F, 0x80, 0x01, 0x81, 0xF0, 0x00, + 0x30, 0x3E, 0x00, 0x02, 0x07, 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x20, 0x0F, 0x80, 0x04, + 0x01, 0xF0, 0x01, 0x80, 0x3E, 0x00, 0x70, 0x07, 0xFF, 0xFE, 0x00, 0xFF, + 0xFF, 0xC0, 0x1F, 0x00, 0x38, 0x03, 0xE0, 0x03, 0x00, 0x7C, 0x00, 0x20, + 0x0F, 0x80, 0x04, 0x01, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x07, 0xC0, + 0x00, 0x00, 0xF8, 0x00, 0x03, 0x1F, 0x00, 0x00, 0x43, 0xE0, 0x00, 0x18, + 0x7C, 0x00, 0x07, 0x0F, 0x80, 0x01, 0xC1, 0xF0, 0x00, 0xF8, 0x7F, 0xFF, + 0xFF, 0x3F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0x1F, + 0x00, 0x07, 0x1F, 0x00, 0x03, 0x1F, 0x00, 0x03, 0x1F, 0x00, 0x01, 0x1F, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, + 0x00, 0x08, 0x1F, 0x00, 0x08, 0x1F, 0x00, 0x18, 0x1F, 0x00, 0x38, 0x1F, + 0xFF, 0xF8, 0x1F, 0xFF, 0xF8, 0x1F, 0x00, 0x38, 0x1F, 0x00, 0x18, 0x1F, + 0x00, 0x08, 0x1F, 0x00, 0x08, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x3F, 0x80, 0x00, 0xFF, + 0xF0, 0x00, 0x00, 0x0F, 0xF0, 0x08, 0x00, 0xFF, 0xFE, 0x70, 0x07, 0xE0, + 0x1F, 0xE0, 0x1F, 0x00, 0x0F, 0xC0, 0x78, 0x00, 0x07, 0x81, 0xE0, 0x00, + 0x07, 0x07, 0xC0, 0x00, 0x0E, 0x1F, 0x00, 0x00, 0x0C, 0x3E, 0x00, 0x00, + 0x08, 0xF8, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, + 0x7C, 0x00, 0x03, 0xFF, 0xF8, 0x00, 0x01, 0xFD, 0xF0, 0x00, 0x01, 0xF3, + 0xE0, 0x00, 0x03, 0xE7, 0xC0, 0x00, 0x07, 0xCF, 0x80, 0x00, 0x0F, 0x8F, + 0x80, 0x00, 0x1F, 0x1F, 0x00, 0x00, 0x3E, 0x3E, 0x00, 0x00, 0x7C, 0x3E, + 0x00, 0x00, 0xF8, 0x7C, 0x00, 0x01, 0xF0, 0x7C, 0x00, 0x03, 0xE0, 0xFC, + 0x00, 0x07, 0xC0, 0xFC, 0x00, 0x0F, 0x80, 0x7C, 0x00, 0x3F, 0x00, 0x7F, + 0x01, 0xFC, 0x00, 0x3F, 0xFF, 0xC0, 0x00, 0x0F, 0xF8, 0x00, 0xFF, 0xE0, + 0x1F, 0xFC, 0xFE, 0x00, 0x1F, 0xC1, 0xF0, 0x00, 0x3E, 0x07, 0xC0, 0x00, + 0xF8, 0x1F, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0x3E, + 0x07, 0xC0, 0x00, 0xF8, 0x1F, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x0F, 0x81, + 0xF0, 0x00, 0x3E, 0x07, 0xC0, 0x00, 0xF8, 0x1F, 0x00, 0x03, 0xE0, 0x7C, + 0x00, 0x0F, 0x81, 0xFF, 0xFF, 0xFE, 0x07, 0xFF, 0xFF, 0xF8, 0x1F, 0x00, + 0x03, 0xE0, 0x7C, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0x3E, 0x07, 0xC0, 0x00, + 0xF8, 0x1F, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x0F, 0x81, 0xF0, 0x00, 0x3E, + 0x07, 0xC0, 0x00, 0xF8, 0x1F, 0x00, 0x03, 0xE0, 0x7C, 0x00, 0x0F, 0x81, + 0xF0, 0x00, 0x3E, 0x07, 0xC0, 0x00, 0xF8, 0x1F, 0x00, 0x03, 0xE0, 0xFE, + 0x00, 0x1F, 0xCF, 0xFE, 0x01, 0xFF, 0xC0, 0xFF, 0xF8, 0xFE, 0x03, 0xE0, + 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x03, + 0xE0, 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, + 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, + 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x0F, 0xE3, 0xFF, 0xE0, 0x0F, 0xFF, + 0x80, 0xFE, 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, + 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x1F, 0x00, + 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x7C, + 0x00, 0x3E, 0x00, 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, + 0xF0, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3C, 0x0E, 0x1E, 0x0F, 0x8F, 0x07, + 0xCF, 0x01, 0xFF, 0x00, 0x7E, 0x00, 0xFF, 0xF8, 0x3F, 0xFC, 0x3F, 0xC0, + 0x07, 0xE0, 0x0F, 0x80, 0x07, 0x80, 0x0F, 0x80, 0x07, 0x00, 0x0F, 0x80, + 0x0E, 0x00, 0x0F, 0x80, 0x1C, 0x00, 0x0F, 0x80, 0x38, 0x00, 0x0F, 0x80, + 0x70, 0x00, 0x0F, 0x80, 0xE0, 0x00, 0x0F, 0x81, 0xC0, 0x00, 0x0F, 0x83, + 0x80, 0x00, 0x0F, 0x87, 0x00, 0x00, 0x0F, 0x9E, 0x00, 0x00, 0x0F, 0xBC, + 0x00, 0x00, 0x0F, 0xFE, 0x00, 0x00, 0x0F, 0xFF, 0x00, 0x00, 0x0F, 0xDF, + 0x80, 0x00, 0x0F, 0x8F, 0xC0, 0x00, 0x0F, 0x87, 0xE0, 0x00, 0x0F, 0x83, + 0xF0, 0x00, 0x0F, 0x81, 0xF8, 0x00, 0x0F, 0x80, 0xFC, 0x00, 0x0F, 0x80, + 0x7E, 0x00, 0x0F, 0x80, 0x3F, 0x00, 0x0F, 0x80, 0x3F, 0x80, 0x0F, 0x80, + 0x1F, 0x80, 0x0F, 0x80, 0x0F, 0xC0, 0x0F, 0x80, 0x07, 0xE0, 0x0F, 0x80, + 0x07, 0xF0, 0x1F, 0xC0, 0x07, 0xFC, 0xFF, 0xF8, 0x3F, 0xFF, 0xFF, 0xF0, + 0x00, 0x0F, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x7C, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, 0x00, + 0x00, 0x7C, 0x00, 0x01, 0x1F, 0x00, 0x00, 0xC7, 0xC0, 0x00, 0x21, 0xF0, + 0x00, 0x18, 0x7C, 0x00, 0x0E, 0x1F, 0x00, 0x1F, 0x8F, 0xFF, 0xFF, 0xCF, + 0xFF, 0xFF, 0xF0, 0xFF, 0x80, 0x00, 0x03, 0xFE, 0x7F, 0x80, 0x00, 0x07, + 0xF0, 0x3F, 0x00, 0x00, 0x1F, 0xC0, 0x7E, 0x00, 0x00, 0x3F, 0x80, 0xFE, + 0x00, 0x00, 0xFF, 0x01, 0xFC, 0x00, 0x01, 0xBE, 0x03, 0x7C, 0x00, 0x03, + 0x7C, 0x06, 0xF8, 0x00, 0x0E, 0xF8, 0x0D, 0xF8, 0x00, 0x19, 0xF0, 0x19, + 0xF0, 0x00, 0x73, 0xE0, 0x33, 0xF0, 0x00, 0xC7, 0xC0, 0x63, 0xE0, 0x03, + 0x8F, 0x80, 0xC7, 0xE0, 0x06, 0x1F, 0x01, 0x87, 0xC0, 0x1C, 0x3E, 0x03, + 0x0F, 0xC0, 0x30, 0x7C, 0x06, 0x0F, 0x80, 0x60, 0xF8, 0x0C, 0x1F, 0x81, + 0x81, 0xF0, 0x18, 0x1F, 0x03, 0x03, 0xE0, 0x30, 0x3F, 0x0C, 0x07, 0xC0, + 0x60, 0x3E, 0x18, 0x0F, 0x80, 0xC0, 0x7C, 0x70, 0x1F, 0x01, 0x80, 0x7C, + 0xC0, 0x3E, 0x03, 0x00, 0xFB, 0x80, 0x7C, 0x06, 0x00, 0xFE, 0x00, 0xF8, + 0x0C, 0x01, 0xFC, 0x01, 0xF0, 0x18, 0x03, 0xF0, 0x03, 0xE0, 0x30, 0x03, + 0xE0, 0x07, 0xC0, 0x60, 0x07, 0x80, 0x0F, 0x81, 0xE0, 0x07, 0x00, 0x1F, + 0x07, 0xE0, 0x0C, 0x00, 0xFF, 0x3F, 0xF0, 0x08, 0x07, 0xFF, 0x80, 0xFF, + 0x00, 0x03, 0xFF, 0x3F, 0x80, 0x00, 0xFC, 0x1F, 0xC0, 0x00, 0x78, 0x0F, + 0xC0, 0x00, 0x30, 0x0F, 0xE0, 0x00, 0x30, 0x0F, 0xF0, 0x00, 0x30, 0x0D, + 0xF8, 0x00, 0x30, 0x0D, 0xFC, 0x00, 0x30, 0x0C, 0xFC, 0x00, 0x30, 0x0C, + 0x7E, 0x00, 0x30, 0x0C, 0x3F, 0x00, 0x30, 0x0C, 0x1F, 0x80, 0x30, 0x0C, + 0x1F, 0xC0, 0x30, 0x0C, 0x0F, 0xE0, 0x30, 0x0C, 0x07, 0xE0, 0x30, 0x0C, + 0x03, 0xF0, 0x30, 0x0C, 0x01, 0xF8, 0x30, 0x0C, 0x01, 0xFC, 0x30, 0x0C, + 0x00, 0xFE, 0x30, 0x0C, 0x00, 0x7E, 0x30, 0x0C, 0x00, 0x3F, 0x30, 0x0C, + 0x00, 0x1F, 0xB0, 0x0C, 0x00, 0x0F, 0xF0, 0x0C, 0x00, 0x0F, 0xF0, 0x0C, + 0x00, 0x07, 0xF0, 0x0C, 0x00, 0x03, 0xF0, 0x0C, 0x00, 0x01, 0xF0, 0x0C, + 0x00, 0x00, 0xF0, 0x1E, 0x00, 0x00, 0xF0, 0x3F, 0x00, 0x00, 0x70, 0xFF, + 0xC0, 0x00, 0x30, 0x00, 0x00, 0x00, 0x10, 0x00, 0x1F, 0xE0, 0x00, 0x03, + 0xFF, 0xF0, 0x00, 0x1F, 0x03, 0xE0, 0x01, 0xF0, 0x03, 0xE0, 0x0F, 0x80, + 0x07, 0xC0, 0x7C, 0x00, 0x0F, 0x01, 0xE0, 0x00, 0x1E, 0x0F, 0x80, 0x00, + 0x7C, 0x3C, 0x00, 0x00, 0xF1, 0xF0, 0x00, 0x03, 0xE7, 0xC0, 0x00, 0x0F, + 0x9E, 0x00, 0x00, 0x1E, 0xF8, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0x01, 0xFF, + 0x80, 0x00, 0x07, 0xFE, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x7F, 0xE0, + 0x00, 0x01, 0xFF, 0x80, 0x00, 0x07, 0xFE, 0x00, 0x00, 0x1F, 0xF8, 0x00, + 0x00, 0x7D, 0xF0, 0x00, 0x03, 0xE7, 0xC0, 0x00, 0x0F, 0x9F, 0x00, 0x00, + 0x3E, 0x3C, 0x00, 0x00, 0xF0, 0xF8, 0x00, 0x07, 0xC1, 0xE0, 0x00, 0x1E, + 0x07, 0xC0, 0x00, 0xF8, 0x0F, 0x80, 0x07, 0xC0, 0x1F, 0x00, 0x3E, 0x00, + 0x1F, 0x03, 0xE0, 0x00, 0x3F, 0xFF, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0xFF, + 0xFF, 0x00, 0x7F, 0xFF, 0x80, 0x7C, 0x1F, 0xC0, 0xF8, 0x07, 0xC1, 0xF0, + 0x07, 0xC3, 0xE0, 0x0F, 0x87, 0xC0, 0x0F, 0x8F, 0x80, 0x1F, 0x1F, 0x00, + 0x3E, 0x3E, 0x00, 0x7C, 0x7C, 0x00, 0xF8, 0xF8, 0x01, 0xF1, 0xF0, 0x07, + 0xC3, 0xE0, 0x0F, 0x87, 0xC0, 0x3E, 0x0F, 0x81, 0xF8, 0x1F, 0xFF, 0xC0, + 0x3F, 0xFE, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, + 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x07, 0xF0, + 0x00, 0x3F, 0xFC, 0x00, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFF, 0xF8, + 0x00, 0x07, 0xC0, 0xF8, 0x00, 0x3E, 0x00, 0x7C, 0x00, 0xF8, 0x00, 0x7C, + 0x03, 0xE0, 0x00, 0x7C, 0x07, 0x80, 0x00, 0x78, 0x1F, 0x00, 0x00, 0xF8, + 0x3C, 0x00, 0x00, 0xF0, 0xF8, 0x00, 0x01, 0xF1, 0xF0, 0x00, 0x03, 0xE3, + 0xC0, 0x00, 0x03, 0xCF, 0x80, 0x00, 0x07, 0xDF, 0x00, 0x00, 0x0F, 0xBE, + 0x00, 0x00, 0x1F, 0x7C, 0x00, 0x00, 0x3E, 0xF8, 0x00, 0x00, 0x7D, 0xF0, + 0x00, 0x00, 0xFB, 0xE0, 0x00, 0x01, 0xF7, 0xC0, 0x00, 0x03, 0xEF, 0x80, + 0x00, 0x07, 0xCF, 0x00, 0x00, 0x1F, 0x1F, 0x00, 0x00, 0x3E, 0x3E, 0x00, + 0x00, 0x7C, 0x3C, 0x00, 0x01, 0xF0, 0x7C, 0x00, 0x03, 0xE0, 0x78, 0x00, + 0x0F, 0x80, 0x78, 0x00, 0x1E, 0x00, 0x78, 0x00, 0x78, 0x00, 0x7C, 0x03, + 0xE0, 0x00, 0x3F, 0x3F, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x03, 0xF8, + 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x1F, + 0x03, 0xF8, 0x01, 0xF0, 0x0F, 0x80, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x03, + 0xE0, 0x1F, 0x00, 0x3E, 0x01, 0xF0, 0x03, 0xE0, 0x1F, 0x00, 0x3E, 0x01, + 0xF0, 0x03, 0xE0, 0x1F, 0x00, 0x3E, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, + 0x7C, 0x01, 0xF0, 0x0F, 0x80, 0x1F, 0x07, 0xF0, 0x01, 0xFF, 0xFC, 0x00, + 0x1F, 0xFE, 0x00, 0x01, 0xF1, 0xF0, 0x00, 0x1F, 0x1F, 0x80, 0x01, 0xF0, + 0xF8, 0x00, 0x1F, 0x07, 0xC0, 0x01, 0xF0, 0x3E, 0x00, 0x1F, 0x03, 0xF0, + 0x01, 0xF0, 0x1F, 0x80, 0x1F, 0x00, 0xFC, 0x01, 0xF0, 0x07, 0xC0, 0x1F, + 0x00, 0x7E, 0x01, 0xF0, 0x03, 0xF0, 0x1F, 0x00, 0x1F, 0x83, 0xF8, 0x00, + 0xFC, 0xFF, 0xF0, 0x0F, 0xF0, 0x03, 0xF0, 0x20, 0x7F, 0xF3, 0x07, 0xC1, + 0xF8, 0x78, 0x03, 0xC3, 0x80, 0x0E, 0x3C, 0x00, 0x31, 0xE0, 0x01, 0xCF, + 0x00, 0x06, 0x7C, 0x00, 0x33, 0xE0, 0x01, 0x9F, 0x80, 0x00, 0x7E, 0x00, + 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0xE0, 0x00, 0xFF, 0xC0, 0x01, + 0xFF, 0x00, 0x07, 0xFE, 0x00, 0x0F, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0x7F, + 0x00, 0x01, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x00, 0xFE, 0x00, + 0x07, 0xF8, 0x00, 0x3F, 0xC0, 0x01, 0xEF, 0x00, 0x1F, 0x3C, 0x01, 0xF1, + 0xF8, 0x1F, 0x0C, 0xFF, 0xF0, 0x40, 0xFE, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xC0, 0x7C, 0x07, 0xF0, 0x0F, 0x80, 0x3C, 0x01, 0xF0, + 0x07, 0x00, 0x3E, 0x00, 0x60, 0x07, 0xC0, 0x08, 0x00, 0xF8, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, + 0x00, 0x01, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, + 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x07, + 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x7F, + 0x00, 0x00, 0x7F, 0xFC, 0x00, 0xFF, 0xF8, 0x03, 0xFF, 0x3F, 0xE0, 0x00, + 0xFC, 0x0F, 0x80, 0x00, 0x78, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, + 0x30, 0x0F, 0x80, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x20, 0x07, 0xC0, 0x00, + 0x60, 0x07, 0xC0, 0x00, 0x60, 0x03, 0xE0, 0x00, 0xC0, 0x03, 0xF0, 0x01, + 0xC0, 0x01, 0xFC, 0x07, 0x80, 0x00, 0x7F, 0xFE, 0x00, 0x00, 0x0F, 0xF8, + 0x00, 0xFF, 0xF8, 0x01, 0xFF, 0x3F, 0xC0, 0x00, 0x7E, 0x0F, 0x80, 0x00, + 0x3C, 0x0F, 0xC0, 0x00, 0x38, 0x07, 0xC0, 0x00, 0x38, 0x07, 0xC0, 0x00, + 0x30, 0x03, 0xE0, 0x00, 0x70, 0x03, 0xE0, 0x00, 0x60, 0x01, 0xF0, 0x00, + 0x60, 0x01, 0xF0, 0x00, 0xE0, 0x01, 0xF8, 0x00, 0xC0, 0x00, 0xF8, 0x01, + 0xC0, 0x00, 0xF8, 0x01, 0x80, 0x00, 0x7C, 0x01, 0x80, 0x00, 0x7C, 0x03, + 0x80, 0x00, 0x3E, 0x03, 0x00, 0x00, 0x3E, 0x07, 0x00, 0x00, 0x1F, 0x06, + 0x00, 0x00, 0x1F, 0x06, 0x00, 0x00, 0x1F, 0x8E, 0x00, 0x00, 0x0F, 0x8C, + 0x00, 0x00, 0x0F, 0x9C, 0x00, 0x00, 0x07, 0xD8, 0x00, 0x00, 0x07, 0xD8, + 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x00, 0xE0, + 0x00, 0x00, 0x00, 0xC0, 0x00, 0x00, 0x00, 0x40, 0x00, 0xFF, 0xF1, 0xFF, + 0xF0, 0x1F, 0xF3, 0xF8, 0x07, 0xF8, 0x00, 0x7C, 0x1F, 0x80, 0x3F, 0x00, + 0x03, 0x80, 0xF8, 0x01, 0xF0, 0x00, 0x30, 0x0F, 0x80, 0x1F, 0x00, 0x03, + 0x00, 0x7C, 0x00, 0xF8, 0x00, 0x30, 0x07, 0xC0, 0x0F, 0x80, 0x06, 0x00, + 0x3E, 0x00, 0x7C, 0x00, 0x60, 0x03, 0xE0, 0x07, 0xC0, 0x06, 0x00, 0x3E, + 0x00, 0x7C, 0x00, 0xC0, 0x01, 0xF0, 0x07, 0xE0, 0x0C, 0x00, 0x1F, 0x00, + 0xFE, 0x01, 0xC0, 0x01, 0xF0, 0x0D, 0xE0, 0x18, 0x00, 0x0F, 0x80, 0xDF, + 0x01, 0x80, 0x00, 0xF8, 0x19, 0xF0, 0x30, 0x00, 0x07, 0xC1, 0x8F, 0x83, + 0x00, 0x00, 0x7C, 0x38, 0xF8, 0x30, 0x00, 0x07, 0xC3, 0x0F, 0x86, 0x00, + 0x00, 0x3E, 0x30, 0x7C, 0x60, 0x00, 0x03, 0xE7, 0x07, 0xCE, 0x00, 0x00, + 0x3E, 0x60, 0x3E, 0xC0, 0x00, 0x01, 0xF6, 0x03, 0xEC, 0x00, 0x00, 0x1F, + 0xE0, 0x3F, 0xC0, 0x00, 0x01, 0xFC, 0x01, 0xF8, 0x00, 0x00, 0x0F, 0xC0, + 0x1F, 0x80, 0x00, 0x00, 0xF8, 0x01, 0xF8, 0x00, 0x00, 0x0F, 0x80, 0x0F, + 0x00, 0x00, 0x00, 0x78, 0x00, 0xF0, 0x00, 0x00, 0x07, 0x00, 0x07, 0x00, + 0x00, 0x00, 0x70, 0x00, 0x60, 0x00, 0x00, 0x03, 0x00, 0x06, 0x00, 0x00, + 0x00, 0x20, 0x00, 0x20, 0x00, 0x7F, 0xFE, 0x03, 0xFF, 0x8F, 0xF8, 0x00, + 0x7E, 0x01, 0xFC, 0x00, 0x1C, 0x00, 0x7E, 0x00, 0x1C, 0x00, 0x1F, 0x00, + 0x0C, 0x00, 0x07, 0xC0, 0x0E, 0x00, 0x03, 0xF0, 0x0E, 0x00, 0x00, 0xF8, + 0x0E, 0x00, 0x00, 0x3E, 0x06, 0x00, 0x00, 0x1F, 0x86, 0x00, 0x00, 0x07, + 0xC7, 0x00, 0x00, 0x01, 0xF7, 0x00, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x00, + 0x3F, 0x00, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x03, 0x9F, 0x00, 0x00, + 0x01, 0x8F, 0xC0, 0x00, 0x01, 0x83, 0xF0, 0x00, 0x01, 0xC0, 0xF8, 0x00, + 0x01, 0xC0, 0x7E, 0x00, 0x01, 0xC0, 0x1F, 0x80, 0x01, 0xC0, 0x07, 0xC0, + 0x00, 0xC0, 0x03, 0xF0, 0x00, 0xE0, 0x00, 0xFC, 0x00, 0xE0, 0x00, 0x7F, + 0x00, 0xF0, 0x00, 0x1F, 0x80, 0xFC, 0x00, 0x1F, 0xF3, 0xFF, 0x80, 0x7F, + 0xFE, 0xFF, 0xF8, 0x03, 0xFF, 0x3F, 0xE0, 0x00, 0x7C, 0x1F, 0xC0, 0x00, + 0x78, 0x0F, 0xC0, 0x00, 0x70, 0x07, 0xE0, 0x00, 0x60, 0x03, 0xF0, 0x00, + 0xE0, 0x01, 0xF0, 0x01, 0xC0, 0x01, 0xF8, 0x01, 0x80, 0x00, 0xFC, 0x03, + 0x80, 0x00, 0x7C, 0x07, 0x00, 0x00, 0x7E, 0x06, 0x00, 0x00, 0x3F, 0x0E, + 0x00, 0x00, 0x1F, 0x1C, 0x00, 0x00, 0x1F, 0x98, 0x00, 0x00, 0x0F, 0xF8, + 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x07, 0xF0, + 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x3F, 0xFF, 0xFF, 0xC7, 0xFF, 0xFF, 0xF8, + 0xF0, 0x00, 0x3E, 0x38, 0x00, 0x0F, 0x86, 0x00, 0x03, 0xF0, 0xC0, 0x00, + 0x7C, 0x10, 0x00, 0x1F, 0x02, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF8, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xFC, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF8, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x7E, + 0x00, 0x01, 0x0F, 0x80, 0x00, 0x63, 0xF0, 0x00, 0x0C, 0xFC, 0x00, 0x03, + 0xBF, 0x00, 0x00, 0xE7, 0xC0, 0x00, 0x7D, 0xFF, 0xFF, 0xFF, 0xBF, 0xFF, + 0xFF, 0xF0, 0xFF, 0xF0, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, + 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, + 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, + 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0F, 0x07, 0xFC, 0xE0, 0x01, 0xC0, + 0x07, 0x00, 0x1C, 0x00, 0x38, 0x00, 0xE0, 0x03, 0x80, 0x07, 0x00, 0x1C, + 0x00, 0x70, 0x00, 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x1C, 0x00, 0x70, 0x01, + 0xC0, 0x03, 0x80, 0x0E, 0x00, 0x38, 0x00, 0x70, 0x01, 0xC0, 0x07, 0x00, + 0x0E, 0x00, 0x38, 0x00, 0xE0, 0x01, 0xC0, 0x07, 0x00, 0x1E, 0x00, 0x38, + 0x00, 0xE0, 0x03, 0xC0, 0x07, 0xFF, 0x83, 0xC0, 0xE0, 0x70, 0x38, 0x1C, + 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, + 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, + 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x3F, 0xFC, + 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0x80, 0x03, 0xDC, + 0x00, 0x39, 0xC0, 0x07, 0x9E, 0x00, 0x70, 0xE0, 0x0F, 0x0F, 0x00, 0xE0, + 0x70, 0x1E, 0x07, 0x81, 0xC0, 0x38, 0x3C, 0x03, 0xC3, 0x80, 0x1C, 0x78, + 0x01, 0xE7, 0x00, 0x0E, 0xF0, 0x00, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xE0, 0x3C, 0x0F, 0x81, 0xF0, 0x1E, 0x03, 0xC0, 0x38, 0x07, 0x03, + 0xF0, 0x07, 0x0E, 0x03, 0x81, 0xC1, 0xE0, 0x30, 0x78, 0x0E, 0x1E, 0x03, + 0x83, 0x00, 0xE0, 0x00, 0x38, 0x00, 0x3E, 0x00, 0x73, 0x80, 0x70, 0xE0, + 0x70, 0x38, 0x38, 0x0E, 0x1C, 0x03, 0x8F, 0x00, 0xE3, 0xC0, 0x38, 0xF0, + 0x0E, 0x3E, 0x07, 0x8F, 0xC3, 0xE1, 0xFF, 0x3F, 0x1F, 0x07, 0x80, 0x06, + 0x00, 0x01, 0xF0, 0x00, 0x3F, 0x80, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, + 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, + 0x00, 0x07, 0x80, 0x00, 0x3C, 0x7E, 0x01, 0xEF, 0xFC, 0x0F, 0xC3, 0xF0, + 0x7C, 0x07, 0x83, 0xC0, 0x3E, 0x1E, 0x00, 0xF0, 0xF0, 0x07, 0xC7, 0x80, + 0x1E, 0x3C, 0x00, 0xF1, 0xE0, 0x07, 0x8F, 0x00, 0x3C, 0x78, 0x01, 0xE3, + 0xC0, 0x0F, 0x1E, 0x00, 0x70, 0xF0, 0x03, 0x87, 0x80, 0x38, 0x3C, 0x01, + 0xC1, 0xE0, 0x1C, 0x0F, 0xC1, 0xC0, 0x1F, 0xFC, 0x00, 0x3F, 0x80, 0x01, + 0xFC, 0x00, 0xFF, 0xE0, 0x38, 0x3E, 0x0E, 0x03, 0xE3, 0x80, 0x7C, 0xE0, + 0x07, 0x18, 0x00, 0x03, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x80, + 0x00, 0x70, 0x00, 0x0E, 0x00, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x1B, 0xC0, + 0x02, 0x7C, 0x01, 0x87, 0xE0, 0x60, 0x7F, 0xF8, 0x07, 0xFE, 0x00, 0x3F, + 0x00, 0x00, 0x00, 0x60, 0x00, 0x0F, 0x80, 0x00, 0xFE, 0x00, 0x00, 0x78, + 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, + 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x7C, 0x78, 0x07, 0xFD, + 0xE0, 0x3C, 0x3F, 0x81, 0xC0, 0x3E, 0x0E, 0x00, 0xF8, 0x38, 0x01, 0xE1, + 0xE0, 0x07, 0x87, 0x00, 0x1E, 0x3C, 0x00, 0x78, 0xF0, 0x01, 0xE3, 0xC0, + 0x07, 0x8F, 0x00, 0x1E, 0x3C, 0x00, 0x78, 0xF0, 0x01, 0xE3, 0xE0, 0x07, + 0x87, 0x80, 0x1E, 0x1F, 0x00, 0x78, 0x3E, 0x03, 0xE0, 0xFC, 0x1F, 0xF0, + 0xFF, 0xDF, 0x00, 0xFC, 0x60, 0x03, 0xF8, 0x03, 0xFF, 0x01, 0xC1, 0xE0, + 0xC0, 0x3C, 0x70, 0x0F, 0x98, 0x01, 0xE7, 0xFF, 0xFB, 0xFF, 0xFE, 0xE0, + 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, 0x80, 0x00, 0xF0, 0x00, 0x3C, 0x00, + 0x1F, 0x00, 0x05, 0xE0, 0x02, 0x7C, 0x01, 0x8F, 0xC1, 0xC3, 0xFF, 0xE0, + 0x7F, 0xF0, 0x07, 0xF0, 0x00, 0x00, 0x7E, 0x00, 0xFF, 0xC0, 0xE3, 0xE0, + 0x60, 0x70, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x1E, 0x00, 0x0F, 0x00, + 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x07, 0xFF, 0x83, 0xFF, 0xC0, 0x3C, + 0x00, 0x1E, 0x00, 0x0F, 0x00, 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x00, + 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x0F, 0x00, 0x07, 0x80, + 0x03, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x3F, + 0x00, 0xFF, 0xF0, 0x00, 0x01, 0xF8, 0x00, 0x3F, 0xF0, 0x03, 0xC7, 0xFE, + 0x3C, 0x1F, 0xF1, 0xC0, 0x70, 0x1E, 0x03, 0xC0, 0xF0, 0x0E, 0x07, 0x80, + 0x70, 0x3C, 0x03, 0x81, 0xE0, 0x1C, 0x07, 0x80, 0xC0, 0x3E, 0x0E, 0x00, + 0x78, 0xE0, 0x01, 0xFC, 0x00, 0x18, 0x00, 0x01, 0x80, 0x00, 0x18, 0x00, + 0x01, 0xE0, 0x00, 0x0F, 0xFF, 0xC0, 0x3F, 0xFF, 0x80, 0xFF, 0xFE, 0x0C, + 0x00, 0x38, 0xC0, 0x00, 0x4C, 0x00, 0x02, 0x60, 0x00, 0x17, 0x00, 0x01, + 0x38, 0x00, 0x09, 0xE0, 0x00, 0x87, 0xC0, 0x38, 0x1F, 0xFF, 0x00, 0x3F, + 0xC0, 0x00, 0x06, 0x00, 0x00, 0xF8, 0x00, 0x0F, 0xE0, 0x00, 0x07, 0x80, + 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, + 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x87, 0xE0, 0x1E, + 0x7F, 0xC0, 0x7B, 0x0F, 0x81, 0xF8, 0x1E, 0x07, 0x80, 0x3C, 0x1E, 0x00, + 0xF0, 0x78, 0x03, 0xC1, 0xE0, 0x0F, 0x07, 0x80, 0x3C, 0x1E, 0x00, 0xF0, + 0x78, 0x03, 0xC1, 0xE0, 0x0F, 0x07, 0x80, 0x3C, 0x1E, 0x00, 0xF0, 0x78, + 0x03, 0xC1, 0xE0, 0x0F, 0x07, 0x80, 0x3C, 0x1E, 0x00, 0xF0, 0x78, 0x03, + 0xC3, 0xF0, 0x1F, 0x9F, 0xF1, 0xFF, 0x0E, 0x03, 0xE0, 0x7C, 0x0F, 0x80, + 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x80, 0x70, + 0x7E, 0x1F, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, + 0x03, 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x07, + 0xE7, 0xFF, 0x00, 0xE0, 0x1F, 0x01, 0xF0, 0x1F, 0x00, 0xE0, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x70, 0x3F, 0x07, + 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, + 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, + 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x00, 0xE0, 0x0E, 0xE0, + 0xEF, 0x1C, 0xFF, 0x87, 0xE0, 0x06, 0x00, 0x00, 0x7C, 0x00, 0x03, 0xF8, + 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x80, + 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x78, 0x00, + 0x00, 0xF0, 0x7F, 0xE1, 0xE0, 0x3E, 0x03, 0xC0, 0x70, 0x07, 0x81, 0x80, + 0x0F, 0x06, 0x00, 0x1E, 0x18, 0x00, 0x3C, 0x60, 0x00, 0x79, 0x80, 0x00, + 0xFF, 0x00, 0x01, 0xFF, 0x00, 0x03, 0xDE, 0x00, 0x07, 0x9E, 0x00, 0x0F, + 0x3E, 0x00, 0x1E, 0x3E, 0x00, 0x3C, 0x3E, 0x00, 0x78, 0x3C, 0x00, 0xF0, + 0x3C, 0x01, 0xE0, 0x7C, 0x03, 0xC0, 0x7C, 0x0F, 0xC0, 0xFE, 0x7F, 0xE3, + 0xFF, 0x03, 0x03, 0xE1, 0xFC, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, + 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, + 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x01, + 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x07, 0xE7, 0xFF, 0x1E, 0x1F, 0x01, + 0xF8, 0x1F, 0xCF, 0xF0, 0xFF, 0x80, 0xFF, 0x0F, 0x70, 0xF8, 0x0F, 0x81, + 0xF8, 0x0F, 0x01, 0xE0, 0x1E, 0x00, 0xF0, 0x3C, 0x03, 0xC0, 0x1E, 0x07, + 0x80, 0x78, 0x03, 0xC0, 0xF0, 0x0F, 0x00, 0x78, 0x1E, 0x01, 0xE0, 0x0F, + 0x03, 0xC0, 0x3C, 0x01, 0xE0, 0x78, 0x07, 0x80, 0x3C, 0x0F, 0x00, 0xF0, + 0x07, 0x81, 0xE0, 0x1E, 0x00, 0xF0, 0x3C, 0x03, 0xC0, 0x1E, 0x07, 0x80, + 0x78, 0x03, 0xC0, 0xF0, 0x0F, 0x00, 0x78, 0x1E, 0x01, 0xE0, 0x0F, 0x03, + 0xC0, 0x3C, 0x01, 0xE0, 0x78, 0x07, 0x80, 0x3C, 0x1F, 0x81, 0xF8, 0x0F, + 0xCF, 0xFC, 0xFF, 0xC7, 0xFE, 0x1E, 0x1F, 0x83, 0xF9, 0xFF, 0x03, 0xFC, + 0x3E, 0x07, 0xC0, 0x7C, 0x1E, 0x00, 0xF0, 0x78, 0x03, 0xC1, 0xE0, 0x0F, + 0x07, 0x80, 0x3C, 0x1E, 0x00, 0xF0, 0x78, 0x03, 0xC1, 0xE0, 0x0F, 0x07, + 0x80, 0x3C, 0x1E, 0x00, 0xF0, 0x78, 0x03, 0xC1, 0xE0, 0x0F, 0x07, 0x80, + 0x3C, 0x1E, 0x00, 0xF0, 0x78, 0x03, 0xC1, 0xE0, 0x0F, 0x0F, 0xC0, 0x7E, + 0x7F, 0xC3, 0xFC, 0x01, 0xFE, 0x00, 0x1F, 0xFE, 0x00, 0xF0, 0x7C, 0x0F, + 0x80, 0xF8, 0x3C, 0x01, 0xF1, 0xE0, 0x03, 0xE7, 0x80, 0x0F, 0xBE, 0x00, + 0x3F, 0xF8, 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0x80, 0x07, 0xFE, 0x00, 0x1F, + 0xF8, 0x00, 0x7F, 0xF0, 0x01, 0xE7, 0xC0, 0x07, 0x9F, 0x80, 0x3E, 0x3E, + 0x00, 0xF0, 0x7C, 0x07, 0x80, 0xF8, 0x3C, 0x01, 0xFF, 0xE0, 0x00, 0xFC, + 0x00, 0x0E, 0x3F, 0x07, 0xF7, 0xFE, 0x07, 0xE0, 0xF8, 0x3E, 0x03, 0xE1, + 0xE0, 0x0F, 0x0F, 0x00, 0x7C, 0x78, 0x03, 0xE3, 0xC0, 0x0F, 0x1E, 0x00, + 0x78, 0xF0, 0x03, 0xC7, 0x80, 0x1E, 0x3C, 0x00, 0xF1, 0xE0, 0x07, 0x8F, + 0x00, 0x38, 0x78, 0x03, 0xC3, 0xC0, 0x1E, 0x1E, 0x00, 0xE0, 0xF8, 0x0E, + 0x07, 0xE0, 0xE0, 0x3D, 0xFE, 0x01, 0xE7, 0xC0, 0x0F, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, + 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x1F, 0x80, 0x03, 0xFF, 0x80, 0x00, 0x01, + 0xF8, 0x20, 0x3F, 0xF3, 0x03, 0xC1, 0xF8, 0x3C, 0x07, 0xC3, 0xC0, 0x1E, + 0x1C, 0x00, 0xF1, 0xE0, 0x07, 0x8E, 0x00, 0x3C, 0xF0, 0x01, 0xE7, 0x80, + 0x0F, 0x3C, 0x00, 0x79, 0xE0, 0x03, 0xCF, 0x00, 0x1E, 0x78, 0x00, 0xF3, + 0xE0, 0x07, 0x9F, 0x00, 0x3C, 0x7C, 0x01, 0xE3, 0xE0, 0x1F, 0x0F, 0xC1, + 0xF8, 0x3F, 0xF3, 0xC0, 0x7E, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, + 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, + 0xC0, 0x00, 0x1E, 0x00, 0x03, 0xF8, 0x00, 0x7F, 0xE0, 0x06, 0x3C, 0xFC, + 0xFE, 0xFA, 0x78, 0xF8, 0x71, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0F, 0x00, + 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, + 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x01, 0xF8, 0x0F, 0xFC, + 0x00, 0x1F, 0x91, 0x87, 0x98, 0x1D, 0xC0, 0x6E, 0x03, 0x70, 0x0B, 0xC0, + 0x5F, 0x80, 0x7E, 0x01, 0xFC, 0x07, 0xF0, 0x0F, 0xE0, 0x3F, 0x00, 0x7E, + 0x01, 0xF0, 0x07, 0xC0, 0x3E, 0x01, 0xF8, 0x0D, 0xE0, 0xC8, 0xF8, 0x00, + 0x04, 0x00, 0xC0, 0x0C, 0x01, 0xC0, 0x3C, 0x07, 0xFC, 0xFF, 0xC3, 0xC0, + 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, + 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xE2, + 0x1F, 0xC0, 0xF8, 0xFC, 0x0F, 0xE1, 0xF0, 0x0F, 0x83, 0xC0, 0x1E, 0x0F, + 0x00, 0x78, 0x3C, 0x01, 0xE0, 0xF0, 0x07, 0x83, 0xC0, 0x1E, 0x0F, 0x00, + 0x78, 0x3C, 0x01, 0xE0, 0xF0, 0x07, 0x83, 0xC0, 0x1E, 0x0F, 0x00, 0x78, + 0x3C, 0x01, 0xE0, 0xF0, 0x07, 0x83, 0xC0, 0x1E, 0x0F, 0x00, 0x78, 0x3C, + 0x01, 0xE0, 0xF8, 0x0F, 0x81, 0xF0, 0xFF, 0x03, 0xFE, 0x7F, 0x07, 0xE1, + 0xC0, 0xFF, 0x81, 0xFC, 0xFC, 0x01, 0xC1, 0xE0, 0x07, 0x07, 0x80, 0x18, + 0x0F, 0x00, 0x60, 0x3C, 0x01, 0x00, 0x78, 0x0C, 0x01, 0xE0, 0x30, 0x07, + 0x81, 0x80, 0x0F, 0x06, 0x00, 0x3C, 0x10, 0x00, 0x78, 0xC0, 0x01, 0xE3, + 0x00, 0x03, 0x98, 0x00, 0x0F, 0x60, 0x00, 0x3D, 0x00, 0x00, 0x7C, 0x00, + 0x01, 0xF0, 0x00, 0x03, 0x80, 0x00, 0x0E, 0x00, 0x00, 0x30, 0x00, 0x00, + 0x40, 0x00, 0xFF, 0x8F, 0xF8, 0x3F, 0x7E, 0x07, 0xE0, 0x0E, 0x3E, 0x03, + 0xC0, 0x0C, 0x1E, 0x03, 0xE0, 0x0C, 0x1E, 0x01, 0xE0, 0x0C, 0x1E, 0x01, + 0xE0, 0x18, 0x0F, 0x00, 0xF0, 0x18, 0x0F, 0x01, 0xF0, 0x10, 0x07, 0x81, + 0xF0, 0x30, 0x07, 0x81, 0x78, 0x30, 0x07, 0x83, 0x78, 0x60, 0x03, 0xC3, + 0x38, 0x60, 0x03, 0xC6, 0x3C, 0x40, 0x01, 0xC6, 0x3C, 0xC0, 0x01, 0xEC, + 0x1E, 0xC0, 0x01, 0xEC, 0x1F, 0x80, 0x00, 0xF8, 0x0F, 0x80, 0x00, 0xF8, + 0x0F, 0x00, 0x00, 0x70, 0x0F, 0x00, 0x00, 0x70, 0x07, 0x00, 0x00, 0x60, + 0x06, 0x00, 0x00, 0x20, 0x02, 0x00, 0x7F, 0xE7, 0xF0, 0x7E, 0x0F, 0x00, + 0xF8, 0x38, 0x01, 0xE0, 0xC0, 0x07, 0xC6, 0x00, 0x0F, 0x30, 0x00, 0x1E, + 0xC0, 0x00, 0x7E, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x07, 0xC0, + 0x00, 0x3F, 0x00, 0x00, 0xDE, 0x00, 0x06, 0x7C, 0x00, 0x30, 0xF0, 0x01, + 0xC1, 0xE0, 0x06, 0x07, 0xC0, 0x30, 0x0F, 0x01, 0xC0, 0x1E, 0x0F, 0x00, + 0xFC, 0xFE, 0x07, 0xFC, 0xFF, 0xC0, 0xFC, 0xFC, 0x01, 0xE1, 0xE0, 0x03, + 0x07, 0x80, 0x18, 0x0F, 0x00, 0x60, 0x3C, 0x01, 0x80, 0x78, 0x0C, 0x01, + 0xE0, 0x30, 0x03, 0xC0, 0xC0, 0x0F, 0x06, 0x00, 0x3E, 0x18, 0x00, 0x78, + 0x40, 0x01, 0xF3, 0x00, 0x03, 0xCC, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0x80, + 0x00, 0x7C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x06, 0x00, 0x00, + 0x18, 0x00, 0x00, 0x40, 0x00, 0x03, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x60, + 0x00, 0x01, 0x80, 0x00, 0x0C, 0x00, 0x0F, 0xF0, 0x00, 0x7F, 0x80, 0x01, + 0xFC, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7F, 0xFF, 0x9F, 0xFF, 0xE6, 0x00, + 0xF1, 0x00, 0x78, 0x40, 0x3E, 0x00, 0x0F, 0x00, 0x07, 0x80, 0x03, 0xE0, + 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x07, 0x80, 0x03, + 0xE0, 0x01, 0xF0, 0x04, 0x78, 0x01, 0x3E, 0x00, 0xDF, 0x00, 0x37, 0x80, + 0x1F, 0xFF, 0xFE, 0xFF, 0xFF, 0x80, 0x01, 0xE0, 0x78, 0x1C, 0x07, 0x80, + 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, + 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x70, 0x1C, 0x0E, 0x00, 0x70, + 0x07, 0x00, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, + 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x01, 0xC0, + 0x1E, 0x00, 0xE0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xE0, 0x0F, 0x00, 0x70, 0x0F, 0x00, 0xE0, 0x1C, 0x03, + 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, + 0x70, 0x0E, 0x01, 0xC0, 0x1C, 0x01, 0xC0, 0x0E, 0x07, 0x01, 0xC0, 0x70, + 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, + 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x3C, 0x07, 0x03, 0xC0, 0xF0, 0x00, + 0x1F, 0x80, 0x00, 0xFF, 0x80, 0xC7, 0x0F, 0x87, 0xB8, 0x0F, 0xFC, 0x00, + 0x07, 0xC0 }; + +const GFXglyph FreeSerif24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 12, 0, 1 }, // 0x20 ' ' + { 0, 5, 32, 16, 6, -31 }, // 0x21 '!' + { 20, 12, 12, 19, 4, -31 }, // 0x22 '"' + { 38, 23, 31, 23, 0, -30 }, // 0x23 '#' + { 128, 19, 37, 24, 2, -33 }, // 0x24 '$' + { 216, 33, 32, 39, 3, -30 }, // 0x25 '%' + { 348, 32, 33, 37, 2, -31 }, // 0x26 '&' + { 480, 4, 12, 9, 3, -31 }, // 0x27 ''' + { 486, 12, 40, 16, 2, -31 }, // 0x28 '(' + { 546, 12, 40, 16, 2, -30 }, // 0x29 ')' + { 606, 16, 19, 24, 4, -30 }, // 0x2A '*' + { 644, 23, 23, 27, 2, -22 }, // 0x2B '+' + { 711, 6, 11, 12, 2, -4 }, // 0x2C ',' + { 720, 11, 2, 16, 2, -10 }, // 0x2D '-' + { 723, 5, 5, 12, 3, -3 }, // 0x2E '.' + { 727, 14, 32, 14, 0, -30 }, // 0x2F '/' + { 783, 22, 33, 23, 1, -31 }, // 0x30 '0' + { 874, 13, 32, 24, 5, -31 }, // 0x31 '1' + { 926, 21, 31, 23, 1, -30 }, // 0x32 '2' + { 1008, 18, 32, 23, 2, -30 }, // 0x33 '3' + { 1080, 21, 31, 24, 1, -30 }, // 0x34 '4' + { 1162, 19, 33, 24, 2, -31 }, // 0x35 '5' + { 1241, 21, 33, 23, 2, -31 }, // 0x36 '6' + { 1328, 20, 31, 24, 1, -30 }, // 0x37 '7' + { 1406, 18, 33, 23, 3, -31 }, // 0x38 '8' + { 1481, 21, 33, 24, 1, -31 }, // 0x39 '9' + { 1568, 5, 22, 12, 4, -20 }, // 0x3A ':' + { 1582, 6, 27, 12, 3, -20 }, // 0x3B ';' + { 1603, 24, 25, 27, 1, -24 }, // 0x3C '<' + { 1678, 24, 11, 27, 1, -16 }, // 0x3D '=' + { 1711, 24, 25, 27, 2, -23 }, // 0x3E '>' + { 1786, 17, 32, 21, 3, -31 }, // 0x3F '?' + { 1854, 32, 33, 41, 4, -31 }, // 0x40 '@' + { 1986, 32, 32, 34, 1, -31 }, // 0x41 'A' + { 2114, 27, 31, 30, 0, -30 }, // 0x42 'B' + { 2219, 28, 33, 31, 2, -31 }, // 0x43 'C' + { 2335, 31, 31, 34, 1, -30 }, // 0x44 'D' + { 2456, 27, 31, 29, 2, -30 }, // 0x45 'E' + { 2561, 24, 31, 27, 2, -30 }, // 0x46 'F' + { 2654, 31, 33, 35, 2, -31 }, // 0x47 'G' + { 2782, 30, 31, 34, 2, -30 }, // 0x48 'H' + { 2899, 13, 31, 15, 1, -30 }, // 0x49 'I' + { 2950, 17, 32, 18, 0, -30 }, // 0x4A 'J' + { 3018, 32, 31, 33, 1, -30 }, // 0x4B 'K' + { 3142, 26, 31, 29, 2, -30 }, // 0x4C 'L' + { 3243, 39, 31, 41, 1, -30 }, // 0x4D 'M' + { 3395, 32, 32, 34, 1, -30 }, // 0x4E 'N' + { 3523, 30, 33, 34, 2, -31 }, // 0x4F 'O' + { 3647, 23, 31, 27, 2, -30 }, // 0x50 'P' + { 3737, 31, 40, 34, 2, -31 }, // 0x51 'Q' + { 3892, 28, 31, 31, 2, -30 }, // 0x52 'R' + { 4001, 21, 33, 25, 2, -31 }, // 0x53 'S' + { 4088, 27, 31, 28, 1, -30 }, // 0x54 'T' + { 4193, 32, 32, 34, 1, -30 }, // 0x55 'U' + { 4321, 32, 32, 33, 0, -30 }, // 0x56 'V' + { 4449, 44, 32, 45, 0, -30 }, // 0x57 'W' + { 4625, 33, 31, 34, 0, -30 }, // 0x58 'X' + { 4753, 32, 31, 33, 0, -30 }, // 0x59 'Y' + { 4877, 27, 31, 29, 1, -30 }, // 0x5A 'Z' + { 4982, 9, 38, 16, 4, -30 }, // 0x5B '[' + { 5025, 14, 32, 14, 0, -30 }, // 0x5C '\' + { 5081, 9, 38, 16, 3, -30 }, // 0x5D ']' + { 5124, 20, 17, 22, 1, -30 }, // 0x5E '^' + { 5167, 24, 2, 23, 0, 5 }, // 0x5F '_' + { 5173, 10, 8, 12, 1, -31 }, // 0x60 '`' + { 5183, 18, 21, 20, 1, -20 }, // 0x61 'a' + { 5231, 21, 32, 24, 1, -31 }, // 0x62 'b' + { 5315, 19, 21, 21, 1, -20 }, // 0x63 'c' + { 5365, 22, 32, 23, 1, -31 }, // 0x64 'd' + { 5453, 18, 21, 21, 1, -20 }, // 0x65 'e' + { 5501, 17, 33, 18, 0, -32 }, // 0x66 'f' + { 5572, 21, 31, 22, 1, -20 }, // 0x67 'g' + { 5654, 22, 32, 23, 0, -31 }, // 0x68 'h' + { 5742, 11, 32, 13, 0, -31 }, // 0x69 'i' + { 5786, 12, 42, 16, 0, -31 }, // 0x6A 'j' + { 5849, 23, 32, 24, 1, -31 }, // 0x6B 'k' + { 5941, 11, 32, 12, 0, -31 }, // 0x6C 'l' + { 5985, 35, 21, 37, 1, -20 }, // 0x6D 'm' + { 6077, 22, 21, 23, 0, -20 }, // 0x6E 'n' + { 6135, 22, 21, 23, 1, -20 }, // 0x6F 'o' + { 6193, 21, 31, 24, 1, -20 }, // 0x70 'p' + { 6275, 21, 31, 23, 1, -20 }, // 0x71 'q' + { 6357, 15, 21, 16, 1, -20 }, // 0x72 'r' + { 6397, 13, 21, 17, 2, -20 }, // 0x73 's' + { 6432, 12, 26, 13, 1, -25 }, // 0x74 't' + { 6471, 22, 21, 23, 1, -20 }, // 0x75 'u' + { 6529, 22, 22, 22, 0, -20 }, // 0x76 'v' + { 6590, 32, 22, 32, 0, -20 }, // 0x77 'w' + { 6678, 22, 21, 23, 0, -20 }, // 0x78 'x' + { 6736, 22, 31, 22, 0, -20 }, // 0x79 'y' + { 6822, 18, 21, 20, 1, -20 }, // 0x7A 'z' + { 6870, 11, 41, 23, 5, -31 }, // 0x7B '{' + { 6927, 3, 32, 9, 3, -30 }, // 0x7C '|' + { 6939, 11, 41, 23, 7, -31 }, // 0x7D '}' + { 6996, 22, 5, 23, 1, -13 } }; // 0x7E '~' + +const GFXfont FreeSerif24pt7b PROGMEM = { + (uint8_t *)FreeSerif24pt7bBitmaps, + (GFXglyph *)FreeSerif24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 7682 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerif9pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerif9pt7b.h new file mode 100644 index 0000000..cdb20c7 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerif9pt7b.h @@ -0,0 +1,195 @@ +const uint8_t FreeSerif9pt7bBitmaps[] PROGMEM = { + 0xFF, 0xEA, 0x03, 0xDE, 0xF7, 0x20, 0x11, 0x09, 0x04, 0x82, 0x4F, 0xF9, + 0x10, 0x89, 0xFF, 0x24, 0x12, 0x09, 0x0C, 0x80, 0x10, 0x7C, 0xD6, 0xD2, + 0xD0, 0xF0, 0x38, 0x1E, 0x17, 0x93, 0x93, 0xD6, 0x7C, 0x10, 0x38, 0x43, + 0x3C, 0x39, 0x21, 0x8A, 0x0C, 0x50, 0x65, 0x39, 0xCB, 0x20, 0xB9, 0x05, + 0x88, 0x4C, 0x44, 0x64, 0x21, 0xC0, 0x0E, 0x00, 0xC8, 0x06, 0x40, 0x32, + 0x01, 0xA0, 0x07, 0x78, 0x31, 0x87, 0x88, 0x46, 0x86, 0x34, 0x30, 0xC1, + 0xC7, 0x17, 0xCF, 0x00, 0xFE, 0x08, 0x88, 0x84, 0x63, 0x18, 0xC6, 0x10, + 0x82, 0x08, 0x20, 0x82, 0x08, 0x21, 0x0C, 0x63, 0x18, 0xC4, 0x22, 0x22, + 0x00, 0x63, 0x9A, 0xDC, 0x72, 0xB6, 0x08, 0x08, 0x04, 0x02, 0x01, 0x0F, + 0xF8, 0x40, 0x20, 0x10, 0x08, 0x00, 0xD8, 0xF0, 0xF0, 0x08, 0x84, 0x22, + 0x10, 0x8C, 0x42, 0x31, 0x00, 0x1C, 0x31, 0x98, 0xD8, 0x3C, 0x1E, 0x0F, + 0x07, 0x83, 0xC1, 0xE0, 0xD8, 0xC4, 0x61, 0xC0, 0x13, 0x8C, 0x63, 0x18, + 0xC6, 0x31, 0x8C, 0x67, 0x80, 0x3C, 0x4E, 0x86, 0x06, 0x06, 0x04, 0x0C, + 0x08, 0x10, 0x20, 0x41, 0xFE, 0x3C, 0xC6, 0x06, 0x04, 0x1C, 0x3E, 0x07, + 0x03, 0x03, 0x03, 0x06, 0xF8, 0x04, 0x18, 0x71, 0x64, 0xC9, 0xA3, 0x46, + 0xFE, 0x18, 0x30, 0x60, 0x0F, 0x10, 0x20, 0x3C, 0x0E, 0x07, 0x03, 0x03, + 0x03, 0x02, 0x04, 0xF8, 0x07, 0x1C, 0x30, 0x60, 0x60, 0xDC, 0xE6, 0xC3, + 0xC3, 0xC3, 0x43, 0x66, 0x3C, 0x7F, 0x82, 0x02, 0x02, 0x04, 0x04, 0x04, + 0x08, 0x08, 0x08, 0x10, 0x10, 0x3C, 0x8F, 0x1E, 0x3E, 0x4F, 0x06, 0x36, + 0xC7, 0x8F, 0x1B, 0x33, 0xC0, 0x3C, 0x66, 0xC2, 0xC3, 0xC3, 0xC3, 0xC3, + 0x63, 0x3F, 0x06, 0x06, 0x0C, 0x38, 0x60, 0xF0, 0x0F, 0xD8, 0x00, 0x03, + 0x28, 0x01, 0x87, 0x0E, 0x1C, 0x0C, 0x03, 0x80, 0x70, 0x0E, 0x00, 0x80, + 0xFF, 0x80, 0x00, 0x00, 0x0F, 0xF8, 0x80, 0x1C, 0x01, 0xC0, 0x1C, 0x01, + 0xC0, 0xE0, 0xE0, 0xE0, 0xC0, 0x00, 0x79, 0x1A, 0x18, 0x30, 0x60, 0x83, + 0x04, 0x10, 0x20, 0x40, 0x03, 0x00, 0x0F, 0x83, 0x8C, 0x60, 0x26, 0x02, + 0xC7, 0x9C, 0xC9, 0xD8, 0x9D, 0x99, 0xD9, 0x26, 0xEC, 0x60, 0x03, 0x04, + 0x0F, 0x80, 0x02, 0x00, 0x10, 0x01, 0xC0, 0x16, 0x00, 0x98, 0x04, 0xC0, + 0x43, 0x03, 0xF8, 0x20, 0x61, 0x03, 0x18, 0x1D, 0xE1, 0xF0, 0xFF, 0x86, + 0x1C, 0xC1, 0x98, 0x33, 0x0C, 0x7E, 0x0C, 0x31, 0x83, 0x30, 0x66, 0x0C, + 0xC3, 0x7F, 0xC0, 0x1F, 0x26, 0x1D, 0x81, 0xE0, 0x1C, 0x01, 0x80, 0x30, + 0x06, 0x00, 0xC0, 0x0C, 0x00, 0xC1, 0x8F, 0xC0, 0xFF, 0x03, 0x1C, 0x30, + 0x63, 0x07, 0x30, 0x33, 0x03, 0x30, 0x33, 0x03, 0x30, 0x33, 0x06, 0x30, + 0xCF, 0xF0, 0xFF, 0x98, 0x26, 0x01, 0x80, 0x61, 0x1F, 0xC6, 0x11, 0x80, + 0x60, 0x18, 0x16, 0x0F, 0xFE, 0xFF, 0xB0, 0x58, 0x0C, 0x06, 0x13, 0xF9, + 0x84, 0xC0, 0x60, 0x30, 0x18, 0x1E, 0x00, 0x1F, 0x23, 0x0E, 0x60, 0x26, + 0x00, 0xC0, 0x0C, 0x0F, 0xC0, 0x6C, 0x06, 0xC0, 0x66, 0x06, 0x30, 0x60, + 0xF8, 0xF1, 0xEC, 0x19, 0x83, 0x30, 0x66, 0x0C, 0xFF, 0x98, 0x33, 0x06, + 0x60, 0xCC, 0x19, 0x83, 0x78, 0xF0, 0xF6, 0x66, 0x66, 0x66, 0x66, 0x6F, + 0x3C, 0x61, 0x86, 0x18, 0x61, 0x86, 0x18, 0x6D, 0xBC, 0xF3, 0xE6, 0x08, + 0x61, 0x06, 0x20, 0x64, 0x07, 0x80, 0x6C, 0x06, 0x60, 0x63, 0x06, 0x18, + 0x60, 0xCF, 0x3F, 0xF0, 0x18, 0x06, 0x01, 0x80, 0x60, 0x18, 0x06, 0x01, + 0x80, 0x60, 0x18, 0x16, 0x0B, 0xFE, 0xF0, 0x0E, 0x70, 0x38, 0xE0, 0x71, + 0xE1, 0x62, 0xC2, 0xC5, 0xC9, 0x89, 0x93, 0x13, 0x26, 0x23, 0x8C, 0x47, + 0x18, 0x84, 0x33, 0x88, 0xF0, 0xE0, 0xEE, 0x09, 0xC1, 0x2C, 0x25, 0xC4, + 0x9C, 0x91, 0x92, 0x1A, 0x41, 0xC8, 0x19, 0x03, 0x70, 0x20, 0x1F, 0x06, + 0x31, 0x83, 0x20, 0x2C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x68, 0x09, + 0x83, 0x18, 0xC1, 0xF0, 0xFE, 0x31, 0x98, 0x6C, 0x36, 0x1B, 0x19, 0xF8, + 0xC0, 0x60, 0x30, 0x18, 0x1E, 0x00, 0x1F, 0x06, 0x31, 0x83, 0x20, 0x2C, + 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x68, 0x19, 0x83, 0x18, 0xC0, 0xE0, + 0x0E, 0x00, 0xE0, 0x07, 0xFE, 0x0C, 0x61, 0x86, 0x30, 0xC6, 0x18, 0xC6, + 0x1F, 0x83, 0x70, 0x67, 0x0C, 0x71, 0x87, 0x78, 0x70, 0x1D, 0x31, 0x98, + 0x4C, 0x07, 0x80, 0xE0, 0x1C, 0x07, 0x01, 0xA0, 0xD8, 0xCB, 0xC0, 0xFF, + 0xF8, 0xCE, 0x18, 0x83, 0x00, 0x60, 0x0C, 0x01, 0x80, 0x30, 0x06, 0x00, + 0xC0, 0x18, 0x07, 0x80, 0xF0, 0xEC, 0x09, 0x81, 0x30, 0x26, 0x04, 0xC0, + 0x98, 0x13, 0x02, 0x60, 0x4C, 0x08, 0xC2, 0x0F, 0x80, 0xF8, 0x77, 0x02, + 0x30, 0x23, 0x04, 0x18, 0x41, 0x84, 0x0C, 0x80, 0xC8, 0x07, 0x00, 0x70, + 0x02, 0x00, 0x20, 0xFB, 0xE7, 0xB0, 0xC0, 0x8C, 0x20, 0x86, 0x18, 0x41, + 0x8C, 0x40, 0xCB, 0x20, 0x65, 0x90, 0x1A, 0x70, 0x0E, 0x38, 0x03, 0x1C, + 0x01, 0x04, 0x00, 0x82, 0x00, 0xFC, 0xF9, 0x83, 0x06, 0x10, 0x19, 0x00, + 0xD0, 0x03, 0x00, 0x1C, 0x01, 0x30, 0x11, 0xC1, 0x86, 0x08, 0x19, 0xE3, + 0xF0, 0xF8, 0xF6, 0x06, 0x30, 0x41, 0x88, 0x1D, 0x00, 0xD0, 0x06, 0x00, + 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, 0xF0, 0x3F, 0xCC, 0x11, 0x06, 0x01, + 0x80, 0x70, 0x0C, 0x03, 0x00, 0xE0, 0x38, 0x06, 0x05, 0xC1, 0x7F, 0xE0, + 0xFB, 0x6D, 0xB6, 0xDB, 0x6D, 0xB8, 0x82, 0x10, 0x82, 0x10, 0x86, 0x10, + 0x86, 0x10, 0xED, 0xB6, 0xDB, 0x6D, 0xB6, 0xF8, 0x18, 0x1C, 0x34, 0x26, + 0x62, 0x42, 0xC1, 0xFF, 0x80, 0x84, 0x20, 0x79, 0x98, 0x30, 0xE6, 0xD9, + 0xB3, 0x3F, 0x20, 0x70, 0x18, 0x0C, 0x06, 0x03, 0x71, 0xCC, 0xC3, 0x61, + 0xB0, 0xD8, 0x6C, 0x63, 0xE0, 0x3C, 0xCF, 0x06, 0x0C, 0x18, 0x18, 0x9E, + 0x01, 0x03, 0x80, 0xC0, 0x60, 0x31, 0xD9, 0x9D, 0x86, 0xC3, 0x61, 0xB0, + 0xCC, 0x63, 0xF0, 0x3C, 0x46, 0xFE, 0xC0, 0xC0, 0xE1, 0x62, 0x3C, 0x1E, + 0x41, 0x83, 0x06, 0x1E, 0x18, 0x30, 0x60, 0xC1, 0x83, 0x0F, 0x00, 0x3C, + 0x19, 0xF6, 0x31, 0x8C, 0x1E, 0x08, 0x04, 0x01, 0xFC, 0x40, 0xB0, 0x2E, + 0x11, 0xF8, 0x20, 0x70, 0x18, 0x0C, 0x06, 0x03, 0x71, 0xCC, 0xC6, 0x63, + 0x31, 0x98, 0xCC, 0x6F, 0x78, 0x60, 0x02, 0xE6, 0x66, 0x66, 0xF0, 0x18, + 0x00, 0x33, 0x8C, 0x63, 0x18, 0xC6, 0x31, 0x8B, 0x80, 0x20, 0x70, 0x18, + 0x0C, 0x06, 0x03, 0x3D, 0x88, 0xD8, 0x78, 0x36, 0x19, 0x8C, 0x6F, 0x78, + 0x2E, 0x66, 0x66, 0x66, 0x66, 0x66, 0xF0, 0xEE, 0x71, 0xCE, 0x66, 0x31, + 0x98, 0xC6, 0x63, 0x19, 0x8C, 0x66, 0x31, 0xBD, 0xEF, 0xEE, 0x39, 0x98, + 0xCC, 0x66, 0x33, 0x19, 0x8D, 0xEF, 0x3E, 0x31, 0xB0, 0x78, 0x3C, 0x1E, + 0x0D, 0x8C, 0x7C, 0xEE, 0x39, 0x98, 0x6C, 0x36, 0x1B, 0x0D, 0x8C, 0xFC, + 0x60, 0x30, 0x18, 0x1E, 0x00, 0x3D, 0x31, 0xB0, 0xD8, 0x6C, 0x36, 0x1B, + 0x8C, 0xFE, 0x03, 0x01, 0x80, 0xC0, 0xF0, 0x6D, 0xC6, 0x18, 0x61, 0x86, + 0x3C, 0x76, 0x38, 0x58, 0x3E, 0x38, 0xFE, 0x27, 0x98, 0xC6, 0x31, 0x8C, + 0x38, 0xE7, 0x31, 0x98, 0xCC, 0x66, 0x33, 0x19, 0x8C, 0x7F, 0xF3, 0x61, + 0x22, 0x32, 0x14, 0x1C, 0x08, 0x08, 0xEF, 0x36, 0x61, 0x62, 0x22, 0x32, + 0x35, 0x41, 0x9C, 0x18, 0x81, 0x08, 0xF7, 0x12, 0x0E, 0x03, 0x01, 0xC1, + 0x21, 0x09, 0xCF, 0xF3, 0x61, 0x62, 0x32, 0x34, 0x14, 0x1C, 0x08, 0x08, + 0x08, 0x10, 0xE0, 0xFD, 0x18, 0x60, 0x83, 0x0C, 0x70, 0xFE, 0x19, 0x8C, + 0x63, 0x18, 0xC4, 0x61, 0x8C, 0x63, 0x18, 0xC3, 0xFF, 0xF0, 0xC3, 0x18, + 0xC6, 0x31, 0x84, 0x33, 0x18, 0xC6, 0x31, 0x98, 0x70, 0x24, 0xC1, 0xC0 }; + +const GFXglyph FreeSerif9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 2, 12, 6, 2, -11 }, // 0x21 '!' + { 3, 5, 4, 7, 1, -11 }, // 0x22 '"' + { 6, 9, 12, 9, 0, -11 }, // 0x23 '#' + { 20, 8, 14, 9, 1, -12 }, // 0x24 '$' + { 34, 13, 12, 15, 1, -11 }, // 0x25 '%' + { 54, 13, 13, 14, 1, -12 }, // 0x26 '&' + { 76, 2, 4, 4, 1, -11 }, // 0x27 ''' + { 77, 5, 15, 6, 1, -11 }, // 0x28 '(' + { 87, 5, 15, 6, 0, -11 }, // 0x29 ')' + { 97, 6, 8, 9, 3, -11 }, // 0x2A '*' + { 103, 9, 9, 10, 0, -8 }, // 0x2B '+' + { 114, 2, 3, 4, 2, 0 }, // 0x2C ',' + { 115, 4, 1, 6, 1, -3 }, // 0x2D '-' + { 116, 2, 2, 5, 1, -1 }, // 0x2E '.' + { 117, 5, 12, 5, 0, -11 }, // 0x2F '/' + { 125, 9, 13, 9, 0, -12 }, // 0x30 '0' + { 140, 5, 13, 9, 2, -12 }, // 0x31 '1' + { 149, 8, 12, 9, 1, -11 }, // 0x32 '2' + { 161, 8, 12, 9, 0, -11 }, // 0x33 '3' + { 173, 7, 12, 9, 1, -11 }, // 0x34 '4' + { 184, 8, 12, 9, 0, -11 }, // 0x35 '5' + { 196, 8, 13, 9, 1, -12 }, // 0x36 '6' + { 209, 8, 12, 9, 0, -11 }, // 0x37 '7' + { 221, 7, 13, 9, 1, -12 }, // 0x38 '8' + { 233, 8, 14, 9, 1, -12 }, // 0x39 '9' + { 247, 2, 8, 5, 1, -7 }, // 0x3A ':' + { 249, 3, 10, 5, 1, -7 }, // 0x3B ';' + { 253, 9, 9, 10, 1, -8 }, // 0x3C '<' + { 264, 9, 5, 10, 1, -6 }, // 0x3D '=' + { 270, 10, 9, 10, 0, -8 }, // 0x3E '>' + { 282, 7, 13, 8, 1, -12 }, // 0x3F '?' + { 294, 12, 13, 16, 2, -12 }, // 0x40 '@' + { 314, 13, 12, 13, 0, -11 }, // 0x41 'A' + { 334, 11, 12, 11, 0, -11 }, // 0x42 'B' + { 351, 11, 12, 12, 1, -11 }, // 0x43 'C' + { 368, 12, 12, 13, 0, -11 }, // 0x44 'D' + { 386, 10, 12, 11, 1, -11 }, // 0x45 'E' + { 401, 9, 12, 10, 1, -11 }, // 0x46 'F' + { 415, 12, 12, 13, 1, -11 }, // 0x47 'G' + { 433, 11, 12, 13, 1, -11 }, // 0x48 'H' + { 450, 4, 12, 6, 1, -11 }, // 0x49 'I' + { 456, 6, 12, 7, 0, -11 }, // 0x4A 'J' + { 465, 12, 12, 13, 1, -11 }, // 0x4B 'K' + { 483, 10, 12, 11, 1, -11 }, // 0x4C 'L' + { 498, 15, 12, 16, 0, -11 }, // 0x4D 'M' + { 521, 11, 12, 13, 1, -11 }, // 0x4E 'N' + { 538, 11, 13, 13, 1, -12 }, // 0x4F 'O' + { 556, 9, 12, 10, 1, -11 }, // 0x50 'P' + { 570, 11, 16, 13, 1, -12 }, // 0x51 'Q' + { 592, 11, 12, 12, 1, -11 }, // 0x52 'R' + { 609, 9, 12, 10, 0, -11 }, // 0x53 'S' + { 623, 11, 12, 11, 0, -11 }, // 0x54 'T' + { 640, 11, 12, 13, 1, -11 }, // 0x55 'U' + { 657, 12, 12, 13, 0, -11 }, // 0x56 'V' + { 675, 17, 12, 17, 0, -11 }, // 0x57 'W' + { 701, 13, 12, 13, 0, -11 }, // 0x58 'X' + { 721, 12, 12, 13, 0, -11 }, // 0x59 'Y' + { 739, 11, 12, 11, 0, -11 }, // 0x5A 'Z' + { 756, 3, 15, 6, 2, -11 }, // 0x5B '[' + { 762, 5, 12, 5, 0, -11 }, // 0x5C '\' + { 770, 3, 15, 6, 1, -11 }, // 0x5D ']' + { 776, 8, 7, 8, 0, -11 }, // 0x5E '^' + { 783, 9, 1, 9, 0, 2 }, // 0x5F '_' + { 785, 4, 3, 5, 0, -11 }, // 0x60 '`' + { 787, 7, 8, 8, 1, -7 }, // 0x61 'a' + { 794, 9, 13, 9, 0, -12 }, // 0x62 'b' + { 809, 7, 8, 8, 0, -7 }, // 0x63 'c' + { 816, 9, 13, 9, 0, -12 }, // 0x64 'd' + { 831, 8, 8, 8, 0, -7 }, // 0x65 'e' + { 839, 7, 13, 7, 1, -12 }, // 0x66 'f' + { 851, 10, 12, 8, 0, -7 }, // 0x67 'g' + { 866, 9, 13, 9, 0, -12 }, // 0x68 'h' + { 881, 4, 11, 5, 1, -10 }, // 0x69 'i' + { 887, 5, 15, 6, 0, -10 }, // 0x6A 'j' + { 897, 9, 13, 9, 1, -12 }, // 0x6B 'k' + { 912, 4, 13, 5, 1, -12 }, // 0x6C 'l' + { 919, 14, 8, 14, 0, -7 }, // 0x6D 'm' + { 933, 9, 8, 9, 0, -7 }, // 0x6E 'n' + { 942, 9, 8, 9, 0, -7 }, // 0x6F 'o' + { 951, 9, 12, 9, 0, -7 }, // 0x70 'p' + { 965, 9, 12, 9, 0, -7 }, // 0x71 'q' + { 979, 6, 8, 6, 0, -7 }, // 0x72 'r' + { 985, 6, 8, 7, 1, -7 }, // 0x73 's' + { 991, 5, 9, 5, 0, -8 }, // 0x74 't' + { 997, 9, 8, 9, 0, -7 }, // 0x75 'u' + { 1006, 8, 8, 8, 0, -7 }, // 0x76 'v' + { 1014, 12, 8, 12, 0, -7 }, // 0x77 'w' + { 1026, 9, 8, 9, 0, -7 }, // 0x78 'x' + { 1035, 8, 12, 8, 0, -7 }, // 0x79 'y' + { 1047, 7, 8, 7, 1, -7 }, // 0x7A 'z' + { 1054, 5, 16, 9, 1, -12 }, // 0x7B '{' + { 1064, 1, 12, 4, 1, -11 }, // 0x7C '|' + { 1066, 5, 16, 9, 3, -11 }, // 0x7D '}' + { 1076, 9, 3, 9, 0, -5 } }; // 0x7E '~' + +const GFXfont FreeSerif9pt7b PROGMEM = { + (uint8_t *)FreeSerif9pt7bBitmaps, + (GFXglyph *)FreeSerif9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 1752 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBold12pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBold12pt7b.h new file mode 100644 index 0000000..1d49981 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBold12pt7b.h @@ -0,0 +1,271 @@ +const uint8_t FreeSerifBold12pt7bBitmaps[] PROGMEM = { + 0x7F, 0xFF, 0x77, 0x66, 0x22, 0x00, 0x6F, 0xF7, 0xE3, 0xF1, 0xF8, 0xFC, + 0x7E, 0x3A, 0x09, 0x04, 0x0C, 0x40, 0xCC, 0x0C, 0xC0, 0x8C, 0x18, 0xC7, + 0xFF, 0x18, 0xC1, 0x88, 0x19, 0x81, 0x98, 0xFF, 0xE3, 0x18, 0x31, 0x83, + 0x18, 0x33, 0x03, 0x30, 0x08, 0x01, 0x00, 0xFC, 0x24, 0xEC, 0x8D, 0x90, + 0xBA, 0x07, 0xC0, 0x7E, 0x07, 0xF0, 0x7F, 0x07, 0xF0, 0x9F, 0x11, 0xE2, + 0x3E, 0x46, 0xE9, 0xC7, 0xC0, 0x20, 0x04, 0x00, 0x1E, 0x0C, 0x0E, 0x7F, + 0x07, 0x10, 0x83, 0xC4, 0x40, 0xE1, 0x30, 0x38, 0x88, 0x0E, 0x26, 0x03, + 0x91, 0x1E, 0x78, 0x8E, 0x40, 0x27, 0x10, 0x11, 0xC4, 0x0C, 0xE1, 0x02, + 0x38, 0x81, 0x0E, 0x20, 0x43, 0x90, 0x20, 0x78, 0x03, 0xE0, 0x01, 0x9E, + 0x00, 0xE3, 0x80, 0x38, 0xE0, 0x0F, 0x30, 0x03, 0xF0, 0x00, 0x78, 0x7C, + 0x1F, 0x06, 0x1B, 0xE1, 0x1C, 0x7C, 0x8F, 0x1F, 0x23, 0xC3, 0xF0, 0xF8, + 0x7C, 0x3E, 0x0F, 0x97, 0xC7, 0xFC, 0xFE, 0x3E, 0xFF, 0xFE, 0x90, 0x00, + 0x31, 0x0C, 0x31, 0x86, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x86, 0x18, 0x60, + 0xC1, 0x02, 0x04, 0x03, 0x06, 0x0C, 0x30, 0x61, 0x87, 0x1C, 0x71, 0xC7, + 0x1C, 0x71, 0x86, 0x38, 0xC2, 0x10, 0x80, 0x1C, 0x6E, 0xFA, 0xEF, 0xF1, + 0xC7, 0xFF, 0xAF, 0xBB, 0x1C, 0x04, 0x00, 0x06, 0x00, 0x60, 0x06, 0x00, + 0x60, 0x06, 0x0F, 0xFF, 0xFF, 0xF0, 0x60, 0x06, 0x00, 0x60, 0x06, 0x00, + 0x60, 0x6F, 0xF7, 0x11, 0x24, 0xFF, 0xFF, 0xC0, 0x6F, 0xF6, 0x03, 0x07, + 0x06, 0x06, 0x0C, 0x0C, 0x0C, 0x18, 0x18, 0x18, 0x30, 0x30, 0x30, 0x60, + 0x60, 0x60, 0xC0, 0x0E, 0x07, 0x71, 0xC7, 0x38, 0xEF, 0x1D, 0xE3, 0xFC, + 0x7F, 0x8F, 0xF1, 0xFE, 0x3F, 0xC7, 0xF8, 0xF7, 0x1C, 0xE3, 0x8E, 0xE0, + 0xF8, 0x06, 0x0F, 0x1F, 0x83, 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, 0x0F, + 0x07, 0x83, 0xC1, 0xE0, 0xF0, 0xF9, 0xFF, 0x0F, 0x03, 0xFC, 0x7F, 0xC4, + 0x3E, 0x01, 0xE0, 0x1E, 0x01, 0xE0, 0x1C, 0x03, 0x80, 0x30, 0x06, 0x00, + 0xC1, 0x18, 0x13, 0xFE, 0x7F, 0xEF, 0xFE, 0x1F, 0x0C, 0xFA, 0x0F, 0x01, + 0xE0, 0x38, 0x0E, 0x03, 0xE0, 0x3E, 0x03, 0xE0, 0x3C, 0x03, 0x80, 0x70, + 0x0D, 0xC1, 0xBC, 0x43, 0xF0, 0x03, 0x80, 0xE0, 0x78, 0x3E, 0x17, 0x89, + 0xE2, 0x79, 0x1E, 0x87, 0xA1, 0xEF, 0xFF, 0xFF, 0xFF, 0xC1, 0xE0, 0x78, + 0x1E, 0x3F, 0xE7, 0xF8, 0xFF, 0x10, 0x04, 0x00, 0xF8, 0x1F, 0xC7, 0xFC, + 0x1F, 0xC0, 0x78, 0x07, 0x00, 0x60, 0x0D, 0xC1, 0x3C, 0x43, 0xF0, 0x00, + 0xE0, 0xF0, 0x38, 0x1E, 0x07, 0x80, 0xF0, 0x3F, 0xE7, 0x9E, 0xF1, 0xFE, + 0x3F, 0xC7, 0xF8, 0xF7, 0x1E, 0xE3, 0x8E, 0x60, 0xF8, 0x7F, 0xEF, 0xFD, + 0xFF, 0xA0, 0x68, 0x0C, 0x03, 0x80, 0x60, 0x0C, 0x03, 0x00, 0x60, 0x0C, + 0x03, 0x00, 0x60, 0x1C, 0x03, 0x00, 0x60, 0x1F, 0x0E, 0x73, 0x87, 0x70, + 0xEF, 0x1D, 0xF3, 0x1F, 0x81, 0xF8, 0x1F, 0xCC, 0xFB, 0x8F, 0xF0, 0xFE, + 0x1F, 0xC3, 0x9C, 0xF1, 0xF8, 0x1F, 0x06, 0x71, 0xC7, 0x78, 0xEF, 0x1F, + 0xE3, 0xFC, 0x7F, 0x8F, 0x79, 0xE7, 0xFC, 0x0F, 0x01, 0xC0, 0x78, 0x1C, + 0x0F, 0x07, 0x00, 0x6F, 0xF6, 0x00, 0x06, 0xFF, 0x60, 0x6F, 0xF6, 0x00, + 0x06, 0xFF, 0x71, 0x22, 0xC0, 0x00, 0x04, 0x00, 0x70, 0x07, 0xC0, 0xFC, + 0x0F, 0x80, 0xF8, 0x0F, 0x80, 0x1F, 0x00, 0x1F, 0x00, 0x1F, 0x00, 0x1F, + 0x00, 0x1F, 0x00, 0x1C, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0xFF, 0xFF, 0x00, 0x03, 0x80, 0x0F, + 0x80, 0x0F, 0x80, 0x0F, 0x80, 0x0F, 0x80, 0x0F, 0x80, 0x1F, 0x01, 0xF0, + 0x1F, 0x03, 0xF0, 0x3E, 0x00, 0xE0, 0x02, 0x00, 0x00, 0x3E, 0x11, 0xEC, + 0x3F, 0x8F, 0xE3, 0xC0, 0xF0, 0x78, 0x18, 0x08, 0x02, 0x00, 0x00, 0x00, + 0x1C, 0x07, 0x81, 0xE0, 0x30, 0x03, 0xF0, 0x0E, 0x18, 0x18, 0x04, 0x30, + 0x66, 0x70, 0xDB, 0x61, 0x99, 0xE3, 0x19, 0xE3, 0x31, 0xE6, 0x31, 0xE6, + 0x31, 0xE6, 0xF2, 0x66, 0xB2, 0x73, 0x3C, 0x38, 0x00, 0x1E, 0x04, 0x03, + 0xF8, 0x00, 0x80, 0x00, 0xC0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x3E, 0x00, + 0x1F, 0x00, 0x1B, 0xC0, 0x09, 0xE0, 0x0C, 0xF8, 0x04, 0x3C, 0x02, 0x1F, + 0x03, 0xFF, 0x81, 0x03, 0xC1, 0x80, 0xF0, 0x80, 0x7D, 0xF0, 0xFF, 0xFF, + 0xC0, 0xF3, 0xC3, 0xC7, 0x8F, 0x1E, 0x3C, 0x78, 0xF1, 0xE3, 0xCE, 0x0F, + 0xF0, 0x3C, 0x70, 0xF0, 0xE3, 0xC3, 0xCF, 0x0F, 0x3C, 0x3C, 0xF0, 0xE3, + 0xC7, 0xBF, 0xF8, 0x07, 0xE2, 0x38, 0x7C, 0xE0, 0x3B, 0xC0, 0x37, 0x00, + 0x7E, 0x00, 0x7C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x03, + 0x80, 0x07, 0x80, 0x27, 0x00, 0xC7, 0x86, 0x03, 0xF0, 0xFF, 0xE0, 0x1E, + 0x1E, 0x0F, 0x07, 0x87, 0x81, 0xE3, 0xC0, 0xF1, 0xE0, 0x3C, 0xF0, 0x1E, + 0x78, 0x0F, 0x3C, 0x07, 0x9E, 0x03, 0xCF, 0x01, 0xE7, 0x80, 0xE3, 0xC0, + 0xF1, 0xE0, 0xF0, 0xF0, 0xE1, 0xFF, 0xC0, 0xFF, 0xFC, 0x78, 0x38, 0xF0, + 0x31, 0xE0, 0x23, 0xC4, 0x07, 0x88, 0x0F, 0x30, 0x1F, 0xE0, 0x3C, 0xC0, + 0x78, 0x80, 0xF1, 0x01, 0xE0, 0x23, 0xC0, 0x47, 0x81, 0x8F, 0x07, 0x7F, + 0xFE, 0xFF, 0xFC, 0xF0, 0x73, 0xC0, 0xCF, 0x01, 0x3C, 0x40, 0xF1, 0x03, + 0xCC, 0x0F, 0xF0, 0x3C, 0xC0, 0xF1, 0x03, 0xC4, 0x0F, 0x00, 0x3C, 0x00, + 0xF0, 0x03, 0xC0, 0x3F, 0xC0, 0x07, 0xE2, 0x1C, 0x3E, 0x38, 0x0E, 0x78, + 0x06, 0x70, 0x06, 0xF0, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF0, 0x00, 0xF0, + 0x7F, 0xF0, 0x1E, 0x70, 0x1E, 0x78, 0x1E, 0x38, 0x1E, 0x1E, 0x1E, 0x07, + 0xF0, 0xFE, 0xFF, 0x78, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0x78, + 0x3C, 0x78, 0x3C, 0x7F, 0xFC, 0x78, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0x78, + 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0xFE, 0xFF, 0xFF, 0x3C, 0x3C, + 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, + 0xFF, 0x0F, 0xF0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, + 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0x03, 0xC0, 0x3C, 0xE3, 0xCE, + 0x38, 0xE3, 0x83, 0xE0, 0xFE, 0x7F, 0x3C, 0x0E, 0x1E, 0x04, 0x0F, 0x04, + 0x07, 0x84, 0x03, 0xCC, 0x01, 0xEE, 0x00, 0xFF, 0x00, 0x7F, 0xC0, 0x3C, + 0xF0, 0x1E, 0x7C, 0x0F, 0x1F, 0x07, 0x87, 0xC3, 0xC1, 0xF1, 0xE0, 0x7D, + 0xFC, 0xFF, 0xFE, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, 0xE0, + 0x07, 0x80, 0x1E, 0x00, 0x78, 0x01, 0xE0, 0x07, 0x80, 0x1E, 0x01, 0x78, + 0x0D, 0xE0, 0x67, 0x83, 0xBF, 0xFE, 0xFC, 0x01, 0xF3, 0xC0, 0x3E, 0x3E, + 0x03, 0xE2, 0xE0, 0x5E, 0x2F, 0x05, 0xE2, 0xF0, 0x5E, 0x27, 0x09, 0xE2, + 0x78, 0x9E, 0x23, 0x91, 0xE2, 0x3D, 0x1E, 0x23, 0xF1, 0xE2, 0x1E, 0x1E, + 0x21, 0xE1, 0xE2, 0x0C, 0x1E, 0x20, 0xC1, 0xEF, 0x88, 0x3F, 0xF8, 0x1E, + 0xF8, 0x18, 0xF8, 0x11, 0xF8, 0x22, 0xF8, 0x45, 0xF0, 0x89, 0xF1, 0x11, + 0xF2, 0x21, 0xF4, 0x41, 0xF8, 0x81, 0xF1, 0x01, 0xE2, 0x03, 0xC4, 0x03, + 0x8C, 0x03, 0x7C, 0x02, 0x07, 0xF0, 0x0F, 0x1E, 0x0E, 0x03, 0x8F, 0x01, + 0xE7, 0x00, 0x77, 0x80, 0x3F, 0xC0, 0x1F, 0xE0, 0x0F, 0xF0, 0x07, 0xF8, + 0x03, 0xFC, 0x01, 0xEE, 0x00, 0xE7, 0x80, 0xF1, 0xC0, 0x70, 0x70, 0x70, + 0x0F, 0xE0, 0xFF, 0x87, 0x9E, 0x78, 0xF7, 0x8F, 0x78, 0xF7, 0x8F, 0x78, + 0xF7, 0x9E, 0x7F, 0x87, 0x80, 0x78, 0x07, 0x80, 0x78, 0x07, 0x80, 0x78, + 0x0F, 0xE0, 0x07, 0xF0, 0x0F, 0x1E, 0x0E, 0x07, 0x8F, 0x01, 0xE7, 0x00, + 0xF7, 0x80, 0x3F, 0xC0, 0x1F, 0xE0, 0x0F, 0xF0, 0x07, 0xF8, 0x03, 0xFC, + 0x01, 0xEE, 0x00, 0xE7, 0x00, 0xF1, 0xC0, 0x70, 0x70, 0x70, 0x1C, 0xF0, + 0x03, 0xE0, 0x01, 0xF8, 0x00, 0x3E, 0x00, 0x07, 0xE0, 0xFF, 0xE0, 0x3C, + 0x78, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x3C, 0x38, 0x3C, + 0x70, 0x3F, 0xC0, 0x3D, 0xE0, 0x3C, 0xF0, 0x3C, 0xF8, 0x3C, 0x78, 0x3C, + 0x3C, 0x3C, 0x3E, 0xFF, 0x1F, 0x1F, 0x27, 0x0E, 0x60, 0x6E, 0x06, 0xF0, + 0x2F, 0x80, 0x7F, 0x07, 0xFC, 0x1F, 0xE0, 0x7E, 0x01, 0xF8, 0x07, 0xC0, + 0x7C, 0x06, 0xF0, 0xC9, 0xF8, 0xFF, 0xFF, 0xC7, 0x9F, 0x0F, 0x1C, 0x1E, + 0x10, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, + 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x07, 0xF8, 0xFE, + 0x1E, 0xF0, 0x09, 0xE0, 0x13, 0xC0, 0x27, 0x80, 0x4F, 0x00, 0x9E, 0x01, + 0x3C, 0x02, 0x78, 0x04, 0xF0, 0x09, 0xE0, 0x13, 0xC0, 0x27, 0x80, 0x47, + 0x81, 0x07, 0x84, 0x07, 0xF0, 0xFF, 0x0F, 0x9E, 0x03, 0x0F, 0x00, 0x83, + 0xC0, 0x81, 0xE0, 0x40, 0xF8, 0x60, 0x3C, 0x20, 0x1E, 0x10, 0x07, 0x90, + 0x03, 0xC8, 0x00, 0xF4, 0x00, 0x7C, 0x00, 0x3E, 0x00, 0x0E, 0x00, 0x07, + 0x00, 0x01, 0x80, 0x00, 0x80, 0x00, 0xFE, 0x7F, 0x9E, 0xF8, 0x3C, 0x08, + 0xF0, 0x78, 0x31, 0xE0, 0xF0, 0x41, 0xE0, 0xF0, 0x83, 0xC3, 0xE3, 0x07, + 0x85, 0xC4, 0x07, 0x93, 0xC8, 0x0F, 0x27, 0xB0, 0x0E, 0x47, 0x40, 0x1F, + 0x0F, 0x80, 0x3E, 0x1F, 0x00, 0x38, 0x1C, 0x00, 0x70, 0x38, 0x00, 0xE0, + 0x30, 0x00, 0x80, 0x40, 0xFF, 0x9F, 0x9F, 0x07, 0x07, 0x83, 0x03, 0xE3, + 0x00, 0xF9, 0x00, 0x3D, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xE0, 0x00, + 0xF8, 0x00, 0xBE, 0x00, 0x8F, 0x00, 0x83, 0xC0, 0xC1, 0xF0, 0xE0, 0xFD, + 0xF8, 0xFF, 0xFF, 0x1F, 0x7C, 0x06, 0x3C, 0x04, 0x3E, 0x0C, 0x1E, 0x08, + 0x0F, 0x10, 0x0F, 0x30, 0x07, 0xA0, 0x07, 0xC0, 0x03, 0xC0, 0x03, 0xC0, + 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x03, 0xC0, 0x0F, 0xF0, 0x7F, 0xFC, + 0xE0, 0xF1, 0x83, 0xE2, 0x07, 0x84, 0x1E, 0x00, 0x7C, 0x00, 0xF0, 0x03, + 0xC0, 0x0F, 0x80, 0x1E, 0x00, 0x7C, 0x08, 0xF0, 0x13, 0xC0, 0x6F, 0x81, + 0x9E, 0x07, 0x7F, 0xFE, 0xFF, 0x39, 0xCE, 0x73, 0x9C, 0xE7, 0x39, 0xCE, + 0x73, 0x9C, 0xE7, 0x39, 0xF0, 0xC0, 0x60, 0x60, 0x60, 0x30, 0x30, 0x30, + 0x18, 0x18, 0x18, 0x0C, 0x0C, 0x0C, 0x06, 0x06, 0x06, 0x03, 0xF9, 0xCE, + 0x73, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9C, 0xE7, 0x39, 0xCF, 0xF0, 0x0C, + 0x07, 0x81, 0xE0, 0xCC, 0x33, 0x18, 0x66, 0x1B, 0x87, 0xC0, 0xC0, 0xFF, + 0xF0, 0xC7, 0x1C, 0x30, 0x1F, 0x0E, 0x71, 0xCF, 0x39, 0xE0, 0x3C, 0x1F, + 0x8E, 0xF3, 0x9E, 0xF3, 0xDE, 0x79, 0xFF, 0x80, 0xF8, 0x07, 0x80, 0x78, + 0x07, 0x80, 0x78, 0x07, 0xB8, 0x7D, 0xE7, 0x8E, 0x78, 0xF7, 0x8F, 0x78, + 0xF7, 0x8F, 0x78, 0xF7, 0x8E, 0x79, 0xC4, 0x78, 0x1F, 0x1D, 0xDC, 0xFE, + 0x7F, 0x07, 0x83, 0xC1, 0xE0, 0x78, 0x3C, 0x47, 0xC0, 0x03, 0xE0, 0x1E, + 0x01, 0xE0, 0x1E, 0x01, 0xE1, 0xDE, 0x7B, 0xE7, 0x1E, 0xF1, 0xEF, 0x1E, + 0xF1, 0xEF, 0x1E, 0xF1, 0xE7, 0x1E, 0x7B, 0xE1, 0xDF, 0x1F, 0x0C, 0x67, + 0x1B, 0xC7, 0xFF, 0xFC, 0x0F, 0x03, 0xC0, 0x78, 0x4E, 0x21, 0xF0, 0x1E, + 0x3B, 0x7B, 0x78, 0x78, 0xFC, 0x78, 0x78, 0x78, 0x78, 0x78, 0x78, 0x78, + 0x78, 0x78, 0xFC, 0x3E, 0x0E, 0x7F, 0xCE, 0x79, 0xEF, 0x3C, 0xE7, 0x0F, + 0xC1, 0x00, 0x60, 0x1C, 0x03, 0xFE, 0x7F, 0xE3, 0xFF, 0x80, 0xF0, 0x33, + 0xFC, 0xF8, 0x07, 0x80, 0x78, 0x07, 0x80, 0x78, 0x07, 0xB8, 0x7D, 0xE7, + 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xEF, + 0xFF, 0x31, 0xE7, 0x8C, 0x03, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, + 0xBF, 0x06, 0x0F, 0x0F, 0x06, 0x00, 0x1F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0xCF, 0xCE, 0x7C, 0xF8, 0x03, + 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0xF9, 0xE1, 0x8F, 0x10, 0x79, + 0x03, 0xD8, 0x1F, 0xE0, 0xF7, 0x87, 0x9E, 0x3C, 0x71, 0xE3, 0xDF, 0xBF, + 0xF9, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0xBF, + 0xFB, 0xCF, 0x0F, 0xBE, 0x79, 0xE7, 0x8F, 0x3C, 0xF1, 0xE7, 0x9E, 0x3C, + 0xF3, 0xC7, 0x9E, 0x78, 0xF3, 0xCF, 0x1E, 0x79, 0xE3, 0xCF, 0x3C, 0x7B, + 0xFF, 0xDF, 0x80, 0xFB, 0x87, 0xDE, 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, + 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0xFF, 0xF0, 0x1F, 0x07, 0x71, 0xC7, + 0x78, 0xFF, 0x1F, 0xE3, 0xFC, 0x7F, 0x8F, 0x71, 0xC7, 0x70, 0x7C, 0x00, + 0xFB, 0x87, 0xDE, 0x78, 0xE7, 0x8F, 0x78, 0xF7, 0x8F, 0x78, 0xF7, 0x8F, + 0x78, 0xE7, 0x9E, 0x7F, 0x87, 0x80, 0x78, 0x07, 0x80, 0x78, 0x0F, 0xC0, + 0x1E, 0x23, 0x9E, 0x71, 0xEF, 0x1E, 0xF1, 0xEF, 0x1E, 0xF1, 0xEF, 0x1E, + 0x71, 0xE7, 0x9E, 0x1F, 0xE0, 0x1E, 0x01, 0xE0, 0x1E, 0x01, 0xE0, 0x3F, + 0xF9, 0xDF, 0xF7, 0xDD, 0xE0, 0x78, 0x1E, 0x07, 0x81, 0xE0, 0x78, 0x1E, + 0x0F, 0xC0, 0x3D, 0x43, 0xC3, 0xE0, 0xFC, 0x7E, 0x1F, 0x87, 0x83, 0xC2, + 0xBC, 0x08, 0x18, 0x38, 0x78, 0xFC, 0x78, 0x78, 0x78, 0x78, 0x78, 0x78, + 0x78, 0x78, 0x79, 0x3E, 0xFB, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, + 0x9E, 0x79, 0xE7, 0x9E, 0x79, 0xE7, 0x9E, 0x3F, 0xF0, 0xFC, 0xEF, 0x08, + 0xE1, 0x1E, 0x41, 0xC8, 0x3D, 0x03, 0xC0, 0x78, 0x0E, 0x00, 0xC0, 0x10, + 0x00, 0xFD, 0xF7, 0xBC, 0x71, 0x9E, 0x38, 0x87, 0x1E, 0x43, 0xCF, 0x40, + 0xEB, 0xA0, 0x7C, 0xF0, 0x1C, 0x70, 0x0E, 0x38, 0x06, 0x08, 0x01, 0x04, + 0x00, 0xFC, 0xF7, 0x84, 0x3C, 0x81, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x80, + 0xBC, 0x13, 0xC2, 0x1E, 0xFB, 0xF0, 0xFC, 0xEF, 0x08, 0xE1, 0x1E, 0x43, + 0xC8, 0x3A, 0x07, 0xC0, 0x78, 0x0E, 0x01, 0xC0, 0x18, 0x02, 0x00, 0x41, + 0xC8, 0x3A, 0x03, 0x80, 0xFF, 0xB1, 0xE8, 0x70, 0x3C, 0x1E, 0x07, 0x83, + 0xC1, 0xE0, 0x78, 0xBC, 0x2F, 0xF8, 0x07, 0x0E, 0x1C, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1C, 0x1C, 0x1C, 0xE0, 0x18, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, + 0x1C, 0x1E, 0x07, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xE0, 0x70, 0x38, 0x38, + 0x38, 0x38, 0x38, 0x38, 0x38, 0x18, 0x07, 0x38, 0x38, 0x38, 0x38, 0x38, + 0x38, 0x38, 0x38, 0x70, 0xE0, 0x70, 0x1F, 0x8B, 0x3F, 0x01, 0xC0 }; + +const GFXglyph FreeSerifBold12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 6, 0, 1 }, // 0x20 ' ' + { 0, 4, 16, 8, 2, -15 }, // 0x21 '!' + { 8, 9, 7, 13, 2, -15 }, // 0x22 '"' + { 16, 12, 16, 12, 0, -15 }, // 0x23 '#' + { 40, 11, 20, 12, 1, -17 }, // 0x24 '$' + { 68, 18, 16, 24, 3, -15 }, // 0x25 '%' + { 104, 18, 16, 20, 1, -15 }, // 0x26 '&' + { 140, 3, 7, 7, 2, -15 }, // 0x27 ''' + { 143, 6, 21, 8, 1, -16 }, // 0x28 '(' + { 159, 6, 21, 8, 1, -16 }, // 0x29 ')' + { 175, 9, 10, 12, 2, -15 }, // 0x2A '*' + { 187, 12, 12, 16, 2, -11 }, // 0x2B '+' + { 205, 4, 8, 6, 1, -3 }, // 0x2C ',' + { 209, 6, 3, 8, 1, -6 }, // 0x2D '-' + { 212, 4, 4, 6, 1, -3 }, // 0x2E '.' + { 214, 8, 17, 7, -1, -15 }, // 0x2F '/' + { 231, 11, 16, 12, 1, -15 }, // 0x30 '0' + { 253, 9, 16, 12, 1, -15 }, // 0x31 '1' + { 271, 12, 16, 12, 0, -15 }, // 0x32 '2' + { 295, 11, 16, 12, 1, -15 }, // 0x33 '3' + { 317, 10, 16, 12, 1, -15 }, // 0x34 '4' + { 337, 11, 16, 12, 1, -15 }, // 0x35 '5' + { 359, 11, 16, 12, 1, -15 }, // 0x36 '6' + { 381, 11, 16, 12, 0, -15 }, // 0x37 '7' + { 403, 11, 16, 12, 1, -15 }, // 0x38 '8' + { 425, 11, 16, 12, 1, -15 }, // 0x39 '9' + { 447, 4, 11, 8, 2, -10 }, // 0x3A ':' + { 453, 4, 15, 8, 2, -10 }, // 0x3B ';' + { 461, 14, 14, 16, 1, -12 }, // 0x3C '<' + { 486, 14, 8, 16, 1, -9 }, // 0x3D '=' + { 500, 14, 14, 16, 1, -12 }, // 0x3E '>' + { 525, 10, 16, 12, 1, -15 }, // 0x3F '?' + { 545, 16, 16, 22, 3, -15 }, // 0x40 '@' + { 577, 17, 16, 17, 0, -15 }, // 0x41 'A' + { 611, 14, 16, 16, 1, -15 }, // 0x42 'B' + { 639, 15, 16, 17, 1, -15 }, // 0x43 'C' + { 669, 17, 16, 18, 0, -15 }, // 0x44 'D' + { 703, 15, 16, 16, 1, -15 }, // 0x45 'E' + { 733, 14, 16, 15, 1, -15 }, // 0x46 'F' + { 761, 16, 16, 19, 1, -15 }, // 0x47 'G' + { 793, 16, 16, 19, 2, -15 }, // 0x48 'H' + { 825, 8, 16, 9, 1, -15 }, // 0x49 'I' + { 841, 12, 18, 12, 0, -15 }, // 0x4A 'J' + { 868, 17, 16, 19, 2, -15 }, // 0x4B 'K' + { 902, 14, 16, 16, 2, -15 }, // 0x4C 'L' + { 930, 20, 16, 23, 1, -15 }, // 0x4D 'M' + { 970, 15, 16, 17, 1, -15 }, // 0x4E 'N' + { 1000, 17, 16, 19, 1, -15 }, // 0x4F 'O' + { 1034, 12, 16, 15, 2, -15 }, // 0x50 'P' + { 1058, 17, 20, 19, 1, -15 }, // 0x51 'Q' + { 1101, 16, 16, 17, 1, -15 }, // 0x52 'R' + { 1133, 12, 16, 14, 1, -15 }, // 0x53 'S' + { 1157, 15, 16, 15, 0, -15 }, // 0x54 'T' + { 1187, 15, 16, 17, 1, -15 }, // 0x55 'U' + { 1217, 17, 17, 17, 0, -15 }, // 0x56 'V' + { 1254, 23, 16, 24, 0, -15 }, // 0x57 'W' + { 1300, 17, 16, 17, 0, -15 }, // 0x58 'X' + { 1334, 16, 16, 17, 1, -15 }, // 0x59 'Y' + { 1366, 15, 16, 16, 0, -15 }, // 0x5A 'Z' + { 1396, 5, 20, 8, 2, -15 }, // 0x5B '[' + { 1409, 8, 17, 7, -1, -15 }, // 0x5C '\' + { 1426, 5, 20, 8, 2, -15 }, // 0x5D ']' + { 1439, 10, 9, 14, 2, -15 }, // 0x5E '^' + { 1451, 12, 1, 12, 0, 4 }, // 0x5F '_' + { 1453, 5, 4, 8, 0, -16 }, // 0x60 '`' + { 1456, 11, 11, 12, 1, -10 }, // 0x61 'a' + { 1472, 12, 16, 13, 1, -15 }, // 0x62 'b' + { 1496, 9, 11, 10, 1, -10 }, // 0x63 'c' + { 1509, 12, 16, 13, 1, -15 }, // 0x64 'd' + { 1533, 10, 11, 11, 1, -10 }, // 0x65 'e' + { 1547, 8, 16, 9, 1, -15 }, // 0x66 'f' + { 1563, 11, 16, 12, 1, -10 }, // 0x67 'g' + { 1585, 12, 16, 13, 1, -15 }, // 0x68 'h' + { 1609, 6, 16, 7, 1, -15 }, // 0x69 'i' + { 1621, 8, 21, 10, 0, -15 }, // 0x6A 'j' + { 1642, 13, 16, 13, 1, -15 }, // 0x6B 'k' + { 1668, 6, 16, 7, 1, -15 }, // 0x6C 'l' + { 1680, 19, 11, 20, 1, -10 }, // 0x6D 'm' + { 1707, 12, 11, 13, 1, -10 }, // 0x6E 'n' + { 1724, 11, 11, 12, 1, -10 }, // 0x6F 'o' + { 1740, 12, 16, 13, 1, -10 }, // 0x70 'p' + { 1764, 12, 16, 13, 1, -10 }, // 0x71 'q' + { 1788, 10, 11, 10, 1, -10 }, // 0x72 'r' + { 1802, 8, 11, 10, 1, -10 }, // 0x73 's' + { 1813, 8, 15, 8, 1, -14 }, // 0x74 't' + { 1828, 12, 11, 14, 1, -10 }, // 0x75 'u' + { 1845, 11, 11, 12, 0, -10 }, // 0x76 'v' + { 1861, 17, 11, 17, 0, -10 }, // 0x77 'w' + { 1885, 12, 11, 12, 0, -10 }, // 0x78 'x' + { 1902, 11, 16, 12, 0, -10 }, // 0x79 'y' + { 1924, 10, 11, 11, 1, -10 }, // 0x7A 'z' + { 1938, 8, 21, 9, 0, -16 }, // 0x7B '{' + { 1959, 2, 17, 5, 2, -15 }, // 0x7C '|' + { 1964, 8, 21, 9, 2, -16 }, // 0x7D '}' + { 1985, 11, 4, 12, 1, -7 } }; // 0x7E '~' + +const GFXfont FreeSerifBold12pt7b PROGMEM = { + (uint8_t *)FreeSerifBold12pt7bBitmaps, + (GFXglyph *)FreeSerifBold12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 2663 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBold18pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBold18pt7b.h new file mode 100644 index 0000000..11d3c7e --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBold18pt7b.h @@ -0,0 +1,462 @@ +const uint8_t FreeSerifBold18pt7bBitmaps[] PROGMEM = { + 0x7B, 0xEF, 0xFF, 0xFF, 0xF7, 0x9E, 0x71, 0xC7, 0x0C, 0x20, 0x82, 0x00, + 0x00, 0x07, 0x3E, 0xFF, 0xFF, 0xDC, 0x60, 0x37, 0x83, 0xFC, 0x1F, 0xE0, + 0xFF, 0x07, 0xB8, 0x3D, 0xC0, 0xCC, 0x06, 0x20, 0x31, 0x01, 0x80, 0x03, + 0x8E, 0x00, 0xC3, 0x80, 0x30, 0xE0, 0x1C, 0x38, 0x07, 0x0E, 0x01, 0xC3, + 0x87, 0xFF, 0xFD, 0xFF, 0xFF, 0x7F, 0xFF, 0xC1, 0x87, 0x00, 0xE1, 0xC0, + 0x38, 0x70, 0x0E, 0x1C, 0x03, 0x86, 0x0F, 0xFF, 0xF3, 0xFF, 0xFC, 0xFF, + 0xFF, 0x07, 0x0E, 0x01, 0xC3, 0x80, 0x70, 0xE0, 0x1C, 0x30, 0x07, 0x0C, + 0x01, 0x87, 0x00, 0x61, 0xC0, 0x02, 0x00, 0x04, 0x00, 0x08, 0x00, 0xFF, + 0x03, 0x27, 0x8C, 0x47, 0x38, 0x86, 0x71, 0x0C, 0xF2, 0x09, 0xF4, 0x03, + 0xF8, 0x03, 0xF8, 0x07, 0xFC, 0x03, 0xFC, 0x03, 0xFE, 0x01, 0xFE, 0x03, + 0xFC, 0x04, 0xFC, 0x08, 0xFA, 0x10, 0xF4, 0x21, 0xEC, 0x43, 0xD8, 0x8F, + 0x3D, 0x3C, 0x3F, 0xF0, 0x1F, 0x00, 0x08, 0x00, 0x10, 0x00, 0x03, 0xC0, + 0x18, 0x01, 0xFE, 0x0F, 0x00, 0x7C, 0xFF, 0xC0, 0x1F, 0x0F, 0x90, 0x07, + 0xC1, 0x06, 0x00, 0xF0, 0x21, 0x80, 0x3E, 0x04, 0x30, 0x07, 0x81, 0x8C, + 0x00, 0xF0, 0x21, 0x80, 0x1E, 0x0C, 0x60, 0x03, 0xC1, 0x18, 0x1E, 0x3C, + 0xE3, 0x0F, 0xE7, 0xF8, 0xC3, 0xE6, 0x3C, 0x18, 0xF8, 0x40, 0x06, 0x3E, + 0x08, 0x01, 0x87, 0x81, 0x00, 0x31, 0xF0, 0x20, 0x0C, 0x3E, 0x04, 0x01, + 0x87, 0x81, 0x00, 0x60, 0xF0, 0x60, 0x18, 0x1E, 0x08, 0x03, 0x03, 0xC7, + 0x00, 0xC0, 0x3F, 0xC0, 0x18, 0x03, 0xE0, 0x00, 0x7E, 0x00, 0x00, 0x7F, + 0xE0, 0x00, 0x38, 0xF8, 0x00, 0x1E, 0x1F, 0x00, 0x07, 0x83, 0xC0, 0x01, + 0xF0, 0xF0, 0x00, 0x7C, 0x38, 0x00, 0x1F, 0x9C, 0x00, 0x03, 0xFC, 0x00, + 0x00, 0xFE, 0x0F, 0xF0, 0x3F, 0x80, 0xF0, 0x1F, 0xF0, 0x18, 0x1C, 0xFE, + 0x0C, 0x0E, 0x1F, 0xC3, 0x07, 0x87, 0xF1, 0x81, 0xE0, 0xFE, 0x40, 0xF8, + 0x1F, 0xF0, 0x3F, 0x07, 0xF8, 0x0F, 0xC0, 0xFE, 0x03, 0xF8, 0x1F, 0xC0, + 0xFE, 0x07, 0xF8, 0x9F, 0xE3, 0xFF, 0xE7, 0xFF, 0x9F, 0xF0, 0xFF, 0xC3, + 0xF8, 0x0F, 0x80, 0x3C, 0x00, 0x6F, 0xFF, 0xFF, 0x66, 0x66, 0x00, 0x81, + 0x81, 0x81, 0x81, 0x80, 0xC0, 0xE0, 0x70, 0x70, 0x38, 0x3C, 0x1E, 0x0F, + 0x07, 0x83, 0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x0E, 0x07, 0x03, 0x80, 0xE0, + 0x70, 0x18, 0x06, 0x01, 0x00, 0x40, 0x10, 0x04, 0x80, 0x30, 0x0C, 0x03, + 0x00, 0xC0, 0x60, 0x38, 0x1C, 0x07, 0x03, 0x81, 0xC0, 0xF0, 0x78, 0x3C, + 0x1E, 0x0F, 0x07, 0x83, 0xC1, 0xE0, 0xE0, 0x70, 0x38, 0x38, 0x1C, 0x0C, + 0x0C, 0x06, 0x04, 0x04, 0x04, 0x00, 0x03, 0x00, 0x1E, 0x00, 0x78, 0x1D, + 0xE6, 0xFB, 0x3D, 0xED, 0xF3, 0xFF, 0x01, 0xC0, 0x7F, 0xF3, 0xED, 0xFF, + 0x33, 0xD9, 0xE6, 0x07, 0x80, 0x1E, 0x00, 0x30, 0x00, 0x00, 0xE0, 0x00, + 0x1C, 0x00, 0x03, 0x80, 0x00, 0x70, 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, + 0x38, 0x00, 0x07, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, + 0x70, 0x00, 0x0E, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x07, 0x00, 0x00, + 0xE0, 0x00, 0x1C, 0x00, 0x03, 0x80, 0x00, 0x73, 0xEF, 0xFF, 0xFD, 0xF0, + 0xC2, 0x18, 0xC6, 0x30, 0xFF, 0xFF, 0xFF, 0xFF, 0x7B, 0xFF, 0xFF, 0xFD, + 0xE0, 0x00, 0xE0, 0x3C, 0x07, 0x00, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x1C, + 0x07, 0x00, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x1C, + 0x07, 0x00, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x1C, 0x07, 0x00, 0xE0, 0x00, + 0x03, 0xC0, 0x0E, 0x70, 0x1E, 0x78, 0x3C, 0x3C, 0x3C, 0x3C, 0x7C, 0x3E, + 0x7C, 0x3E, 0x7C, 0x3E, 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, + 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3E, 0x7C, 0x3E, + 0x7C, 0x3E, 0x3C, 0x3C, 0x3C, 0x3C, 0x1E, 0x78, 0x0E, 0x70, 0x03, 0xC0, + 0x00, 0xC0, 0x3C, 0x0F, 0xC3, 0xFC, 0x4F, 0xC0, 0xFC, 0x0F, 0xC0, 0xFC, + 0x0F, 0xC0, 0xFC, 0x0F, 0xC0, 0xFC, 0x0F, 0xC0, 0xFC, 0x0F, 0xC0, 0xFC, + 0x0F, 0xC0, 0xFC, 0x0F, 0xC0, 0xFC, 0x0F, 0xC0, 0xFC, 0x1F, 0xEF, 0xFF, + 0x03, 0xE0, 0x0F, 0xF8, 0x1F, 0xFC, 0x3F, 0xFC, 0x30, 0xFE, 0x60, 0x7E, + 0x40, 0x3E, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x78, + 0x00, 0x70, 0x00, 0xE0, 0x00, 0xC0, 0x01, 0x80, 0x03, 0x00, 0x06, 0x01, + 0x0C, 0x03, 0x1F, 0xFF, 0x1F, 0xFF, 0x3F, 0xFE, 0x7F, 0xFE, 0xFF, 0xFE, + 0x03, 0xF0, 0x0F, 0xF8, 0x3F, 0xFC, 0x21, 0xFE, 0x40, 0xFE, 0x00, 0x7E, + 0x00, 0x7E, 0x00, 0x7C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xFC, 0x03, 0xFE, + 0x00, 0x7E, 0x00, 0x3F, 0x00, 0x1F, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0F, + 0x00, 0x0E, 0x70, 0x0E, 0xFC, 0x1C, 0xFE, 0x38, 0x7F, 0xE0, 0x3F, 0x80, + 0x00, 0x38, 0x00, 0xF0, 0x03, 0xE0, 0x07, 0xC0, 0x1F, 0x80, 0x5F, 0x00, + 0xBE, 0x02, 0x7C, 0x08, 0xF8, 0x31, 0xF0, 0x43, 0xE1, 0x07, 0xC4, 0x0F, + 0x88, 0x1F, 0x20, 0x3E, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF8, + 0x07, 0xC0, 0x0F, 0x80, 0x1F, 0x00, 0x3E, 0x00, 0x7C, 0x0F, 0xFE, 0x1F, + 0xF8, 0x7F, 0xF0, 0xFF, 0xE1, 0x80, 0x03, 0x00, 0x0C, 0x00, 0x18, 0x00, + 0x3F, 0x80, 0xFF, 0xC1, 0xFF, 0xC3, 0xFF, 0xC3, 0xFF, 0x80, 0x3F, 0x80, + 0x0F, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x18, 0x00, 0x37, 0x80, 0x4F, 0x81, + 0x9F, 0xC6, 0x3F, 0xF8, 0x1F, 0x80, 0x00, 0x07, 0x00, 0x7C, 0x01, 0xF0, + 0x03, 0xC0, 0x0F, 0x80, 0x1F, 0x00, 0x1F, 0x00, 0x3E, 0x00, 0x7E, 0x00, + 0x7F, 0xF0, 0x7F, 0xFC, 0xFC, 0x7E, 0xFC, 0x7E, 0xFC, 0x3F, 0xFC, 0x3F, + 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, 0x7C, 0x3F, 0x7C, 0x3E, 0x3C, 0x3E, + 0x3E, 0x3C, 0x1E, 0x78, 0x07, 0xE0, 0x7F, 0xFF, 0x7F, 0xFE, 0x7F, 0xFE, + 0xFF, 0xFE, 0xFF, 0xFC, 0xC0, 0x1C, 0x80, 0x18, 0x80, 0x38, 0x00, 0x38, + 0x00, 0x70, 0x00, 0x70, 0x00, 0x70, 0x00, 0xE0, 0x00, 0xE0, 0x00, 0xE0, + 0x01, 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x03, 0x80, 0x03, 0x80, 0x07, 0x80, + 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x0F, 0xE0, 0x38, 0x78, 0x70, 0x3C, + 0xF0, 0x1E, 0xF0, 0x1E, 0xF8, 0x1E, 0xF8, 0x1E, 0xFE, 0x3C, 0x7F, 0xB0, + 0x7F, 0xE0, 0x3F, 0xF0, 0x0F, 0xF8, 0x1F, 0xFC, 0x39, 0xFE, 0x70, 0xFF, + 0xF0, 0x3F, 0xF0, 0x3F, 0xF0, 0x1F, 0xF0, 0x1F, 0xF0, 0x1E, 0x78, 0x3E, + 0x7C, 0x7C, 0x3F, 0xF8, 0x0F, 0xE0, 0x07, 0xE0, 0x1E, 0x78, 0x3C, 0x7C, + 0x7C, 0x3C, 0x7C, 0x3E, 0xFC, 0x3E, 0xFC, 0x3F, 0xFC, 0x3F, 0xFC, 0x3F, + 0xFC, 0x3F, 0xFC, 0x3F, 0x7E, 0x3F, 0x7E, 0x3F, 0x3F, 0xFE, 0x0F, 0xFE, + 0x00, 0x7E, 0x00, 0x7C, 0x00, 0xF8, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xC0, + 0x0F, 0x80, 0x3E, 0x00, 0xE0, 0x00, 0x7B, 0xFF, 0xFF, 0xFD, 0xE0, 0x00, + 0x00, 0x07, 0xBF, 0xFF, 0xFF, 0xDE, 0x39, 0xFB, 0xF7, 0xEF, 0xC7, 0x00, + 0x00, 0x00, 0x01, 0xE7, 0xEF, 0xFF, 0xFF, 0xBF, 0x06, 0x08, 0x30, 0xC2, + 0x18, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x0F, 0x80, 0x07, 0xF0, + 0x03, 0xFC, 0x01, 0xFE, 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x3F, 0x80, 0x1F, + 0xC0, 0x03, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0xFE, 0x00, 0x07, 0xF0, 0x00, + 0x3F, 0x80, 0x01, 0xFE, 0x00, 0x0F, 0xE0, 0x00, 0x7C, 0x00, 0x01, 0x80, + 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1F, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, 0x18, 0x00, 0x03, + 0xE0, 0x00, 0x7F, 0x00, 0x07, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0xFE, 0x00, + 0x07, 0xF0, 0x00, 0x3F, 0x80, 0x01, 0xFC, 0x00, 0x3F, 0x80, 0x1F, 0xC0, + 0x0F, 0xE0, 0x07, 0xF0, 0x07, 0xF8, 0x03, 0xFC, 0x00, 0xFE, 0x00, 0x1F, + 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xC0, 0xFF, 0xC7, 0x1F, + 0xB8, 0x3E, 0xF0, 0xFF, 0xC3, 0xFF, 0x0F, 0xD8, 0x3F, 0x00, 0xF8, 0x07, + 0xC0, 0x1E, 0x00, 0x60, 0x03, 0x00, 0x08, 0x00, 0x20, 0x00, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x70, 0x03, 0xE0, 0x1F, 0x80, 0x7E, 0x01, 0xF8, 0x01, + 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFF, 0xE0, 0x07, 0xC0, 0xF0, 0x0F, 0x00, + 0x38, 0x1E, 0x00, 0x0C, 0x3C, 0x07, 0x06, 0x38, 0x1F, 0x72, 0x78, 0x3C, + 0xF3, 0x78, 0x78, 0xE1, 0xF0, 0x70, 0xE1, 0xF0, 0xF0, 0xE1, 0xF0, 0xE0, + 0xC1, 0xF1, 0xE1, 0xC1, 0xF1, 0xC1, 0xC1, 0xF1, 0xC3, 0x82, 0xF1, 0xC3, + 0x86, 0x71, 0xC7, 0x8C, 0x79, 0xFB, 0xF8, 0x78, 0xF1, 0xF0, 0x3C, 0x00, + 0x00, 0x1E, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0xC0, 0x78, 0x03, 0xFF, + 0xE0, 0x00, 0x7F, 0x80, 0x00, 0x10, 0x00, 0x00, 0x38, 0x00, 0x00, 0x38, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0xFE, 0x00, 0x01, 0xBF, 0x00, 0x01, 0xBF, 0x00, 0x01, 0x1F, + 0x00, 0x03, 0x1F, 0x80, 0x02, 0x1F, 0x80, 0x06, 0x0F, 0xC0, 0x06, 0x0F, + 0xC0, 0x04, 0x07, 0xE0, 0x0F, 0xFF, 0xE0, 0x0F, 0xFF, 0xE0, 0x18, 0x03, + 0xF0, 0x18, 0x03, 0xF0, 0x30, 0x01, 0xF8, 0x30, 0x01, 0xF8, 0x70, 0x01, + 0xFC, 0xFE, 0x0F, 0xFF, 0xFF, 0xFE, 0x07, 0xFF, 0xFE, 0x0F, 0xE1, 0xF8, + 0x3F, 0x07, 0xC1, 0xF8, 0x3F, 0x0F, 0xC1, 0xF8, 0x7E, 0x0F, 0xC3, 0xF0, + 0x7E, 0x1F, 0x87, 0xE0, 0xFC, 0x7C, 0x07, 0xFF, 0x00, 0x3F, 0xFF, 0x01, + 0xF8, 0xFE, 0x0F, 0xC1, 0xF8, 0x7E, 0x0F, 0xC3, 0xF0, 0x3F, 0x1F, 0x81, + 0xF8, 0xFC, 0x0F, 0xC7, 0xE0, 0x7E, 0x3F, 0x03, 0xF1, 0xF8, 0x3F, 0x0F, + 0xC3, 0xF0, 0xFF, 0xFF, 0x1F, 0xFF, 0xC0, 0x00, 0x7E, 0x04, 0x07, 0xFF, + 0x18, 0x1F, 0x07, 0xF0, 0x7C, 0x03, 0xE1, 0xF0, 0x03, 0xC7, 0xC0, 0x03, + 0x9F, 0x80, 0x03, 0x3F, 0x00, 0x06, 0x7C, 0x00, 0x05, 0xF8, 0x00, 0x03, + 0xF0, 0x00, 0x07, 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x1F, 0x80, 0x00, 0x3F, + 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x01, 0xF8, + 0x00, 0x01, 0xF0, 0x00, 0x23, 0xF0, 0x00, 0xC3, 0xF0, 0x07, 0x03, 0xF0, + 0x3C, 0x01, 0xFF, 0xE0, 0x00, 0xFF, 0x00, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, + 0x00, 0x7E, 0x1F, 0x80, 0xFC, 0x1F, 0x81, 0xF8, 0x1F, 0x83, 0xF0, 0x1F, + 0x07, 0xE0, 0x3F, 0x0F, 0xC0, 0x7E, 0x1F, 0x80, 0x7E, 0x3F, 0x00, 0xFC, + 0x7E, 0x01, 0xF8, 0xFC, 0x03, 0xF1, 0xF8, 0x07, 0xE3, 0xF0, 0x0F, 0xC7, + 0xE0, 0x1F, 0x8F, 0xC0, 0x3F, 0x1F, 0x80, 0x7C, 0x3F, 0x01, 0xF8, 0x7E, + 0x03, 0xE0, 0xFC, 0x0F, 0x81, 0xF8, 0x1F, 0x03, 0xF0, 0xFC, 0x0F, 0xFF, + 0xE0, 0x7F, 0xFF, 0x00, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0x0F, 0xC0, 0x78, + 0x7E, 0x01, 0xC3, 0xF0, 0x06, 0x1F, 0x80, 0x10, 0xFC, 0x10, 0x87, 0xE0, + 0x80, 0x3F, 0x0C, 0x01, 0xF8, 0xE0, 0x0F, 0xFF, 0x00, 0x7F, 0xF8, 0x03, + 0xF1, 0xC0, 0x1F, 0x86, 0x00, 0xFC, 0x10, 0x07, 0xE0, 0x80, 0x3F, 0x00, + 0x09, 0xF8, 0x00, 0xCF, 0xC0, 0x0C, 0x7E, 0x00, 0x63, 0xF0, 0x0F, 0x1F, + 0x81, 0xFB, 0xFF, 0xFF, 0xDF, 0xFF, 0xFC, 0xFF, 0xFF, 0xEF, 0xFF, 0xFC, + 0xFC, 0x0F, 0x9F, 0x80, 0x73, 0xF0, 0x06, 0x7E, 0x00, 0x4F, 0xC1, 0x09, + 0xF8, 0x20, 0x3F, 0x0C, 0x07, 0xE3, 0x80, 0xFF, 0xF0, 0x1F, 0xFE, 0x03, + 0xF1, 0xC0, 0x7E, 0x18, 0x0F, 0xC1, 0x01, 0xF8, 0x20, 0x3F, 0x00, 0x07, + 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x1F, + 0xE0, 0x07, 0xFF, 0x00, 0x00, 0x7E, 0x02, 0x01, 0xFF, 0xE3, 0x01, 0xF0, + 0x3F, 0x81, 0xF0, 0x07, 0xC1, 0xF0, 0x01, 0xE1, 0xF0, 0x00, 0x71, 0xF8, + 0x00, 0x18, 0xFC, 0x00, 0x0C, 0x7C, 0x00, 0x02, 0x7E, 0x00, 0x00, 0x3F, + 0x00, 0x00, 0x1F, 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03, + 0xF0, 0x0F, 0xFF, 0xF8, 0x01, 0xFE, 0x7C, 0x00, 0x7E, 0x3F, 0x00, 0x3F, + 0x1F, 0x80, 0x1F, 0x87, 0xC0, 0x0F, 0xC1, 0xF0, 0x07, 0xE0, 0xFC, 0x03, + 0xF0, 0x1F, 0x83, 0xF0, 0x07, 0xFF, 0xE0, 0x00, 0x7F, 0x80, 0x00, 0xFF, + 0xC3, 0xFF, 0x7F, 0x81, 0xFE, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, + 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, + 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0xFF, 0xFC, 0x3F, 0xFF, 0xFC, 0x3F, + 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, + 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x3F, + 0x00, 0xFC, 0x3F, 0x00, 0xFC, 0x7F, 0x81, 0xFE, 0xFF, 0xC3, 0xFF, 0xFF, + 0xEF, 0xF0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x07, + 0xE0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x07, 0xE0, + 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x1F, 0xE7, 0xFF, 0x07, 0xFF, 0x01, 0xFE, + 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, + 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, + 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, 0x00, 0xFC, + 0x70, 0xFC, 0xF8, 0xFC, 0xF8, 0xF8, 0xF0, 0xF8, 0x71, 0xF0, 0x7F, 0xE0, + 0x1F, 0x80, 0xFF, 0xC3, 0xFF, 0x3F, 0xC0, 0x3E, 0x0F, 0xC0, 0x1C, 0x07, + 0xE0, 0x18, 0x03, 0xF0, 0x18, 0x01, 0xF8, 0x18, 0x00, 0xFC, 0x18, 0x00, + 0x7E, 0x18, 0x00, 0x3F, 0x18, 0x00, 0x1F, 0x9C, 0x00, 0x0F, 0xDF, 0x00, + 0x07, 0xFF, 0xC0, 0x03, 0xFF, 0xF0, 0x01, 0xF9, 0xF8, 0x00, 0xFC, 0xFE, + 0x00, 0x7E, 0x3F, 0x80, 0x3F, 0x0F, 0xE0, 0x1F, 0x83, 0xF8, 0x0F, 0xC0, + 0xFC, 0x07, 0xE0, 0x7F, 0x03, 0xF0, 0x1F, 0xC1, 0xF8, 0x07, 0xF1, 0xFE, + 0x03, 0xFD, 0xFF, 0x8F, 0xFF, 0xFF, 0xE0, 0x03, 0xFC, 0x00, 0x0F, 0xC0, + 0x00, 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, + 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0x7E, 0x00, + 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x01, 0x3F, + 0x00, 0x19, 0xF8, 0x00, 0xCF, 0xC0, 0x0C, 0x7E, 0x00, 0x63, 0xF0, 0x0F, + 0x1F, 0x81, 0xFB, 0xFF, 0xFF, 0xDF, 0xFF, 0xFE, 0xFF, 0x80, 0x03, 0xFE, + 0x7F, 0x00, 0x07, 0xF8, 0x7E, 0x00, 0x0F, 0xE0, 0xFE, 0x00, 0x3F, 0xC1, + 0x7C, 0x00, 0x5F, 0x82, 0xFC, 0x01, 0xBF, 0x05, 0xF8, 0x02, 0x7E, 0x09, + 0xF8, 0x0C, 0xFC, 0x13, 0xF0, 0x11, 0xF8, 0x23, 0xE0, 0x23, 0xF0, 0x47, + 0xE0, 0xC7, 0xE0, 0x87, 0xC1, 0x0F, 0xC1, 0x0F, 0xC6, 0x1F, 0x82, 0x0F, + 0x88, 0x3F, 0x04, 0x1F, 0xB0, 0x7E, 0x08, 0x3F, 0x60, 0xFC, 0x10, 0x3E, + 0x81, 0xF8, 0x20, 0x7F, 0x03, 0xF0, 0x40, 0x7C, 0x07, 0xE0, 0x80, 0xF8, + 0x0F, 0xC1, 0x00, 0xE0, 0x1F, 0x82, 0x01, 0xC0, 0x3F, 0x0E, 0x03, 0x80, + 0xFF, 0x7F, 0x82, 0x03, 0xFF, 0xFE, 0x00, 0xFE, 0xFE, 0x00, 0x70, 0xFE, + 0x00, 0x40, 0xFE, 0x00, 0x81, 0xFC, 0x01, 0x03, 0xFC, 0x02, 0x05, 0xFC, + 0x04, 0x09, 0xFC, 0x08, 0x11, 0xFC, 0x10, 0x23, 0xF8, 0x20, 0x43, 0xF8, + 0x40, 0x83, 0xF8, 0x81, 0x03, 0xF9, 0x02, 0x03, 0xFA, 0x04, 0x03, 0xF4, + 0x08, 0x07, 0xF8, 0x10, 0x07, 0xF0, 0x20, 0x07, 0xE0, 0x40, 0x07, 0xC0, + 0x80, 0x07, 0x81, 0x00, 0x0F, 0x02, 0x00, 0x0E, 0x0E, 0x00, 0x0C, 0x7F, + 0x00, 0x08, 0x00, 0x7F, 0x00, 0x01, 0xFF, 0xF0, 0x01, 0xF0, 0x7C, 0x01, + 0xF0, 0x1F, 0x01, 0xF0, 0x07, 0xC1, 0xF0, 0x01, 0xF1, 0xF8, 0x00, 0xFC, + 0xFC, 0x00, 0x7E, 0x7C, 0x00, 0x1F, 0x7E, 0x00, 0x0F, 0xFF, 0x00, 0x07, + 0xFF, 0x80, 0x03, 0xFF, 0xC0, 0x01, 0xFF, 0xE0, 0x00, 0xFF, 0xF0, 0x00, + 0x7F, 0xF8, 0x00, 0x3F, 0x7C, 0x00, 0x1F, 0x3E, 0x00, 0x1F, 0x9F, 0x80, + 0x0F, 0xC7, 0xC0, 0x07, 0xC1, 0xF0, 0x07, 0xC0, 0xFC, 0x07, 0xE0, 0x3F, + 0x07, 0xC0, 0x07, 0xFF, 0xC0, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0xFC, 0x0F, + 0xFF, 0xE0, 0xFC, 0x7E, 0x1F, 0x87, 0xE3, 0xF0, 0x7E, 0x7E, 0x0F, 0xCF, + 0xC1, 0xF9, 0xF8, 0x3F, 0x3F, 0x07, 0xE7, 0xE0, 0xFC, 0xFC, 0x3F, 0x1F, + 0x8F, 0xC3, 0xFF, 0xF0, 0x7F, 0xF8, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, + 0x00, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, + 0x00, 0x1F, 0xE0, 0x07, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x01, 0xFF, 0xF0, + 0x01, 0xF0, 0x7C, 0x01, 0xF0, 0x1F, 0x01, 0xF0, 0x07, 0xC1, 0xF0, 0x01, + 0xF1, 0xF8, 0x00, 0xFC, 0xFC, 0x00, 0x7E, 0x7C, 0x00, 0x1F, 0x7E, 0x00, + 0x0F, 0xFF, 0x00, 0x07, 0xFF, 0x80, 0x03, 0xFF, 0xC0, 0x01, 0xFF, 0xE0, + 0x00, 0xFF, 0xF0, 0x00, 0x7F, 0xF8, 0x00, 0x3F, 0x7C, 0x00, 0x1F, 0x3E, + 0x00, 0x0F, 0x9F, 0x80, 0x0F, 0xC7, 0xC0, 0x07, 0xC1, 0xF0, 0x07, 0xC0, + 0x78, 0x03, 0xC0, 0x1E, 0x07, 0xC0, 0x03, 0xFF, 0x80, 0x00, 0x7F, 0x00, + 0x00, 0x3F, 0xC0, 0x00, 0x0F, 0xF0, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFF, + 0xF8, 0x00, 0x0F, 0xE0, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0x00, 0xFC, 0x3F, + 0x01, 0xF8, 0x3F, 0x03, 0xF0, 0x3F, 0x07, 0xE0, 0x7E, 0x0F, 0xC0, 0xFC, + 0x1F, 0x81, 0xF8, 0x3F, 0x03, 0xF0, 0x7E, 0x07, 0xC0, 0xFC, 0x1F, 0x81, + 0xF8, 0x7E, 0x03, 0xFF, 0xF0, 0x07, 0xFF, 0xC0, 0x0F, 0xDF, 0xC0, 0x1F, + 0x9F, 0x80, 0x3F, 0x1F, 0x80, 0x7E, 0x3F, 0x80, 0xFC, 0x3F, 0x81, 0xF8, + 0x3F, 0x03, 0xF0, 0x7F, 0x07, 0xE0, 0x7F, 0x1F, 0xE0, 0x7F, 0x7F, 0xE0, + 0xFF, 0x07, 0xC2, 0x1F, 0xF2, 0x3C, 0x3E, 0x70, 0x0E, 0xF0, 0x06, 0xF0, + 0x06, 0xF0, 0x02, 0xF8, 0x00, 0xFE, 0x00, 0xFF, 0x80, 0x7F, 0xE0, 0x3F, + 0xF8, 0x1F, 0xFC, 0x0F, 0xFE, 0x03, 0xFE, 0x00, 0xFF, 0x00, 0x3F, 0x80, + 0x1F, 0xC0, 0x0F, 0xC0, 0x0F, 0xE0, 0x0E, 0xF0, 0x1E, 0xF8, 0x3C, 0x9F, + 0xF8, 0x87, 0xE0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x7E, 0x3F, 0x83, + 0xF0, 0x7C, 0x1F, 0x81, 0xC0, 0xFC, 0x06, 0x07, 0xE0, 0x20, 0x3F, 0x00, + 0x01, 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x1F, + 0x80, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF8, 0x00, + 0x0F, 0xC0, 0x00, 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, + 0x00, 0x0F, 0xF0, 0x01, 0xFF, 0xE0, 0xFF, 0xC1, 0xFD, 0xFE, 0x01, 0xC3, + 0xF0, 0x02, 0x0F, 0xC0, 0x08, 0x3F, 0x00, 0x20, 0xFC, 0x00, 0x83, 0xF0, + 0x02, 0x0F, 0xC0, 0x08, 0x3F, 0x00, 0x20, 0xFC, 0x00, 0x83, 0xF0, 0x02, + 0x0F, 0xC0, 0x08, 0x3F, 0x00, 0x20, 0xFC, 0x00, 0x83, 0xF0, 0x02, 0x0F, + 0xC0, 0x08, 0x3F, 0x00, 0x20, 0xFC, 0x00, 0x83, 0xF0, 0x02, 0x0F, 0xC0, + 0x18, 0x1F, 0x80, 0x40, 0x7E, 0x03, 0x00, 0xFC, 0x18, 0x01, 0xFF, 0xC0, + 0x00, 0xFC, 0x00, 0xFF, 0xF0, 0x7F, 0x3F, 0xC0, 0x1E, 0x1F, 0x80, 0x0C, + 0x1F, 0x80, 0x08, 0x0F, 0xC0, 0x18, 0x0F, 0xC0, 0x18, 0x07, 0xE0, 0x10, + 0x07, 0xE0, 0x30, 0x07, 0xE0, 0x20, 0x03, 0xF0, 0x60, 0x03, 0xF0, 0x60, + 0x01, 0xF8, 0x40, 0x01, 0xF8, 0xC0, 0x00, 0xF8, 0x80, 0x00, 0xFC, 0x80, + 0x00, 0xFD, 0x80, 0x00, 0x7F, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3E, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x1C, 0x00, + 0x00, 0x0C, 0x00, 0xFF, 0xE7, 0xFF, 0x0F, 0xCF, 0xE0, 0x7F, 0x00, 0xE1, + 0xF8, 0x0F, 0xC0, 0x30, 0x7E, 0x03, 0xF0, 0x0C, 0x1F, 0x80, 0x7C, 0x02, + 0x03, 0xE0, 0x1F, 0x81, 0x80, 0xFC, 0x07, 0xE0, 0x60, 0x3F, 0x03, 0xF8, + 0x10, 0x07, 0xC0, 0xBF, 0x0C, 0x01, 0xF8, 0x2F, 0xC3, 0x00, 0x7E, 0x19, + 0xF0, 0x80, 0x0F, 0x84, 0x7C, 0x60, 0x03, 0xF3, 0x0F, 0x98, 0x00, 0xFC, + 0xC3, 0xE4, 0x00, 0x1F, 0x20, 0xFB, 0x00, 0x07, 0xF8, 0x1F, 0xC0, 0x00, + 0xFC, 0x07, 0xE0, 0x00, 0x3F, 0x01, 0xF8, 0x00, 0x0F, 0xC0, 0x3E, 0x00, + 0x01, 0xE0, 0x0F, 0x00, 0x00, 0x78, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x70, + 0x00, 0x03, 0x00, 0x18, 0x00, 0x00, 0xC0, 0x06, 0x00, 0x00, 0x20, 0x00, + 0x80, 0x00, 0xFF, 0xF3, 0xFE, 0x7F, 0x80, 0x78, 0x3F, 0x80, 0x70, 0x1F, + 0xC0, 0x60, 0x0F, 0xC0, 0xC0, 0x0F, 0xE1, 0x80, 0x07, 0xF1, 0x00, 0x03, + 0xF3, 0x00, 0x03, 0xFE, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7F, 0x00, 0x00, 0xFF, 0x80, 0x00, + 0x9F, 0x80, 0x01, 0x8F, 0xC0, 0x03, 0x0F, 0xE0, 0x06, 0x07, 0xE0, 0x06, + 0x07, 0xF0, 0x0C, 0x03, 0xF8, 0x1C, 0x03, 0xF8, 0x3C, 0x03, 0xFC, 0xFF, + 0x0F, 0xFF, 0xFF, 0xF0, 0xFF, 0x7F, 0x80, 0x1E, 0x3F, 0x80, 0x1C, 0x1F, + 0x80, 0x18, 0x1F, 0xC0, 0x10, 0x0F, 0xC0, 0x30, 0x07, 0xE0, 0x20, 0x07, + 0xE0, 0x60, 0x03, 0xF0, 0xC0, 0x03, 0xF0, 0x80, 0x01, 0xF9, 0x80, 0x01, + 0xFF, 0x00, 0x00, 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7E, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFF, 0x00, 0x01, + 0xFF, 0x80, 0x7F, 0xFF, 0xF3, 0xFF, 0xFF, 0x9F, 0x01, 0xF8, 0xE0, 0x1F, + 0x86, 0x01, 0xFC, 0x20, 0x0F, 0xC1, 0x00, 0xFC, 0x00, 0x07, 0xE0, 0x00, + 0x7E, 0x00, 0x07, 0xE0, 0x00, 0x3F, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x80, + 0x01, 0xF8, 0x00, 0x1F, 0x80, 0x01, 0xFC, 0x01, 0x0F, 0xC0, 0x18, 0xFC, + 0x00, 0xC7, 0xE0, 0x06, 0x7E, 0x00, 0x77, 0xF0, 0x07, 0x3F, 0x00, 0xFB, + 0xFF, 0xFF, 0xDF, 0xFF, 0xFE, 0xFF, 0xFF, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, 0xFF, 0xFF, 0xE0, 0x1E, + 0x01, 0xC0, 0x38, 0x07, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x1C, 0x03, 0x80, + 0x70, 0x07, 0x00, 0xE0, 0x1C, 0x01, 0xC0, 0x38, 0x07, 0x00, 0x70, 0x0E, + 0x01, 0xC0, 0x1C, 0x03, 0x80, 0x70, 0x0F, 0x00, 0xE0, 0xFF, 0xFF, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0xFF, 0xFF, 0x03, 0x80, 0x0F, 0x00, 0x1F, 0x00, 0x7E, 0x00, 0xEE, 0x03, + 0x9C, 0x07, 0x1C, 0x1C, 0x38, 0x38, 0x38, 0xE0, 0x71, 0xC0, 0x77, 0x00, + 0xEE, 0x00, 0xE0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xE0, 0xF0, + 0x78, 0x3C, 0x0E, 0x07, 0x0F, 0xE0, 0x3F, 0xF0, 0x78, 0xF8, 0x78, 0x7C, + 0x78, 0x7C, 0x38, 0x7C, 0x00, 0x7C, 0x03, 0xFC, 0x1E, 0x7C, 0x7C, 0x7C, + 0xFC, 0x7C, 0xFC, 0x7C, 0xFC, 0xFC, 0xFF, 0xFD, 0x7F, 0x7F, 0x3C, 0x3C, + 0xFC, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1F, + 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0xF8, 0x1F, 0x7F, 0x87, 0xE3, + 0xF1, 0xF0, 0x7E, 0x7C, 0x0F, 0x9F, 0x03, 0xF7, 0xC0, 0xFD, 0xF0, 0x3F, + 0x7C, 0x0F, 0xDF, 0x03, 0xF7, 0xC0, 0xFD, 0xF0, 0x3E, 0x7C, 0x1F, 0x1F, + 0x8F, 0xC6, 0x7F, 0xC1, 0x07, 0xC0, 0x07, 0xC0, 0x7F, 0xC3, 0xC7, 0x9F, + 0x1E, 0x78, 0x7B, 0xE1, 0xCF, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, + 0x80, 0x3F, 0x00, 0x7C, 0x00, 0xFC, 0x61, 0xFF, 0x03, 0xF0, 0x00, 0x7F, + 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xC0, + 0x01, 0xF0, 0x00, 0x7C, 0x07, 0x9F, 0x07, 0xF7, 0xC3, 0xE3, 0xF1, 0xF8, + 0x7C, 0x7C, 0x1F, 0x3F, 0x07, 0xCF, 0xC1, 0xF3, 0xF0, 0x7C, 0xFC, 0x1F, + 0x3F, 0x07, 0xCF, 0xC1, 0xF1, 0xF0, 0x7C, 0x7E, 0x1F, 0x0F, 0x8F, 0xC1, + 0xFD, 0xFC, 0x3E, 0x70, 0x0F, 0xC0, 0x7F, 0xC3, 0xC7, 0x1E, 0x1E, 0xF8, + 0x7B, 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0xC0, 0x1F, + 0x03, 0x7E, 0x18, 0xFF, 0xC1, 0xFE, 0x03, 0xF0, 0x0F, 0x83, 0xF8, 0xF3, + 0xBE, 0xF7, 0xDC, 0xF8, 0x1F, 0x03, 0xE0, 0xFF, 0x1F, 0xE1, 0xF0, 0x3E, + 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, + 0xC0, 0xF8, 0x1F, 0x07, 0xF8, 0x0F, 0xC0, 0x1F, 0xFF, 0xDF, 0x1F, 0xFF, + 0x07, 0x8F, 0x83, 0xE7, 0xC1, 0xF3, 0xE0, 0xF9, 0xF0, 0x7C, 0x78, 0x3C, + 0x1E, 0x3E, 0x03, 0xFC, 0x03, 0x00, 0x07, 0x00, 0x07, 0x80, 0x03, 0xFF, + 0xF1, 0xFF, 0xFE, 0x7F, 0xFF, 0x8F, 0xFF, 0xF8, 0x01, 0xFC, 0x00, 0x7F, + 0x00, 0x73, 0xFF, 0xF0, 0x7F, 0xC0, 0xFC, 0x00, 0x3E, 0x00, 0x1F, 0x00, + 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x00, 0xF8, 0x00, 0x7C, + 0x7C, 0x3E, 0xFF, 0x1F, 0xCF, 0xCF, 0x83, 0xE7, 0xC1, 0xF3, 0xE0, 0xF9, + 0xF0, 0x7C, 0xF8, 0x3E, 0x7C, 0x1F, 0x3E, 0x0F, 0x9F, 0x07, 0xCF, 0x83, + 0xE7, 0xC1, 0xF3, 0xE0, 0xF9, 0xF0, 0x7D, 0xFC, 0x7F, 0x39, 0xFB, 0xF7, + 0xE7, 0x80, 0x00, 0x00, 0xFC, 0xF9, 0xF3, 0xE7, 0xCF, 0x9F, 0x3E, 0x7C, + 0xF9, 0xF3, 0xE7, 0xCF, 0x9F, 0x7F, 0x03, 0xC0, 0xFC, 0x1F, 0x83, 0xF0, + 0x3C, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, + 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, + 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7D, 0xCF, 0xF9, 0xEE, 0x7C, 0xFF, 0x0F, + 0x80, 0xFC, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, + 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x7F, 0x9F, 0x07, 0x87, + 0xC1, 0x81, 0xF0, 0xC0, 0x7C, 0x60, 0x1F, 0x30, 0x07, 0xDE, 0x01, 0xFF, + 0xC0, 0x7F, 0xF0, 0x1F, 0x3E, 0x07, 0xCF, 0xC1, 0xF1, 0xF8, 0x7C, 0x3E, + 0x1F, 0x07, 0xC7, 0xC1, 0xFB, 0xF9, 0xFF, 0xFC, 0xF9, 0xF3, 0xE7, 0xCF, + 0x9F, 0x3E, 0x7C, 0xF9, 0xF3, 0xE7, 0xCF, 0x9F, 0x3E, 0x7C, 0xF9, 0xF3, + 0xE7, 0xCF, 0x9F, 0x7F, 0xFC, 0x7C, 0x1F, 0x0F, 0xBF, 0xCF, 0xF1, 0xF8, + 0xFF, 0x3F, 0x3E, 0x0F, 0x83, 0xE7, 0xC1, 0xF0, 0x7C, 0xF8, 0x3E, 0x0F, + 0x9F, 0x07, 0xC1, 0xF3, 0xE0, 0xF8, 0x3E, 0x7C, 0x1F, 0x07, 0xCF, 0x83, + 0xE0, 0xF9, 0xF0, 0x7C, 0x1F, 0x3E, 0x0F, 0x83, 0xE7, 0xC1, 0xF0, 0x7C, + 0xF8, 0x3E, 0x0F, 0x9F, 0x07, 0xC1, 0xF7, 0xF1, 0xFC, 0x7F, 0xFC, 0x7C, + 0x3E, 0xFF, 0x1F, 0xCF, 0xCF, 0x83, 0xE7, 0xC1, 0xF3, 0xE0, 0xF9, 0xF0, + 0x7C, 0xF8, 0x3E, 0x7C, 0x1F, 0x3E, 0x0F, 0x9F, 0x07, 0xCF, 0x83, 0xE7, + 0xC1, 0xF3, 0xE0, 0xF9, 0xF0, 0x7D, 0xFC, 0x7F, 0x07, 0xF0, 0x0F, 0xFE, + 0x0F, 0x8F, 0x8F, 0x87, 0xE7, 0xC1, 0xF7, 0xE0, 0xFF, 0xF0, 0x7F, 0xF8, + 0x3F, 0xFC, 0x1F, 0xFE, 0x0F, 0xFF, 0x07, 0xEF, 0x83, 0xE7, 0xC1, 0xF1, + 0xF1, 0xF0, 0x7F, 0xF0, 0x0F, 0xE0, 0xFE, 0x7C, 0x07, 0xDF, 0xE0, 0xFE, + 0x3E, 0x1F, 0x07, 0xE3, 0xE0, 0x7C, 0x7C, 0x0F, 0xCF, 0x81, 0xF9, 0xF0, + 0x3F, 0x3E, 0x07, 0xE7, 0xC0, 0xFC, 0xF8, 0x1F, 0x9F, 0x03, 0xE3, 0xE0, + 0xFC, 0x7E, 0x3F, 0x0F, 0xBF, 0xC1, 0xF3, 0xE0, 0x3E, 0x00, 0x07, 0xC0, + 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7E, 0x00, 0x1F, 0xE0, + 0x00, 0x07, 0xC1, 0x0F, 0xF9, 0x8F, 0xCD, 0xCF, 0xC3, 0xE7, 0xC1, 0xF7, + 0xE0, 0xFB, 0xF0, 0x7D, 0xF8, 0x3E, 0xFC, 0x1F, 0x7E, 0x0F, 0xBF, 0x07, + 0xDF, 0x83, 0xE7, 0xE1, 0xF1, 0xF1, 0xF8, 0x7F, 0x7C, 0x1F, 0x3E, 0x00, + 0x1F, 0x00, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xE0, 0x01, 0xF0, 0x01, 0xF8, + 0x01, 0xFE, 0xFC, 0x73, 0xEF, 0xDF, 0xFE, 0xFC, 0xF7, 0xC3, 0xBE, 0x01, + 0xF0, 0x0F, 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x07, 0xC0, 0x3E, + 0x01, 0xF0, 0x1F, 0xE0, 0x1E, 0x23, 0xFE, 0x70, 0xEE, 0x06, 0xE0, 0x2F, + 0x80, 0xFF, 0x07, 0xFC, 0x3F, 0xE0, 0xFF, 0x81, 0xF8, 0x07, 0xC0, 0x7E, + 0x0E, 0xBF, 0xC8, 0xF8, 0x04, 0x03, 0x01, 0xC0, 0xF0, 0x7C, 0x3F, 0xEF, + 0xF9, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, 0x7C, 0x1F, 0x07, 0xC1, 0xF0, + 0x7C, 0x5F, 0x37, 0xF8, 0xFE, 0x1E, 0x00, 0xFC, 0x7F, 0x1F, 0x07, 0xC7, + 0xC1, 0xF1, 0xF0, 0x7C, 0x7C, 0x1F, 0x1F, 0x07, 0xC7, 0xC1, 0xF1, 0xF0, + 0x7C, 0x7C, 0x1F, 0x1F, 0x07, 0xC7, 0xC1, 0xF1, 0xF0, 0x7C, 0x7C, 0x1F, + 0x1F, 0x8F, 0xC3, 0xFD, 0xFC, 0x7C, 0x60, 0xFF, 0x9F, 0xBF, 0x83, 0x0F, + 0x81, 0x87, 0xE0, 0x81, 0xF0, 0x40, 0xF8, 0x40, 0x3E, 0x20, 0x1F, 0x30, + 0x07, 0xD0, 0x03, 0xF8, 0x00, 0xF8, 0x00, 0x7C, 0x00, 0x3C, 0x00, 0x0E, + 0x00, 0x07, 0x00, 0x01, 0x00, 0xFF, 0x3F, 0xCF, 0x7E, 0x1F, 0x06, 0x3E, + 0x0F, 0x06, 0x3E, 0x0F, 0x84, 0x1F, 0x0F, 0x8C, 0x1F, 0x1F, 0x88, 0x0F, + 0x17, 0xC8, 0x0F, 0x97, 0xD8, 0x0F, 0xB3, 0xD0, 0x07, 0xE3, 0xF0, 0x07, + 0xE3, 0xE0, 0x03, 0xC1, 0xE0, 0x03, 0xC1, 0xE0, 0x03, 0x81, 0xC0, 0x01, + 0x80, 0xC0, 0x01, 0x80, 0x80, 0xFF, 0x3F, 0x7E, 0x0C, 0x3E, 0x08, 0x3F, + 0x18, 0x1F, 0x30, 0x0F, 0xE0, 0x0F, 0xC0, 0x07, 0xE0, 0x03, 0xE0, 0x03, + 0xF0, 0x05, 0xF8, 0x0C, 0xF8, 0x18, 0xFC, 0x30, 0x7E, 0x70, 0x7E, 0xFC, + 0xFF, 0xFF, 0x3F, 0x7E, 0x0C, 0x7C, 0x0C, 0x3E, 0x08, 0x3E, 0x08, 0x1E, + 0x18, 0x1F, 0x10, 0x0F, 0x30, 0x0F, 0xA0, 0x0F, 0xA0, 0x07, 0xE0, 0x07, + 0xC0, 0x03, 0xC0, 0x03, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x00, 0x01, + 0x00, 0x61, 0x00, 0xF2, 0x00, 0xF6, 0x00, 0xFC, 0x00, 0x78, 0x00, 0x7F, + 0xFD, 0xFF, 0xF7, 0x0F, 0xD0, 0x3E, 0x01, 0xF0, 0x0F, 0xC0, 0x3E, 0x01, + 0xF0, 0x0F, 0xC0, 0x3E, 0x01, 0xF8, 0x0F, 0xC1, 0x3E, 0x05, 0xF8, 0x7F, + 0xFF, 0xFF, 0xFF, 0x01, 0xE0, 0xF8, 0x3E, 0x07, 0x80, 0xF0, 0x1E, 0x03, + 0xC0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x07, 0x87, + 0x80, 0x1E, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, + 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF8, 0x0F, 0x80, 0x78, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, 0xF0, 0x0F, 0x80, 0xF0, + 0x0F, 0x01, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, + 0x01, 0xE0, 0x3C, 0x03, 0xC0, 0x0F, 0x0F, 0x03, 0xC0, 0x78, 0x0F, 0x01, + 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x78, 0x0F, 0x03, 0xE0, + 0xF8, 0x3C, 0x00, 0x3E, 0x00, 0x7F, 0xC6, 0xFF, 0xFF, 0x61, 0xFE, 0x00, + 0x7C }; + +const GFXglyph FreeSerifBold18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 9, 0, 1 }, // 0x20 ' ' + { 0, 6, 24, 12, 3, -23 }, // 0x21 '!' + { 18, 13, 10, 19, 3, -23 }, // 0x22 '"' + { 35, 18, 24, 17, 0, -23 }, // 0x23 '#' + { 89, 15, 28, 17, 1, -25 }, // 0x24 '$' + { 142, 27, 24, 35, 4, -23 }, // 0x25 '%' + { 223, 26, 25, 29, 2, -23 }, // 0x26 '&' + { 305, 4, 10, 10, 3, -23 }, // 0x27 ''' + { 310, 9, 30, 12, 2, -23 }, // 0x28 '(' + { 344, 9, 30, 12, 1, -23 }, // 0x29 ')' + { 378, 14, 15, 18, 2, -23 }, // 0x2A '*' + { 405, 19, 19, 24, 2, -17 }, // 0x2B '+' + { 451, 6, 12, 9, 1, -5 }, // 0x2C ',' + { 460, 8, 4, 12, 2, -9 }, // 0x2D '-' + { 464, 6, 6, 9, 1, -5 }, // 0x2E '.' + { 469, 11, 25, 10, -1, -23 }, // 0x2F '/' + { 504, 16, 24, 18, 1, -23 }, // 0x30 '0' + { 552, 12, 24, 18, 3, -23 }, // 0x31 '1' + { 588, 16, 24, 17, 1, -23 }, // 0x32 '2' + { 636, 16, 24, 18, 0, -23 }, // 0x33 '3' + { 684, 15, 24, 18, 1, -23 }, // 0x34 '4' + { 729, 15, 24, 18, 1, -23 }, // 0x35 '5' + { 774, 16, 24, 18, 1, -23 }, // 0x36 '6' + { 822, 16, 24, 17, 1, -23 }, // 0x37 '7' + { 870, 16, 24, 17, 1, -23 }, // 0x38 '8' + { 918, 16, 24, 18, 1, -23 }, // 0x39 '9' + { 966, 6, 16, 12, 3, -15 }, // 0x3A ':' + { 978, 7, 22, 12, 2, -15 }, // 0x3B ';' + { 998, 19, 20, 24, 2, -18 }, // 0x3C '<' + { 1046, 19, 12, 24, 2, -14 }, // 0x3D '=' + { 1075, 19, 20, 24, 3, -18 }, // 0x3E '>' + { 1123, 14, 24, 18, 2, -23 }, // 0x3F '?' + { 1165, 24, 25, 33, 4, -23 }, // 0x40 '@' + { 1240, 24, 24, 25, 1, -23 }, // 0x41 'A' + { 1312, 21, 24, 23, 1, -23 }, // 0x42 'B' + { 1375, 23, 25, 25, 1, -23 }, // 0x43 'C' + { 1447, 23, 24, 26, 1, -23 }, // 0x44 'D' + { 1516, 21, 24, 23, 2, -23 }, // 0x45 'E' + { 1579, 19, 24, 22, 2, -23 }, // 0x46 'F' + { 1636, 25, 25, 27, 1, -23 }, // 0x47 'G' + { 1715, 24, 24, 27, 2, -23 }, // 0x48 'H' + { 1787, 11, 24, 14, 2, -23 }, // 0x49 'I' + { 1820, 16, 27, 18, 0, -23 }, // 0x4A 'J' + { 1874, 25, 24, 27, 2, -23 }, // 0x4B 'K' + { 1949, 21, 24, 23, 2, -23 }, // 0x4C 'L' + { 2012, 31, 24, 33, 1, -23 }, // 0x4D 'M' + { 2105, 23, 24, 25, 1, -23 }, // 0x4E 'N' + { 2174, 25, 25, 27, 1, -23 }, // 0x4F 'O' + { 2253, 19, 24, 22, 2, -23 }, // 0x50 'P' + { 2310, 25, 30, 27, 1, -23 }, // 0x51 'Q' + { 2404, 23, 24, 25, 2, -23 }, // 0x52 'R' + { 2473, 16, 25, 20, 2, -23 }, // 0x53 'S' + { 2523, 21, 24, 23, 1, -23 }, // 0x54 'T' + { 2586, 22, 25, 25, 2, -23 }, // 0x55 'U' + { 2655, 24, 24, 25, 0, -23 }, // 0x56 'V' + { 2727, 34, 25, 34, 0, -23 }, // 0x57 'W' + { 2834, 24, 24, 25, 1, -23 }, // 0x58 'X' + { 2906, 24, 24, 25, 1, -23 }, // 0x59 'Y' + { 2978, 21, 24, 23, 1, -23 }, // 0x5A 'Z' + { 3041, 8, 29, 12, 2, -23 }, // 0x5B '[' + { 3070, 11, 25, 10, -1, -23 }, // 0x5C '\' + { 3105, 8, 29, 12, 2, -23 }, // 0x5D ']' + { 3134, 15, 13, 20, 3, -23 }, // 0x5E '^' + { 3159, 18, 3, 17, 0, 3 }, // 0x5F '_' + { 3166, 8, 6, 12, 0, -23 }, // 0x60 '`' + { 3172, 16, 16, 18, 1, -15 }, // 0x61 'a' + { 3204, 18, 24, 19, 1, -23 }, // 0x62 'b' + { 3258, 14, 16, 15, 1, -15 }, // 0x63 'c' + { 3286, 18, 24, 19, 1, -23 }, // 0x64 'd' + { 3340, 14, 16, 16, 1, -15 }, // 0x65 'e' + { 3368, 11, 24, 14, 2, -23 }, // 0x66 'f' + { 3401, 17, 23, 17, 1, -15 }, // 0x67 'g' + { 3450, 17, 24, 19, 1, -23 }, // 0x68 'h' + { 3501, 7, 24, 10, 2, -23 }, // 0x69 'i' + { 3522, 11, 31, 14, 0, -23 }, // 0x6A 'j' + { 3565, 18, 24, 19, 1, -23 }, // 0x6B 'k' + { 3619, 7, 24, 10, 1, -23 }, // 0x6C 'l' + { 3640, 27, 16, 29, 1, -15 }, // 0x6D 'm' + { 3694, 17, 16, 19, 1, -15 }, // 0x6E 'n' + { 3728, 17, 16, 18, 1, -15 }, // 0x6F 'o' + { 3762, 19, 23, 19, 0, -15 }, // 0x70 'p' + { 3817, 17, 23, 19, 1, -15 }, // 0x71 'q' + { 3866, 13, 16, 15, 1, -15 }, // 0x72 'r' + { 3892, 12, 16, 14, 1, -15 }, // 0x73 's' + { 3916, 10, 21, 12, 1, -20 }, // 0x74 't' + { 3943, 18, 16, 20, 1, -15 }, // 0x75 'u' + { 3979, 17, 16, 17, 0, -15 }, // 0x76 'v' + { 4013, 24, 16, 25, 0, -15 }, // 0x77 'w' + { 4061, 16, 16, 18, 1, -15 }, // 0x78 'x' + { 4093, 16, 23, 17, 0, -15 }, // 0x79 'y' + { 4139, 14, 16, 16, 0, -15 }, // 0x7A 'z' + { 4167, 11, 31, 14, 1, -24 }, // 0x7B '{' + { 4210, 3, 25, 8, 2, -23 }, // 0x7C '|' + { 4220, 11, 31, 14, 3, -24 }, // 0x7D '}' + { 4263, 16, 5, 18, 1, -11 } }; // 0x7E '~' + +const GFXfont FreeSerifBold18pt7b PROGMEM = { + (uint8_t *)FreeSerifBold18pt7bBitmaps, + (GFXglyph *)FreeSerifBold18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 4945 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBold24pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBold24pt7b.h new file mode 100644 index 0000000..0eb2d0b --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBold24pt7b.h @@ -0,0 +1,759 @@ +const uint8_t FreeSerifBold24pt7bBitmaps[] PROGMEM = { + 0x3C, 0x7E, 0xFE, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x7E, 0x7E, 0x7C, 0x7C, + 0x3C, 0x3C, 0x38, 0x38, 0x38, 0x38, 0x18, 0x10, 0x10, 0x10, 0x00, 0x00, + 0x00, 0x00, 0x3C, 0x7E, 0xFF, 0xFF, 0xFF, 0xFF, 0x7E, 0x3C, 0x70, 0x07, + 0x7C, 0x07, 0xFE, 0x03, 0xFF, 0x01, 0xFF, 0x80, 0xFF, 0xC0, 0x7F, 0xC0, + 0x3E, 0xE0, 0x0E, 0x70, 0x07, 0x38, 0x03, 0x9C, 0x01, 0xC4, 0x00, 0xE2, + 0x00, 0x20, 0x00, 0xF0, 0x70, 0x01, 0xC0, 0xE0, 0x03, 0x81, 0xC0, 0x0F, + 0x07, 0x80, 0x1E, 0x0F, 0x00, 0x3C, 0x1E, 0x00, 0x78, 0x3C, 0x00, 0xF0, + 0x78, 0x01, 0xC0, 0xE0, 0x03, 0x81, 0xC0, 0xFF, 0xFF, 0xF9, 0xFF, 0xFF, + 0xF3, 0xFF, 0xFF, 0xE0, 0x78, 0x3C, 0x00, 0xF0, 0x78, 0x01, 0xC0, 0xE0, + 0x03, 0x81, 0xC0, 0x0F, 0x07, 0x80, 0x1E, 0x0F, 0x00, 0x3C, 0x1E, 0x0F, + 0xFF, 0xFF, 0xDF, 0xFF, 0xFF, 0xBF, 0xFF, 0xFF, 0x03, 0x81, 0xC0, 0x0F, + 0x07, 0x80, 0x1E, 0x0F, 0x00, 0x3C, 0x1E, 0x00, 0x78, 0x3C, 0x00, 0xF0, + 0x78, 0x01, 0xE0, 0xE0, 0x03, 0x81, 0xC0, 0x07, 0x07, 0x80, 0x1E, 0x0F, + 0x00, 0x00, 0x60, 0x00, 0x03, 0x00, 0x00, 0x18, 0x00, 0x00, 0xC0, 0x00, + 0x7F, 0xF0, 0x0F, 0x37, 0xE0, 0xE1, 0x8F, 0x8E, 0x0C, 0x3C, 0x70, 0x60, + 0xE7, 0x83, 0x03, 0x3C, 0x18, 0x19, 0xF0, 0xC0, 0x4F, 0xC6, 0x02, 0x7F, + 0xF0, 0x03, 0xFF, 0x80, 0x0F, 0xFE, 0x00, 0x3F, 0xFC, 0x00, 0xFF, 0xF0, + 0x03, 0xFF, 0xE0, 0x0F, 0xFF, 0x80, 0x1F, 0xFE, 0x00, 0x3F, 0xF8, 0x01, + 0xFF, 0xC0, 0x0C, 0xFF, 0x00, 0x63, 0xFA, 0x03, 0x0F, 0xD0, 0x18, 0x3E, + 0x80, 0xC1, 0xF6, 0x06, 0x0F, 0xB8, 0x30, 0x79, 0xC1, 0x87, 0xCF, 0x0C, + 0x3C, 0x7E, 0x67, 0xC0, 0xFF, 0xF8, 0x00, 0xFE, 0x00, 0x00, 0xC0, 0x00, + 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0x80, 0x00, 0x00, 0x00, 0x00, 0x30, + 0x00, 0x3E, 0x00, 0x0C, 0x00, 0x0F, 0xF0, 0x03, 0x80, 0x07, 0xE7, 0x03, + 0xE0, 0x01, 0xF8, 0x7F, 0xFC, 0x00, 0x3E, 0x07, 0xF7, 0x00, 0x0F, 0xC0, + 0x80, 0xE0, 0x03, 0xF0, 0x10, 0x38, 0x00, 0x7E, 0x02, 0x07, 0x00, 0x0F, + 0x80, 0x41, 0xC0, 0x03, 0xF0, 0x10, 0x30, 0x00, 0x7E, 0x02, 0x0E, 0x00, + 0x0F, 0x80, 0xC1, 0x80, 0x01, 0xF0, 0x10, 0x70, 0x00, 0x3E, 0x06, 0x1C, + 0x00, 0x07, 0xC1, 0x83, 0x80, 0x00, 0x7C, 0x60, 0xE0, 0x1F, 0x07, 0xF8, + 0x18, 0x0F, 0xF8, 0x7C, 0x07, 0x07, 0xF1, 0x00, 0x00, 0xC1, 0xF8, 0x10, + 0x00, 0x38, 0x3F, 0x02, 0x00, 0x06, 0x0F, 0xC0, 0x40, 0x01, 0xC3, 0xF0, + 0x08, 0x00, 0x30, 0x7E, 0x01, 0x00, 0x0E, 0x1F, 0x80, 0x40, 0x03, 0x83, + 0xF0, 0x08, 0x00, 0x60, 0x7E, 0x01, 0x00, 0x1C, 0x0F, 0x80, 0x40, 0x03, + 0x01, 0xF0, 0x18, 0x00, 0xE0, 0x3E, 0x02, 0x00, 0x18, 0x03, 0xC0, 0xC0, + 0x07, 0x00, 0x7C, 0x70, 0x00, 0xC0, 0x07, 0xFC, 0x00, 0x38, 0x00, 0x7E, + 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x0F, 0xFE, 0x00, 0x00, 0x07, 0x8F, + 0xE0, 0x00, 0x03, 0xC1, 0xF8, 0x00, 0x00, 0xF0, 0x3F, 0x00, 0x00, 0x7C, + 0x07, 0xC0, 0x00, 0x1F, 0x01, 0xF0, 0x00, 0x07, 0xE0, 0x7C, 0x00, 0x01, + 0xF8, 0x1E, 0x00, 0x00, 0x7F, 0x07, 0x80, 0x00, 0x1F, 0xE3, 0x80, 0x00, + 0x03, 0xFF, 0xC0, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x00, 0x1F, 0xE0, 0x3F, + 0xF0, 0x07, 0xFC, 0x01, 0xF0, 0x07, 0xFF, 0x00, 0x78, 0x07, 0xBF, 0xE0, + 0x1C, 0x03, 0x87, 0xFC, 0x07, 0x01, 0xE0, 0xFF, 0x81, 0x80, 0xF0, 0x3F, + 0xE0, 0xC0, 0x7C, 0x07, 0xFC, 0x30, 0x1F, 0x00, 0xFF, 0x98, 0x0F, 0xC0, + 0x3F, 0xFC, 0x03, 0xF0, 0x07, 0xFF, 0x00, 0xFE, 0x00, 0xFF, 0x80, 0x3F, + 0x80, 0x3F, 0xF0, 0x0F, 0xF0, 0x07, 0xFE, 0x03, 0xFC, 0x00, 0xFF, 0x81, + 0x7F, 0x80, 0x3F, 0xF8, 0xDF, 0xF0, 0x1F, 0xFF, 0xE3, 0xFF, 0x0E, 0xFF, + 0xF8, 0xFF, 0xFE, 0x1F, 0xFC, 0x0F, 0xFE, 0x03, 0xFE, 0x00, 0xFE, 0x00, + 0x3E, 0x00, 0x77, 0xFF, 0xFF, 0xFF, 0xEE, 0x73, 0x9C, 0xE2, 0x00, 0x00, + 0x00, 0x03, 0x00, 0x60, 0x1C, 0x03, 0x80, 0x70, 0x06, 0x00, 0xE0, 0x1C, + 0x01, 0xC0, 0x3C, 0x03, 0xC0, 0x78, 0x07, 0x80, 0x78, 0x07, 0x80, 0xF8, + 0x0F, 0x80, 0xF8, 0x0F, 0x80, 0xF8, 0x0F, 0x80, 0xF8, 0x0F, 0x80, 0xF8, + 0x0F, 0x80, 0x78, 0x07, 0x80, 0x78, 0x03, 0xC0, 0x3C, 0x01, 0xC0, 0x1C, + 0x00, 0xE0, 0x0E, 0x00, 0x70, 0x03, 0x00, 0x18, 0x00, 0xC0, 0x03, 0x00, + 0x10, 0x00, 0x0C, 0x00, 0x60, 0x03, 0x00, 0x18, 0x00, 0xC0, 0x06, 0x00, + 0x70, 0x03, 0x80, 0x38, 0x03, 0xC0, 0x3C, 0x03, 0xE0, 0x1E, 0x01, 0xE0, + 0x1E, 0x01, 0xF0, 0x1F, 0x01, 0xF0, 0x1F, 0x01, 0xF0, 0x1F, 0x01, 0xF0, + 0x1F, 0x01, 0xF0, 0x1F, 0x01, 0xE0, 0x1E, 0x01, 0xE0, 0x3C, 0x03, 0xC0, + 0x38, 0x03, 0x80, 0x70, 0x07, 0x00, 0xE0, 0x0C, 0x01, 0x80, 0x30, 0x0C, + 0x00, 0x80, 0x00, 0x01, 0xC0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, + 0x03, 0xE0, 0x3C, 0x78, 0xEF, 0x9C, 0x7B, 0xF7, 0x3F, 0xFE, 0xDF, 0x8F, + 0xFF, 0xC0, 0x7F, 0x00, 0x3F, 0xC0, 0x7E, 0xBF, 0x3F, 0x77, 0xEF, 0x9C, + 0xFF, 0xC7, 0x1E, 0x63, 0xE3, 0x80, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x80, + 0x01, 0xC0, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, 0xE0, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x00, 0x01, + 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, 0x80, 0x0F, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x07, + 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x07, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0x3C, 0x7E, 0xFE, 0xFF, 0xFF, 0xFF, 0x7F, 0x07, 0x06, 0x06, 0x0C, + 0x18, 0x30, 0x60, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFE, 0x3C, + 0x7E, 0xFF, 0xFF, 0xFF, 0xFF, 0x7E, 0x3C, 0x00, 0x1E, 0x00, 0x7C, 0x00, + 0xF0, 0x01, 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x7C, 0x00, 0xF0, + 0x01, 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x7C, 0x00, 0xF0, 0x01, + 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x7C, 0x00, 0xF0, 0x01, 0xE0, + 0x03, 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0xF0, 0x01, 0xE0, 0x03, + 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0xF0, 0x00, 0x00, 0xFC, 0x00, + 0x0F, 0x3C, 0x00, 0x78, 0x78, 0x03, 0xE1, 0xF0, 0x1F, 0x03, 0xE0, 0x7C, + 0x0F, 0x83, 0xF0, 0x3F, 0x0F, 0xC0, 0xFC, 0x7F, 0x03, 0xF9, 0xFC, 0x0F, + 0xE7, 0xF0, 0x3F, 0xBF, 0xC0, 0xFE, 0xFF, 0x03, 0xFF, 0xFC, 0x0F, 0xFF, + 0xF0, 0x3F, 0xFF, 0xC0, 0xFF, 0xFF, 0x03, 0xFF, 0xFC, 0x0F, 0xFF, 0xF0, + 0x3F, 0xFF, 0xC0, 0xFF, 0xFF, 0x03, 0xFF, 0xFC, 0x0F, 0xFF, 0xF0, 0x3F, + 0x9F, 0xC0, 0xFE, 0x7F, 0x03, 0xF9, 0xFC, 0x0F, 0xE3, 0xF0, 0x3F, 0x0F, + 0xC0, 0xFC, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x80, 0xF8, 0x7C, 0x01, 0xE1, + 0xE0, 0x03, 0xCF, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x18, 0x00, 0x1E, 0x00, + 0x1F, 0x80, 0x1F, 0xE0, 0x1F, 0xF8, 0x1D, 0xFE, 0x00, 0x3F, 0x80, 0x0F, + 0xE0, 0x03, 0xF8, 0x00, 0xFE, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x03, 0xF8, + 0x00, 0xFE, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x03, 0xF8, 0x00, 0xFE, 0x00, + 0x3F, 0x80, 0x0F, 0xE0, 0x03, 0xF8, 0x00, 0xFE, 0x00, 0x3F, 0x80, 0x0F, + 0xE0, 0x03, 0xF8, 0x00, 0xFE, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x03, 0xF8, + 0x00, 0xFE, 0x00, 0x7F, 0x80, 0x3F, 0xF8, 0xFF, 0xFF, 0xC0, 0x00, 0xFC, + 0x00, 0x1F, 0xF8, 0x03, 0xFF, 0xE0, 0x3F, 0xFF, 0x81, 0xFF, 0xFC, 0x1C, + 0x1F, 0xF1, 0xC0, 0x7F, 0x8C, 0x01, 0xFC, 0x40, 0x0F, 0xE0, 0x00, 0x3F, + 0x00, 0x01, 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, + 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x00, + 0x00, 0x70, 0x00, 0x07, 0x80, 0x00, 0x38, 0x00, 0x03, 0x80, 0x00, 0x38, + 0x01, 0x03, 0x80, 0x18, 0x38, 0x00, 0x81, 0x80, 0x1C, 0x1F, 0xFF, 0xE1, + 0xFF, 0xFF, 0x1F, 0xFF, 0xF9, 0xFF, 0xFF, 0x9F, 0xFF, 0xFC, 0xFF, 0xFF, + 0xE0, 0x00, 0xFE, 0x00, 0x3F, 0xFC, 0x03, 0xFF, 0xF0, 0x30, 0xFF, 0xC2, + 0x01, 0xFE, 0x30, 0x0F, 0xF1, 0x00, 0x3F, 0x80, 0x01, 0xFC, 0x00, 0x0F, + 0xE0, 0x00, 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x01, 0xF0, 0x00, + 0x1F, 0xC0, 0x03, 0xFF, 0x00, 0x3F, 0xFC, 0x00, 0x7F, 0xF0, 0x00, 0xFF, + 0x80, 0x03, 0xFE, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0x80, 0x00, 0xFC, 0x00, + 0x07, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0x80, 0x00, 0x3C, + 0x00, 0x01, 0xC7, 0x80, 0x0E, 0x7F, 0x00, 0xE3, 0xFC, 0x06, 0x1F, 0xF8, + 0xE0, 0x7F, 0xFC, 0x00, 0xFF, 0x00, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x1E, + 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xE0, 0x00, + 0xFF, 0x00, 0x0D, 0xF8, 0x00, 0xEF, 0xC0, 0x06, 0x7E, 0x00, 0x63, 0xF0, + 0x07, 0x1F, 0x80, 0x30, 0xFC, 0x03, 0x07, 0xE0, 0x38, 0x3F, 0x03, 0x81, + 0xF8, 0x18, 0x0F, 0xC1, 0xC0, 0x7E, 0x1C, 0x03, 0xF0, 0xC0, 0x1F, 0x8E, + 0x00, 0xFC, 0x7F, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xC0, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0xFC, 0x00, + 0x07, 0xE0, 0x00, 0x3F, 0x00, 0x01, 0xF8, 0x00, 0x0F, 0xC0, 0x07, 0xFF, + 0xF0, 0x7F, 0xFF, 0x0F, 0xFF, 0xE0, 0xFF, 0xFE, 0x0F, 0xFF, 0xE1, 0xFF, + 0xFC, 0x18, 0x00, 0x01, 0x80, 0x00, 0x18, 0x00, 0x03, 0x00, 0x00, 0x3F, + 0x80, 0x03, 0xFF, 0x80, 0x7F, 0xFE, 0x07, 0xFF, 0xF0, 0x7F, 0xFF, 0x87, + 0xFF, 0xFC, 0x7F, 0xFF, 0xC0, 0x07, 0xFC, 0x00, 0x1F, 0xE0, 0x00, 0x7E, + 0x00, 0x03, 0xE0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x00, + 0xC0, 0x00, 0x0C, 0x78, 0x00, 0x8F, 0xE0, 0x18, 0xFF, 0x87, 0x0F, 0xFF, + 0xE0, 0x7F, 0xF8, 0x01, 0xFE, 0x00, 0x00, 0x00, 0x38, 0x00, 0x1F, 0x00, + 0x07, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, + 0x00, 0xFC, 0x00, 0x0F, 0xE0, 0x00, 0xFE, 0x00, 0x0F, 0xF0, 0x00, 0x7F, + 0x00, 0x07, 0xF8, 0x00, 0x3F, 0xFF, 0x01, 0xFF, 0xFE, 0x1F, 0xF1, 0xFC, + 0xFF, 0x07, 0xE7, 0xF8, 0x3F, 0xBF, 0xC1, 0xFD, 0xFE, 0x07, 0xFF, 0xF0, + 0x3F, 0xFF, 0x81, 0xFF, 0xFC, 0x0F, 0xFF, 0xE0, 0x7F, 0xFF, 0x03, 0xFB, + 0xF8, 0x1F, 0xDF, 0xC0, 0xFE, 0xFE, 0x07, 0xE3, 0xF0, 0x3F, 0x1F, 0xC1, + 0xF0, 0x7E, 0x0F, 0x01, 0xF0, 0xF8, 0x03, 0xC7, 0x00, 0x07, 0xE0, 0x00, + 0x3F, 0xFF, 0xF9, 0xFF, 0xFF, 0xDF, 0xFF, 0xFE, 0xFF, 0xFF, 0xE7, 0xFF, + 0xFF, 0x3F, 0xFF, 0xF9, 0x80, 0x07, 0x98, 0x00, 0x3C, 0xC0, 0x03, 0xE4, + 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, + 0xC0, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0xF0, 0x00, + 0x07, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x01, 0xF0, + 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x07, 0xC0, 0x00, 0x3C, 0x00, 0x01, + 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, + 0x01, 0xFE, 0x00, 0x38, 0x7C, 0x07, 0x80, 0xF0, 0x78, 0x07, 0xC3, 0xC0, + 0x1F, 0x3E, 0x00, 0xF9, 0xF0, 0x07, 0xCF, 0xC0, 0x3E, 0x7E, 0x01, 0xF3, + 0xF8, 0x0F, 0x1F, 0xE0, 0xF8, 0x7F, 0xC7, 0x83, 0xFF, 0xF0, 0x0F, 0xFE, + 0x00, 0x7F, 0xFC, 0x01, 0xFF, 0xF0, 0x03, 0xFF, 0xC0, 0x1F, 0xFF, 0x03, + 0xBF, 0xFC, 0x7C, 0x7F, 0xE7, 0xC1, 0xFF, 0x3E, 0x07, 0xFF, 0xE0, 0x1F, + 0xFF, 0x00, 0x7F, 0xF8, 0x03, 0xFF, 0xC0, 0x0F, 0xFE, 0x00, 0x7F, 0xF0, + 0x03, 0xE7, 0x80, 0x1F, 0x3E, 0x01, 0xF0, 0xF8, 0x0F, 0x83, 0xE1, 0xF8, + 0x0F, 0xFF, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFC, 0x00, 0x1C, 0x3C, 0x00, + 0xF0, 0x78, 0x07, 0x81, 0xF8, 0x3E, 0x07, 0xE1, 0xF8, 0x0F, 0xC7, 0xE0, + 0x3F, 0x3F, 0x80, 0xFE, 0xFE, 0x03, 0xFB, 0xF8, 0x0F, 0xFF, 0xE0, 0x3F, + 0xFF, 0x80, 0xFF, 0xFE, 0x03, 0xFF, 0xF8, 0x0F, 0xFF, 0xE0, 0x3F, 0xDF, + 0xC0, 0xFF, 0x7F, 0x03, 0xFC, 0xFC, 0x0F, 0xF3, 0xFC, 0x7F, 0x83, 0xFF, + 0xFE, 0x07, 0xF7, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0x00, 0x03, 0xF8, + 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x00, 0x03, 0xF8, 0x00, 0x0F, 0xC0, 0x00, + 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x01, 0xF0, 0x00, 0x3F, 0x00, + 0x03, 0x80, 0x00, 0x00, 0x3C, 0x7E, 0xFF, 0xFF, 0xFF, 0xFF, 0x7E, 0x3C, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3C, 0x7E, 0xFF, 0xFF, + 0xFF, 0xFF, 0x7E, 0x3C, 0x3C, 0x3F, 0x3F, 0xDF, 0xEF, 0xF7, 0xF9, 0xF8, + 0x78, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x78, 0x7F, 0x7F, + 0xBF, 0xFF, 0xFF, 0xFB, 0xFC, 0xFE, 0x07, 0x03, 0x01, 0x81, 0x81, 0x81, + 0x83, 0x81, 0x00, 0x00, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, + 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0xFF, 0xC0, 0x01, 0xFF, 0x80, 0x01, + 0xFF, 0x80, 0x01, 0xFF, 0x80, 0x01, 0xFF, 0x80, 0x01, 0xFF, 0x80, 0x01, + 0xFF, 0x80, 0x01, 0xFF, 0x80, 0x00, 0xFF, 0x80, 0x00, 0x3F, 0xE0, 0x00, + 0x07, 0xFE, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0x7F, + 0xE0, 0x00, 0x07, 0xFF, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x03, 0xFF, 0x00, + 0x00, 0x3F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x03, + 0xC0, 0x00, 0x00, 0x30, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, + 0xC0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x03, 0xFC, 0x00, + 0x00, 0xFF, 0xC0, 0x00, 0x0F, 0xFC, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x0F, + 0xFE, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0x07, 0xFE, 0x00, 0x00, 0x7F, 0xE0, + 0x00, 0x07, 0xFE, 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x1F, 0xF0, 0x00, 0x1F, + 0xF8, 0x00, 0x1F, 0xF8, 0x00, 0x1F, 0xF8, 0x00, 0x1F, 0xF8, 0x00, 0x1F, + 0xF8, 0x00, 0x1F, 0xF8, 0x00, 0x1F, 0xF8, 0x00, 0x3F, 0xF0, 0x00, 0x0F, + 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x30, 0x00, 0x00, + 0x00, 0x07, 0xF0, 0x07, 0xFF, 0x03, 0x87, 0xE1, 0xC0, 0xFC, 0xF0, 0x3F, + 0xBE, 0x07, 0xEF, 0xC1, 0xFF, 0xF0, 0x7F, 0xFC, 0x1F, 0xDF, 0x07, 0xF7, + 0x81, 0xFC, 0x00, 0xFE, 0x00, 0x3F, 0x80, 0x1F, 0xC0, 0x07, 0xE0, 0x03, + 0xE0, 0x00, 0xF0, 0x00, 0x70, 0x00, 0x18, 0x00, 0x04, 0x00, 0x01, 0x00, + 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x3C, 0x00, 0x1F, 0x80, 0x0F, 0xF0, 0x03, 0xFC, 0x00, 0xFF, 0x00, 0x3F, + 0xC0, 0x07, 0xE0, 0x00, 0xF0, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x1F, + 0xFF, 0xC0, 0x00, 0x1F, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x1E, 0x00, 0x3C, + 0x00, 0x03, 0x80, 0x3C, 0x00, 0x00, 0xE0, 0x3C, 0x00, 0x00, 0x30, 0x3E, + 0x00, 0x00, 0x0C, 0x3E, 0x00, 0x3C, 0x37, 0x1F, 0x00, 0x7E, 0xF1, 0x9F, + 0x00, 0x7C, 0xF8, 0xCF, 0x80, 0x78, 0x7C, 0x37, 0xC0, 0x7C, 0x3C, 0x1F, + 0xC0, 0x3C, 0x1E, 0x0F, 0xE0, 0x3C, 0x0F, 0x07, 0xF0, 0x3E, 0x0F, 0x03, + 0xF8, 0x1E, 0x07, 0x81, 0xFC, 0x0F, 0x03, 0xC0, 0xFE, 0x0F, 0x03, 0xE0, + 0x7F, 0x07, 0x81, 0xE0, 0x6F, 0x83, 0xC1, 0xF0, 0x37, 0xC1, 0xE1, 0x78, + 0x31, 0xF0, 0xF9, 0xBC, 0x18, 0xF8, 0x3F, 0x9E, 0x38, 0x3C, 0x0F, 0x0F, + 0xF8, 0x1F, 0x00, 0x01, 0xF0, 0x07, 0x80, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x00, 0xF8, 0x00, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0x07, 0xC0, + 0x00, 0xC0, 0x01, 0xF8, 0x03, 0xE0, 0x00, 0x3F, 0xFF, 0xC0, 0x00, 0x03, + 0xFF, 0x00, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x03, 0x80, 0x00, 0x00, + 0x03, 0x80, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, + 0x07, 0xE0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, + 0x0F, 0xF0, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, + 0x37, 0xF8, 0x00, 0x00, 0x33, 0xF8, 0x00, 0x00, 0x33, 0xFC, 0x00, 0x00, + 0x61, 0xFC, 0x00, 0x00, 0x61, 0xFE, 0x00, 0x00, 0xC1, 0xFE, 0x00, 0x00, + 0xC0, 0xFF, 0x00, 0x00, 0xC0, 0xFF, 0x00, 0x01, 0x80, 0x7F, 0x00, 0x01, + 0x80, 0x7F, 0x80, 0x03, 0x80, 0x7F, 0x80, 0x03, 0xFF, 0xFF, 0xC0, 0x03, + 0xFF, 0xFF, 0xC0, 0x07, 0x00, 0x3F, 0xC0, 0x06, 0x00, 0x1F, 0xE0, 0x0E, + 0x00, 0x1F, 0xE0, 0x0C, 0x00, 0x0F, 0xF0, 0x0C, 0x00, 0x0F, 0xF0, 0x1C, + 0x00, 0x0F, 0xF8, 0x1C, 0x00, 0x0F, 0xF8, 0x7E, 0x00, 0x0F, 0xFC, 0xFF, + 0x80, 0x7F, 0xFF, 0xFF, 0xFF, 0xF0, 0x0F, 0xFF, 0xFF, 0xE0, 0x1F, 0xF8, + 0x7F, 0x00, 0xFF, 0x03, 0xFC, 0x0F, 0xF0, 0x3F, 0xC0, 0xFF, 0x01, 0xFE, + 0x0F, 0xF0, 0x1F, 0xE0, 0xFF, 0x01, 0xFE, 0x0F, 0xF0, 0x1F, 0xE0, 0xFF, + 0x01, 0xFE, 0x0F, 0xF0, 0x1F, 0xC0, 0xFF, 0x03, 0xFC, 0x0F, 0xF0, 0x3F, + 0x00, 0xFF, 0x0F, 0xC0, 0x0F, 0xFF, 0xE0, 0x00, 0xFF, 0xFF, 0xC0, 0x0F, + 0xF0, 0xFF, 0x00, 0xFF, 0x03, 0xFC, 0x0F, 0xF0, 0x1F, 0xE0, 0xFF, 0x01, + 0xFE, 0x0F, 0xF0, 0x0F, 0xF0, 0xFF, 0x00, 0xFF, 0x0F, 0xF0, 0x0F, 0xF0, + 0xFF, 0x00, 0xFF, 0x0F, 0xF0, 0x0F, 0xF0, 0xFF, 0x00, 0xFF, 0x0F, 0xF0, + 0x0F, 0xE0, 0xFF, 0x01, 0xFE, 0x0F, 0xF0, 0x1F, 0xC0, 0xFF, 0x87, 0xF0, + 0x3F, 0xFF, 0xFE, 0x0F, 0xFF, 0xFF, 0x00, 0x00, 0x0F, 0xF0, 0x08, 0x01, + 0xFF, 0xF0, 0x60, 0x0F, 0xC1, 0xF9, 0x80, 0xFC, 0x01, 0xFE, 0x07, 0xE0, + 0x01, 0xF8, 0x3F, 0x00, 0x03, 0xE1, 0xFC, 0x00, 0x07, 0x87, 0xE0, 0x00, + 0x1E, 0x3F, 0x80, 0x00, 0x38, 0xFE, 0x00, 0x00, 0x67, 0xF8, 0x00, 0x01, + 0x9F, 0xC0, 0x00, 0x02, 0x7F, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x0F, + 0xF0, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x03, 0xFC, + 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x00, 0xFF, 0x00, + 0x00, 0x03, 0xFC, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x1F, 0xE0, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0x87, 0xF0, 0x00, 0x07, 0x0F, 0xE0, 0x00, 0x38, 0x1F, 0x80, 0x01, 0xC0, + 0x3F, 0x00, 0x1E, 0x00, 0x7F, 0x01, 0xE0, 0x00, 0x7F, 0xFF, 0x00, 0x00, + 0x3F, 0xE0, 0x00, 0xFF, 0xFF, 0xE0, 0x00, 0x3F, 0xFF, 0xFE, 0x00, 0x0F, + 0xF8, 0x7F, 0x80, 0x0F, 0xF0, 0x1F, 0xC0, 0x0F, 0xF0, 0x0F, 0xF0, 0x0F, + 0xF0, 0x07, 0xF0, 0x0F, 0xF0, 0x03, 0xF8, 0x0F, 0xF0, 0x03, 0xFC, 0x0F, + 0xF0, 0x01, 0xFC, 0x0F, 0xF0, 0x01, 0xFE, 0x0F, 0xF0, 0x01, 0xFE, 0x0F, + 0xF0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, + 0xF0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, + 0xF0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, 0xF0, 0x00, 0xFF, 0x0F, + 0xF0, 0x00, 0xFE, 0x0F, 0xF0, 0x00, 0xFE, 0x0F, 0xF0, 0x01, 0xFE, 0x0F, + 0xF0, 0x01, 0xFC, 0x0F, 0xF0, 0x01, 0xFC, 0x0F, 0xF0, 0x03, 0xF8, 0x0F, + 0xF0, 0x03, 0xF0, 0x0F, 0xF0, 0x07, 0xE0, 0x0F, 0xF0, 0x0F, 0xC0, 0x0F, + 0xF8, 0x3F, 0x80, 0x1F, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0xF0, 0x00, 0xFF, + 0xFF, 0xFF, 0xC3, 0xFF, 0xFF, 0xFC, 0x1F, 0xE0, 0x1F, 0xC1, 0xFE, 0x00, + 0x3C, 0x1F, 0xE0, 0x01, 0xC1, 0xFE, 0x00, 0x0C, 0x1F, 0xE0, 0x00, 0xC1, + 0xFE, 0x00, 0x04, 0x1F, 0xE0, 0x20, 0x41, 0xFE, 0x02, 0x00, 0x1F, 0xE0, + 0x60, 0x01, 0xFE, 0x06, 0x00, 0x1F, 0xE0, 0xE0, 0x01, 0xFE, 0x1E, 0x00, + 0x1F, 0xFF, 0xE0, 0x01, 0xFF, 0xFE, 0x00, 0x1F, 0xE3, 0xE0, 0x01, 0xFE, + 0x0E, 0x00, 0x1F, 0xE0, 0x60, 0x01, 0xFE, 0x06, 0x00, 0x1F, 0xE0, 0x20, + 0x01, 0xFE, 0x02, 0x00, 0x1F, 0xE0, 0x00, 0x11, 0xFE, 0x00, 0x03, 0x1F, + 0xE0, 0x00, 0x71, 0xFE, 0x00, 0x07, 0x1F, 0xE0, 0x00, 0xE1, 0xFE, 0x00, + 0x1E, 0x1F, 0xE0, 0x03, 0xE3, 0xFF, 0x01, 0xFE, 0xFF, 0xFF, 0xFF, 0xEF, + 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0x9F, 0xFF, 0xFF, 0xC7, 0xFC, 0x07, + 0xE3, 0xFC, 0x00, 0xF1, 0xFE, 0x00, 0x38, 0xFF, 0x00, 0x0C, 0x7F, 0x80, + 0x06, 0x3F, 0xC0, 0x01, 0x1F, 0xE0, 0x20, 0x8F, 0xF0, 0x10, 0x07, 0xF8, + 0x18, 0x03, 0xFC, 0x0C, 0x01, 0xFE, 0x0E, 0x00, 0xFF, 0x1F, 0x00, 0x7F, + 0xFF, 0x80, 0x3F, 0xFF, 0xC0, 0x1F, 0xE3, 0xE0, 0x0F, 0xF0, 0x70, 0x07, + 0xF8, 0x18, 0x03, 0xFC, 0x0C, 0x01, 0xFE, 0x02, 0x00, 0xFF, 0x01, 0x00, + 0x7F, 0x80, 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, + 0x07, 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x00, + 0x00, 0xFF, 0xC0, 0x01, 0xFF, 0xFC, 0x00, 0x00, 0x0F, 0xF0, 0x08, 0x00, + 0x3F, 0xFE, 0x0C, 0x00, 0x3F, 0x07, 0xC6, 0x00, 0x7E, 0x00, 0xFF, 0x00, + 0x7E, 0x00, 0x1F, 0x80, 0x7E, 0x00, 0x07, 0xC0, 0x7F, 0x00, 0x01, 0xE0, + 0x3F, 0x00, 0x00, 0x70, 0x3F, 0x80, 0x00, 0x38, 0x1F, 0xC0, 0x00, 0x0C, + 0x1F, 0xE0, 0x00, 0x06, 0x0F, 0xE0, 0x00, 0x01, 0x07, 0xF0, 0x00, 0x00, + 0x07, 0xF8, 0x00, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x01, 0xFE, 0x00, 0x00, + 0x00, 0xFF, 0x00, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x00, 0x3F, 0xC0, 0x00, + 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x0F, 0xF0, 0x03, 0xFF, 0xFF, 0xF8, 0x00, + 0x3F, 0xF1, 0xFC, 0x00, 0x0F, 0xF0, 0xFF, 0x00, 0x07, 0xF8, 0x7F, 0x80, + 0x03, 0xFC, 0x1F, 0xC0, 0x01, 0xFE, 0x0F, 0xE0, 0x00, 0xFF, 0x03, 0xF8, + 0x00, 0x7F, 0x80, 0xFC, 0x00, 0x3F, 0xC0, 0x3F, 0x00, 0x1F, 0xE0, 0x0F, + 0xC0, 0x0F, 0xF0, 0x03, 0xF8, 0x1F, 0xF0, 0x00, 0x7F, 0xFF, 0xC0, 0x00, + 0x07, 0xFE, 0x00, 0x00, 0xFF, 0xFC, 0x1F, 0xFF, 0x9F, 0xF8, 0x03, 0xFF, + 0x07, 0xF8, 0x00, 0xFF, 0x03, 0xFC, 0x00, 0x7F, 0x81, 0xFE, 0x00, 0x3F, + 0xC0, 0xFF, 0x00, 0x1F, 0xE0, 0x7F, 0x80, 0x0F, 0xF0, 0x3F, 0xC0, 0x07, + 0xF8, 0x1F, 0xE0, 0x03, 0xFC, 0x0F, 0xF0, 0x01, 0xFE, 0x07, 0xF8, 0x00, + 0xFF, 0x03, 0xFC, 0x00, 0x7F, 0x81, 0xFE, 0x00, 0x3F, 0xC0, 0xFF, 0x00, + 0x1F, 0xE0, 0x7F, 0x80, 0x0F, 0xF0, 0x3F, 0xFF, 0xFF, 0xF8, 0x1F, 0xFF, + 0xFF, 0xFC, 0x0F, 0xF0, 0x01, 0xFE, 0x07, 0xF8, 0x00, 0xFF, 0x03, 0xFC, + 0x00, 0x7F, 0x81, 0xFE, 0x00, 0x3F, 0xC0, 0xFF, 0x00, 0x1F, 0xE0, 0x7F, + 0x80, 0x0F, 0xF0, 0x3F, 0xC0, 0x07, 0xF8, 0x1F, 0xE0, 0x03, 0xFC, 0x0F, + 0xF0, 0x01, 0xFE, 0x07, 0xF8, 0x00, 0xFF, 0x03, 0xFC, 0x00, 0x7F, 0x81, + 0xFE, 0x00, 0x3F, 0xC0, 0xFF, 0x00, 0x1F, 0xE0, 0xFF, 0xC0, 0x1F, 0xF9, + 0xFF, 0xF8, 0x3F, 0xFF, 0xFF, 0xFE, 0x7F, 0xE0, 0x7F, 0x80, 0xFF, 0x01, + 0xFE, 0x03, 0xFC, 0x07, 0xF8, 0x0F, 0xF0, 0x1F, 0xE0, 0x3F, 0xC0, 0x7F, + 0x80, 0xFF, 0x01, 0xFE, 0x03, 0xFC, 0x07, 0xF8, 0x0F, 0xF0, 0x1F, 0xE0, + 0x3F, 0xC0, 0x7F, 0x80, 0xFF, 0x01, 0xFE, 0x03, 0xFC, 0x07, 0xF8, 0x0F, + 0xF0, 0x1F, 0xE0, 0x3F, 0xC0, 0x7F, 0x80, 0xFF, 0x01, 0xFE, 0x03, 0xFC, + 0x0F, 0xFC, 0x7F, 0xFF, 0x01, 0xFF, 0xFC, 0x00, 0xFF, 0xC0, 0x01, 0xFE, + 0x00, 0x07, 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, + 0x07, 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x07, + 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x07, 0xF8, + 0x00, 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x07, 0xF8, 0x00, + 0x1F, 0xE0, 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x07, 0xF8, 0x00, 0x1F, + 0xE0, 0x00, 0x7F, 0x80, 0x01, 0xFE, 0x00, 0x07, 0xF8, 0x78, 0x1F, 0xE3, + 0xF0, 0x7F, 0x8F, 0xC1, 0xFC, 0x3F, 0x07, 0xF0, 0xFC, 0x1F, 0xC1, 0xE0, + 0xFE, 0x07, 0xC3, 0xF0, 0x0F, 0xFF, 0x80, 0x07, 0xF0, 0x00, 0xFF, 0xFC, + 0x1F, 0xFF, 0x0F, 0xFC, 0x00, 0xFF, 0x01, 0xFE, 0x00, 0x1E, 0x00, 0x7F, + 0x80, 0x07, 0x00, 0x1F, 0xE0, 0x03, 0x80, 0x07, 0xF8, 0x01, 0xC0, 0x01, + 0xFE, 0x00, 0xE0, 0x00, 0x7F, 0x80, 0x70, 0x00, 0x1F, 0xE0, 0x38, 0x00, + 0x07, 0xF8, 0x1C, 0x00, 0x01, 0xFE, 0x0E, 0x00, 0x00, 0x7F, 0x87, 0x00, + 0x00, 0x1F, 0xE3, 0xC0, 0x00, 0x07, 0xF9, 0xF8, 0x00, 0x01, 0xFE, 0xFE, + 0x00, 0x00, 0x7F, 0xFF, 0xC0, 0x00, 0x1F, 0xFF, 0xF8, 0x00, 0x07, 0xFD, + 0xFF, 0x00, 0x01, 0xFE, 0x7F, 0xE0, 0x00, 0x7F, 0x8F, 0xF8, 0x00, 0x1F, + 0xE1, 0xFF, 0x00, 0x07, 0xF8, 0x3F, 0xE0, 0x01, 0xFE, 0x07, 0xFC, 0x00, + 0x7F, 0x81, 0xFF, 0x80, 0x1F, 0xE0, 0x3F, 0xE0, 0x07, 0xF8, 0x07, 0xFC, + 0x01, 0xFE, 0x00, 0xFF, 0x80, 0x7F, 0x80, 0x1F, 0xF0, 0x1F, 0xE0, 0x07, + 0xFE, 0x07, 0xF8, 0x00, 0xFF, 0x83, 0xFF, 0x00, 0x3F, 0xF3, 0xFF, 0xF0, + 0xFF, 0xFF, 0xFF, 0xFE, 0x00, 0x03, 0xFF, 0x00, 0x00, 0x1F, 0xE0, 0x00, + 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x1F, + 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, + 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, + 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xE0, + 0x00, 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, + 0x1F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x01, 0x1F, 0xE0, 0x00, 0x31, 0xFE, + 0x00, 0x03, 0x1F, 0xE0, 0x00, 0x71, 0xFE, 0x00, 0x07, 0x1F, 0xE0, 0x00, + 0xE1, 0xFE, 0x00, 0x1E, 0x1F, 0xE0, 0x07, 0xE3, 0xFF, 0x01, 0xFE, 0xFF, + 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xFE, 0x7F, 0xF0, 0x00, 0x01, 0xFF, 0xE1, + 0xFF, 0x00, 0x00, 0x3F, 0xF0, 0x1F, 0xE0, 0x00, 0x0F, 0xFC, 0x03, 0xFC, + 0x00, 0x01, 0xFF, 0x80, 0x7F, 0xC0, 0x00, 0x2F, 0xF0, 0x0B, 0xF8, 0x00, + 0x0D, 0xFE, 0x01, 0x7F, 0x80, 0x01, 0xBF, 0xC0, 0x27, 0xF0, 0x00, 0x67, + 0xF8, 0x04, 0xFF, 0x00, 0x0C, 0xFF, 0x00, 0x8F, 0xE0, 0x03, 0x1F, 0xE0, + 0x11, 0xFE, 0x00, 0x63, 0xFC, 0x02, 0x3F, 0xC0, 0x08, 0x7F, 0x80, 0x43, + 0xF8, 0x03, 0x0F, 0xF0, 0x08, 0x7F, 0x80, 0x61, 0xFE, 0x01, 0x07, 0xF0, + 0x18, 0x3F, 0xC0, 0x20, 0xFF, 0x03, 0x07, 0xF8, 0x04, 0x0F, 0xE0, 0xC0, + 0xFF, 0x00, 0x81, 0xFE, 0x18, 0x1F, 0xE0, 0x10, 0x3F, 0xC6, 0x03, 0xFC, + 0x02, 0x03, 0xF8, 0xC0, 0x7F, 0x80, 0x40, 0x7F, 0x98, 0x0F, 0xF0, 0x08, + 0x07, 0xF6, 0x01, 0xFE, 0x01, 0x00, 0xFF, 0xC0, 0x3F, 0xC0, 0x20, 0x0F, + 0xF0, 0x07, 0xF8, 0x04, 0x01, 0xFE, 0x00, 0xFF, 0x00, 0x80, 0x1F, 0x80, + 0x1F, 0xE0, 0x10, 0x03, 0xF0, 0x03, 0xFC, 0x02, 0x00, 0x7E, 0x00, 0x7F, + 0x80, 0x40, 0x07, 0x80, 0x0F, 0xF0, 0x0C, 0x00, 0xF0, 0x01, 0xFE, 0x07, + 0xC0, 0x0C, 0x00, 0x7F, 0xE7, 0xFF, 0x01, 0x80, 0x3F, 0xFF, 0xFF, 0xC0, + 0x03, 0xFE, 0xFF, 0xC0, 0x01, 0xF0, 0xFF, 0xC0, 0x01, 0xC0, 0xFF, 0xC0, + 0x01, 0x80, 0xFF, 0x80, 0x03, 0x01, 0xFF, 0x80, 0x06, 0x03, 0xFF, 0x80, + 0x0C, 0x07, 0xFF, 0x80, 0x18, 0x0D, 0xFF, 0x80, 0x30, 0x19, 0xFF, 0x00, + 0x60, 0x31, 0xFF, 0x00, 0xC0, 0x61, 0xFF, 0x01, 0x80, 0xC1, 0xFF, 0x03, + 0x01, 0x83, 0xFF, 0x06, 0x03, 0x03, 0xFE, 0x0C, 0x06, 0x03, 0xFE, 0x18, + 0x0C, 0x03, 0xFE, 0x30, 0x18, 0x03, 0xFE, 0x60, 0x30, 0x03, 0xFE, 0xC0, + 0x60, 0x07, 0xFD, 0x80, 0xC0, 0x07, 0xFF, 0x01, 0x80, 0x07, 0xFE, 0x03, + 0x00, 0x07, 0xFC, 0x06, 0x00, 0x07, 0xF8, 0x0C, 0x00, 0x07, 0xF0, 0x18, + 0x00, 0x0F, 0xE0, 0x30, 0x00, 0x0F, 0xC0, 0x60, 0x00, 0x0F, 0x80, 0xC0, + 0x00, 0x0F, 0x01, 0xC0, 0x00, 0x0E, 0x0F, 0xC0, 0x00, 0x1C, 0x7F, 0xE0, + 0x00, 0x18, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x3F, 0xFF, 0x80, 0x00, 0x3F, + 0x07, 0xF0, 0x00, 0x7E, 0x00, 0xFC, 0x00, 0x7E, 0x00, 0x3F, 0x00, 0x7E, + 0x00, 0x1F, 0xC0, 0x7F, 0x00, 0x07, 0xF0, 0x3F, 0x00, 0x03, 0xF8, 0x3F, + 0x80, 0x00, 0xFE, 0x3F, 0xC0, 0x00, 0x7F, 0x1F, 0xE0, 0x00, 0x3F, 0xCF, + 0xE0, 0x00, 0x0F, 0xEF, 0xF0, 0x00, 0x07, 0xF7, 0xF8, 0x00, 0x03, 0xFF, + 0xFC, 0x00, 0x01, 0xFF, 0xFE, 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x7F, + 0xFF, 0x80, 0x00, 0x3F, 0xFF, 0xC0, 0x00, 0x1F, 0xFF, 0xE0, 0x00, 0x0F, + 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xF8, 0x00, 0x03, 0xFD, 0xFC, 0x00, 0x01, + 0xFC, 0xFE, 0x00, 0x01, 0xFE, 0x7F, 0x80, 0x00, 0xFF, 0x1F, 0xC0, 0x00, + 0x7F, 0x0F, 0xE0, 0x00, 0x3F, 0x83, 0xF8, 0x00, 0x3F, 0x80, 0xFC, 0x00, + 0x1F, 0x80, 0x3F, 0x00, 0x1F, 0x80, 0x0F, 0xC0, 0x1F, 0x80, 0x03, 0xF8, + 0x3F, 0x80, 0x00, 0x7F, 0xFF, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0xFF, + 0xFF, 0xE0, 0x1F, 0xFF, 0xFF, 0x01, 0xFE, 0x1F, 0xE0, 0x7F, 0x81, 0xFC, + 0x1F, 0xE0, 0x7F, 0x87, 0xF8, 0x0F, 0xE1, 0xFE, 0x03, 0xFC, 0x7F, 0x80, + 0xFF, 0x1F, 0xE0, 0x3F, 0xC7, 0xF8, 0x0F, 0xF1, 0xFE, 0x03, 0xFC, 0x7F, + 0x80, 0xFF, 0x1F, 0xE0, 0x3F, 0x87, 0xF8, 0x1F, 0xE1, 0xFE, 0x07, 0xF0, + 0x7F, 0x87, 0xF8, 0x1F, 0xFF, 0xF8, 0x07, 0xFF, 0xF8, 0x01, 0xFE, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xF8, 0x00, 0x01, 0xFE, + 0x00, 0x00, 0x7F, 0x80, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xF8, 0x00, 0x01, + 0xFE, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xF8, 0x00, + 0x03, 0xFF, 0x00, 0x03, 0xFF, 0xF0, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, + 0x3F, 0xFF, 0x80, 0x00, 0x3F, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0xFC, 0x00, + 0x7E, 0x00, 0x3F, 0x00, 0x7E, 0x00, 0x1F, 0xC0, 0x7F, 0x00, 0x07, 0xF0, + 0x3F, 0x00, 0x03, 0xF8, 0x3F, 0x80, 0x00, 0xFE, 0x1F, 0xC0, 0x00, 0x7F, + 0x1F, 0xE0, 0x00, 0x3F, 0xCF, 0xE0, 0x00, 0x0F, 0xE7, 0xF0, 0x00, 0x07, + 0xF7, 0xF8, 0x00, 0x03, 0xFF, 0xFC, 0x00, 0x01, 0xFF, 0xFE, 0x00, 0x00, + 0xFF, 0xFF, 0x00, 0x00, 0x7F, 0xFF, 0x80, 0x00, 0x3F, 0xFF, 0xC0, 0x00, + 0x1F, 0xFF, 0xE0, 0x00, 0x0F, 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xF8, 0x00, + 0x03, 0xFD, 0xFC, 0x00, 0x01, 0xFC, 0xFE, 0x00, 0x01, 0xFE, 0x7F, 0x80, + 0x00, 0xFF, 0x1F, 0xC0, 0x00, 0x7F, 0x0F, 0xE0, 0x00, 0x3F, 0x83, 0xF8, + 0x00, 0x3F, 0x80, 0xFC, 0x00, 0x1F, 0x80, 0x3F, 0x00, 0x1F, 0x80, 0x0F, + 0xC0, 0x1F, 0x80, 0x03, 0xF0, 0x1F, 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x00, + 0x0F, 0xFC, 0x00, 0x00, 0x03, 0xFF, 0x00, 0x00, 0x01, 0xFF, 0xC0, 0x00, + 0x00, 0x7F, 0xF0, 0x00, 0x00, 0x1F, 0xFC, 0x00, 0x00, 0x07, 0xFF, 0x80, + 0x00, 0x00, 0xFF, 0xFF, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0xFF, 0xFF, 0xE0, + 0x00, 0xFF, 0xFF, 0xF8, 0x00, 0x7F, 0xC3, 0xFC, 0x00, 0xFF, 0x01, 0xFC, + 0x01, 0xFE, 0x03, 0xFC, 0x03, 0xFC, 0x03, 0xF8, 0x07, 0xF8, 0x07, 0xF8, + 0x0F, 0xF0, 0x0F, 0xF0, 0x1F, 0xE0, 0x1F, 0xE0, 0x3F, 0xC0, 0x3F, 0xC0, + 0x7F, 0x80, 0x7F, 0x80, 0xFF, 0x00, 0xFF, 0x01, 0xFE, 0x01, 0xFC, 0x03, + 0xFC, 0x07, 0xF8, 0x07, 0xF8, 0x1F, 0xE0, 0x0F, 0xF0, 0xFF, 0x00, 0x1F, + 0xFF, 0xF8, 0x00, 0x3F, 0xFF, 0xE0, 0x00, 0x7F, 0x9F, 0xE0, 0x00, 0xFF, + 0x3F, 0xC0, 0x01, 0xFE, 0x3F, 0xC0, 0x03, 0xFC, 0x7F, 0xC0, 0x07, 0xF8, + 0x7F, 0xC0, 0x0F, 0xF0, 0x7F, 0x80, 0x1F, 0xE0, 0xFF, 0x80, 0x3F, 0xC0, + 0xFF, 0x80, 0x7F, 0x80, 0xFF, 0x00, 0xFF, 0x01, 0xFF, 0x01, 0xFE, 0x01, + 0xFF, 0x03, 0xFC, 0x01, 0xFF, 0x0F, 0xFC, 0x03, 0xFE, 0x7F, 0xFE, 0x03, + 0xFF, 0x03, 0xF8, 0x10, 0x7F, 0xF9, 0x87, 0xC1, 0xFC, 0x78, 0x03, 0xE7, + 0x80, 0x0F, 0x3C, 0x00, 0x3B, 0xE0, 0x01, 0xDF, 0x00, 0x06, 0xF8, 0x00, + 0x37, 0xE0, 0x00, 0xBF, 0x80, 0x01, 0xFF, 0x00, 0x0F, 0xFE, 0x00, 0x3F, + 0xFC, 0x01, 0xFF, 0xF8, 0x07, 0xFF, 0xF0, 0x1F, 0xFF, 0xC0, 0x7F, 0xFF, + 0x00, 0xFF, 0xFC, 0x01, 0xFF, 0xE0, 0x03, 0xFF, 0x80, 0x07, 0xFC, 0x00, + 0x1F, 0xF0, 0x00, 0x3F, 0x80, 0x01, 0xFE, 0x00, 0x07, 0xF0, 0x00, 0x3F, + 0xC0, 0x01, 0xEE, 0x00, 0x0F, 0x78, 0x00, 0xF3, 0xE0, 0x0F, 0x9F, 0xC0, + 0xF8, 0x8F, 0xFF, 0x04, 0x0F, 0xE0, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFC, 0x3F, 0xC3, 0xFF, 0x03, 0xFC, 0x0F, 0xE0, 0x3F, 0xC0, + 0x7C, 0x03, 0xFC, 0x03, 0xC0, 0x3F, 0xC0, 0x38, 0x03, 0xFC, 0x01, 0x80, + 0x3F, 0xC0, 0x10, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x03, 0xFC, + 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, + 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, + 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x03, 0xFC, 0x00, + 0x00, 0x3F, 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x03, + 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, + 0x00, 0x03, 0xFC, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0x3F, 0xFF, 0xC0, 0xFF, + 0xFE, 0x07, 0xFC, 0xFF, 0xC0, 0x07, 0xC1, 0xFE, 0x00, 0x0E, 0x07, 0xF8, + 0x00, 0x18, 0x1F, 0xE0, 0x00, 0x60, 0x7F, 0x80, 0x01, 0x81, 0xFE, 0x00, + 0x06, 0x07, 0xF8, 0x00, 0x18, 0x1F, 0xE0, 0x00, 0x60, 0x7F, 0x80, 0x01, + 0x81, 0xFE, 0x00, 0x06, 0x07, 0xF8, 0x00, 0x18, 0x1F, 0xE0, 0x00, 0x60, + 0x7F, 0x80, 0x01, 0x81, 0xFE, 0x00, 0x06, 0x07, 0xF8, 0x00, 0x18, 0x1F, + 0xE0, 0x00, 0x60, 0x7F, 0x80, 0x01, 0x81, 0xFE, 0x00, 0x06, 0x07, 0xF8, + 0x00, 0x18, 0x1F, 0xE0, 0x00, 0x60, 0x7F, 0x80, 0x01, 0x81, 0xFE, 0x00, + 0x06, 0x07, 0xF8, 0x00, 0x18, 0x1F, 0xE0, 0x00, 0x60, 0x7F, 0x80, 0x03, + 0x00, 0xFF, 0x00, 0x0C, 0x03, 0xFC, 0x00, 0x30, 0x07, 0xF0, 0x01, 0x80, + 0x0F, 0xE0, 0x0E, 0x00, 0x1F, 0xE0, 0xF0, 0x00, 0x1F, 0xFF, 0x00, 0x00, + 0x1F, 0xF0, 0x00, 0xFF, 0xFF, 0x01, 0xFF, 0x9F, 0xFC, 0x00, 0x1F, 0x07, + 0xFC, 0x00, 0x07, 0x01, 0xFE, 0x00, 0x03, 0x00, 0x7F, 0x80, 0x03, 0x80, + 0x3F, 0xC0, 0x01, 0x80, 0x1F, 0xE0, 0x00, 0xC0, 0x07, 0xF8, 0x00, 0xC0, + 0x03, 0xFC, 0x00, 0x60, 0x00, 0xFF, 0x00, 0x30, 0x00, 0x7F, 0x80, 0x30, + 0x00, 0x1F, 0xE0, 0x18, 0x00, 0x0F, 0xF0, 0x18, 0x00, 0x07, 0xF8, 0x0C, + 0x00, 0x01, 0xFE, 0x06, 0x00, 0x00, 0xFF, 0x06, 0x00, 0x00, 0x3F, 0xC3, + 0x00, 0x00, 0x1F, 0xE3, 0x80, 0x00, 0x0F, 0xF1, 0x80, 0x00, 0x03, 0xFC, + 0xC0, 0x00, 0x01, 0xFE, 0xC0, 0x00, 0x00, 0x7F, 0xE0, 0x00, 0x00, 0x3F, + 0xF0, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x03, + 0xF8, 0x00, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, + 0x01, 0x80, 0x00, 0xFF, 0xF8, 0x7F, 0xFF, 0x0F, 0xFB, 0xFF, 0x00, 0xFF, + 0xC0, 0x1F, 0x0F, 0xF0, 0x03, 0xFC, 0x00, 0x70, 0x3F, 0x80, 0x0F, 0xE0, + 0x03, 0x81, 0xFE, 0x00, 0x7F, 0x80, 0x1C, 0x0F, 0xF0, 0x03, 0xFC, 0x00, + 0xC0, 0x3F, 0x80, 0x0F, 0xE0, 0x06, 0x01, 0xFE, 0x00, 0x7F, 0x00, 0x70, + 0x0F, 0xF0, 0x07, 0xFC, 0x03, 0x00, 0x3F, 0x80, 0x3F, 0xE0, 0x18, 0x01, + 0xFE, 0x01, 0xFF, 0x01, 0xC0, 0x0F, 0xF0, 0x1B, 0xFC, 0x0C, 0x00, 0x3F, + 0x80, 0xCF, 0xE0, 0x60, 0x01, 0xFE, 0x06, 0x7F, 0x07, 0x00, 0x0F, 0xF0, + 0x63, 0xFC, 0x30, 0x00, 0x3F, 0x83, 0x0F, 0xE1, 0x80, 0x01, 0xFE, 0x30, + 0x7F, 0x1C, 0x00, 0x07, 0xF1, 0x81, 0xFC, 0xC0, 0x00, 0x3F, 0x8C, 0x0F, + 0xE6, 0x00, 0x01, 0xFE, 0xC0, 0x7F, 0x70, 0x00, 0x07, 0xF6, 0x01, 0xFB, + 0x00, 0x00, 0x3F, 0xE0, 0x0F, 0xF8, 0x00, 0x01, 0xFF, 0x00, 0x7F, 0xC0, + 0x00, 0x07, 0xF8, 0x01, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x00, + 0x01, 0xFC, 0x00, 0x7F, 0x00, 0x00, 0x07, 0xE0, 0x01, 0xF0, 0x00, 0x00, + 0x3E, 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x00, 0x07, + 0x00, 0x01, 0xC0, 0x00, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x00, 0x01, 0xC0, + 0x00, 0x70, 0x00, 0x00, 0x04, 0x00, 0x01, 0x00, 0x00, 0xFF, 0xFF, 0x0F, + 0xFF, 0x3F, 0xF8, 0x01, 0xF8, 0x1F, 0xF8, 0x01, 0xE0, 0x0F, 0xF8, 0x01, + 0xC0, 0x0F, 0xF8, 0x01, 0x80, 0x07, 0xFC, 0x03, 0x80, 0x03, 0xFE, 0x07, + 0x00, 0x03, 0xFE, 0x06, 0x00, 0x01, 0xFF, 0x0C, 0x00, 0x00, 0xFF, 0x9C, + 0x00, 0x00, 0xFF, 0x98, 0x00, 0x00, 0x7F, 0xF0, 0x00, 0x00, 0x3F, 0xF0, + 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x0F, 0xFC, + 0x00, 0x00, 0x0F, 0xFE, 0x00, 0x00, 0x19, 0xFE, 0x00, 0x00, 0x31, 0xFF, + 0x00, 0x00, 0x70, 0xFF, 0x80, 0x00, 0x60, 0x7F, 0x80, 0x00, 0xC0, 0x7F, + 0xC0, 0x01, 0xC0, 0x3F, 0xE0, 0x03, 0x80, 0x1F, 0xE0, 0x07, 0x00, 0x1F, + 0xF0, 0x07, 0x00, 0x0F, 0xF8, 0x0F, 0x00, 0x0F, 0xF8, 0x3F, 0x80, 0x1F, + 0xFC, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0x03, 0xFF, 0x7F, 0xF0, 0x00, + 0x7E, 0x1F, 0xF0, 0x00, 0x38, 0x1F, 0xF0, 0x00, 0x38, 0x0F, 0xF0, 0x00, + 0x70, 0x0F, 0xF8, 0x00, 0x60, 0x07, 0xF8, 0x00, 0x60, 0x07, 0xFC, 0x00, + 0xC0, 0x03, 0xFC, 0x01, 0xC0, 0x01, 0xFE, 0x01, 0x80, 0x01, 0xFE, 0x03, + 0x00, 0x00, 0xFF, 0x03, 0x00, 0x00, 0xFF, 0x86, 0x00, 0x00, 0x7F, 0x8E, + 0x00, 0x00, 0x7F, 0xCC, 0x00, 0x00, 0x3F, 0xD8, 0x00, 0x00, 0x3F, 0xF8, + 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x1F, 0xF8, 0x00, 0x00, 0x7F, 0xFE, + 0x00, 0x3F, 0xFF, 0xFF, 0xE3, 0xFF, 0xFF, 0xFC, 0x3F, 0x80, 0x7F, 0xC3, + 0xE0, 0x07, 0xF8, 0x38, 0x00, 0xFF, 0x83, 0x80, 0x0F, 0xF0, 0x30, 0x01, + 0xFE, 0x07, 0x00, 0x3F, 0xE0, 0x60, 0x03, 0xFC, 0x06, 0x00, 0x7F, 0xC0, + 0x00, 0x0F, 0xF8, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x1F, 0xF0, 0x00, 0x01, + 0xFE, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x7F, 0x80, + 0x00, 0x0F, 0xF8, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x03, + 0xFE, 0x00, 0x00, 0x3F, 0xC0, 0x01, 0x07, 0xFC, 0x00, 0x30, 0xFF, 0x80, + 0x03, 0x0F, 0xF0, 0x00, 0x31, 0xFF, 0x00, 0x07, 0x1F, 0xE0, 0x00, 0xF3, + 0xFE, 0x00, 0x1E, 0x7F, 0xC0, 0x03, 0xE7, 0xF8, 0x01, 0xFE, 0xFF, 0xFF, + 0xFF, 0xEF, 0xFF, 0xFF, 0xFE, 0xFF, 0xFF, 0xFF, 0xF0, 0x7C, 0x0F, 0x81, + 0xF0, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, + 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, + 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, + 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xFF, 0xFF, 0xF8, 0xF0, + 0x01, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0xC0, 0x07, 0x80, 0x0F, 0x00, + 0x1F, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x7C, 0x00, 0x78, 0x00, 0xF0, 0x01, + 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1F, + 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xE0, + 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, + 0x1E, 0xFF, 0xFF, 0xFC, 0x1F, 0x81, 0xF0, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, + 0x03, 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, + 0xE0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, + 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, 0xC0, 0xF8, 0x1F, 0x03, 0xE0, 0x7C, + 0x0F, 0x81, 0xF0, 0x3F, 0xFF, 0xFF, 0xF8, 0x00, 0x78, 0x00, 0x07, 0xC0, + 0x00, 0x3F, 0x00, 0x03, 0xF8, 0x00, 0x1F, 0xE0, 0x01, 0xEF, 0x00, 0x0F, + 0x3C, 0x00, 0xF1, 0xE0, 0x07, 0x87, 0x80, 0x78, 0x3C, 0x03, 0xC0, 0xF0, + 0x3C, 0x07, 0x81, 0xE0, 0x1E, 0x1E, 0x00, 0xF0, 0xF0, 0x07, 0xCF, 0x00, + 0x1E, 0x78, 0x00, 0xF8, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0x70, 0x1F, 0x03, 0xF0, 0x7E, 0x03, 0xE0, 0x3E, 0x01, 0xE0, 0x1E, + 0x00, 0xE0, 0x03, 0xFC, 0x00, 0x3F, 0xFC, 0x03, 0xE1, 0xF8, 0x0F, 0x03, + 0xF0, 0x7C, 0x07, 0xC1, 0xF8, 0x1F, 0x87, 0xE0, 0x7E, 0x1F, 0x81, 0xF8, + 0x3C, 0x07, 0xE0, 0x00, 0x1F, 0x80, 0x01, 0xFE, 0x00, 0x3F, 0xF8, 0x03, + 0xE7, 0xE0, 0x3E, 0x1F, 0x83, 0xF0, 0x7E, 0x1F, 0x81, 0xF8, 0x7E, 0x07, + 0xE3, 0xF8, 0x1F, 0x8F, 0xE0, 0x7E, 0x3F, 0x83, 0xF8, 0xFF, 0x1F, 0xE1, + 0xFF, 0xDF, 0xF7, 0xFE, 0x3F, 0x07, 0xE0, 0xF8, 0xFF, 0x80, 0x00, 0x1F, + 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03, 0xF0, 0x00, 0x01, 0xF8, 0x00, 0x00, + 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0x80, 0x00, + 0x0F, 0xC7, 0xF0, 0x07, 0xEF, 0xFE, 0x03, 0xFC, 0x3F, 0x81, 0xFC, 0x0F, + 0xE0, 0xFC, 0x03, 0xF0, 0x7E, 0x01, 0xFC, 0x3F, 0x00, 0xFE, 0x1F, 0x80, + 0x3F, 0x8F, 0xC0, 0x1F, 0xC7, 0xE0, 0x0F, 0xE3, 0xF0, 0x07, 0xF1, 0xF8, + 0x03, 0xF8, 0xFC, 0x01, 0xFC, 0x7E, 0x00, 0xFE, 0x3F, 0x00, 0x7F, 0x1F, + 0x80, 0x3F, 0x0F, 0xC0, 0x1F, 0x87, 0xE0, 0x1F, 0xC3, 0xF0, 0x0F, 0xC1, + 0xF8, 0x07, 0xE0, 0xFE, 0x07, 0xE0, 0x73, 0x87, 0xE0, 0x30, 0xFF, 0xC0, + 0x10, 0x1F, 0x80, 0x00, 0x00, 0xFC, 0x00, 0x7F, 0xE0, 0x3E, 0x3E, 0x0F, + 0x83, 0xE3, 0xE0, 0x7C, 0x7C, 0x0F, 0x9F, 0x01, 0xF3, 0xE0, 0x1C, 0x7C, + 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, + 0x00, 0x3F, 0x00, 0x07, 0xF0, 0x00, 0xFE, 0x00, 0x0F, 0xE0, 0x01, 0xFC, + 0x00, 0x1F, 0xC0, 0x21, 0xFE, 0x0C, 0x3F, 0xFF, 0x01, 0xFF, 0x80, 0x0F, + 0xC0, 0x00, 0x1F, 0xF8, 0x00, 0x03, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, + 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, + 0xF8, 0x00, 0x01, 0xF8, 0x03, 0xF1, 0xF8, 0x07, 0xFD, 0xF8, 0x1F, 0xC7, + 0xF8, 0x1F, 0x83, 0xF8, 0x3F, 0x01, 0xF8, 0x7F, 0x01, 0xF8, 0x7E, 0x01, + 0xF8, 0x7E, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, + 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, + 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0x7E, 0x01, 0xF8, 0x7F, 0x01, + 0xF8, 0x3F, 0x03, 0xF8, 0x3F, 0x03, 0xF8, 0x1F, 0x87, 0xFC, 0x0F, 0xFD, + 0xFF, 0x03, 0xF1, 0xC0, 0x03, 0xF0, 0x03, 0xFF, 0x01, 0xE1, 0xE0, 0xF8, + 0x7C, 0x3C, 0x0F, 0x1F, 0x03, 0xE7, 0xC0, 0xFB, 0xF0, 0x3E, 0xFC, 0x0F, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0xFC, 0x00, 0x3F, 0x00, 0x0F, + 0xC0, 0x03, 0xF8, 0x00, 0xFE, 0x00, 0x1F, 0x80, 0x07, 0xF0, 0x0C, 0xFC, + 0x06, 0x3F, 0xC3, 0x07, 0xFF, 0x80, 0xFF, 0xC0, 0x0F, 0xC0, 0x00, 0xFC, + 0x01, 0xFF, 0x81, 0xF1, 0xC1, 0xF0, 0xF0, 0xF8, 0xF8, 0xFC, 0x7C, 0x7E, + 0x1C, 0x3F, 0x00, 0x1F, 0x80, 0x0F, 0xC0, 0x07, 0xE0, 0x1F, 0xFF, 0x0F, + 0xFF, 0x80, 0xFC, 0x00, 0x7E, 0x00, 0x3F, 0x00, 0x1F, 0x80, 0x0F, 0xC0, + 0x07, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0x7E, 0x00, 0x3F, + 0x00, 0x1F, 0x80, 0x0F, 0xC0, 0x07, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x00, + 0xFC, 0x00, 0x7E, 0x00, 0x7F, 0x80, 0xFF, 0xF8, 0x00, 0x07, 0xF0, 0x03, + 0xFF, 0xFC, 0xF8, 0x7F, 0xBE, 0x07, 0x87, 0xC0, 0xF9, 0xF8, 0x1F, 0xBF, + 0x03, 0xF7, 0xE0, 0x7E, 0xFC, 0x0F, 0xDF, 0x81, 0xF9, 0xF0, 0x3F, 0x3E, + 0x07, 0xC3, 0xE1, 0xF8, 0x3C, 0x7E, 0x01, 0xFF, 0x00, 0x60, 0x00, 0x38, + 0x00, 0x0F, 0x00, 0x01, 0xF0, 0x00, 0x7F, 0xFF, 0x0F, 0xFF, 0xF9, 0xFF, + 0xFF, 0x9F, 0xFF, 0xF9, 0xFF, 0xFF, 0x0F, 0xFF, 0xEF, 0x00, 0x3F, 0xC0, + 0x03, 0xF8, 0x00, 0x7F, 0x00, 0x1C, 0xF8, 0x07, 0x0F, 0xFF, 0xC0, 0x7F, + 0xC0, 0xFF, 0x80, 0x00, 0x3F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, + 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, + 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x87, 0xE0, 0x1F, 0x9F, 0xF0, 0x1F, 0xBF, + 0xF8, 0x1F, 0xF1, 0xF8, 0x1F, 0xC0, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, + 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, + 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, + 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, + 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x3F, 0xC1, 0xFE, 0xFF, 0xE3, + 0xFF, 0x0F, 0x07, 0xE1, 0xFE, 0x3F, 0xC7, 0xF8, 0x7F, 0x03, 0xC0, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x7F, 0xC3, 0xF8, 0x3F, 0x07, 0xE0, 0xFC, 0x1F, + 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x07, 0xE0, 0xFC, 0x1F, 0x83, + 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x07, 0xE1, 0xFE, 0xFF, 0xE0, 0x00, + 0x70, 0x07, 0xF0, 0x3F, 0xC0, 0xFF, 0x03, 0xFC, 0x07, 0xF0, 0x0F, 0x80, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xFF, 0x01, 0xFC, 0x03, 0xF0, + 0x0F, 0xC0, 0x3F, 0x00, 0xFC, 0x03, 0xF0, 0x0F, 0xC0, 0x3F, 0x00, 0xFC, + 0x03, 0xF0, 0x0F, 0xC0, 0x3F, 0x00, 0xFC, 0x03, 0xF0, 0x0F, 0xC0, 0x3F, + 0x00, 0xFC, 0x03, 0xF0, 0x0F, 0xC0, 0x3F, 0x00, 0xFC, 0x03, 0xF0, 0x0F, + 0xDC, 0x3F, 0xF8, 0xFB, 0xE3, 0xEF, 0x0F, 0xBC, 0x7C, 0x7F, 0xE0, 0x7E, + 0x00, 0xFF, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x03, 0xF0, + 0x00, 0x01, 0xF8, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, + 0x00, 0x00, 0x1F, 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xE1, 0xFF, 0x83, + 0xF0, 0x3F, 0x01, 0xF8, 0x0E, 0x00, 0xFC, 0x06, 0x00, 0x7E, 0x06, 0x00, + 0x3F, 0x06, 0x00, 0x1F, 0x86, 0x00, 0x0F, 0xC7, 0x00, 0x07, 0xE7, 0x80, + 0x03, 0xF7, 0xE0, 0x01, 0xFF, 0xF8, 0x00, 0xFF, 0xFC, 0x00, 0x7E, 0x7F, + 0x00, 0x3F, 0x1F, 0xC0, 0x1F, 0x8F, 0xE0, 0x0F, 0xC3, 0xF8, 0x07, 0xE0, + 0xFE, 0x03, 0xF0, 0x7F, 0x81, 0xF8, 0x1F, 0xC0, 0xFC, 0x0F, 0xF0, 0xFF, + 0x07, 0xFD, 0xFF, 0xC7, 0xFF, 0xFF, 0x87, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, + 0x3F, 0x07, 0xE0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, + 0x07, 0xE0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x07, + 0xE0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xF8, 0x3F, 0x0F, 0xF7, + 0xFF, 0x00, 0x07, 0xE0, 0x3F, 0x07, 0xFC, 0xFF, 0x87, 0xFC, 0x0F, 0xEF, + 0xFE, 0x7F, 0xF0, 0x3F, 0xC3, 0xFF, 0x1F, 0x81, 0xFC, 0x0F, 0xE0, 0x7E, + 0x0F, 0xC0, 0x7E, 0x03, 0xF0, 0x7E, 0x03, 0xF0, 0x1F, 0x83, 0xF0, 0x1F, + 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x07, 0xE0, 0xFC, 0x07, 0xE0, 0x3F, 0x07, + 0xE0, 0x3F, 0x01, 0xF8, 0x3F, 0x01, 0xF8, 0x0F, 0xC1, 0xF8, 0x0F, 0xC0, + 0x7E, 0x0F, 0xC0, 0x7E, 0x03, 0xF0, 0x7E, 0x03, 0xF0, 0x1F, 0x83, 0xF0, + 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x07, 0xE0, 0xFC, 0x07, 0xE0, 0x3F, + 0x07, 0xE0, 0x3F, 0x01, 0xF8, 0x3F, 0x01, 0xF8, 0x0F, 0xC1, 0xF8, 0x0F, + 0xC0, 0x7E, 0x1F, 0xE0, 0xFF, 0x07, 0xFB, 0xFF, 0x8F, 0xFC, 0x7F, 0xE0, + 0x00, 0x07, 0xE0, 0xFF, 0x9F, 0xF0, 0x3F, 0xBF, 0xF8, 0x1F, 0xF1, 0xF8, + 0x1F, 0xC0, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, + 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, + 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, + 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, 0x1F, 0x80, 0xFC, + 0x1F, 0x80, 0xFC, 0x3F, 0xC1, 0xFE, 0xFF, 0xE3, 0xFF, 0x01, 0xFC, 0x00, + 0x3F, 0xF8, 0x03, 0xE3, 0xE0, 0x3E, 0x0F, 0x83, 0xF0, 0x7E, 0x1F, 0x01, + 0xF1, 0xF8, 0x0F, 0xCF, 0xC0, 0x7E, 0xFE, 0x03, 0xFF, 0xF0, 0x1F, 0xFF, + 0x80, 0xFF, 0xFC, 0x07, 0xFF, 0xE0, 0x3F, 0xFF, 0x01, 0xFF, 0xF8, 0x0F, + 0xFF, 0xC0, 0x7F, 0x7E, 0x03, 0xF3, 0xF0, 0x1F, 0x8F, 0x80, 0xF8, 0x7E, + 0x0F, 0xC1, 0xF0, 0x7C, 0x07, 0xC7, 0xC0, 0x1F, 0xFC, 0x00, 0x3F, 0x80, + 0x00, 0x0F, 0xC0, 0xFF, 0xBF, 0xF0, 0x3F, 0xF1, 0xF8, 0x1F, 0xC0, 0xFC, + 0x1F, 0xC0, 0xFC, 0x1F, 0x80, 0xFE, 0x1F, 0x80, 0x7E, 0x1F, 0x80, 0x7F, + 0x1F, 0x80, 0x7F, 0x1F, 0x80, 0x7F, 0x1F, 0x80, 0x7F, 0x1F, 0x80, 0x7F, + 0x1F, 0x80, 0x7F, 0x1F, 0x80, 0x7F, 0x1F, 0x80, 0x7F, 0x1F, 0x80, 0x7F, + 0x1F, 0x80, 0x7E, 0x1F, 0x80, 0x7E, 0x1F, 0x80, 0xFE, 0x1F, 0x80, 0xFC, + 0x1F, 0xC1, 0xF8, 0x1F, 0xE3, 0xF8, 0x1F, 0xBF, 0xE0, 0x1F, 0x8F, 0xC0, + 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, + 0x1F, 0x80, 0x00, 0x1F, 0x80, 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0xF8, 0x00, + 0x00, 0xF8, 0x08, 0x07, 0xFE, 0x18, 0x0F, 0xC7, 0x38, 0x1F, 0x83, 0xF8, + 0x3F, 0x01, 0xF8, 0x3F, 0x01, 0xF8, 0x7F, 0x01, 0xF8, 0x7E, 0x01, 0xF8, + 0x7E, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, + 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, 0xFE, 0x01, 0xF8, + 0xFE, 0x01, 0xF8, 0x7E, 0x01, 0xF8, 0x7F, 0x01, 0xF8, 0x7F, 0x01, 0xF8, + 0x3F, 0x83, 0xF8, 0x1F, 0xC7, 0xF8, 0x0F, 0xFD, 0xF8, 0x03, 0xF1, 0xF8, + 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, + 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x03, 0xFC, 0x00, 0x0F, 0xFF, + 0x00, 0x07, 0x9F, 0xF3, 0xF8, 0xFE, 0xFF, 0x8F, 0xFF, 0xF1, 0xFE, 0x7E, + 0x3F, 0x87, 0x87, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, + 0x7E, 0x00, 0x0F, 0xC0, 0x01, 0xF8, 0x00, 0x3F, 0x00, 0x07, 0xE0, 0x00, + 0xFC, 0x00, 0x1F, 0x80, 0x03, 0xF0, 0x00, 0x7E, 0x00, 0x0F, 0xC0, 0x01, + 0xF8, 0x00, 0x7F, 0x80, 0x3F, 0xFC, 0x00, 0x0F, 0x84, 0x3F, 0xF8, 0xE1, + 0xF3, 0x80, 0xEF, 0x00, 0xDE, 0x01, 0xBE, 0x01, 0x7E, 0x00, 0xFF, 0x01, + 0xFF, 0x81, 0xFF, 0xC3, 0xFF, 0xC3, 0xFF, 0xC1, 0xFF, 0x80, 0xFF, 0x80, + 0x7F, 0x80, 0x7F, 0x80, 0x7F, 0x00, 0x7E, 0x00, 0xFE, 0x01, 0xDF, 0x0F, + 0x37, 0xFC, 0x43, 0xF0, 0x01, 0x00, 0x0C, 0x00, 0x70, 0x01, 0xC0, 0x0F, + 0x00, 0x7C, 0x03, 0xF0, 0x1F, 0xC0, 0xFF, 0xF3, 0xFF, 0xC3, 0xF0, 0x0F, + 0xC0, 0x3F, 0x00, 0xFC, 0x03, 0xF0, 0x0F, 0xC0, 0x3F, 0x00, 0xFC, 0x03, + 0xF0, 0x0F, 0xC0, 0x3F, 0x00, 0xFC, 0x03, 0xF0, 0x0F, 0xC0, 0x3F, 0x00, + 0xFC, 0x23, 0xF0, 0x8F, 0xE6, 0x1F, 0xF0, 0x7F, 0x80, 0xF8, 0x00, 0xFF, + 0x87, 0xFC, 0x1F, 0xC0, 0xFE, 0x07, 0xE0, 0x3F, 0x03, 0xF0, 0x1F, 0x81, + 0xF8, 0x0F, 0xC0, 0xFC, 0x07, 0xE0, 0x7E, 0x03, 0xF0, 0x3F, 0x01, 0xF8, + 0x1F, 0x80, 0xFC, 0x0F, 0xC0, 0x7E, 0x07, 0xE0, 0x3F, 0x03, 0xF0, 0x1F, + 0x81, 0xF8, 0x0F, 0xC0, 0xFC, 0x07, 0xE0, 0x7E, 0x03, 0xF0, 0x3F, 0x01, + 0xF8, 0x1F, 0x80, 0xFC, 0x0F, 0xC0, 0x7E, 0x07, 0xE0, 0x7F, 0x03, 0xF8, + 0x7F, 0xC0, 0xFF, 0xEF, 0xF8, 0x3F, 0xE7, 0xC0, 0x0F, 0xC2, 0x00, 0xFF, + 0xF1, 0xFC, 0xFF, 0x01, 0xE3, 0xFC, 0x03, 0x07, 0xF0, 0x0C, 0x1F, 0xC0, + 0x60, 0x3F, 0x81, 0x80, 0xFE, 0x04, 0x01, 0xF8, 0x30, 0x07, 0xF0, 0xC0, + 0x1F, 0xC6, 0x00, 0x3F, 0x98, 0x00, 0xFE, 0x40, 0x01, 0xFB, 0x00, 0x07, + 0xFC, 0x00, 0x1F, 0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFE, 0x00, 0x01, 0xF0, + 0x00, 0x07, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, + 0x01, 0x00, 0x00, 0xFF, 0xE7, 0xFF, 0x3F, 0xBF, 0xE0, 0xFE, 0x07, 0x0F, + 0xE0, 0x7F, 0x03, 0x83, 0xF0, 0x1F, 0x81, 0x81, 0xFC, 0x0F, 0xC0, 0xC0, + 0xFE, 0x07, 0xF0, 0x40, 0x3F, 0x03, 0xF8, 0x60, 0x1F, 0xC3, 0xFC, 0x30, + 0x07, 0xE1, 0xFE, 0x10, 0x03, 0xF0, 0x9F, 0x98, 0x01, 0xFC, 0xCF, 0xCC, + 0x00, 0x7E, 0x67, 0xEC, 0x00, 0x3F, 0xE1, 0xFE, 0x00, 0x1F, 0xF0, 0xFE, + 0x00, 0x07, 0xF0, 0x7F, 0x00, 0x03, 0xF8, 0x3F, 0x80, 0x00, 0xFC, 0x0F, + 0x80, 0x00, 0x7C, 0x07, 0xC0, 0x00, 0x3E, 0x03, 0xE0, 0x00, 0x0F, 0x00, + 0xE0, 0x00, 0x07, 0x00, 0x70, 0x00, 0x03, 0x80, 0x38, 0x00, 0x00, 0x80, + 0x08, 0x00, 0xFF, 0xF3, 0xFD, 0xFF, 0x03, 0xC3, 0xFC, 0x0E, 0x07, 0xF0, + 0x30, 0x1F, 0xE1, 0x80, 0x3F, 0x8C, 0x00, 0x7F, 0x70, 0x01, 0xFF, 0x80, + 0x03, 0xFC, 0x00, 0x0F, 0xF0, 0x00, 0x1F, 0xE0, 0x00, 0x3F, 0x80, 0x00, + 0xFF, 0x00, 0x07, 0xFE, 0x00, 0x1B, 0xF8, 0x00, 0xCF, 0xF0, 0x06, 0x1F, + 0xC0, 0x38, 0x3F, 0x80, 0xC0, 0xFF, 0x07, 0x01, 0xFC, 0x3C, 0x07, 0xFB, + 0xFC, 0x7F, 0xF0, 0xFF, 0xE3, 0xFB, 0xFC, 0x07, 0x8F, 0xE0, 0x18, 0x7F, + 0x01, 0x81, 0xF8, 0x0C, 0x0F, 0xE0, 0x60, 0x7F, 0x06, 0x01, 0xF8, 0x30, + 0x0F, 0xE1, 0x80, 0x7F, 0x18, 0x01, 0xF8, 0xC0, 0x0F, 0xE6, 0x00, 0x3F, + 0x60, 0x01, 0xFF, 0x00, 0x0F, 0xF0, 0x00, 0x3F, 0x80, 0x01, 0xFC, 0x00, + 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x07, 0x00, 0x00, 0x38, + 0x00, 0x00, 0x80, 0x00, 0x0C, 0x00, 0x00, 0x60, 0x03, 0x82, 0x00, 0x3E, + 0x30, 0x01, 0xF1, 0x00, 0x0F, 0x98, 0x00, 0x3F, 0x80, 0x00, 0xF0, 0x00, + 0x00, 0x7F, 0xFF, 0xEF, 0xFF, 0xFD, 0xE0, 0x7F, 0x30, 0x1F, 0xC6, 0x07, + 0xF8, 0x80, 0xFE, 0x00, 0x3F, 0xC0, 0x07, 0xF0, 0x01, 0xFC, 0x00, 0x3F, + 0x80, 0x0F, 0xE0, 0x03, 0xFC, 0x00, 0x7F, 0x00, 0x1F, 0xE0, 0x03, 0xF8, + 0x00, 0xFE, 0x03, 0x3F, 0xC0, 0x67, 0xF0, 0x19, 0xFE, 0x07, 0x3F, 0x83, + 0xEF, 0xFF, 0xFD, 0xFF, 0xFF, 0x80, 0x00, 0x7C, 0x07, 0xE0, 0x3E, 0x00, + 0xF8, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, + 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, + 0x1F, 0x00, 0xF8, 0x03, 0xC0, 0x3C, 0x01, 0xF0, 0x00, 0xF0, 0x03, 0xE0, + 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, + 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, + 0x00, 0x3E, 0x00, 0xF8, 0x01, 0xF8, 0x01, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF0, 0xF8, 0x01, 0xF8, 0x01, 0xF0, 0x07, 0xC0, 0x0F, 0x80, 0x3E, 0x00, + 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, + 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0x7C, 0x00, 0xF0, + 0x00, 0xF0, 0x03, 0xE0, 0x3C, 0x01, 0xF0, 0x0F, 0x80, 0x3E, 0x00, 0xF8, + 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, + 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x01, 0xF0, 0x07, 0xC0, 0x7E, + 0x03, 0xE0, 0x00, 0x0F, 0x80, 0x00, 0xFF, 0xC0, 0x47, 0xFF, 0xC3, 0x9F, + 0xFF, 0xFF, 0x70, 0x7F, 0xF8, 0x80, 0x7F, 0xC0, 0x00, 0x3E, 0x00 }; + +const GFXglyph FreeSerifBold24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 12, 0, 1 }, // 0x20 ' ' + { 0, 8, 34, 16, 4, -32 }, // 0x21 '!' + { 34, 17, 13, 26, 4, -32 }, // 0x22 '"' + { 62, 23, 33, 23, 0, -32 }, // 0x23 '#' + { 157, 21, 39, 24, 1, -34 }, // 0x24 '$' + { 260, 35, 34, 47, 6, -32 }, // 0x25 '%' + { 409, 34, 34, 39, 3, -32 }, // 0x26 '&' + { 554, 5, 13, 13, 4, -32 }, // 0x27 ''' + { 563, 12, 41, 16, 2, -32 }, // 0x28 '(' + { 625, 12, 41, 16, 1, -32 }, // 0x29 ')' + { 687, 18, 21, 24, 3, -32 }, // 0x2A '*' + { 735, 26, 25, 32, 3, -24 }, // 0x2B '+' + { 817, 8, 15, 12, 2, -6 }, // 0x2C ',' + { 832, 11, 5, 16, 2, -12 }, // 0x2D '-' + { 839, 8, 8, 12, 2, -6 }, // 0x2E '.' + { 847, 15, 33, 13, -1, -32 }, // 0x2F '/' + { 909, 22, 34, 23, 1, -32 }, // 0x30 '0' + { 1003, 18, 33, 23, 3, -32 }, // 0x31 '1' + { 1078, 21, 33, 24, 1, -32 }, // 0x32 '2' + { 1165, 21, 34, 24, 1, -32 }, // 0x33 '3' + { 1255, 21, 33, 24, 1, -32 }, // 0x34 '4' + { 1342, 20, 32, 23, 2, -31 }, // 0x35 '5' + { 1422, 21, 34, 24, 1, -32 }, // 0x36 '6' + { 1512, 21, 32, 23, 1, -31 }, // 0x37 '7' + { 1596, 21, 34, 23, 1, -32 }, // 0x38 '8' + { 1686, 22, 34, 23, 1, -32 }, // 0x39 '9' + { 1780, 8, 24, 16, 4, -22 }, // 0x3A ':' + { 1804, 9, 31, 16, 3, -22 }, // 0x3B ';' + { 1839, 26, 26, 32, 3, -24 }, // 0x3C '<' + { 1924, 26, 17, 32, 3, -20 }, // 0x3D '=' + { 1980, 26, 26, 32, 3, -24 }, // 0x3E '>' + { 2065, 18, 34, 24, 3, -32 }, // 0x3F '?' + { 2142, 33, 34, 44, 5, -32 }, // 0x40 '@' + { 2283, 32, 33, 34, 1, -32 }, // 0x41 'A' + { 2415, 28, 32, 31, 1, -31 }, // 0x42 'B' + { 2527, 30, 34, 33, 2, -32 }, // 0x43 'C' + { 2655, 32, 32, 34, 1, -31 }, // 0x44 'D' + { 2783, 28, 32, 32, 2, -31 }, // 0x45 'E' + { 2895, 25, 32, 29, 2, -31 }, // 0x46 'F' + { 2995, 33, 34, 36, 2, -32 }, // 0x47 'G' + { 3136, 33, 32, 37, 2, -31 }, // 0x48 'H' + { 3268, 15, 32, 18, 2, -31 }, // 0x49 'I' + { 3328, 22, 37, 24, 0, -31 }, // 0x4A 'J' + { 3430, 34, 32, 36, 2, -31 }, // 0x4B 'K' + { 3566, 28, 32, 31, 2, -31 }, // 0x4C 'L' + { 3678, 43, 32, 45, 0, -31 }, // 0x4D 'M' + { 3850, 31, 32, 34, 1, -31 }, // 0x4E 'N' + { 3974, 33, 34, 37, 2, -32 }, // 0x4F 'O' + { 4115, 26, 32, 30, 2, -31 }, // 0x50 'P' + { 4219, 33, 41, 37, 2, -32 }, // 0x51 'Q' + { 4389, 31, 32, 34, 2, -31 }, // 0x52 'R' + { 4513, 21, 34, 27, 3, -32 }, // 0x53 'S' + { 4603, 28, 32, 30, 1, -31 }, // 0x54 'T' + { 4715, 30, 33, 34, 2, -31 }, // 0x55 'U' + { 4839, 33, 32, 33, 0, -31 }, // 0x56 'V' + { 4971, 45, 33, 46, 1, -31 }, // 0x57 'W' + { 5157, 32, 32, 34, 1, -31 }, // 0x58 'X' + { 5285, 32, 32, 33, 1, -31 }, // 0x59 'Y' + { 5413, 28, 32, 30, 1, -31 }, // 0x5A 'Z' + { 5525, 11, 39, 16, 3, -31 }, // 0x5B '[' + { 5579, 15, 33, 13, -1, -32 }, // 0x5C '\' + { 5641, 11, 39, 16, 2, -31 }, // 0x5D ']' + { 5695, 21, 17, 27, 3, -31 }, // 0x5E '^' + { 5740, 24, 3, 23, 0, 5 }, // 0x5F '_' + { 5749, 11, 9, 16, 0, -33 }, // 0x60 '`' + { 5762, 22, 24, 23, 1, -22 }, // 0x61 'a' + { 5828, 25, 33, 26, 0, -31 }, // 0x62 'b' + { 5932, 19, 24, 20, 1, -22 }, // 0x63 'c' + { 5989, 24, 33, 26, 1, -31 }, // 0x64 'd' + { 6088, 18, 24, 21, 1, -22 }, // 0x65 'e' + { 6142, 17, 33, 18, 1, -32 }, // 0x66 'f' + { 6213, 19, 32, 24, 2, -22 }, // 0x67 'g' + { 6289, 24, 32, 26, 0, -31 }, // 0x68 'h' + { 6385, 11, 33, 14, 1, -32 }, // 0x69 'i' + { 6431, 14, 42, 18, 0, -32 }, // 0x6A 'j' + { 6505, 25, 32, 26, 0, -31 }, // 0x6B 'k' + { 6605, 11, 32, 13, 0, -31 }, // 0x6C 'l' + { 6649, 37, 23, 39, 0, -22 }, // 0x6D 'm' + { 6756, 24, 23, 26, 0, -22 }, // 0x6E 'n' + { 6825, 21, 24, 24, 1, -22 }, // 0x6F 'o' + { 6888, 24, 32, 26, 0, -22 }, // 0x70 'p' + { 6984, 24, 32, 26, 1, -22 }, // 0x71 'q' + { 7080, 19, 23, 20, 0, -22 }, // 0x72 'r' + { 7135, 15, 24, 19, 2, -22 }, // 0x73 's' + { 7180, 14, 31, 16, 1, -29 }, // 0x74 't' + { 7235, 25, 23, 27, 0, -21 }, // 0x75 'u' + { 7307, 22, 23, 23, 0, -21 }, // 0x76 'v' + { 7371, 33, 23, 33, 0, -21 }, // 0x77 'w' + { 7466, 22, 22, 24, 1, -21 }, // 0x78 'x' + { 7527, 21, 31, 23, 0, -21 }, // 0x79 'y' + { 7609, 19, 22, 21, 1, -21 }, // 0x7A 'z' + { 7662, 14, 42, 19, 1, -33 }, // 0x7B '{' + { 7736, 4, 33, 10, 3, -32 }, // 0x7C '|' + { 7753, 14, 42, 19, 4, -33 }, // 0x7D '}' + { 7827, 22, 7, 24, 1, -14 } }; // 0x7E '~' + +const GFXfont FreeSerifBold24pt7b PROGMEM = { + (uint8_t *)FreeSerifBold24pt7bBitmaps, + (GFXglyph *)FreeSerifBold24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 8519 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBold9pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBold9pt7b.h new file mode 100644 index 0000000..52dbe36 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBold9pt7b.h @@ -0,0 +1,202 @@ +const uint8_t FreeSerifBold9pt7bBitmaps[] PROGMEM = { + 0xFF, 0xF4, 0x92, 0x1F, 0xF0, 0xCF, 0x3C, 0xE3, 0x88, 0x13, 0x09, 0x84, + 0xC2, 0x47, 0xF9, 0x90, 0xC8, 0x4C, 0xFF, 0x13, 0x09, 0x0C, 0x86, 0x40, + 0x10, 0x38, 0xD6, 0x92, 0xD2, 0xF0, 0x7C, 0x3E, 0x17, 0x93, 0x93, 0xD6, + 0x7C, 0x10, 0x3C, 0x21, 0xCF, 0x0E, 0x24, 0x30, 0xA0, 0xC5, 0x03, 0x34, + 0xE7, 0x26, 0x40, 0xB9, 0x04, 0xC4, 0x23, 0x30, 0x8C, 0x84, 0x1C, 0x0F, + 0x00, 0xCC, 0x06, 0x60, 0x3E, 0x00, 0xE7, 0x8F, 0x18, 0x9C, 0x8C, 0xE4, + 0xE3, 0xC7, 0x9E, 0x3C, 0x72, 0xFD, 0xE0, 0xFF, 0x80, 0x32, 0x44, 0xCC, + 0xCC, 0xCC, 0xC4, 0x62, 0x10, 0x84, 0x22, 0x33, 0x33, 0x33, 0x32, 0x64, + 0x80, 0x31, 0x6B, 0xB1, 0x8E, 0xD6, 0x8C, 0x00, 0x08, 0x04, 0x02, 0x01, + 0x0F, 0xF8, 0x40, 0x20, 0x10, 0x08, 0x00, 0xDF, 0x95, 0x00, 0xFF, 0xFF, + 0x80, 0x0C, 0x21, 0x86, 0x10, 0xC3, 0x08, 0x61, 0x84, 0x30, 0xC0, 0x1C, + 0x33, 0x98, 0xDC, 0x7E, 0x3F, 0x1F, 0x8F, 0xC7, 0xE3, 0xB1, 0x98, 0xC3, + 0x80, 0x08, 0xE3, 0x8E, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0xBF, 0x3C, 0x3F, + 0x23, 0xC0, 0xE0, 0x70, 0x30, 0x38, 0x18, 0x18, 0x18, 0x5F, 0xDF, 0xE0, + 0x7C, 0x8E, 0x0E, 0x0E, 0x0C, 0x1E, 0x07, 0x03, 0x03, 0x02, 0xE6, 0xF8, + 0x06, 0x0E, 0x0E, 0x3E, 0x2E, 0x4E, 0x8E, 0x8E, 0xFF, 0xFF, 0x0E, 0x0E, + 0x3F, 0x7E, 0x40, 0x40, 0xF8, 0xFC, 0x1E, 0x06, 0x02, 0x02, 0xE4, 0xF8, + 0x07, 0x1C, 0x30, 0x70, 0xFC, 0xE6, 0xE7, 0xE7, 0xE7, 0x67, 0x66, 0x3C, + 0x7F, 0x3F, 0xA0, 0xD0, 0x40, 0x60, 0x30, 0x10, 0x18, 0x0C, 0x04, 0x06, + 0x03, 0x00, 0x3C, 0xC6, 0xC6, 0xC6, 0xFC, 0x7C, 0x3E, 0xCF, 0xC7, 0xC7, + 0xC6, 0x7C, 0x3E, 0x33, 0xB8, 0xDC, 0x7E, 0x3F, 0x1D, 0xCE, 0x7F, 0x07, + 0x07, 0x0F, 0x1C, 0x00, 0xFF, 0x80, 0x3F, 0xE0, 0xFF, 0x80, 0x37, 0xE5, + 0x40, 0x00, 0x00, 0x70, 0x78, 0x78, 0x78, 0x38, 0x03, 0x80, 0x3C, 0x03, + 0xC0, 0x30, 0xFF, 0xC0, 0x00, 0x00, 0x00, 0xFF, 0xC0, 0xC0, 0x3C, 0x03, + 0xC0, 0x1C, 0x01, 0xC1, 0xE1, 0xE1, 0xE0, 0xE0, 0x00, 0x00, 0x3D, 0x9F, + 0x3E, 0x70, 0xE1, 0x04, 0x08, 0x00, 0x70, 0xE1, 0xC0, 0x0F, 0x81, 0x83, + 0x18, 0xC4, 0x89, 0x9C, 0x4C, 0xE4, 0x67, 0x22, 0x39, 0x22, 0x4F, 0xE3, + 0x00, 0x0C, 0x10, 0x1F, 0x00, 0x02, 0x00, 0x30, 0x01, 0xC0, 0x0E, 0x00, + 0xB8, 0x05, 0xC0, 0x4F, 0x02, 0x38, 0x3F, 0xE1, 0x07, 0x18, 0x3D, 0xE3, + 0xF0, 0xFF, 0x87, 0x1C, 0xE3, 0x9C, 0x73, 0x9C, 0x7F, 0x0E, 0x71, 0xC7, + 0x38, 0xE7, 0x1C, 0xE7, 0x7F, 0xC0, 0x1F, 0x26, 0x1D, 0xC1, 0xB0, 0x1E, + 0x01, 0xC0, 0x38, 0x07, 0x00, 0xE0, 0x0E, 0x04, 0xE1, 0x0F, 0xC0, 0xFF, + 0x0E, 0x71, 0xC7, 0x38, 0x77, 0x0E, 0xE1, 0xDC, 0x3B, 0x87, 0x70, 0xCE, + 0x39, 0xC6, 0x7F, 0x80, 0xFF, 0xCE, 0x19, 0xC1, 0x38, 0x87, 0x30, 0xFE, + 0x1C, 0xC3, 0x88, 0x70, 0x2E, 0x0D, 0xC3, 0x7F, 0xE0, 0xFF, 0xDC, 0x37, + 0x05, 0xC4, 0x73, 0x1F, 0xC7, 0x31, 0xC4, 0x70, 0x1C, 0x07, 0x03, 0xE0, + 0x1F, 0x23, 0x0E, 0x70, 0x6E, 0x02, 0xE0, 0x0E, 0x00, 0xE1, 0xFE, 0x0E, + 0x60, 0xE7, 0x0E, 0x38, 0xE0, 0xF8, 0xF9, 0xF7, 0x0E, 0x70, 0xE7, 0x0E, + 0x70, 0xE7, 0xFE, 0x70, 0xE7, 0x0E, 0x70, 0xE7, 0x0E, 0x70, 0xEF, 0x9F, + 0xFB, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9D, 0xF0, 0x1F, 0x0E, 0x0E, 0x0E, + 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0x0E, 0xCE, 0xCC, 0x78, 0xF9, 0xF3, + 0x82, 0x1C, 0x20, 0xE2, 0x07, 0x20, 0x3F, 0x01, 0xDC, 0x0E, 0x70, 0x73, + 0xC3, 0x8F, 0x1C, 0x3D, 0xF3, 0xF0, 0xF8, 0x0E, 0x01, 0xC0, 0x38, 0x07, + 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x2E, 0x09, 0xC3, 0x7F, 0xE0, 0xF8, + 0x0F, 0x3C, 0x1E, 0x3C, 0x1E, 0x2E, 0x2E, 0x2E, 0x2E, 0x26, 0x4E, 0x27, + 0x4E, 0x27, 0x4E, 0x23, 0x8E, 0x23, 0x8E, 0x21, 0x0E, 0x71, 0x1F, 0xF0, + 0xEE, 0x09, 0xE1, 0x3E, 0x25, 0xE4, 0x9E, 0x91, 0xD2, 0x1E, 0x43, 0xC8, + 0x39, 0x03, 0x70, 0x20, 0x1F, 0x83, 0x0C, 0x70, 0xEE, 0x07, 0xE0, 0x7E, + 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0x77, 0x0E, 0x30, 0xC1, 0xF8, 0xFF, 0x1C, + 0xE7, 0x1D, 0xC7, 0x71, 0xDC, 0xE7, 0xF1, 0xC0, 0x70, 0x1C, 0x07, 0x03, + 0xE0, 0x0F, 0x83, 0x9C, 0x70, 0xE6, 0x06, 0xE0, 0x7E, 0x07, 0xE0, 0x7E, + 0x07, 0xE0, 0x76, 0x06, 0x30, 0xC1, 0x98, 0x0F, 0x00, 0x78, 0x03, 0xE0, + 0xFF, 0x07, 0x38, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x38, 0x7E, 0x07, 0x70, + 0x77, 0x87, 0x3C, 0x71, 0xEF, 0x8F, 0x39, 0x47, 0xC1, 0xC0, 0xF0, 0x7C, + 0x3E, 0x0F, 0x83, 0xC3, 0xC6, 0xBC, 0xFF, 0xFC, 0xE3, 0x8E, 0x10, 0xE0, + 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x01, 0xF0, + 0xF8, 0xEE, 0x09, 0xC1, 0x38, 0x27, 0x04, 0xE0, 0x9C, 0x13, 0x82, 0x70, + 0x4E, 0x08, 0xE2, 0x0F, 0x80, 0xFC, 0x7B, 0xC1, 0x0E, 0x08, 0x70, 0x81, + 0xC4, 0x0E, 0x20, 0x7A, 0x01, 0xD0, 0x0E, 0x80, 0x38, 0x01, 0xC0, 0x04, + 0x00, 0x20, 0x00, 0xFD, 0xFB, 0xDC, 0x38, 0x43, 0x87, 0x10, 0xE1, 0xC4, + 0x38, 0xF2, 0x07, 0x2E, 0x81, 0xD3, 0xA0, 0x34, 0x70, 0x0E, 0x1C, 0x03, + 0x87, 0x00, 0x60, 0x80, 0x10, 0x20, 0xFE, 0xF3, 0xC3, 0x0F, 0x10, 0x39, + 0x00, 0xF0, 0x03, 0x80, 0x1E, 0x01, 0x70, 0x09, 0xC0, 0x8F, 0x08, 0x3D, + 0xF3, 0xF0, 0xFC, 0x7B, 0xC1, 0x8E, 0x08, 0x38, 0x81, 0xE8, 0x07, 0x40, + 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x1F, 0x00, 0xFF, 0xD8, + 0x72, 0x1E, 0x43, 0x80, 0xE0, 0x1C, 0x07, 0x01, 0xC0, 0x38, 0x2E, 0x0F, + 0x83, 0x7F, 0xE0, 0xFC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xCC, 0xF0, 0xC1, + 0x06, 0x18, 0x20, 0xC3, 0x04, 0x18, 0x60, 0x83, 0x0C, 0xF3, 0x33, 0x33, + 0x33, 0x33, 0x33, 0x33, 0xF0, 0x18, 0x1C, 0x34, 0x26, 0x62, 0x43, 0xC1, + 0xFF, 0x80, 0xC6, 0x30, 0x7C, 0x63, 0xB1, 0xC0, 0xE1, 0xF3, 0x3B, 0x9D, + 0xCE, 0xFF, 0x80, 0xF0, 0x1C, 0x07, 0x01, 0xDC, 0x7B, 0x9C, 0x77, 0x1D, + 0xC7, 0x71, 0xDC, 0x77, 0x39, 0x3C, 0x3C, 0xED, 0x9F, 0x0E, 0x1C, 0x38, + 0x39, 0x3C, 0x07, 0x80, 0xE0, 0x38, 0xEE, 0x77, 0xB8, 0xEE, 0x3B, 0x8E, + 0xE3, 0xB8, 0xE7, 0x78, 0xEF, 0x3C, 0x66, 0xE6, 0xFE, 0xE0, 0xE0, 0xE0, + 0x72, 0x3C, 0x3E, 0xED, 0xC7, 0xC7, 0x0E, 0x1C, 0x38, 0x70, 0xE1, 0xC7, + 0xC0, 0x31, 0xDF, 0xBF, 0x7E, 0xE7, 0x90, 0x60, 0xFC, 0xFE, 0x0C, 0x17, + 0xC0, 0xF0, 0x1C, 0x07, 0x01, 0xDC, 0x7B, 0x9C, 0xE7, 0x39, 0xCE, 0x73, + 0x9C, 0xE7, 0x3B, 0xFF, 0x73, 0x9D, 0xE7, 0x39, 0xCE, 0x73, 0x9D, 0xF0, + 0x1C, 0x71, 0xCF, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x7D, 0xBE, + 0xF0, 0x1C, 0x07, 0x01, 0xCE, 0x71, 0x1C, 0x87, 0x41, 0xF8, 0x77, 0x1C, + 0xE7, 0x1B, 0xEF, 0xF3, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9D, 0xF0, 0xF7, + 0x38, 0xF7, 0xB9, 0xCE, 0x73, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9C, 0xE7, + 0x39, 0xCE, 0xFF, 0xFE, 0xF7, 0x1E, 0xE7, 0x39, 0xCE, 0x73, 0x9C, 0xE7, + 0x39, 0xCE, 0xFF, 0xC0, 0x3E, 0x31, 0xB8, 0xFC, 0x7E, 0x3F, 0x1F, 0x8E, + 0xC6, 0x3E, 0x00, 0xF7, 0x1E, 0xE7, 0x1D, 0xC7, 0x71, 0xDC, 0x77, 0x1D, + 0xCE, 0x7F, 0x1C, 0x07, 0x01, 0xC0, 0xF8, 0x00, 0x3C, 0x9C, 0xEE, 0x3B, + 0x8E, 0xE3, 0xB8, 0xEE, 0x39, 0xCE, 0x3F, 0x80, 0xE0, 0x38, 0x0E, 0x07, + 0xC0, 0xF7, 0x7B, 0x70, 0x70, 0x70, 0x70, 0x70, 0x70, 0xF8, 0x7E, 0x73, + 0xC7, 0x8E, 0x39, 0xB0, 0x10, 0xCF, 0x9C, 0x71, 0xC7, 0x1C, 0x71, 0xD3, + 0x80, 0xF7, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9C, 0xE7, 0x39, 0xCE, 0x3F, + 0xC0, 0xFB, 0xB8, 0x8C, 0x87, 0x43, 0xC0, 0xE0, 0x70, 0x10, 0x08, 0x00, + 0xF7, 0xB6, 0x31, 0x73, 0xA3, 0x3A, 0x3D, 0xA3, 0xDC, 0x18, 0xC1, 0x88, + 0x10, 0x80, 0xFB, 0xB8, 0x8E, 0x83, 0x81, 0xC0, 0xF0, 0x98, 0xCE, 0xEF, + 0x80, 0xF7, 0x62, 0x72, 0x34, 0x34, 0x3C, 0x18, 0x18, 0x10, 0x10, 0x10, + 0xE0, 0xE0, 0xFF, 0x1C, 0x70, 0xE3, 0x87, 0x1C, 0x71, 0xFE, 0x19, 0x8C, + 0x63, 0x18, 0xCC, 0x61, 0x8C, 0x63, 0x18, 0xC3, 0xFF, 0xF8, 0xC3, 0x18, + 0xC6, 0x31, 0x86, 0x33, 0x18, 0xC6, 0x31, 0x98, 0xF0, 0x8E }; + +const GFXglyph FreeSerifBold9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 3, 12, 6, 1, -11 }, // 0x21 '!' + { 5, 6, 5, 10, 2, -11 }, // 0x22 '"' + { 9, 9, 13, 9, 0, -12 }, // 0x23 '#' + { 24, 8, 14, 9, 1, -12 }, // 0x24 '$' + { 38, 14, 12, 18, 2, -11 }, // 0x25 '%' + { 59, 13, 12, 15, 1, -11 }, // 0x26 '&' + { 79, 2, 5, 5, 1, -11 }, // 0x27 ''' + { 81, 4, 15, 6, 1, -11 }, // 0x28 '(' + { 89, 4, 15, 6, 1, -11 }, // 0x29 ')' + { 97, 7, 7, 9, 2, -11 }, // 0x2A '*' + { 104, 9, 9, 12, 1, -8 }, // 0x2B '+' + { 115, 3, 6, 4, 1, -2 }, // 0x2C ',' + { 118, 4, 2, 6, 1, -4 }, // 0x2D '-' + { 119, 3, 3, 4, 1, -2 }, // 0x2E '.' + { 121, 6, 13, 5, 0, -11 }, // 0x2F '/' + { 131, 9, 12, 9, 0, -11 }, // 0x30 '0' + { 145, 6, 12, 9, 1, -11 }, // 0x31 '1' + { 154, 9, 12, 9, 0, -11 }, // 0x32 '2' + { 168, 8, 12, 9, 0, -11 }, // 0x33 '3' + { 180, 8, 12, 9, 1, -11 }, // 0x34 '4' + { 192, 8, 12, 9, 1, -11 }, // 0x35 '5' + { 204, 8, 12, 9, 1, -11 }, // 0x36 '6' + { 216, 9, 12, 9, 0, -11 }, // 0x37 '7' + { 230, 8, 12, 9, 1, -11 }, // 0x38 '8' + { 242, 9, 12, 9, 0, -11 }, // 0x39 '9' + { 256, 3, 9, 6, 1, -8 }, // 0x3A ':' + { 260, 3, 12, 6, 2, -8 }, // 0x3B ';' + { 265, 10, 10, 12, 1, -9 }, // 0x3C '<' + { 278, 10, 5, 12, 1, -6 }, // 0x3D '=' + { 285, 10, 10, 12, 1, -8 }, // 0x3E '>' + { 298, 7, 12, 9, 1, -11 }, // 0x3F '?' + { 309, 13, 12, 17, 2, -11 }, // 0x40 '@' + { 329, 13, 12, 13, 0, -11 }, // 0x41 'A' + { 349, 11, 12, 12, 0, -11 }, // 0x42 'B' + { 366, 11, 12, 13, 1, -11 }, // 0x43 'C' + { 383, 11, 12, 13, 1, -11 }, // 0x44 'D' + { 400, 11, 12, 12, 1, -11 }, // 0x45 'E' + { 417, 10, 12, 11, 1, -11 }, // 0x46 'F' + { 432, 12, 12, 14, 1, -11 }, // 0x47 'G' + { 450, 12, 12, 14, 1, -11 }, // 0x48 'H' + { 468, 5, 12, 7, 1, -11 }, // 0x49 'I' + { 476, 8, 14, 9, 0, -11 }, // 0x4A 'J' + { 490, 13, 12, 14, 1, -11 }, // 0x4B 'K' + { 510, 11, 12, 12, 1, -11 }, // 0x4C 'L' + { 527, 16, 12, 17, 0, -11 }, // 0x4D 'M' + { 551, 11, 12, 13, 1, -11 }, // 0x4E 'N' + { 568, 12, 12, 14, 1, -11 }, // 0x4F 'O' + { 586, 10, 12, 11, 1, -11 }, // 0x50 'P' + { 601, 12, 15, 14, 1, -11 }, // 0x51 'Q' + { 624, 12, 12, 13, 1, -11 }, // 0x52 'R' + { 642, 8, 12, 10, 1, -11 }, // 0x53 'S' + { 654, 12, 12, 12, 0, -11 }, // 0x54 'T' + { 672, 11, 12, 13, 1, -11 }, // 0x55 'U' + { 689, 13, 13, 13, 0, -11 }, // 0x56 'V' + { 711, 18, 12, 18, 0, -11 }, // 0x57 'W' + { 738, 13, 12, 13, 0, -11 }, // 0x58 'X' + { 758, 13, 12, 13, 0, -11 }, // 0x59 'Y' + { 778, 11, 12, 12, 1, -11 }, // 0x5A 'Z' + { 795, 4, 15, 6, 1, -11 }, // 0x5B '[' + { 803, 6, 13, 5, 0, -11 }, // 0x5C '\' + { 813, 4, 15, 6, 1, -11 }, // 0x5D ']' + { 821, 8, 7, 10, 1, -11 }, // 0x5E '^' + { 828, 9, 1, 9, 0, 3 }, // 0x5F '_' + { 830, 4, 3, 6, 0, -12 }, // 0x60 '`' + { 832, 9, 9, 9, 0, -8 }, // 0x61 'a' + { 843, 10, 12, 10, 0, -11 }, // 0x62 'b' + { 858, 7, 9, 8, 0, -8 }, // 0x63 'c' + { 866, 10, 12, 10, 0, -11 }, // 0x64 'd' + { 881, 8, 9, 8, 0, -8 }, // 0x65 'e' + { 890, 7, 12, 7, 0, -11 }, // 0x66 'f' + { 901, 7, 13, 9, 1, -8 }, // 0x67 'g' + { 913, 10, 12, 10, 0, -11 }, // 0x68 'h' + { 928, 5, 12, 5, 0, -11 }, // 0x69 'i' + { 936, 6, 16, 7, 0, -11 }, // 0x6A 'j' + { 948, 10, 12, 10, 0, -11 }, // 0x6B 'k' + { 963, 5, 12, 5, 0, -11 }, // 0x6C 'l' + { 971, 15, 9, 15, 0, -8 }, // 0x6D 'm' + { 988, 10, 9, 10, 0, -8 }, // 0x6E 'n' + { 1000, 9, 9, 9, 0, -8 }, // 0x6F 'o' + { 1011, 10, 13, 10, 0, -8 }, // 0x70 'p' + { 1028, 10, 13, 10, 0, -8 }, // 0x71 'q' + { 1045, 8, 9, 8, 0, -8 }, // 0x72 'r' + { 1054, 5, 9, 7, 1, -8 }, // 0x73 's' + { 1060, 6, 11, 6, 0, -10 }, // 0x74 't' + { 1069, 10, 9, 10, 0, -8 }, // 0x75 'u' + { 1081, 9, 9, 9, 0, -8 }, // 0x76 'v' + { 1092, 12, 9, 13, 0, -8 }, // 0x77 'w' + { 1106, 9, 9, 9, 0, -8 }, // 0x78 'x' + { 1117, 8, 13, 9, 0, -8 }, // 0x79 'y' + { 1130, 7, 9, 8, 1, -8 }, // 0x7A 'z' + { 1138, 5, 16, 7, 0, -12 }, // 0x7B '{' + { 1148, 1, 13, 4, 1, -11 }, // 0x7C '|' + { 1150, 5, 16, 7, 2, -12 }, // 0x7D '}' + { 1160, 8, 2, 9, 1, -4 } }; // 0x7E '~' + +const GFXfont FreeSerifBold9pt7b PROGMEM = { + (uint8_t *)FreeSerifBold9pt7bBitmaps, + (GFXglyph *)FreeSerifBold9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 1834 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic12pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic12pt7b.h new file mode 100644 index 0000000..1f674e9 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic12pt7b.h @@ -0,0 +1,292 @@ +const uint8_t FreeSerifBoldItalic12pt7bBitmaps[] PROGMEM = { + 0x07, 0x07, 0x07, 0x0F, 0x0E, 0x0E, 0x0C, 0x0C, 0x08, 0x18, 0x10, 0x00, + 0x00, 0x60, 0xF0, 0xF0, 0x60, 0x61, 0xF1, 0xF8, 0xF8, 0x6C, 0x34, 0x12, + 0x08, 0x01, 0x8C, 0x06, 0x60, 0x31, 0x80, 0xCC, 0x06, 0x30, 0xFF, 0xF0, + 0xC6, 0x03, 0x18, 0x0C, 0xC0, 0x63, 0x0F, 0xFF, 0x0C, 0x60, 0x33, 0x01, + 0x8C, 0x06, 0x30, 0x19, 0x80, 0x00, 0x80, 0x08, 0x07, 0xC1, 0x96, 0x31, + 0x33, 0x13, 0x3A, 0x23, 0xE0, 0x1E, 0x01, 0xF0, 0x07, 0x80, 0x7C, 0x05, + 0xC4, 0xCC, 0x48, 0xCC, 0x8C, 0xF8, 0x83, 0x30, 0x1E, 0x01, 0x00, 0x00, + 0x02, 0x07, 0x83, 0x03, 0x9F, 0x81, 0xC4, 0x20, 0x71, 0x10, 0x3C, 0x44, + 0x0E, 0x22, 0x03, 0x88, 0x80, 0xE4, 0x40, 0x1E, 0x31, 0xE0, 0x08, 0xE4, + 0x06, 0x71, 0x01, 0x3C, 0x40, 0x8E, 0x10, 0x23, 0x88, 0x10, 0xE2, 0x04, + 0x39, 0x02, 0x07, 0x80, 0x00, 0xF0, 0x01, 0x98, 0x03, 0x98, 0x03, 0x98, + 0x03, 0xB0, 0x03, 0xE0, 0x03, 0x80, 0x0F, 0x9F, 0x19, 0xCE, 0x31, 0xCC, + 0x61, 0xC8, 0xE1, 0xC8, 0xE0, 0xF0, 0xE0, 0xE0, 0xF0, 0x70, 0x78, 0x79, + 0x3F, 0xBE, 0x7F, 0xED, 0x20, 0x02, 0x08, 0x20, 0xC3, 0x0E, 0x18, 0x30, + 0xE1, 0x83, 0x06, 0x0C, 0x18, 0x30, 0x20, 0x40, 0x80, 0x81, 0x01, 0x00, + 0x10, 0x10, 0x20, 0x20, 0x40, 0xC1, 0x83, 0x06, 0x0C, 0x18, 0x70, 0xE1, + 0x83, 0x0C, 0x18, 0x61, 0x86, 0x00, 0x00, 0x0C, 0x33, 0x6C, 0x9B, 0xAE, + 0x1C, 0x3F, 0xEC, 0x9B, 0x36, 0x0C, 0x02, 0x00, 0x06, 0x00, 0x60, 0x06, + 0x00, 0x60, 0x06, 0x0F, 0xFF, 0xFF, 0xF0, 0x60, 0x06, 0x00, 0x60, 0x06, + 0x00, 0x60, 0x31, 0xCE, 0x31, 0x08, 0x98, 0xFF, 0xFF, 0xC0, 0x6F, 0xF6, + 0x01, 0x80, 0x60, 0x30, 0x0C, 0x07, 0x01, 0x80, 0xE0, 0x30, 0x1C, 0x06, + 0x01, 0x80, 0xC0, 0x30, 0x18, 0x06, 0x03, 0x00, 0x03, 0x81, 0xC8, 0x71, + 0x1C, 0x33, 0x86, 0xE1, 0xDC, 0x3B, 0x87, 0xE0, 0xFC, 0x3B, 0x87, 0x70, + 0xEC, 0x39, 0x87, 0x31, 0xC2, 0x30, 0x3C, 0x00, 0x01, 0xC3, 0xF0, 0x38, + 0x0E, 0x03, 0x81, 0xE0, 0x70, 0x1C, 0x0F, 0x03, 0x80, 0xE0, 0x38, 0x1E, + 0x07, 0x01, 0xC0, 0xF0, 0xFF, 0x80, 0x07, 0x81, 0xF8, 0x47, 0x90, 0x70, + 0x0E, 0x01, 0xC0, 0x30, 0x0E, 0x01, 0x80, 0x60, 0x18, 0x06, 0x01, 0x80, + 0x40, 0x8F, 0xF3, 0xFC, 0xFF, 0x80, 0x07, 0xC3, 0x3C, 0x03, 0x80, 0x70, + 0x0C, 0x03, 0x81, 0xC0, 0xFC, 0x07, 0xC0, 0x78, 0x07, 0x00, 0xE0, 0x1C, + 0x03, 0x30, 0xE7, 0x10, 0x7C, 0x00, 0x00, 0x10, 0x01, 0x80, 0x3C, 0x03, + 0xE0, 0x2E, 0x02, 0x70, 0x23, 0x82, 0x38, 0x21, 0xC2, 0x0E, 0x1F, 0xF9, + 0xFF, 0xC0, 0x38, 0x01, 0xC0, 0x1C, 0x00, 0xE0, 0x07, 0xF0, 0x7E, 0x0F, + 0xE0, 0x80, 0x08, 0x01, 0xE0, 0x1F, 0x83, 0xF8, 0x03, 0xC0, 0x1C, 0x00, + 0xC0, 0x0C, 0x00, 0xC0, 0x08, 0x61, 0x8F, 0x30, 0x7C, 0x00, 0x00, 0x60, + 0x78, 0x1C, 0x0F, 0x01, 0xC0, 0x70, 0x1F, 0xC3, 0x8C, 0xE1, 0xDC, 0x3B, + 0x87, 0x61, 0xEC, 0x3D, 0x87, 0x31, 0xE2, 0x38, 0x3C, 0x00, 0x3F, 0xEF, + 0xF9, 0xFF, 0x60, 0xC8, 0x18, 0x06, 0x00, 0x80, 0x30, 0x0C, 0x01, 0x80, + 0x60, 0x1C, 0x03, 0x00, 0xC0, 0x18, 0x06, 0x00, 0x03, 0x81, 0x88, 0x61, + 0x8C, 0x31, 0x86, 0x38, 0xC7, 0xB0, 0x78, 0x0F, 0x86, 0x71, 0x87, 0x60, + 0x6C, 0x0D, 0x81, 0xB0, 0x63, 0x18, 0x3E, 0x00, 0x07, 0x81, 0xC8, 0x71, + 0x8E, 0x33, 0xC6, 0x70, 0xCE, 0x39, 0xC7, 0x38, 0xE3, 0x38, 0x3F, 0x01, + 0xC0, 0x38, 0x0E, 0x03, 0x81, 0xC0, 0xE0, 0x00, 0x0C, 0x3C, 0x78, 0x60, + 0x00, 0x00, 0x00, 0x61, 0xE3, 0xC3, 0x00, 0x0E, 0x0F, 0x0F, 0x0E, 0x00, + 0x00, 0x00, 0x00, 0x38, 0x38, 0x38, 0x18, 0x10, 0x20, 0x40, 0x00, 0x10, + 0x07, 0x01, 0xF0, 0x7C, 0x3F, 0x0F, 0x80, 0xE0, 0x0F, 0x80, 0x3E, 0x00, + 0xF8, 0x03, 0xE0, 0x07, 0x00, 0x10, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, + 0xFF, 0xFF, 0xFF, 0x80, 0x07, 0x00, 0x3F, 0x00, 0x3E, 0x00, 0x7C, 0x00, + 0xF8, 0x01, 0xE0, 0x1F, 0x07, 0xE0, 0xF8, 0x1F, 0x01, 0xE0, 0x0C, 0x00, + 0x00, 0x1E, 0x19, 0x8C, 0xE6, 0x70, 0x38, 0x38, 0x1C, 0x18, 0x18, 0x08, + 0x08, 0x00, 0x00, 0x03, 0x03, 0xC1, 0xE0, 0x60, 0x00, 0x03, 0xF0, 0x07, + 0x06, 0x06, 0x00, 0x86, 0x0E, 0x66, 0x0D, 0xDB, 0x0C, 0xE7, 0x06, 0x33, + 0x83, 0x31, 0xC3, 0x18, 0xE1, 0x8C, 0x70, 0xCC, 0x4C, 0x66, 0x46, 0x1F, + 0xC1, 0x80, 0x00, 0x30, 0x10, 0x07, 0xF0, 0x00, 0x10, 0x00, 0x30, 0x00, + 0x70, 0x00, 0x70, 0x00, 0xF0, 0x01, 0xF0, 0x01, 0x78, 0x03, 0x78, 0x02, + 0x38, 0x04, 0x38, 0x0C, 0x38, 0x0F, 0xF8, 0x18, 0x3C, 0x30, 0x3C, 0x20, + 0x3C, 0x60, 0x3C, 0xF8, 0x7F, 0x1F, 0xFC, 0x07, 0x9E, 0x07, 0x0F, 0x07, + 0x0F, 0x0F, 0x0F, 0x0F, 0x1E, 0x0E, 0x3C, 0x0F, 0xE0, 0x1E, 0x3C, 0x1E, + 0x1E, 0x1C, 0x1E, 0x3C, 0x1E, 0x3C, 0x1E, 0x3C, 0x3E, 0x38, 0x3C, 0x7C, + 0x78, 0xFF, 0xE0, 0x01, 0xF2, 0x0E, 0x1C, 0x38, 0x18, 0xE0, 0x33, 0xC0, + 0x4F, 0x00, 0x9E, 0x00, 0x7C, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, + 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x1E, 0x04, 0x1E, 0x30, 0x0F, 0x80, 0x1F, + 0xFC, 0x01, 0xE3, 0xC0, 0x70, 0x78, 0x1C, 0x0E, 0x0F, 0x03, 0xC3, 0xC0, + 0xF0, 0xE0, 0x3C, 0x38, 0x0F, 0x1E, 0x03, 0xC7, 0x81, 0xF1, 0xC0, 0x78, + 0xF0, 0x1E, 0x3C, 0x0F, 0x0F, 0x03, 0xC3, 0x81, 0xC1, 0xE1, 0xE0, 0xFF, + 0xE0, 0x00, 0x1F, 0xFF, 0x83, 0xC1, 0xC1, 0xC0, 0x40, 0xE0, 0x20, 0xF0, + 0x00, 0x78, 0xC0, 0x38, 0x40, 0x1F, 0xE0, 0x1E, 0x70, 0x0F, 0x18, 0x07, + 0x08, 0x03, 0x84, 0x03, 0xC0, 0x61, 0xE0, 0x20, 0xE0, 0x30, 0xF8, 0x78, + 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0x07, 0x87, 0x07, 0x02, 0x07, 0x02, 0x0F, + 0x00, 0x0F, 0x18, 0x0E, 0x10, 0x0F, 0xF0, 0x1E, 0x70, 0x1E, 0x30, 0x1C, + 0x20, 0x1C, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x38, 0x00, 0x7C, 0x00, 0xFE, + 0x00, 0x01, 0xF9, 0x03, 0xC3, 0x83, 0x81, 0xC3, 0x80, 0x43, 0xC0, 0x23, + 0xC0, 0x01, 0xE0, 0x01, 0xF0, 0x00, 0xF0, 0x3F, 0xF8, 0x0F, 0x3C, 0x07, + 0x9E, 0x03, 0xCF, 0x01, 0xC3, 0x80, 0xE1, 0xE0, 0xF0, 0x78, 0x70, 0x0F, + 0xE0, 0x00, 0x1F, 0xE7, 0xF0, 0x78, 0x3C, 0x07, 0x83, 0xC0, 0x70, 0x3C, + 0x0F, 0x03, 0x80, 0xF0, 0x78, 0x0E, 0x07, 0x80, 0xE0, 0x70, 0x1F, 0xFF, + 0x01, 0xE0, 0xF0, 0x1C, 0x0F, 0x03, 0xC0, 0xE0, 0x3C, 0x1E, 0x03, 0xC1, + 0xE0, 0x38, 0x1E, 0x07, 0xC3, 0xE0, 0xFE, 0x7F, 0x00, 0x1F, 0xC1, 0xE0, + 0x70, 0x1C, 0x0F, 0x03, 0xC0, 0xE0, 0x38, 0x1E, 0x07, 0x81, 0xC0, 0x70, + 0x3C, 0x0F, 0x03, 0x81, 0xF0, 0xFE, 0x00, 0x01, 0xFC, 0x03, 0xC0, 0x0F, + 0x00, 0x38, 0x00, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x70, 0x01, 0xC0, 0x0F, + 0x00, 0x3C, 0x00, 0xE0, 0x07, 0x80, 0x1E, 0x0E, 0x70, 0x3B, 0xC0, 0xCE, + 0x01, 0xF0, 0x00, 0x1F, 0xEF, 0x83, 0xC1, 0x81, 0xC1, 0x80, 0xE1, 0x80, + 0xF1, 0x80, 0x79, 0x00, 0x39, 0x00, 0x1F, 0x80, 0x1F, 0xE0, 0x0F, 0x70, + 0x07, 0x3C, 0x07, 0x8E, 0x03, 0xC7, 0x01, 0xE3, 0xC0, 0xE0, 0xE0, 0xF8, + 0x78, 0xFE, 0xFE, 0x00, 0x1F, 0xE0, 0x0F, 0x00, 0x1C, 0x00, 0x38, 0x00, + 0xF0, 0x01, 0xE0, 0x03, 0x80, 0x07, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x70, + 0x00, 0xE0, 0x03, 0xC0, 0x27, 0x00, 0xCE, 0x03, 0x3C, 0x1E, 0xFF, 0xFC, + 0x0F, 0x80, 0x7E, 0x0F, 0x00, 0xF0, 0x1E, 0x03, 0xE0, 0x3C, 0x0F, 0x80, + 0xB8, 0x17, 0x01, 0x70, 0x5E, 0x02, 0xF1, 0xBC, 0x05, 0xE2, 0x70, 0x11, + 0xC8, 0xE0, 0x23, 0xB3, 0xC0, 0x47, 0x47, 0x81, 0x0F, 0x8E, 0x02, 0x1E, + 0x1C, 0x04, 0x38, 0x78, 0x08, 0x70, 0xF0, 0x30, 0xC3, 0xE0, 0xF9, 0x8F, + 0xE0, 0x1F, 0x03, 0xE0, 0xF0, 0x38, 0x1E, 0x02, 0x03, 0xE0, 0xC0, 0xBC, + 0x10, 0x13, 0xC2, 0x02, 0x78, 0x40, 0x47, 0x90, 0x10, 0xF2, 0x02, 0x0F, + 0x40, 0x41, 0xE8, 0x18, 0x1E, 0x02, 0x03, 0xC0, 0x40, 0x38, 0x08, 0x06, + 0x03, 0x00, 0x40, 0x10, 0x08, 0x00, 0x01, 0xF8, 0x07, 0x1C, 0x0E, 0x0E, + 0x1E, 0x0F, 0x3C, 0x0F, 0x3C, 0x0F, 0x78, 0x0F, 0x78, 0x0F, 0xF8, 0x1F, + 0xF0, 0x1E, 0xF0, 0x1E, 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, 0x78, 0x70, 0x70, + 0x38, 0xE0, 0x1F, 0x80, 0x1F, 0xFC, 0x07, 0x9E, 0x07, 0x0F, 0x07, 0x0F, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0E, 0x1E, 0x0E, 0x3C, 0x1F, 0xF0, 0x1E, 0x00, + 0x1C, 0x00, 0x1C, 0x00, 0x3C, 0x00, 0x38, 0x00, 0x38, 0x00, 0x7C, 0x00, + 0xFE, 0x00, 0x01, 0xF8, 0x07, 0x1C, 0x0E, 0x0E, 0x1E, 0x0F, 0x3C, 0x0F, + 0x3C, 0x0F, 0x78, 0x0F, 0x78, 0x1F, 0xF8, 0x1F, 0xF0, 0x1E, 0xF0, 0x1E, + 0xF0, 0x3C, 0xF0, 0x3C, 0xF0, 0x78, 0x70, 0x70, 0x39, 0xC0, 0x0E, 0x00, + 0x08, 0x02, 0x3F, 0x04, 0x7F, 0xF8, 0x83, 0xF0, 0x1F, 0xF8, 0x07, 0x9E, + 0x07, 0x8F, 0x07, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, 0x1E, 0x0E, 0x3C, + 0x1F, 0xF0, 0x1E, 0xF0, 0x1C, 0xF0, 0x3C, 0xF0, 0x3C, 0x78, 0x3C, 0x78, + 0x3C, 0x78, 0x7C, 0x3C, 0xFE, 0x3E, 0x07, 0x91, 0xC7, 0x18, 0x73, 0x82, + 0x38, 0x23, 0xC0, 0x3E, 0x01, 0xF0, 0x0F, 0x80, 0x7C, 0x01, 0xE0, 0x1E, + 0x40, 0xE4, 0x0E, 0x60, 0xCE, 0x1C, 0x9F, 0x00, 0x7F, 0xFE, 0xE7, 0x9D, + 0x0E, 0x16, 0x3C, 0x20, 0x78, 0x40, 0xE0, 0x01, 0xC0, 0x07, 0x80, 0x0F, + 0x00, 0x1C, 0x00, 0x38, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0x80, 0x0F, 0x00, + 0x1E, 0x00, 0xFF, 0x00, 0x7F, 0x1F, 0x3C, 0x0E, 0x38, 0x04, 0x38, 0x0C, + 0x78, 0x08, 0x78, 0x08, 0x70, 0x08, 0x70, 0x10, 0xF0, 0x10, 0xF0, 0x10, + 0xF0, 0x10, 0xF0, 0x20, 0xF0, 0x20, 0xF0, 0x20, 0xF0, 0x40, 0x78, 0xC0, + 0x3F, 0x00, 0xFF, 0x1F, 0x3C, 0x06, 0x3C, 0x04, 0x3C, 0x08, 0x3C, 0x08, + 0x3C, 0x10, 0x1C, 0x20, 0x1C, 0x20, 0x1E, 0x40, 0x1E, 0x80, 0x1E, 0x80, + 0x1F, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0C, 0x00, 0x08, 0x00, 0xFE, 0x7C, + 0x79, 0xE1, 0xC1, 0x8F, 0x0E, 0x08, 0x78, 0x70, 0x43, 0xC7, 0x84, 0x1E, + 0x3E, 0x20, 0x72, 0xF2, 0x03, 0x97, 0x90, 0x1D, 0x1D, 0x00, 0xE8, 0xE8, + 0x07, 0x87, 0x80, 0x3C, 0x3C, 0x01, 0xC1, 0xC0, 0x0E, 0x0E, 0x00, 0x20, + 0x60, 0x01, 0x02, 0x00, 0x1F, 0xCF, 0x83, 0xC1, 0x81, 0xE1, 0x80, 0x71, + 0x80, 0x39, 0x80, 0x1F, 0x80, 0x07, 0x80, 0x03, 0x80, 0x01, 0xE0, 0x01, + 0xF0, 0x00, 0xB8, 0x00, 0x9C, 0x00, 0x8F, 0x00, 0x83, 0x80, 0xC1, 0xC0, + 0xE0, 0xF0, 0xF9, 0xFE, 0x00, 0xFE, 0x7C, 0xE0, 0x63, 0x81, 0x0F, 0x08, + 0x1C, 0x40, 0x71, 0x01, 0xE8, 0x03, 0xC0, 0x0E, 0x00, 0x38, 0x01, 0xE0, + 0x07, 0x80, 0x1C, 0x00, 0x70, 0x03, 0xC0, 0x0F, 0x00, 0xFF, 0x00, 0x1F, + 0xFE, 0x38, 0x78, 0x60, 0xF1, 0x83, 0xC2, 0x0F, 0x00, 0x1E, 0x00, 0x78, + 0x01, 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xF8, 0x01, 0xE0, 0x47, + 0x81, 0x1F, 0x06, 0x3C, 0x3C, 0xFF, 0xF0, 0x07, 0xC1, 0x80, 0xE0, 0x30, + 0x0C, 0x03, 0x01, 0xC0, 0x60, 0x18, 0x06, 0x03, 0x80, 0xC0, 0x30, 0x0C, + 0x07, 0x01, 0xC0, 0x60, 0x18, 0x0E, 0x03, 0xE0, 0xC3, 0x06, 0x18, 0x61, + 0x83, 0x0C, 0x30, 0xC1, 0x86, 0x18, 0x60, 0xC3, 0x0F, 0x81, 0xC0, 0xE0, + 0x60, 0x30, 0x18, 0x1C, 0x0C, 0x06, 0x03, 0x03, 0x81, 0x80, 0xC0, 0x60, + 0x70, 0x38, 0x18, 0x0C, 0x0E, 0x1F, 0x00, 0x0C, 0x07, 0x81, 0xE0, 0xDC, + 0x33, 0x18, 0xC6, 0x1B, 0x06, 0xC0, 0xC0, 0xFF, 0xF0, 0xC7, 0x0C, 0x30, + 0x07, 0x70, 0xCE, 0x1C, 0xE3, 0x8E, 0x70, 0xC7, 0x0C, 0x71, 0xCE, 0x1C, + 0xE1, 0x8E, 0x79, 0xE9, 0xA7, 0x1C, 0x02, 0x07, 0xC0, 0x38, 0x06, 0x01, + 0xC0, 0x38, 0x06, 0x71, 0xF7, 0x38, 0xE7, 0x1C, 0xC3, 0xB8, 0x77, 0x1C, + 0xE3, 0xB8, 0xE7, 0x18, 0xE6, 0x0F, 0x80, 0x07, 0x0C, 0xCE, 0x66, 0x07, + 0x03, 0x83, 0x81, 0xC0, 0xE0, 0x70, 0xBC, 0x87, 0x80, 0x00, 0x08, 0x03, + 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x70, 0x01, 0xC0, 0x77, 0x03, 0x3C, 0x18, + 0xE0, 0xE3, 0x87, 0x0E, 0x1C, 0x70, 0x71, 0xC3, 0x87, 0x0E, 0x3C, 0x38, + 0xE8, 0xE5, 0xA1, 0xE7, 0x00, 0x07, 0x0C, 0xCE, 0x66, 0x37, 0x33, 0xBB, + 0xB1, 0xE0, 0xE0, 0x70, 0xB8, 0x87, 0x80, 0x00, 0x38, 0x01, 0xB0, 0x0C, + 0xC0, 0x30, 0x01, 0xC0, 0x07, 0x00, 0x7E, 0x00, 0xE0, 0x03, 0x80, 0x0E, + 0x00, 0x30, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, 0x70, 0x03, 0x80, 0x0E, + 0x00, 0x38, 0x00, 0xC0, 0x33, 0x00, 0xD8, 0x01, 0xC0, 0x00, 0x03, 0x80, + 0x73, 0xC7, 0x1C, 0x38, 0xE1, 0xCF, 0x06, 0x70, 0x1E, 0x01, 0x00, 0x1C, + 0x00, 0xF8, 0x07, 0xF0, 0xC7, 0x8C, 0x0C, 0x60, 0x63, 0x86, 0x07, 0xE0, + 0x01, 0x00, 0xF8, 0x01, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x31, 0xC3, + 0xBE, 0x1E, 0x70, 0xE3, 0x8F, 0x38, 0x71, 0xC3, 0x8E, 0x1C, 0xE1, 0xC7, + 0x0E, 0x3A, 0x71, 0xD3, 0x0F, 0x00, 0x1C, 0x71, 0xC0, 0x00, 0x6F, 0x8E, + 0x31, 0xC7, 0x18, 0x63, 0x8E, 0xBC, 0xE0, 0x00, 0xE0, 0x1C, 0x03, 0x80, + 0x00, 0x00, 0x0F, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x70, 0x0E, 0x01, 0xC0, + 0x38, 0x0E, 0x01, 0xC0, 0x38, 0x06, 0x01, 0xC3, 0x38, 0x6E, 0x07, 0x80, + 0x01, 0x00, 0xF8, 0x01, 0xC0, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x33, 0xE3, + 0x8C, 0x1C, 0xC0, 0xE4, 0x06, 0x40, 0x7E, 0x03, 0xF0, 0x1D, 0x81, 0xCE, + 0x0E, 0x72, 0x71, 0xA3, 0x8E, 0x00, 0x06, 0x7C, 0x70, 0xE1, 0xC3, 0x0E, + 0x1C, 0x38, 0x61, 0xC3, 0x87, 0x0C, 0x38, 0x72, 0xE9, 0xE0, 0x3C, 0x73, + 0xC7, 0x7D, 0x71, 0xE7, 0x9C, 0xF1, 0xCE, 0x3C, 0xF3, 0x8E, 0x39, 0xC3, + 0x8E, 0x71, 0xC3, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xD7, 0x1C, 0x7B, 0x8E, + 0x1C, 0x3C, 0xF1, 0xD7, 0x1E, 0x73, 0xCE, 0x3C, 0xE3, 0x8E, 0x39, 0xC7, + 0x9C, 0x71, 0xC7, 0x1D, 0x71, 0xEE, 0x1C, 0x0F, 0x06, 0x63, 0x9D, 0xC7, + 0x71, 0xF8, 0x7E, 0x3F, 0x8E, 0xE3, 0xB9, 0xC6, 0x60, 0xF0, 0x0F, 0x38, + 0x1F, 0x70, 0x71, 0xC1, 0xC7, 0x0E, 0x1C, 0x38, 0xF0, 0xE3, 0x83, 0x8E, + 0x1C, 0x70, 0x71, 0xC1, 0xCE, 0x07, 0xE0, 0x38, 0x00, 0xE0, 0x03, 0x80, + 0x3F, 0x00, 0x07, 0x70, 0xCE, 0x18, 0xE3, 0x8E, 0x70, 0xE7, 0x1C, 0xF1, + 0xCE, 0x1C, 0xE3, 0x8E, 0x38, 0xE7, 0x87, 0xB0, 0x07, 0x00, 0x70, 0x0F, + 0x03, 0xF8, 0x0D, 0xDF, 0x71, 0xAC, 0xF0, 0x38, 0x0E, 0x03, 0x81, 0xC0, + 0x70, 0x1C, 0x0E, 0x00, 0x1D, 0x99, 0x8C, 0x46, 0x23, 0x80, 0xE0, 0x70, + 0x1C, 0x06, 0x23, 0x19, 0x17, 0x00, 0x0C, 0x10, 0xE3, 0xF3, 0x86, 0x1C, + 0x38, 0x71, 0xC3, 0x87, 0x0E, 0x9E, 0x38, 0x00, 0xF8, 0xE3, 0x8E, 0x38, + 0xC3, 0x9C, 0x71, 0xC7, 0x18, 0x71, 0x87, 0x38, 0xE3, 0x8E, 0xFA, 0xF3, + 0xAE, 0x3C, 0xF0, 0xDC, 0x33, 0x0C, 0xC2, 0x31, 0x8C, 0xC3, 0x60, 0xF0, + 0x38, 0x0C, 0x02, 0x00, 0xE0, 0x86, 0xE3, 0x0C, 0xC6, 0x19, 0x9C, 0x23, + 0x78, 0xC7, 0xF9, 0x0E, 0x74, 0x1C, 0xF0, 0x31, 0xC0, 0x43, 0x00, 0x84, + 0x00, 0x0E, 0x31, 0xF3, 0x83, 0xA0, 0x0E, 0x00, 0x70, 0x03, 0x80, 0x1C, + 0x00, 0xE0, 0x0B, 0x02, 0x5D, 0x3C, 0xF1, 0xC3, 0x00, 0x04, 0x67, 0x8C, + 0x79, 0x87, 0x10, 0xE2, 0x1C, 0x81, 0x90, 0x3A, 0x07, 0x80, 0xF0, 0x1C, + 0x03, 0x00, 0x40, 0x08, 0x32, 0x07, 0x80, 0x3F, 0xCF, 0xE6, 0x30, 0x08, + 0x04, 0x02, 0x01, 0x00, 0xC0, 0x30, 0x1E, 0x0F, 0x98, 0x76, 0x07, 0x00, + 0x01, 0xE0, 0x70, 0x1C, 0x03, 0x80, 0x60, 0x1C, 0x03, 0x80, 0x60, 0x0C, + 0x03, 0x80, 0xF0, 0x3C, 0x07, 0x00, 0x40, 0x0C, 0x01, 0x80, 0x70, 0x0E, + 0x01, 0xC0, 0x30, 0x03, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0x07, 0x00, 0xE0, + 0x18, 0x06, 0x01, 0x80, 0xE0, 0x38, 0x0C, 0x03, 0x00, 0xC0, 0x10, 0x1F, + 0x07, 0x03, 0x80, 0xE0, 0x30, 0x0C, 0x07, 0x01, 0x80, 0xE0, 0xE0, 0x00, + 0x38, 0x0F, 0xCD, 0x1F, 0x80, 0xE0 }; + +const GFXglyph FreeSerifBoldItalic12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 6, 0, 1 }, // 0x20 ' ' + { 0, 8, 17, 9, 2, -15 }, // 0x21 '!' + { 17, 9, 7, 13, 4, -15 }, // 0x22 '"' + { 25, 14, 16, 12, -1, -15 }, // 0x23 '#' + { 53, 12, 20, 12, 0, -17 }, // 0x24 '$' + { 83, 18, 18, 20, 1, -16 }, // 0x25 '%' + { 124, 16, 17, 19, 0, -15 }, // 0x26 '&' + { 158, 3, 7, 7, 3, -15 }, // 0x27 ''' + { 161, 7, 21, 8, 1, -15 }, // 0x28 '(' + { 180, 7, 21, 8, -1, -15 }, // 0x29 ')' + { 199, 10, 10, 12, 1, -15 }, // 0x2A '*' + { 212, 12, 12, 14, 1, -11 }, // 0x2B '+' + { 230, 5, 8, 6, -2, -3 }, // 0x2C ',' + { 235, 6, 3, 8, 0, -6 }, // 0x2D '-' + { 238, 4, 4, 6, 0, -2 }, // 0x2E '.' + { 240, 10, 16, 8, 0, -15 }, // 0x2F '/' + { 260, 11, 17, 12, 0, -15 }, // 0x30 '0' + { 284, 10, 17, 12, 0, -15 }, // 0x31 '1' + { 306, 11, 17, 12, 0, -15 }, // 0x32 '2' + { 330, 11, 17, 12, 0, -15 }, // 0x33 '3' + { 354, 13, 16, 12, 0, -15 }, // 0x34 '4' + { 380, 12, 17, 12, 0, -15 }, // 0x35 '5' + { 406, 11, 17, 12, 1, -15 }, // 0x36 '6' + { 430, 11, 16, 12, 2, -15 }, // 0x37 '7' + { 452, 11, 17, 12, 0, -15 }, // 0x38 '8' + { 476, 11, 17, 12, 0, -15 }, // 0x39 '9' + { 500, 7, 12, 6, 0, -10 }, // 0x3A ':' + { 511, 8, 15, 6, -1, -10 }, // 0x3B ';' + { 526, 12, 13, 14, 1, -12 }, // 0x3C '<' + { 546, 12, 6, 14, 2, -8 }, // 0x3D '=' + { 555, 13, 13, 14, 1, -12 }, // 0x3E '>' + { 577, 9, 17, 12, 2, -15 }, // 0x3F '?' + { 597, 17, 16, 20, 1, -15 }, // 0x40 '@' + { 631, 16, 17, 17, 0, -15 }, // 0x41 'A' + { 665, 16, 17, 15, 0, -15 }, // 0x42 'B' + { 699, 15, 17, 15, 1, -15 }, // 0x43 'C' + { 731, 18, 17, 17, 0, -15 }, // 0x44 'D' + { 770, 17, 17, 15, 0, -15 }, // 0x45 'E' + { 807, 16, 17, 15, 0, -15 }, // 0x46 'F' + { 841, 17, 17, 17, 1, -15 }, // 0x47 'G' + { 878, 20, 17, 18, 0, -15 }, // 0x48 'H' + { 921, 10, 17, 9, 0, -15 }, // 0x49 'I' + { 943, 14, 18, 12, 0, -15 }, // 0x4A 'J' + { 975, 17, 17, 16, 0, -15 }, // 0x4B 'K' + { 1012, 15, 17, 15, 0, -15 }, // 0x4C 'L' + { 1044, 23, 17, 21, 0, -15 }, // 0x4D 'M' + { 1093, 19, 17, 17, 0, -15 }, // 0x4E 'N' + { 1134, 16, 17, 16, 1, -15 }, // 0x4F 'O' + { 1168, 16, 17, 14, 0, -15 }, // 0x50 'P' + { 1202, 16, 21, 16, 1, -15 }, // 0x51 'Q' + { 1244, 16, 17, 16, 0, -15 }, // 0x52 'R' + { 1278, 12, 17, 12, 0, -15 }, // 0x53 'S' + { 1304, 15, 17, 14, 2, -15 }, // 0x54 'T' + { 1336, 16, 17, 17, 3, -15 }, // 0x55 'U' + { 1370, 16, 16, 17, 3, -15 }, // 0x56 'V' + { 1402, 21, 16, 22, 3, -15 }, // 0x57 'W' + { 1444, 17, 17, 17, 0, -15 }, // 0x58 'X' + { 1481, 14, 17, 15, 3, -15 }, // 0x59 'Y' + { 1511, 15, 17, 13, 0, -15 }, // 0x5A 'Z' + { 1543, 10, 20, 8, -1, -15 }, // 0x5B '[' + { 1568, 6, 16, 10, 3, -15 }, // 0x5C '\' + { 1580, 9, 20, 8, -1, -15 }, // 0x5D ']' + { 1603, 10, 9, 14, 2, -15 }, // 0x5E '^' + { 1615, 12, 1, 12, 0, 4 }, // 0x5F '_' + { 1617, 5, 4, 8, 2, -15 }, // 0x60 '`' + { 1620, 12, 12, 12, 0, -10 }, // 0x61 'a' + { 1638, 11, 18, 12, 1, -16 }, // 0x62 'b' + { 1663, 9, 12, 10, 1, -10 }, // 0x63 'c' + { 1677, 14, 18, 12, 0, -16 }, // 0x64 'd' + { 1709, 9, 12, 10, 1, -10 }, // 0x65 'e' + { 1723, 14, 22, 12, -2, -16 }, // 0x66 'f' + { 1762, 13, 16, 12, -1, -10 }, // 0x67 'g' + { 1788, 13, 18, 13, 0, -16 }, // 0x68 'h' + { 1818, 6, 17, 7, 1, -15 }, // 0x69 'i' + { 1831, 11, 21, 8, -2, -15 }, // 0x6A 'j' + { 1860, 13, 18, 12, 0, -16 }, // 0x6B 'k' + { 1890, 7, 18, 7, 1, -16 }, // 0x6C 'l' + { 1906, 18, 12, 18, 0, -10 }, // 0x6D 'm' + { 1933, 12, 12, 13, 0, -10 }, // 0x6E 'n' + { 1951, 10, 12, 11, 1, -10 }, // 0x6F 'o' + { 1966, 14, 16, 12, -2, -10 }, // 0x70 'p' + { 1994, 12, 16, 12, 0, -10 }, // 0x71 'q' + { 2018, 10, 11, 10, 0, -10 }, // 0x72 'r' + { 2032, 9, 12, 9, 0, -10 }, // 0x73 's' + { 2046, 7, 15, 7, 1, -13 }, // 0x74 't' + { 2060, 12, 12, 13, 1, -10 }, // 0x75 'u' + { 2078, 10, 11, 11, 1, -10 }, // 0x76 'v' + { 2092, 15, 11, 16, 1, -10 }, // 0x77 'w' + { 2113, 13, 12, 11, -1, -10 }, // 0x78 'x' + { 2133, 11, 16, 10, -1, -10 }, // 0x79 'y' + { 2155, 10, 13, 10, 0, -10 }, // 0x7A 'z' + { 2172, 11, 21, 8, 0, -16 }, // 0x7B '{' + { 2201, 2, 16, 6, 3, -15 }, // 0x7C '|' + { 2205, 10, 21, 8, -3, -16 }, // 0x7D '}' + { 2232, 11, 4, 14, 1, -7 } }; // 0x7E '~' + +const GFXfont FreeSerifBoldItalic12pt7b PROGMEM = { + (uint8_t *)FreeSerifBoldItalic12pt7bBitmaps, + (GFXglyph *)FreeSerifBoldItalic12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 2910 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic18pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic18pt7b.h new file mode 100644 index 0000000..e24eea6 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic18pt7b.h @@ -0,0 +1,500 @@ +const uint8_t FreeSerifBoldItalic18pt7bBitmaps[] PROGMEM = { + 0x01, 0xC0, 0x7C, 0x0F, 0x81, 0xF0, 0x3E, 0x07, 0x80, 0xF0, 0x3C, 0x07, + 0x80, 0xE0, 0x1C, 0x03, 0x00, 0x60, 0x0C, 0x03, 0x00, 0x60, 0x08, 0x00, + 0x00, 0x00, 0x00, 0x07, 0x81, 0xF8, 0x3F, 0x07, 0xE0, 0x78, 0x00, 0x38, + 0x1D, 0xE0, 0xF7, 0x83, 0xDC, 0x0E, 0x70, 0x39, 0xC0, 0xE6, 0x03, 0x18, + 0x0C, 0x40, 0x23, 0x01, 0x80, 0x00, 0x38, 0x60, 0x07, 0x0E, 0x00, 0x70, + 0xC0, 0x06, 0x1C, 0x00, 0xE1, 0xC0, 0x0E, 0x38, 0x01, 0xC3, 0x81, 0xFF, + 0xFF, 0x1F, 0xFF, 0xE1, 0xFF, 0xFE, 0x03, 0x86, 0x00, 0x30, 0xE0, 0x07, + 0x0E, 0x00, 0x71, 0xC0, 0x0E, 0x1C, 0x0F, 0xFF, 0xF8, 0xFF, 0xFF, 0x0F, + 0xFF, 0xF0, 0x1C, 0x30, 0x01, 0x87, 0x00, 0x38, 0x70, 0x03, 0x0E, 0x00, + 0x70, 0xE0, 0x07, 0x0C, 0x00, 0xE1, 0xC0, 0x00, 0x00, 0x08, 0x00, 0x0C, + 0x00, 0x7E, 0x00, 0xFF, 0xC0, 0xF3, 0x70, 0x71, 0x9C, 0x70, 0xC6, 0x38, + 0x43, 0x1C, 0x61, 0x0F, 0x30, 0x87, 0xD8, 0x03, 0xF8, 0x00, 0xFE, 0x00, + 0x3F, 0x80, 0x0F, 0xE0, 0x03, 0xF8, 0x01, 0xFC, 0x00, 0xDF, 0x10, 0x47, + 0x88, 0x63, 0xCC, 0x31, 0xE6, 0x10, 0xF3, 0x98, 0x71, 0xCC, 0x78, 0x7E, + 0x78, 0x07, 0xF8, 0x03, 0xF0, 0x01, 0x80, 0x00, 0xC0, 0x00, 0x03, 0xC0, + 0x18, 0x01, 0xFE, 0x0F, 0x00, 0x7C, 0xFF, 0xC0, 0x1F, 0x0F, 0x98, 0x07, + 0xC1, 0x06, 0x00, 0xF8, 0x21, 0x80, 0x3E, 0x04, 0x30, 0x07, 0xC1, 0x8C, + 0x00, 0xF0, 0x21, 0x80, 0x1E, 0x0C, 0x60, 0x03, 0xC1, 0x0C, 0x00, 0x78, + 0xC3, 0x03, 0xC7, 0xF8, 0x61, 0xFC, 0x7C, 0x18, 0x7C, 0xC0, 0x06, 0x1F, + 0x08, 0x00, 0xC7, 0xC1, 0x00, 0x30, 0xF0, 0x20, 0x06, 0x3E, 0x04, 0x01, + 0x87, 0xC1, 0x00, 0x30, 0xF0, 0x20, 0x0C, 0x1E, 0x0C, 0x03, 0x03, 0xC1, + 0x00, 0x60, 0x3C, 0xC0, 0x18, 0x07, 0xF8, 0x03, 0x00, 0x7C, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x1F, 0xF0, 0x00, 0x1E, 0x38, 0x00, 0x0E, 0x0E, 0x00, + 0x0F, 0x07, 0x00, 0x07, 0x83, 0x80, 0x03, 0xC3, 0x80, 0x01, 0xE3, 0x80, + 0x00, 0xF7, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x7F, 0x0F, + 0xF0, 0xE7, 0x81, 0xE0, 0xE3, 0xE0, 0xE0, 0xE1, 0xF0, 0x60, 0xE0, 0x7C, + 0x60, 0xF0, 0x3E, 0x20, 0x78, 0x1F, 0xB0, 0x3C, 0x07, 0xF0, 0x1F, 0x03, + 0xF0, 0x0F, 0x80, 0xFC, 0x03, 0xF0, 0x7F, 0x8D, 0xFF, 0xEF, 0xFC, 0x7F, + 0xE3, 0xFC, 0x0F, 0xC0, 0x78, 0x00, 0x3B, 0xDE, 0xE7, 0x39, 0x8C, 0x46, + 0x00, 0x00, 0x60, 0x18, 0x06, 0x01, 0x80, 0x60, 0x1C, 0x07, 0x01, 0xE0, + 0x38, 0x0F, 0x01, 0xC0, 0x38, 0x0F, 0x01, 0xE0, 0x38, 0x07, 0x00, 0xE0, + 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x00, 0xC0, 0x18, 0x03, 0x00, 0x60, 0x06, + 0x00, 0xC0, 0x08, 0x00, 0x80, 0x10, 0x00, 0x06, 0x00, 0x40, 0x04, 0x00, + 0x80, 0x18, 0x01, 0x00, 0x30, 0x06, 0x00, 0xC0, 0x1C, 0x03, 0x80, 0x70, + 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x01, 0xE0, 0x3C, 0x07, 0x00, 0xE0, 0x3C, + 0x07, 0x00, 0xE0, 0x38, 0x06, 0x01, 0xC0, 0x70, 0x18, 0x06, 0x01, 0x80, + 0x00, 0x07, 0x00, 0x38, 0x01, 0xC1, 0x8E, 0x3E, 0x23, 0xF9, 0x3F, 0xEB, + 0xE0, 0xE0, 0xFF, 0xF7, 0x93, 0xF8, 0x9F, 0x8E, 0x60, 0x70, 0x03, 0x80, + 0x08, 0x00, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, + 0x00, 0x0E, 0x00, 0x07, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, + 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x03, 0x80, + 0x01, 0xC0, 0x00, 0x1C, 0x7C, 0xF9, 0xF1, 0xE1, 0xC3, 0x0C, 0x30, 0xC2, + 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0xE0, 0x7B, 0xFF, 0xFF, 0x78, 0x00, 0x1C, + 0x00, 0xE0, 0x03, 0x80, 0x1E, 0x00, 0x70, 0x01, 0xC0, 0x0E, 0x00, 0x38, + 0x01, 0xC0, 0x07, 0x00, 0x38, 0x00, 0xE0, 0x07, 0x80, 0x1C, 0x00, 0x70, + 0x03, 0x80, 0x0E, 0x00, 0x70, 0x01, 0xC0, 0x0E, 0x00, 0x38, 0x01, 0xC0, + 0x07, 0x00, 0x1C, 0x00, 0xE0, 0x00, 0x00, 0xF0, 0x07, 0x30, 0x1C, 0x30, + 0x78, 0x60, 0xE0, 0xE3, 0xC1, 0xCF, 0x83, 0x9E, 0x0F, 0x3C, 0x1E, 0xF8, + 0x3D, 0xE0, 0x7B, 0xC1, 0xFF, 0x83, 0xFF, 0x07, 0xBC, 0x0F, 0x78, 0x3E, + 0xF0, 0x7D, 0xE0, 0xF3, 0x81, 0xE7, 0x07, 0x8E, 0x0F, 0x0C, 0x3C, 0x18, + 0x70, 0x19, 0xC0, 0x1E, 0x00, 0x00, 0x06, 0x01, 0xF8, 0x1F, 0xF0, 0x03, + 0xE0, 0x07, 0x80, 0x1F, 0x00, 0x3E, 0x00, 0x7C, 0x00, 0xF0, 0x03, 0xE0, + 0x07, 0xC0, 0x0F, 0x80, 0x1E, 0x00, 0x7C, 0x00, 0xF8, 0x01, 0xE0, 0x07, + 0xC0, 0x0F, 0x80, 0x1F, 0x00, 0x3C, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, + 0x0F, 0xC0, 0xFF, 0xF0, 0x00, 0xF8, 0x01, 0xFC, 0x03, 0xFE, 0x06, 0x3F, + 0x08, 0x1F, 0x18, 0x0F, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0E, + 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x30, 0x00, 0x70, 0x00, 0xC0, + 0x01, 0x80, 0x03, 0x00, 0x06, 0x02, 0x0C, 0x06, 0x08, 0x0C, 0x1F, 0xFC, + 0x3F, 0xFC, 0x7F, 0xF8, 0xFF, 0xF8, 0x00, 0xF0, 0x07, 0xF8, 0x1F, 0xF0, + 0x61, 0xF0, 0x81, 0xE0, 0x03, 0xC0, 0x07, 0x80, 0x0E, 0x00, 0x3C, 0x00, + 0xE0, 0x07, 0xC0, 0x3F, 0xC0, 0x1F, 0x80, 0x0F, 0x80, 0x1F, 0x00, 0x1E, + 0x00, 0x3C, 0x00, 0x78, 0x00, 0xF0, 0x01, 0xC0, 0x07, 0x9C, 0x0E, 0x3C, + 0x38, 0x7F, 0xE0, 0x7E, 0x00, 0x00, 0x00, 0xC0, 0x00, 0x70, 0x00, 0x3C, + 0x00, 0x1E, 0x00, 0x0F, 0x80, 0x07, 0xE0, 0x02, 0xF8, 0x01, 0x3C, 0x00, + 0x9F, 0x00, 0x47, 0xC0, 0x31, 0xE0, 0x18, 0x78, 0x0C, 0x3E, 0x06, 0x0F, + 0x83, 0x03, 0xC1, 0x80, 0xF0, 0x7F, 0xFF, 0x1F, 0xFF, 0xCF, 0xFF, 0xF0, + 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x07, 0xC0, 0x01, + 0xFF, 0x00, 0xFF, 0x80, 0xFF, 0xC0, 0x7F, 0xE0, 0x60, 0x00, 0x30, 0x00, + 0x10, 0x00, 0x1F, 0x00, 0x0F, 0xE0, 0x0F, 0xF8, 0x07, 0xFE, 0x00, 0x3F, + 0x00, 0x07, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x38, 0x00, 0x1C, 0x00, + 0x0E, 0x00, 0x06, 0x00, 0x03, 0x00, 0x03, 0x87, 0x83, 0x83, 0xE3, 0x81, + 0xFF, 0x80, 0x3F, 0x00, 0x00, 0x00, 0x03, 0x80, 0x0F, 0x80, 0x1F, 0x00, + 0x3E, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x1F, 0x00, + 0x1F, 0xF0, 0x1F, 0xFE, 0x0F, 0xCF, 0x07, 0xC3, 0xC7, 0xE1, 0xE3, 0xE0, + 0xF1, 0xF0, 0x78, 0xF8, 0x3C, 0x78, 0x3E, 0x3C, 0x1F, 0x1E, 0x0F, 0x0F, + 0x0F, 0x83, 0x87, 0x81, 0xE7, 0x80, 0x7F, 0x80, 0x0F, 0x80, 0x00, 0x3F, + 0xFF, 0x3F, 0xFE, 0x3F, 0xFE, 0x7F, 0xFC, 0x60, 0x1C, 0x80, 0x38, 0x80, + 0x30, 0x00, 0x70, 0x00, 0x60, 0x00, 0xE0, 0x01, 0xC0, 0x01, 0xC0, 0x03, + 0x80, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x1C, + 0x00, 0x38, 0x00, 0x38, 0x00, 0x70, 0x00, 0xF0, 0x00, 0xE0, 0x00, 0x00, + 0xF8, 0x00, 0xFF, 0x00, 0xE1, 0xC0, 0xE0, 0xF0, 0xF0, 0x38, 0x78, 0x1C, + 0x3C, 0x0E, 0x1F, 0x07, 0x0F, 0x87, 0x07, 0xE7, 0x01, 0xFF, 0x00, 0x7E, + 0x00, 0x1F, 0x80, 0x3F, 0xE0, 0x73, 0xF0, 0x70, 0xFC, 0x70, 0x3E, 0x70, + 0x0F, 0x38, 0x07, 0x9C, 0x03, 0xCE, 0x01, 0xE7, 0x00, 0xE1, 0xC0, 0xE0, + 0x70, 0xE0, 0x0F, 0xC0, 0x00, 0x00, 0xF8, 0x01, 0xFF, 0x01, 0xF3, 0xC1, + 0xF0, 0xE1, 0xF0, 0x70, 0xF0, 0x3C, 0xF8, 0x1E, 0x7C, 0x0F, 0x3C, 0x0F, + 0x9E, 0x07, 0xCF, 0x03, 0xE7, 0x83, 0xF3, 0xC1, 0xF0, 0xF1, 0xF8, 0x3F, + 0xF8, 0x0F, 0xFC, 0x00, 0x7C, 0x00, 0x7C, 0x00, 0x7E, 0x00, 0x3E, 0x00, + 0x3C, 0x00, 0x7C, 0x00, 0x7C, 0x00, 0xF0, 0x00, 0xC0, 0x00, 0x00, 0x07, + 0x83, 0xF0, 0xFC, 0x3F, 0x07, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x78, 0x3F, 0x0F, 0xC3, 0xF0, 0x78, 0x00, 0x03, 0xC0, 0xFC, + 0x1F, 0x83, 0xF0, 0x3C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x0C, 0x03, 0xC0, 0x7C, 0x0F, 0x80, 0xF0, 0x0E, 0x01, 0x80, 0x30, 0x0C, + 0x03, 0x01, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0x7C, 0x00, + 0x7F, 0x00, 0x7F, 0x00, 0xFF, 0x00, 0xFF, 0x00, 0xFE, 0x00, 0xFE, 0x00, + 0x3E, 0x00, 0x0F, 0xC0, 0x01, 0xFC, 0x00, 0x1F, 0xE0, 0x01, 0xFE, 0x00, + 0x0F, 0xE0, 0x00, 0xFF, 0x00, 0x0F, 0xC0, 0x00, 0xF0, 0x00, 0x04, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, + 0x38, 0x00, 0x0F, 0x80, 0x03, 0xF8, 0x00, 0x3F, 0x80, 0x03, 0xFC, 0x00, + 0x3F, 0xC0, 0x01, 0xFC, 0x00, 0x1F, 0xC0, 0x01, 0xF0, 0x00, 0xFC, 0x00, + 0xFE, 0x01, 0xFE, 0x01, 0xFE, 0x01, 0xFC, 0x03, 0xFC, 0x00, 0xFC, 0x00, + 0x3C, 0x00, 0x08, 0x00, 0x00, 0x07, 0xC0, 0xFF, 0x0E, 0x3C, 0x70, 0xF3, + 0xC7, 0x8C, 0x3C, 0x01, 0xE0, 0x1F, 0x00, 0xF0, 0x07, 0x80, 0x78, 0x07, + 0x80, 0x30, 0x03, 0x00, 0x10, 0x01, 0x80, 0x08, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x07, 0x80, 0x7E, 0x03, 0xF0, 0x1F, 0x80, 0x78, 0x00, 0x00, 0x3F, + 0x80, 0x00, 0xFF, 0xF8, 0x01, 0xF0, 0x1E, 0x01, 0xE0, 0x03, 0x81, 0xC0, + 0x00, 0xE1, 0xC0, 0x18, 0x38, 0xE0, 0x3F, 0xCC, 0xE0, 0x3C, 0xE7, 0x70, + 0x3C, 0x71, 0xF0, 0x1C, 0x30, 0xF8, 0x1E, 0x38, 0x7C, 0x0E, 0x1C, 0x3E, + 0x0F, 0x0E, 0x1F, 0x07, 0x0E, 0x0F, 0x83, 0x87, 0x0D, 0xC1, 0xC7, 0x86, + 0x70, 0xE5, 0xC6, 0x38, 0x7C, 0xFE, 0x1C, 0x1C, 0x3E, 0x07, 0x00, 0x00, + 0x01, 0xC0, 0x00, 0x00, 0x78, 0x00, 0x40, 0x1F, 0x00, 0xE0, 0x03, 0xFF, + 0xE0, 0x00, 0x3F, 0x80, 0x00, 0x00, 0x00, 0x80, 0x00, 0x03, 0x00, 0x00, + 0x0E, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x03, + 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x17, 0xC0, 0x00, 0x67, 0x80, 0x00, 0x8F, + 0x00, 0x03, 0x1F, 0x00, 0x0C, 0x3E, 0x00, 0x10, 0x7C, 0x00, 0x60, 0xF8, + 0x00, 0x81, 0xF0, 0x03, 0xFF, 0xE0, 0x0F, 0xFF, 0xE0, 0x18, 0x07, 0xC0, + 0x60, 0x0F, 0x81, 0xC0, 0x1F, 0x03, 0x00, 0x3E, 0x0E, 0x00, 0x7C, 0x3C, + 0x00, 0xFC, 0xFE, 0x0F, 0xFE, 0x07, 0xFF, 0xE0, 0x01, 0xFF, 0xFC, 0x01, + 0xF8, 0x7E, 0x01, 0xF8, 0x3F, 0x01, 0xF0, 0x3F, 0x01, 0xF0, 0x3F, 0x01, + 0xF0, 0x3F, 0x03, 0xE0, 0x3F, 0x03, 0xE0, 0x7E, 0x03, 0xE0, 0xFC, 0x03, + 0xE3, 0xF0, 0x07, 0xFF, 0x80, 0x07, 0xC3, 0xE0, 0x07, 0xC1, 0xF8, 0x0F, + 0xC0, 0xF8, 0x0F, 0x80, 0xFC, 0x0F, 0x80, 0xFC, 0x0F, 0x80, 0xFC, 0x1F, + 0x80, 0xFC, 0x1F, 0x01, 0xFC, 0x1F, 0x01, 0xF8, 0x1F, 0x03, 0xF0, 0x3F, + 0x0F, 0xE0, 0x7F, 0xFF, 0xC0, 0xFF, 0xFE, 0x00, 0x00, 0x1F, 0x82, 0x01, + 0xFF, 0xE8, 0x07, 0xE0, 0xF0, 0x3F, 0x80, 0xE0, 0xFE, 0x00, 0xC1, 0xF8, + 0x01, 0x87, 0xE0, 0x02, 0x1F, 0x80, 0x04, 0x3F, 0x00, 0x00, 0xFC, 0x00, + 0x01, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0x80, 0x00, + 0x3F, 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFC, 0x00, 0x01, 0xF8, 0x00, 0x03, + 0xF0, 0x00, 0x03, 0xE0, 0x01, 0x07, 0xE0, 0x06, 0x07, 0xE0, 0x18, 0x07, + 0xE0, 0xE0, 0x07, 0xFF, 0x00, 0x01, 0xF8, 0x00, 0x07, 0xFF, 0xE0, 0x01, + 0xFF, 0xFE, 0x00, 0x1F, 0x87, 0xE0, 0x07, 0xE0, 0x7C, 0x01, 0xF0, 0x1F, + 0x80, 0x7C, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x0F, 0x80, 0x3F, 0x03, 0xE0, + 0x0F, 0xC0, 0xF8, 0x03, 0xF0, 0x3E, 0x00, 0xFC, 0x1F, 0x00, 0x3F, 0x07, + 0xC0, 0x0F, 0xC1, 0xF0, 0x07, 0xF0, 0xFC, 0x01, 0xF8, 0x3E, 0x00, 0x7E, + 0x0F, 0x80, 0x3F, 0x83, 0xE0, 0x0F, 0xC1, 0xF8, 0x07, 0xF0, 0x7C, 0x01, + 0xF8, 0x1F, 0x00, 0xFC, 0x07, 0xC0, 0x7E, 0x03, 0xF0, 0x7E, 0x01, 0xFF, + 0xFF, 0x00, 0xFF, 0xFE, 0x00, 0x00, 0x07, 0xFF, 0xFE, 0x03, 0xFF, 0xFC, + 0x07, 0xE0, 0x78, 0x0F, 0xC0, 0x60, 0x1F, 0x00, 0x40, 0x3E, 0x00, 0x80, + 0x7C, 0x01, 0x01, 0xF8, 0x10, 0x03, 0xE0, 0x60, 0x07, 0xC3, 0x80, 0x0F, + 0xFF, 0x00, 0x3F, 0xFE, 0x00, 0x7C, 0x38, 0x00, 0xF8, 0x30, 0x03, 0xF0, + 0x60, 0x07, 0xC0, 0x80, 0x0F, 0x81, 0x00, 0x1F, 0x00, 0x10, 0x7E, 0x00, + 0x60, 0xF8, 0x01, 0xC1, 0xF0, 0x07, 0x03, 0xE0, 0x1E, 0x0F, 0xC0, 0xFC, + 0x3F, 0xFF, 0xF8, 0xFF, 0xFF, 0xE0, 0x07, 0xFF, 0xFE, 0x03, 0xFF, 0xFC, + 0x07, 0xE0, 0x78, 0x0F, 0xC0, 0x60, 0x1F, 0x00, 0x40, 0x3E, 0x00, 0x80, + 0x7C, 0x01, 0x01, 0xF8, 0x20, 0x03, 0xE0, 0xC0, 0x07, 0xC3, 0x80, 0x0F, + 0xFE, 0x00, 0x3F, 0xFC, 0x00, 0x7C, 0x38, 0x00, 0xF8, 0x30, 0x03, 0xF0, + 0x60, 0x07, 0xC0, 0x80, 0x0F, 0x81, 0x00, 0x1F, 0x00, 0x00, 0x7E, 0x00, + 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0xC0, 0x00, + 0x3F, 0x80, 0x00, 0xFF, 0xC0, 0x00, 0x00, 0x1F, 0xC2, 0x00, 0xFF, 0xF6, + 0x01, 0xF8, 0x3C, 0x03, 0xE0, 0x1C, 0x0F, 0xC0, 0x0C, 0x0F, 0xC0, 0x08, + 0x1F, 0x80, 0x08, 0x3F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x7E, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFE, 0x00, 0x00, 0xFC, 0x03, 0xFF, + 0xFC, 0x00, 0xFC, 0xFC, 0x00, 0xF8, 0xFC, 0x00, 0xF8, 0xFC, 0x00, 0xF8, + 0xFC, 0x00, 0xF0, 0x7C, 0x01, 0xF0, 0x7E, 0x01, 0xF0, 0x3E, 0x01, 0xF0, + 0x1F, 0x83, 0xE0, 0x0F, 0xFF, 0x80, 0x01, 0xFC, 0x00, 0x07, 0xFF, 0x3F, + 0xF8, 0x0F, 0xE0, 0x7F, 0x00, 0x7E, 0x01, 0xF8, 0x03, 0xF0, 0x0F, 0x80, + 0x1F, 0x00, 0x7C, 0x00, 0xF8, 0x07, 0xE0, 0x07, 0xC0, 0x3E, 0x00, 0x7E, + 0x01, 0xF0, 0x03, 0xE0, 0x0F, 0x80, 0x1F, 0x00, 0xF8, 0x00, 0xF8, 0x07, + 0xC0, 0x0F, 0xFF, 0xFE, 0x00, 0x7F, 0xFF, 0xF0, 0x03, 0xE0, 0x1F, 0x00, + 0x3F, 0x00, 0xF8, 0x01, 0xF0, 0x07, 0xC0, 0x0F, 0x80, 0x7E, 0x00, 0x7C, + 0x03, 0xE0, 0x07, 0xE0, 0x1F, 0x00, 0x3E, 0x00, 0xF8, 0x01, 0xF0, 0x0F, + 0xC0, 0x0F, 0x80, 0x7C, 0x00, 0xFC, 0x03, 0xE0, 0x0F, 0xE0, 0x3F, 0x80, + 0xFF, 0xC7, 0xFF, 0x00, 0x07, 0xFE, 0x03, 0xF8, 0x07, 0xE0, 0x0F, 0xC0, + 0x1F, 0x00, 0x3E, 0x00, 0x7C, 0x01, 0xF0, 0x03, 0xE0, 0x07, 0xC0, 0x0F, + 0x80, 0x3E, 0x00, 0x7C, 0x00, 0xF8, 0x03, 0xF0, 0x07, 0xC0, 0x0F, 0x80, + 0x1F, 0x00, 0x7C, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, 0x0F, 0xC0, 0x3F, + 0x80, 0xFF, 0xC0, 0x00, 0x3F, 0xF0, 0x01, 0xFE, 0x00, 0x0F, 0xC0, 0x00, + 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x1F, 0x80, 0x01, 0xF0, 0x00, + 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, + 0x07, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x0F, 0xC0, + 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x61, 0xF0, + 0x0F, 0x3F, 0x00, 0xE7, 0xE0, 0x07, 0xFC, 0x00, 0x3F, 0x00, 0x00, 0x07, + 0xFF, 0x3F, 0x80, 0xFE, 0x07, 0x80, 0x7E, 0x03, 0x00, 0x3F, 0x03, 0x00, + 0x1F, 0x03, 0x00, 0x0F, 0x83, 0x00, 0x07, 0xC3, 0x00, 0x07, 0xE3, 0x00, + 0x03, 0xE3, 0x00, 0x01, 0xF3, 0x00, 0x00, 0xFB, 0x80, 0x00, 0xFB, 0xC0, + 0x00, 0x7F, 0xE0, 0x00, 0x3E, 0xF8, 0x00, 0x3F, 0x7C, 0x00, 0x1F, 0x1F, + 0x00, 0x0F, 0x8F, 0x80, 0x07, 0xC7, 0xE0, 0x07, 0xE1, 0xF0, 0x03, 0xE0, + 0xFC, 0x01, 0xF0, 0x3E, 0x00, 0xF8, 0x1F, 0x00, 0xFC, 0x07, 0xC0, 0xFE, + 0x07, 0xF0, 0xFF, 0xCF, 0xFC, 0x00, 0x07, 0xFF, 0x00, 0x07, 0xF0, 0x00, + 0x1F, 0x80, 0x00, 0x7E, 0x00, 0x01, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x1F, + 0x00, 0x00, 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x3E, 0x00, + 0x01, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x1F, 0x00, 0x00, 0xFC, 0x00, 0x03, + 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x3E, 0x00, 0x11, 0xF0, 0x00, 0xC7, 0xC0, + 0x06, 0x1F, 0x00, 0x38, 0x7C, 0x01, 0xE3, 0xF0, 0x3F, 0x9F, 0xFF, 0xFC, + 0xFF, 0xFF, 0xF0, 0x07, 0xF8, 0x00, 0x7F, 0x80, 0xFC, 0x00, 0x3F, 0x80, + 0x3E, 0x00, 0x3F, 0x80, 0x1F, 0x00, 0x3F, 0x80, 0x1F, 0x80, 0x1F, 0xC0, + 0x0F, 0xE0, 0x1B, 0xE0, 0x07, 0xF0, 0x0D, 0xF0, 0x02, 0xF8, 0x0D, 0xF0, + 0x03, 0x7C, 0x0C, 0xF8, 0x01, 0xBE, 0x06, 0x7C, 0x00, 0xDF, 0x06, 0x7C, + 0x00, 0xCF, 0x83, 0x3E, 0x00, 0x67, 0xC3, 0x1F, 0x00, 0x31, 0xE3, 0x0F, + 0x80, 0x38, 0xF9, 0x8F, 0x80, 0x18, 0x7D, 0x87, 0xC0, 0x0C, 0x3F, 0x83, + 0xE0, 0x06, 0x1F, 0xC1, 0xF0, 0x06, 0x0F, 0xC1, 0xF0, 0x03, 0x07, 0xC0, + 0xF8, 0x01, 0x83, 0xE0, 0x7C, 0x01, 0xC0, 0xE0, 0x7E, 0x00, 0xE0, 0x70, + 0x3F, 0x00, 0xF8, 0x30, 0x3F, 0x80, 0xFF, 0x10, 0x7F, 0xF0, 0x00, 0x07, + 0xF0, 0x0F, 0xE0, 0x3E, 0x00, 0x78, 0x07, 0xE0, 0x06, 0x00, 0x7C, 0x00, + 0xC0, 0x1F, 0xC0, 0x10, 0x03, 0xF8, 0x06, 0x00, 0x6F, 0x80, 0xC0, 0x19, + 0xF0, 0x10, 0x03, 0x3F, 0x02, 0x00, 0x63, 0xE0, 0xC0, 0x0C, 0x7C, 0x18, + 0x03, 0x07, 0xC2, 0x00, 0x60, 0xF8, 0x40, 0x0C, 0x0F, 0x98, 0x03, 0x81, + 0xF3, 0x00, 0x60, 0x3F, 0x40, 0x0C, 0x03, 0xF8, 0x01, 0x80, 0x7F, 0x00, + 0x60, 0x07, 0xC0, 0x0C, 0x00, 0xF8, 0x01, 0x80, 0x0F, 0x00, 0x70, 0x01, + 0xE0, 0x0E, 0x00, 0x18, 0x03, 0xE0, 0x03, 0x00, 0x02, 0x00, 0x60, 0x00, + 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0xC0, 0x07, 0xC3, 0xE0, 0x1F, 0x03, 0xC0, + 0x7C, 0x03, 0xC1, 0xF0, 0x07, 0x87, 0xE0, 0x0F, 0x8F, 0x80, 0x1F, 0x3F, + 0x00, 0x3E, 0x7C, 0x00, 0x7D, 0xF8, 0x01, 0xFB, 0xE0, 0x03, 0xF7, 0xC0, + 0x07, 0xDF, 0x80, 0x1F, 0xBF, 0x00, 0x3F, 0x7C, 0x00, 0x7C, 0xF8, 0x01, + 0xF9, 0xF0, 0x03, 0xE3, 0xE0, 0x0F, 0xC7, 0xC0, 0x1F, 0x07, 0x80, 0x7C, + 0x0F, 0x81, 0xF0, 0x0F, 0x87, 0xC0, 0x0F, 0xFE, 0x00, 0x07, 0xF0, 0x00, + 0x07, 0xFF, 0xE0, 0x03, 0xFF, 0xF0, 0x07, 0xE3, 0xF0, 0x0F, 0x83, 0xE0, + 0x1F, 0x07, 0xE0, 0x3E, 0x0F, 0xC0, 0x7C, 0x1F, 0x81, 0xF0, 0x3F, 0x03, + 0xE0, 0xFE, 0x07, 0xC1, 0xF8, 0x0F, 0x87, 0xF0, 0x3E, 0x1F, 0xC0, 0x7F, + 0xFE, 0x00, 0xFF, 0xF0, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x80, + 0x00, 0x1F, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF8, 0x00, 0x01, 0xF0, 0x00, + 0x03, 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x80, 0x00, 0xFF, 0xC0, 0x00, + 0x00, 0x1F, 0xC0, 0x00, 0xFF, 0xC0, 0x07, 0xC3, 0xE0, 0x1F, 0x03, 0xC0, + 0x7C, 0x03, 0xC1, 0xF0, 0x07, 0x87, 0xE0, 0x0F, 0x8F, 0x80, 0x1F, 0x3F, + 0x00, 0x3E, 0x7C, 0x00, 0x7D, 0xF8, 0x01, 0xFB, 0xF0, 0x03, 0xF7, 0xC0, + 0x07, 0xDF, 0x80, 0x0F, 0xBF, 0x00, 0x3F, 0x7C, 0x00, 0x7C, 0xF8, 0x01, + 0xF9, 0xF0, 0x03, 0xE3, 0xE0, 0x07, 0xC7, 0xC0, 0x1F, 0x07, 0x80, 0x7C, + 0x0F, 0x01, 0xF0, 0x0F, 0x07, 0x80, 0x07, 0xFE, 0x00, 0x03, 0x80, 0x00, + 0x0C, 0x00, 0x00, 0x3C, 0x00, 0x20, 0xFF, 0xC1, 0x87, 0xFF, 0xFE, 0x1E, + 0xFF, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xFF, 0xE0, 0x01, 0xFF, 0xFC, + 0x01, 0xF8, 0x7E, 0x01, 0xF8, 0x3F, 0x01, 0xF8, 0x3F, 0x01, 0xF0, 0x3F, + 0x01, 0xF0, 0x3F, 0x03, 0xF0, 0x3F, 0x03, 0xE0, 0x7E, 0x03, 0xE0, 0xFE, + 0x03, 0xE1, 0xF8, 0x07, 0xFF, 0xF0, 0x07, 0xFF, 0x80, 0x07, 0xDF, 0xC0, + 0x0F, 0xCF, 0xC0, 0x0F, 0xCF, 0xC0, 0x0F, 0x8F, 0xE0, 0x0F, 0x87, 0xE0, + 0x1F, 0x87, 0xE0, 0x1F, 0x03, 0xF0, 0x1F, 0x03, 0xF0, 0x1F, 0x03, 0xF0, + 0x3F, 0x01, 0xF8, 0x7F, 0x01, 0xF8, 0xFF, 0xE1, 0xFE, 0x00, 0xF8, 0x40, + 0xFF, 0xB0, 0x38, 0x3C, 0x1C, 0x07, 0x0F, 0x01, 0xC3, 0xC0, 0x20, 0xF0, + 0x08, 0x3E, 0x02, 0x0F, 0xC0, 0x03, 0xF8, 0x00, 0x7F, 0x00, 0x0F, 0xE0, + 0x01, 0xFC, 0x00, 0x3F, 0x80, 0x07, 0xE0, 0x00, 0xFC, 0x00, 0x1F, 0x00, + 0x03, 0xC4, 0x00, 0xF1, 0x00, 0x3C, 0x60, 0x0F, 0x38, 0x07, 0x8F, 0x83, + 0xC2, 0x3F, 0xE0, 0x83, 0xF0, 0x00, 0x3F, 0xFF, 0xF9, 0xFF, 0xFF, 0xCF, + 0x1F, 0x1E, 0x70, 0xF8, 0x77, 0x0F, 0x83, 0x30, 0x7C, 0x09, 0x03, 0xE0, + 0x40, 0x3F, 0x02, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x07, + 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, + 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x00, 0x00, 0xF8, + 0x00, 0x07, 0xC0, 0x00, 0x7E, 0x00, 0x07, 0xF0, 0x00, 0xFF, 0xF0, 0x00, + 0x7F, 0xF0, 0xFF, 0x1F, 0xC0, 0x3E, 0x1F, 0x80, 0x1C, 0x1F, 0x80, 0x18, + 0x1F, 0x00, 0x18, 0x1F, 0x00, 0x18, 0x1F, 0x00, 0x30, 0x3F, 0x00, 0x30, + 0x3E, 0x00, 0x30, 0x3E, 0x00, 0x30, 0x7E, 0x00, 0x60, 0x7C, 0x00, 0x60, + 0x7C, 0x00, 0x60, 0x7C, 0x00, 0xC0, 0x7C, 0x00, 0xC0, 0xF8, 0x00, 0xC0, + 0xF8, 0x00, 0xC0, 0xF8, 0x01, 0x80, 0xF8, 0x01, 0x80, 0xF8, 0x03, 0x80, + 0xF8, 0x03, 0x00, 0x7C, 0x06, 0x00, 0x7E, 0x1E, 0x00, 0x3F, 0xF8, 0x00, + 0x0F, 0xE0, 0x00, 0xFF, 0xE0, 0x7F, 0x3F, 0x80, 0x1C, 0x1F, 0x80, 0x18, + 0x1F, 0x80, 0x18, 0x1F, 0x80, 0x30, 0x1F, 0x80, 0x30, 0x0F, 0x80, 0x60, + 0x0F, 0x80, 0x40, 0x0F, 0x80, 0xC0, 0x0F, 0x81, 0x80, 0x0F, 0x81, 0x00, + 0x0F, 0xC3, 0x00, 0x0F, 0xC6, 0x00, 0x07, 0xC6, 0x00, 0x07, 0xCC, 0x00, + 0x07, 0xC8, 0x00, 0x07, 0xD8, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF0, 0x00, + 0x07, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0xC0, 0x00, 0x03, 0x80, 0x00, + 0x03, 0x00, 0x00, 0x03, 0x00, 0x00, 0xFF, 0xCF, 0xF8, 0x7E, 0x7F, 0x07, + 0xE0, 0x38, 0x7C, 0x07, 0x80, 0x60, 0xF8, 0x0F, 0x00, 0x81, 0xF0, 0x1E, + 0x03, 0x03, 0xE0, 0x3E, 0x04, 0x07, 0xE0, 0xFC, 0x18, 0x07, 0xC1, 0xF8, + 0x20, 0x0F, 0x87, 0xF0, 0xC0, 0x1F, 0x0B, 0xE1, 0x00, 0x3E, 0x37, 0xC6, + 0x00, 0x7C, 0x47, 0x88, 0x00, 0xF9, 0x8F, 0x30, 0x01, 0xF2, 0x1F, 0x40, + 0x03, 0xEC, 0x3E, 0x80, 0x03, 0xF0, 0x7F, 0x00, 0x07, 0xE0, 0xFC, 0x00, + 0x0F, 0x81, 0xF8, 0x00, 0x1F, 0x03, 0xE0, 0x00, 0x3C, 0x07, 0xC0, 0x00, + 0x78, 0x07, 0x00, 0x00, 0xF0, 0x0E, 0x00, 0x00, 0xC0, 0x18, 0x00, 0x01, + 0x80, 0x30, 0x00, 0x02, 0x00, 0x40, 0x00, 0x0F, 0xFE, 0x3F, 0x81, 0xFC, + 0x07, 0x80, 0x7C, 0x03, 0x00, 0x3F, 0x03, 0x00, 0x0F, 0x83, 0x80, 0x07, + 0xC1, 0x80, 0x03, 0xE1, 0x80, 0x00, 0xF9, 0x80, 0x00, 0x7D, 0x80, 0x00, + 0x3F, 0x80, 0x00, 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x03, 0xE0, 0x00, + 0x01, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xBE, 0x00, 0x00, 0xCF, 0x00, + 0x00, 0xC7, 0xC0, 0x00, 0xC3, 0xE0, 0x00, 0xC1, 0xF0, 0x00, 0xC0, 0x7C, + 0x00, 0xE0, 0x3E, 0x00, 0xE0, 0x1F, 0x00, 0xF8, 0x1F, 0xE0, 0xFF, 0x1F, + 0xF8, 0x00, 0xFF, 0xC3, 0xF9, 0xF8, 0x07, 0x87, 0xC0, 0x38, 0x3E, 0x01, + 0x81, 0xF0, 0x18, 0x07, 0xC0, 0x80, 0x3E, 0x0C, 0x01, 0xF0, 0xC0, 0x07, + 0xC4, 0x00, 0x3E, 0x60, 0x01, 0xF6, 0x00, 0x07, 0xA0, 0x00, 0x3F, 0x00, + 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0xFC, 0x00, 0x07, 0xC0, 0x00, 0x3E, + 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, + 0x7E, 0x00, 0x07, 0xF0, 0x00, 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xF8, 0x3F, + 0xFF, 0xC3, 0xE0, 0x7E, 0x1C, 0x07, 0xE0, 0xC0, 0x3E, 0x0C, 0x03, 0xF0, + 0x40, 0x3F, 0x00, 0x03, 0xF0, 0x00, 0x1F, 0x80, 0x01, 0xF8, 0x00, 0x1F, + 0x80, 0x00, 0xF8, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, 0x00, + 0x7E, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x83, 0xE0, 0x0C, 0x3F, 0x00, + 0xC3, 0xF0, 0x0E, 0x1F, 0x00, 0xF1, 0xF8, 0x1F, 0x9F, 0xFF, 0xF8, 0xFF, + 0xFF, 0xC0, 0x01, 0xFC, 0x0F, 0xE0, 0x3C, 0x00, 0xE0, 0x03, 0x80, 0x1E, + 0x00, 0x78, 0x01, 0xC0, 0x07, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0x80, 0x0E, + 0x00, 0x38, 0x01, 0xE0, 0x07, 0x00, 0x1C, 0x00, 0x70, 0x03, 0xC0, 0x0F, + 0x00, 0x38, 0x00, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x70, 0x01, 0xC0, 0x0F, + 0x00, 0x3C, 0x00, 0xFF, 0x03, 0xF8, 0x00, 0xE0, 0x38, 0x07, 0x01, 0xC0, + 0x70, 0x0C, 0x03, 0x80, 0xE0, 0x38, 0x07, 0x01, 0xC0, 0x70, 0x0C, 0x03, + 0x80, 0xE0, 0x38, 0x07, 0x01, 0xC0, 0x70, 0x0C, 0x03, 0x80, 0xE0, 0x38, + 0x07, 0x01, 0xC0, 0x03, 0xFC, 0x0F, 0xF0, 0x03, 0x80, 0x0E, 0x00, 0x38, + 0x01, 0xE0, 0x07, 0x80, 0x1C, 0x00, 0x70, 0x03, 0xC0, 0x0F, 0x00, 0x38, + 0x00, 0xE0, 0x07, 0x80, 0x1E, 0x00, 0x70, 0x01, 0xC0, 0x0F, 0x00, 0x3C, + 0x00, 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x78, 0x01, 0xE0, 0x07, 0x00, 0x1C, + 0x00, 0xF0, 0x03, 0xC0, 0xFE, 0x03, 0xF8, 0x00, 0x03, 0xC0, 0x03, 0xC0, + 0x07, 0xE0, 0x07, 0xE0, 0x0E, 0x70, 0x0E, 0x70, 0x1C, 0x78, 0x1C, 0x38, + 0x3C, 0x3C, 0x38, 0x1C, 0x78, 0x1E, 0x70, 0x0E, 0xF0, 0x0E, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0xE1, 0xE3, 0xC1, 0xC1, 0xC0, 0xC0, 0x00, + 0xF7, 0x80, 0xFD, 0xE0, 0x7C, 0xF0, 0x3C, 0x3C, 0x1E, 0x0F, 0x0F, 0x83, + 0x83, 0xC1, 0xE1, 0xE0, 0x78, 0x78, 0x1C, 0x3E, 0x0F, 0x0F, 0x03, 0xC3, + 0xC1, 0xF0, 0xF0, 0xFC, 0xFE, 0x6F, 0x6F, 0xF3, 0xF1, 0xF8, 0xF8, 0x3C, + 0x1C, 0x00, 0x01, 0xE0, 0x1F, 0xC0, 0x07, 0xC0, 0x07, 0xC0, 0x07, 0x80, + 0x07, 0x80, 0x0F, 0x80, 0x0F, 0x00, 0x0F, 0x00, 0x0F, 0x3C, 0x1E, 0xFE, + 0x1F, 0x9F, 0x1F, 0x0F, 0x1E, 0x0F, 0x3E, 0x0F, 0x3C, 0x0F, 0x3C, 0x1F, + 0x78, 0x1E, 0x78, 0x1E, 0x78, 0x3C, 0x78, 0x3C, 0xF0, 0x78, 0xF0, 0xF0, + 0xF1, 0xE0, 0x7F, 0xC0, 0x3F, 0x00, 0x01, 0xF0, 0x3F, 0xC3, 0xCE, 0x3C, + 0xF3, 0xC7, 0x1E, 0x01, 0xE0, 0x0F, 0x00, 0xF8, 0x07, 0x80, 0x3C, 0x01, + 0xE0, 0x0F, 0x03, 0x78, 0x31, 0xE3, 0x0F, 0xF0, 0x1E, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x78, 0x00, 0x0F, + 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x01, 0xEF, 0x00, 0x7F, 0xE0, 0x3E, 0x7C, + 0x07, 0x8F, 0x01, 0xE1, 0xE0, 0x78, 0x3C, 0x0F, 0x0F, 0x83, 0xC1, 0xE0, + 0x78, 0x3C, 0x1E, 0x0F, 0x83, 0xC1, 0xF0, 0x78, 0x7C, 0x0F, 0x0F, 0x91, + 0xE3, 0xF6, 0x3F, 0xDF, 0x83, 0xF3, 0xE0, 0x3C, 0x38, 0x00, 0x01, 0xE0, + 0x3F, 0x83, 0xCE, 0x3C, 0x73, 0xC3, 0x9E, 0x1D, 0xE1, 0xCF, 0x1C, 0xFB, + 0xC7, 0xF8, 0x3C, 0x01, 0xE0, 0x0F, 0x02, 0x78, 0x31, 0xE3, 0x0F, 0xF0, + 0x1E, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x1D, 0xC0, 0x01, 0xCE, 0x00, 0x1C, + 0x70, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x07, 0x80, 0x00, + 0x3C, 0x00, 0x0F, 0xFC, 0x00, 0x7F, 0xE0, 0x00, 0xF0, 0x00, 0x07, 0x80, + 0x00, 0x3C, 0x00, 0x03, 0xE0, 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x07, + 0x80, 0x00, 0x7C, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, 0x00, + 0x07, 0x80, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, + 0x00, 0x0F, 0x00, 0x0E, 0x70, 0x00, 0x77, 0x80, 0x03, 0xF8, 0x00, 0x0F, + 0x80, 0x00, 0x00, 0xFE, 0x00, 0x7F, 0xFC, 0x1F, 0x1F, 0x87, 0xC3, 0xC1, + 0xF0, 0x78, 0x3C, 0x1F, 0x07, 0x83, 0xE0, 0xF0, 0xF8, 0x0E, 0x3E, 0x01, + 0xFF, 0x80, 0x3F, 0xC0, 0x0C, 0x00, 0x03, 0xC0, 0x00, 0x7F, 0x80, 0x0F, + 0xFE, 0x00, 0x7F, 0xF0, 0x70, 0xFF, 0x1C, 0x03, 0xE3, 0x80, 0x3C, 0x70, + 0x07, 0x0F, 0x03, 0xE0, 0xFF, 0xF0, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x03, + 0xE0, 0x00, 0xF0, 0x00, 0xF8, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1E, 0x00, + 0x1F, 0x00, 0x0F, 0x0E, 0x07, 0x9F, 0x83, 0xDF, 0xC3, 0xE9, 0xE1, 0xE8, + 0xF0, 0xF8, 0xF8, 0x7C, 0x78, 0x7C, 0x3C, 0x3E, 0x3E, 0x1E, 0x1E, 0x1F, + 0x0F, 0x0F, 0x0F, 0x87, 0x87, 0xCB, 0xC3, 0xCB, 0xE1, 0xE9, 0xE0, 0xFC, + 0xF0, 0x38, 0x00, 0x03, 0x03, 0xC1, 0xE0, 0xF0, 0x30, 0x00, 0x00, 0x00, + 0x07, 0x3F, 0x87, 0x83, 0xC1, 0xE0, 0xF0, 0xF0, 0x78, 0x3C, 0x1E, 0x1E, + 0x0F, 0x27, 0x17, 0x93, 0xF1, 0xF8, 0x70, 0x00, 0x00, 0x06, 0x00, 0x0F, + 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x06, 0x00, 0xFE, 0x00, 0x3E, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x3C, + 0x00, 0x7C, 0x00, 0x78, 0x00, 0x78, 0x00, 0x78, 0x00, 0xF8, 0x00, 0xF0, + 0x00, 0xF0, 0x00, 0xF0, 0x01, 0xF0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, + 0x03, 0xC0, 0xE3, 0xC0, 0xE7, 0x80, 0xFF, 0x00, 0x7C, 0x00, 0x1F, 0xC0, + 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1E, + 0x00, 0x1F, 0x00, 0x0F, 0x3F, 0x87, 0x87, 0x83, 0xC3, 0x03, 0xE3, 0x01, + 0xE3, 0x00, 0xF3, 0x00, 0x7B, 0x80, 0x7B, 0xC0, 0x3F, 0xE0, 0x1E, 0xF0, + 0x1F, 0x78, 0x0F, 0x1E, 0x07, 0x8F, 0x13, 0xC7, 0x93, 0xE1, 0xF9, 0xE0, + 0xF8, 0xF0, 0x38, 0x00, 0x1F, 0xC0, 0xF8, 0x1F, 0x03, 0xC0, 0x78, 0x1F, + 0x03, 0xE0, 0x78, 0x0F, 0x01, 0xE0, 0x78, 0x0F, 0x01, 0xE0, 0x3C, 0x0F, + 0x01, 0xE0, 0x3C, 0x0F, 0x81, 0xE0, 0x3C, 0x8F, 0x31, 0xEC, 0x3F, 0x07, + 0xC0, 0x70, 0x00, 0x01, 0x87, 0x07, 0x0F, 0xE7, 0xE7, 0xE0, 0xF3, 0xF9, + 0xF8, 0x3D, 0x9E, 0x9E, 0x0F, 0x47, 0xC7, 0x83, 0xE1, 0xD1, 0xE1, 0xF8, + 0xF8, 0xF0, 0x7C, 0x3C, 0x3C, 0x1F, 0x0F, 0x1F, 0x0F, 0x87, 0xC7, 0x83, + 0xE1, 0xE1, 0xE0, 0xF0, 0x78, 0x78, 0x3C, 0x1E, 0x3C, 0x1F, 0x0F, 0x0F, + 0x27, 0x83, 0xC3, 0xD1, 0xE0, 0xF0, 0xFC, 0xF8, 0x78, 0x1C, 0x00, 0x01, + 0x8F, 0x0F, 0xE7, 0xE0, 0xF3, 0xF8, 0x3C, 0x9E, 0x0F, 0x47, 0x87, 0xA3, + 0xC1, 0xE8, 0xF0, 0x7C, 0x3C, 0x1E, 0x1E, 0x0F, 0x87, 0x83, 0xE1, 0xE0, + 0xF0, 0xF8, 0x3C, 0x3C, 0x1F, 0x0F, 0x27, 0x83, 0xD1, 0xE0, 0xFC, 0x78, + 0x1C, 0x00, 0x01, 0xF0, 0x0E, 0x30, 0x38, 0x70, 0xF0, 0xF3, 0xC1, 0xE7, + 0x83, 0xDE, 0x07, 0xBC, 0x1F, 0xF8, 0x3F, 0xE0, 0x7B, 0xC0, 0xF7, 0x83, + 0xCF, 0x07, 0x9E, 0x1E, 0x1C, 0x38, 0x1C, 0xE0, 0x1F, 0x00, 0x00, 0xE3, + 0x80, 0xFD, 0xF8, 0x0F, 0xFF, 0x81, 0xE8, 0xF0, 0x3E, 0x1E, 0x07, 0x83, + 0xC0, 0xF0, 0x78, 0x3E, 0x1F, 0x07, 0x83, 0xC0, 0xF0, 0x78, 0x1E, 0x1F, + 0x07, 0x83, 0xC0, 0xF0, 0xF8, 0x1E, 0x1E, 0x03, 0xC7, 0x80, 0xFF, 0xE0, + 0x1E, 0xF0, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x03, 0xC0, 0x00, + 0xF8, 0x00, 0x3F, 0xC0, 0x00, 0x01, 0xEF, 0x07, 0xFF, 0x0F, 0x1E, 0x1E, + 0x1E, 0x1E, 0x1E, 0x3C, 0x1E, 0x7C, 0x3C, 0x78, 0x3C, 0x78, 0x3C, 0xF0, + 0x7C, 0xF0, 0x78, 0xF0, 0xF8, 0xF0, 0xF8, 0xF1, 0xF0, 0xFE, 0xF0, 0x7E, + 0xF0, 0x39, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x01, 0xE0, 0x03, 0xC0, 0x03, + 0xC0, 0x1F, 0xF8, 0x03, 0x9C, 0x7F, 0x7C, 0x3D, 0xF8, 0x7A, 0xE0, 0xF8, + 0x03, 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x3E, 0x00, 0x7C, 0x00, 0xF0, 0x01, + 0xE0, 0x07, 0xC0, 0x0F, 0x00, 0x1E, 0x00, 0x7C, 0x00, 0x07, 0x18, 0xFF, + 0xC7, 0x1C, 0x70, 0x63, 0x81, 0x1E, 0x08, 0xF8, 0x07, 0xE0, 0x1F, 0x00, + 0x7C, 0x01, 0xF0, 0x07, 0x84, 0x3C, 0x20, 0xE1, 0x87, 0x1C, 0x70, 0x9E, + 0x00, 0x00, 0x80, 0x60, 0x30, 0x1C, 0x1F, 0x1F, 0xF7, 0xFC, 0x78, 0x1E, + 0x07, 0x83, 0xC0, 0xF0, 0x3C, 0x1F, 0x07, 0x81, 0xE0, 0x79, 0x3C, 0x4F, + 0x23, 0xF0, 0xFC, 0x1C, 0x00, 0x0F, 0x0F, 0x3F, 0x87, 0x8F, 0x83, 0xC7, + 0xC1, 0xE3, 0xE1, 0xE1, 0xE0, 0xF0, 0xF0, 0x78, 0xF8, 0x78, 0x78, 0x3C, + 0x3C, 0x3E, 0x1E, 0x1F, 0x1E, 0x1F, 0x0F, 0x17, 0x97, 0x9B, 0xCB, 0xF9, + 0xF9, 0xF8, 0xF8, 0x78, 0x38, 0x00, 0x18, 0x37, 0xC3, 0xDE, 0x1E, 0x78, + 0x73, 0xC1, 0x9E, 0x08, 0xF0, 0xC7, 0x84, 0x3C, 0x41, 0xE4, 0x0F, 0x40, + 0x7C, 0x03, 0xC0, 0x1C, 0x00, 0xC0, 0x04, 0x00, 0x38, 0x10, 0xDF, 0x06, + 0x3D, 0xE0, 0xC7, 0xBC, 0x38, 0x73, 0xC7, 0x06, 0x79, 0xF0, 0x8F, 0x3E, + 0x11, 0xEB, 0xC4, 0x3F, 0x79, 0x07, 0xCF, 0x60, 0xF9, 0xE8, 0x1E, 0x3E, + 0x03, 0x87, 0x80, 0x70, 0xF0, 0x0C, 0x0C, 0x01, 0x01, 0x00, 0x03, 0x83, + 0x87, 0xF1, 0xF0, 0x3C, 0xF8, 0x0F, 0x60, 0x03, 0xD0, 0x00, 0xF8, 0x00, + 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x1F, 0x00, 0x0F, + 0xC0, 0x02, 0xF1, 0x39, 0x3C, 0xCF, 0xCF, 0xE3, 0xE1, 0xF0, 0x70, 0x38, + 0x00, 0x01, 0x83, 0x07, 0xE3, 0xC1, 0xF1, 0xE0, 0x78, 0xF0, 0x3E, 0x18, + 0x1F, 0x08, 0x07, 0x84, 0x03, 0xC6, 0x01, 0xE2, 0x00, 0xFB, 0x00, 0x3D, + 0x00, 0x1F, 0x80, 0x0F, 0x80, 0x07, 0xC0, 0x03, 0xC0, 0x01, 0xE0, 0x00, + 0xE0, 0x00, 0x60, 0x00, 0x60, 0x0E, 0x60, 0x0F, 0xE0, 0x07, 0xE0, 0x01, + 0xC0, 0x00, 0x1F, 0xFC, 0x3F, 0xF8, 0x7F, 0xE1, 0x81, 0x82, 0x06, 0x00, + 0x08, 0x00, 0x20, 0x00, 0xC0, 0x03, 0x00, 0x0C, 0x00, 0x10, 0x00, 0x40, + 0x01, 0x80, 0x07, 0xC0, 0x1F, 0x86, 0x3F, 0x8E, 0xCF, 0x9C, 0x07, 0x30, + 0x03, 0xC0, 0x00, 0x1E, 0x00, 0xF8, 0x03, 0xC0, 0x0F, 0x00, 0x1E, 0x00, + 0x38, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x1E, 0x00, 0x3C, + 0x00, 0x78, 0x01, 0xE0, 0x03, 0xC0, 0x1F, 0x00, 0x7E, 0x00, 0x30, 0x00, + 0x60, 0x00, 0xE0, 0x01, 0xC0, 0x07, 0x80, 0x0F, 0x00, 0x1E, 0x00, 0x38, + 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, 0x00, 0x0E, 0x00, 0x0C, 0x00, + 0x0F, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0, + 0x00, 0xF0, 0x00, 0x70, 0x00, 0x70, 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, + 0x07, 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x78, 0x00, 0xE0, 0x03, 0xC0, 0x07, + 0x80, 0x0F, 0x00, 0x1C, 0x00, 0x18, 0x00, 0x10, 0x00, 0xF0, 0x03, 0xF0, + 0x0F, 0x00, 0x1E, 0x00, 0x38, 0x00, 0xF0, 0x01, 0xE0, 0x03, 0xC0, 0x07, + 0x00, 0x1E, 0x00, 0x3C, 0x00, 0x70, 0x01, 0xE0, 0x0F, 0x80, 0x7C, 0x00, + 0x3E, 0x00, 0x7F, 0xC6, 0xFF, 0xFF, 0x61, 0xFE, 0x00, 0x7C }; + +const GFXglyph FreeSerifBoldItalic18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 9, 0, 1 }, // 0x20 ' ' + { 0, 11, 25, 14, 2, -23 }, // 0x21 '!' + { 35, 14, 10, 19, 4, -23 }, // 0x22 '"' + { 53, 20, 25, 17, -1, -24 }, // 0x23 '#' + { 116, 17, 29, 18, 0, -25 }, // 0x24 '$' + { 178, 27, 25, 29, 1, -23 }, // 0x25 '%' + { 263, 25, 25, 27, 0, -23 }, // 0x26 '&' + { 342, 5, 10, 10, 4, -23 }, // 0x27 ''' + { 349, 11, 30, 12, 1, -23 }, // 0x28 '(' + { 391, 11, 30, 12, -2, -23 }, // 0x29 ')' + { 433, 13, 15, 18, 2, -23 }, // 0x2A '*' + { 458, 17, 17, 20, 1, -16 }, // 0x2B '+' + { 495, 7, 11, 9, -2, -4 }, // 0x2C ',' + { 505, 9, 4, 12, 0, -9 }, // 0x2D '-' + { 510, 6, 5, 9, 0, -3 }, // 0x2E '.' + { 514, 14, 25, 12, 0, -23 }, // 0x2F '/' + { 558, 15, 25, 18, 1, -23 }, // 0x30 '0' + { 605, 15, 25, 17, 0, -23 }, // 0x31 '1' + { 652, 16, 25, 18, 0, -23 }, // 0x32 '2' + { 702, 15, 25, 17, 1, -23 }, // 0x33 '3' + { 749, 18, 24, 17, 0, -23 }, // 0x34 '4' + { 803, 17, 25, 18, 0, -23 }, // 0x35 '5' + { 857, 17, 25, 18, 1, -23 }, // 0x36 '6' + { 911, 16, 24, 17, 3, -23 }, // 0x37 '7' + { 959, 17, 25, 18, 0, -23 }, // 0x38 '8' + { 1013, 17, 25, 18, 0, -23 }, // 0x39 '9' + { 1067, 10, 17, 9, 0, -15 }, // 0x3A ':' + { 1089, 11, 22, 9, -1, -15 }, // 0x3B ';' + { 1120, 18, 19, 20, 1, -18 }, // 0x3C '<' + { 1163, 18, 10, 20, 2, -13 }, // 0x3D '=' + { 1186, 18, 19, 20, 2, -18 }, // 0x3E '>' + { 1229, 13, 25, 17, 3, -23 }, // 0x3F '?' + { 1270, 25, 25, 29, 2, -23 }, // 0x40 '@' + { 1349, 23, 25, 24, 0, -23 }, // 0x41 'A' + { 1421, 24, 25, 22, 0, -23 }, // 0x42 'B' + { 1496, 23, 25, 22, 1, -23 }, // 0x43 'C' + { 1568, 26, 25, 25, 0, -23 }, // 0x44 'D' + { 1650, 23, 25, 22, 0, -23 }, // 0x45 'E' + { 1722, 23, 25, 21, 0, -23 }, // 0x46 'F' + { 1794, 24, 25, 25, 2, -23 }, // 0x47 'G' + { 1869, 29, 25, 26, 0, -23 }, // 0x48 'H' + { 1960, 15, 25, 13, 0, -23 }, // 0x49 'I' + { 2007, 20, 27, 17, 0, -23 }, // 0x4A 'J' + { 2075, 25, 25, 23, 0, -23 }, // 0x4B 'K' + { 2154, 22, 25, 21, 0, -23 }, // 0x4C 'L' + { 2223, 33, 25, 31, 0, -23 }, // 0x4D 'M' + { 2327, 27, 25, 25, 0, -23 }, // 0x4E 'N' + { 2412, 23, 25, 24, 1, -23 }, // 0x4F 'O' + { 2484, 23, 25, 21, 0, -23 }, // 0x50 'P' + { 2556, 23, 31, 24, 1, -23 }, // 0x51 'Q' + { 2646, 24, 25, 23, 0, -23 }, // 0x52 'R' + { 2721, 18, 25, 18, 0, -23 }, // 0x53 'S' + { 2778, 21, 25, 21, 3, -23 }, // 0x54 'T' + { 2844, 24, 25, 25, 4, -23 }, // 0x55 'U' + { 2919, 24, 25, 25, 4, -23 }, // 0x56 'V' + { 2994, 31, 25, 32, 4, -23 }, // 0x57 'W' + { 3091, 25, 25, 24, 0, -23 }, // 0x58 'X' + { 3170, 21, 25, 22, 4, -23 }, // 0x59 'Y' + { 3236, 21, 25, 20, 0, -23 }, // 0x5A 'Z' + { 3302, 14, 30, 12, -1, -23 }, // 0x5B '[' + { 3355, 10, 25, 14, 4, -23 }, // 0x5C '\' + { 3387, 14, 30, 12, -2, -23 }, // 0x5D ']' + { 3440, 16, 13, 20, 2, -23 }, // 0x5E '^' + { 3466, 18, 3, 17, 0, 3 }, // 0x5F '_' + { 3473, 7, 6, 12, 3, -23 }, // 0x60 '`' + { 3479, 18, 17, 18, 0, -15 }, // 0x61 'a' + { 3518, 16, 26, 17, 1, -24 }, // 0x62 'b' + { 3570, 13, 17, 15, 1, -15 }, // 0x63 'c' + { 3598, 19, 25, 18, 1, -23 }, // 0x64 'd' + { 3658, 13, 17, 15, 1, -15 }, // 0x65 'e' + { 3686, 21, 32, 17, -3, -24 }, // 0x66 'f' + { 3770, 19, 23, 17, -1, -15 }, // 0x67 'g' + { 3825, 17, 25, 19, 1, -23 }, // 0x68 'h' + { 3879, 9, 25, 10, 1, -23 }, // 0x69 'i' + { 3908, 16, 31, 12, -3, -23 }, // 0x6A 'j' + { 3970, 17, 25, 18, 1, -23 }, // 0x6B 'k' + { 4024, 11, 25, 10, 1, -23 }, // 0x6C 'l' + { 4059, 26, 17, 27, 0, -15 }, // 0x6D 'm' + { 4115, 18, 17, 18, 0, -15 }, // 0x6E 'n' + { 4154, 15, 17, 17, 1, -15 }, // 0x6F 'o' + { 4186, 19, 23, 17, -2, -15 }, // 0x70 'p' + { 4241, 16, 23, 17, 1, -15 }, // 0x71 'q' + { 4287, 15, 16, 14, 0, -15 }, // 0x72 'r' + { 4317, 13, 17, 12, 0, -15 }, // 0x73 's' + { 4345, 10, 22, 10, 1, -20 }, // 0x74 't' + { 4373, 17, 17, 19, 1, -15 }, // 0x75 'u' + { 4410, 13, 16, 15, 2, -15 }, // 0x76 'v' + { 4436, 19, 16, 23, 3, -15 }, // 0x77 'w' + { 4474, 18, 17, 17, -1, -15 }, // 0x78 'x' + { 4513, 17, 23, 15, -2, -15 }, // 0x79 'y' + { 4562, 15, 19, 14, 0, -15 }, // 0x7A 'z' + { 4598, 15, 32, 12, 0, -24 }, // 0x7B '{' + { 4658, 3, 25, 9, 4, -23 }, // 0x7C '|' + { 4668, 15, 32, 12, -5, -24 }, // 0x7D '}' + { 4728, 16, 5, 20, 2, -11 } }; // 0x7E '~' + +const GFXfont FreeSerifBoldItalic18pt7b PROGMEM = { + (uint8_t *)FreeSerifBoldItalic18pt7bBitmaps, + (GFXglyph *)FreeSerifBoldItalic18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 5410 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic24pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic24pt7b.h new file mode 100644 index 0000000..fcb857e --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic24pt7b.h @@ -0,0 +1,793 @@ +const uint8_t FreeSerifBoldItalic24pt7bBitmaps[] PROGMEM = { + 0x00, 0x3C, 0x00, 0xFC, 0x01, 0xF8, 0x07, 0xF0, 0x0F, 0xE0, 0x1F, 0xC0, + 0x3F, 0x00, 0x7E, 0x00, 0xF8, 0x01, 0xF0, 0x07, 0xC0, 0x0F, 0x80, 0x1E, + 0x00, 0x3C, 0x00, 0x70, 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x00, 0x0E, 0x00, + 0x18, 0x00, 0x30, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0xF0, 0x03, 0xF0, 0x0F, 0xF0, 0x1F, 0xE0, 0x3F, 0xC0, 0x3F, 0x00, + 0x3C, 0x00, 0x1C, 0x01, 0xC7, 0xC0, 0x7D, 0xF8, 0x1F, 0xBF, 0x03, 0xF7, + 0xC0, 0x7C, 0xF8, 0x0F, 0x9E, 0x01, 0xE3, 0xC0, 0x3C, 0x70, 0x07, 0x1E, + 0x00, 0xE3, 0x80, 0x38, 0x70, 0x07, 0x0C, 0x00, 0xC0, 0x00, 0x03, 0xC1, + 0xE0, 0x00, 0x70, 0x38, 0x00, 0x1E, 0x0F, 0x00, 0x03, 0xC1, 0xE0, 0x00, + 0x70, 0x38, 0x00, 0x1E, 0x0F, 0x00, 0x03, 0x81, 0xC0, 0x00, 0xF0, 0x78, + 0x00, 0x1E, 0x0F, 0x00, 0x07, 0x83, 0xC0, 0x1F, 0xFF, 0xFF, 0x83, 0xFF, + 0xFF, 0xF0, 0x7F, 0xFF, 0xFC, 0x00, 0xE0, 0x70, 0x00, 0x3C, 0x1E, 0x00, + 0x07, 0x83, 0xC0, 0x00, 0xE0, 0x70, 0x00, 0x3C, 0x1E, 0x00, 0x07, 0x83, + 0xC0, 0x00, 0xE0, 0x70, 0x07, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFC, 0x1F, + 0xFF, 0xFF, 0x00, 0x38, 0x1C, 0x00, 0x0F, 0x07, 0x80, 0x01, 0xE0, 0xF0, + 0x00, 0x38, 0x1C, 0x00, 0x0F, 0x07, 0x80, 0x01, 0xC0, 0xE0, 0x00, 0x78, + 0x3C, 0x00, 0x0F, 0x07, 0x80, 0x01, 0xC0, 0xE0, 0x00, 0x78, 0x3C, 0x00, + 0x00, 0x00, 0x00, 0xE0, 0x00, 0x00, 0xC0, 0x00, 0x00, 0xC0, 0x00, 0x1F, + 0xE0, 0x00, 0x7F, 0xF8, 0x01, 0xF1, 0x9E, 0x01, 0xC1, 0x8F, 0x03, 0x83, + 0x8F, 0x03, 0x83, 0x06, 0x07, 0x83, 0x06, 0x07, 0x87, 0x06, 0x07, 0xC7, + 0x04, 0x07, 0xE6, 0x04, 0x07, 0xFE, 0x00, 0x03, 0xFE, 0x00, 0x03, 0xFF, + 0x00, 0x01, 0xFF, 0x80, 0x00, 0xFF, 0xC0, 0x00, 0x7F, 0xE0, 0x00, 0x1F, + 0xE0, 0x00, 0x1F, 0xF0, 0x00, 0x3F, 0xF0, 0x00, 0x3B, 0xF8, 0x20, 0x31, + 0xF8, 0x20, 0x30, 0xF8, 0x60, 0x70, 0xF8, 0x60, 0x60, 0xF8, 0x60, 0x60, + 0xF8, 0xF0, 0xE0, 0xF0, 0xF0, 0xE1, 0xE0, 0x78, 0xC3, 0xE0, 0x3C, 0xC7, + 0xC0, 0x0F, 0xFF, 0x00, 0x03, 0xFC, 0x00, 0x01, 0x80, 0x00, 0x03, 0x80, + 0x00, 0x03, 0x80, 0x00, 0x03, 0x00, 0x00, 0x03, 0x00, 0x00, 0x01, 0xF0, + 0x00, 0x70, 0x00, 0xFF, 0x80, 0x1C, 0x00, 0x3F, 0x38, 0x1F, 0x00, 0x0F, + 0xC7, 0xFF, 0xE0, 0x03, 0xF0, 0x3F, 0xB8, 0x00, 0x7E, 0x04, 0x07, 0x00, + 0x1F, 0x80, 0x81, 0xC0, 0x03, 0xF0, 0x10, 0x38, 0x00, 0xFC, 0x02, 0x0E, + 0x00, 0x1F, 0x80, 0x81, 0x80, 0x03, 0xF0, 0x10, 0x70, 0x00, 0x7C, 0x06, + 0x1C, 0x00, 0x0F, 0x80, 0x83, 0x80, 0x01, 0xF0, 0x30, 0xE0, 0x00, 0x1E, + 0x0C, 0x1C, 0x07, 0xC3, 0xE3, 0x07, 0x03, 0xFC, 0x3F, 0xC0, 0xC0, 0xFC, + 0x43, 0xE0, 0x38, 0x3E, 0x0C, 0x00, 0x0E, 0x0F, 0xC0, 0x80, 0x01, 0xC3, + 0xF0, 0x10, 0x00, 0x70, 0xFC, 0x02, 0x00, 0x0C, 0x1F, 0x80, 0x40, 0x03, + 0x83, 0xE0, 0x08, 0x00, 0x60, 0xFC, 0x02, 0x00, 0x1C, 0x1F, 0x80, 0x40, + 0x07, 0x03, 0xE0, 0x10, 0x00, 0xE0, 0x7C, 0x02, 0x00, 0x38, 0x0F, 0x80, + 0xC0, 0x06, 0x01, 0xF0, 0x30, 0x01, 0xC0, 0x1F, 0x0C, 0x00, 0x30, 0x01, + 0xFF, 0x00, 0x0E, 0x00, 0x1F, 0x80, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x00, + 0xFF, 0x80, 0x00, 0x01, 0xF1, 0xE0, 0x00, 0x00, 0xF0, 0x78, 0x00, 0x00, + 0xF0, 0x3C, 0x00, 0x00, 0x78, 0x1E, 0x00, 0x00, 0x7C, 0x0F, 0x00, 0x00, + 0x3E, 0x0F, 0x80, 0x00, 0x1F, 0x07, 0x80, 0x00, 0x0F, 0x87, 0x80, 0x00, + 0x07, 0xC7, 0x80, 0x00, 0x03, 0xFF, 0x00, 0x00, 0x01, 0xFE, 0x00, 0x00, + 0x00, 0xFC, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x01, 0xFF, 0x07, 0xFE, + 0x03, 0xCF, 0xC0, 0xFE, 0x03, 0xC7, 0xE0, 0x3C, 0x07, 0xC3, 0xF0, 0x1C, + 0x07, 0xC0, 0xFC, 0x0C, 0x03, 0xC0, 0x7E, 0x0E, 0x03, 0xE0, 0x3F, 0x0E, + 0x01, 0xF0, 0x1F, 0xC6, 0x01, 0xF8, 0x07, 0xF6, 0x00, 0xFC, 0x03, 0xFF, + 0x00, 0x7E, 0x00, 0xFF, 0x00, 0x3F, 0x80, 0x7F, 0x80, 0x1F, 0xC0, 0x1F, + 0xC0, 0x07, 0xF0, 0x0F, 0xF0, 0x13, 0xFE, 0x0F, 0xFE, 0x18, 0xFF, 0xFE, + 0xFF, 0xF8, 0x3F, 0xFE, 0x3F, 0xF8, 0x07, 0xF8, 0x03, 0xF0, 0x00, 0x1C, + 0x7D, 0xFB, 0xF7, 0xCF, 0x9E, 0x3C, 0x71, 0xE3, 0x87, 0x0C, 0x00, 0x00, + 0x04, 0x00, 0x70, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x3C, 0x01, + 0xE0, 0x0F, 0x00, 0x3C, 0x01, 0xE0, 0x0F, 0x80, 0x3C, 0x00, 0xF0, 0x07, + 0xC0, 0x1E, 0x00, 0x78, 0x03, 0xE0, 0x0F, 0x80, 0x3E, 0x00, 0xF0, 0x03, + 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x3C, 0x00, + 0x70, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, 0x30, 0x00, 0xE0, 0x01, 0x80, + 0x06, 0x00, 0x0C, 0x00, 0x30, 0x00, 0x60, 0x01, 0x80, 0x00, 0x00, 0x01, + 0x00, 0x06, 0x00, 0x08, 0x00, 0x30, 0x00, 0x40, 0x01, 0x80, 0x06, 0x00, + 0x1C, 0x00, 0x30, 0x00, 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x38, 0x00, 0xF0, + 0x03, 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xF0, 0x03, 0xC0, 0x0F, 0x00, 0x7C, + 0x01, 0xF0, 0x07, 0xC0, 0x1E, 0x00, 0x78, 0x03, 0xE0, 0x0F, 0x80, 0x3C, + 0x01, 0xF0, 0x07, 0x80, 0x1E, 0x00, 0xF0, 0x03, 0x80, 0x1E, 0x00, 0xF0, + 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x06, 0x00, 0x30, 0x00, 0x80, 0x00, 0x00, + 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x07, 0x0E, 0x1D, 0xF1, + 0xC7, 0xFF, 0x11, 0xFF, 0xE2, 0x3F, 0x7E, 0x4F, 0xC0, 0x3E, 0x00, 0x07, + 0xC0, 0x3F, 0x27, 0xEF, 0xC4, 0x7F, 0xF8, 0x8F, 0xFE, 0x38, 0xFB, 0x87, + 0x0E, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0x70, 0x00, 0x00, + 0x78, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x78, + 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x03, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x01, + 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, + 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, + 0x07, 0x80, 0x00, 0x0F, 0x07, 0xE1, 0xFC, 0x7F, 0x1F, 0xC3, 0xF0, 0x7C, + 0x0E, 0x03, 0x80, 0xC0, 0x60, 0x30, 0x18, 0x1C, 0x04, 0x00, 0x7F, 0xF7, + 0xFF, 0x7F, 0xEF, 0xFE, 0xFF, 0xE0, 0x3C, 0x7E, 0xFF, 0xFF, 0xFF, 0x7E, + 0x3C, 0x00, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, + 0x78, 0x00, 0x1E, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x07, + 0xC0, 0x00, 0xF0, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x3C, + 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x01, 0xE0, + 0x00, 0x7C, 0x00, 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x78, 0x00, 0x0F, 0x00, + 0x03, 0xC0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x03, 0xC0, 0x00, 0xF8, 0x00, + 0x1E, 0x00, 0x07, 0xC0, 0x00, 0xF0, 0x00, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0xE3, 0x80, 0x0F, 0x07, 0x00, 0x7C, 0x1C, 0x03, 0xE0, 0x78, 0x0F, 0x81, + 0xE0, 0x7C, 0x07, 0x83, 0xF0, 0x1F, 0x0F, 0xC0, 0xFC, 0x7E, 0x03, 0xF1, + 0xF8, 0x0F, 0xCF, 0xE0, 0x3F, 0x3F, 0x00, 0xFD, 0xFC, 0x07, 0xF7, 0xF0, + 0x1F, 0xDF, 0xC0, 0x7F, 0x7E, 0x01, 0xFB, 0xF8, 0x0F, 0xEF, 0xE0, 0x3F, + 0xBF, 0x80, 0xFE, 0xFC, 0x03, 0xF3, 0xF0, 0x1F, 0xCF, 0xC0, 0x7F, 0x3F, + 0x01, 0xF8, 0xFC, 0x07, 0xE3, 0xE0, 0x3F, 0x0F, 0x80, 0xFC, 0x1E, 0x07, + 0xE0, 0x78, 0x1F, 0x00, 0xE0, 0x78, 0x03, 0x83, 0xC0, 0x07, 0x1E, 0x00, + 0x07, 0xE0, 0x00, 0x00, 0x00, 0x70, 0x01, 0xFE, 0x01, 0xFF, 0xE0, 0x00, + 0xFE, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, 0x01, 0xFC, 0x00, + 0x1F, 0x80, 0x01, 0xF8, 0x00, 0x3F, 0x80, 0x03, 0xF8, 0x00, 0x3F, 0x00, + 0x03, 0xF0, 0x00, 0x7F, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x07, 0xE0, + 0x00, 0xFE, 0x00, 0x0F, 0xC0, 0x00, 0xFC, 0x00, 0x1F, 0xC0, 0x01, 0xFC, + 0x00, 0x1F, 0x80, 0x01, 0xF8, 0x00, 0x3F, 0x80, 0x03, 0xF0, 0x00, 0x3F, + 0x00, 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x1F, 0xF8, 0x0F, 0xFF, 0xF0, 0x00, + 0x0F, 0x80, 0x01, 0xFF, 0x80, 0x0F, 0xFF, 0x00, 0x7F, 0xFE, 0x03, 0x83, + 0xF8, 0x0C, 0x07, 0xF0, 0x60, 0x1F, 0xC3, 0x00, 0x3F, 0x00, 0x00, 0xFC, + 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xC0, 0x00, 0x3E, 0x00, 0x01, 0xF8, 0x00, + 0x07, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x1E, + 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x3C, 0x00, 0x01, 0xE0, 0x00, + 0x0E, 0x00, 0x00, 0x70, 0x06, 0x03, 0x80, 0x10, 0x1C, 0x00, 0xC0, 0xE0, + 0x06, 0x07, 0xFF, 0xF8, 0x3F, 0xFF, 0xE1, 0xFF, 0xFF, 0x0F, 0xFF, 0xFC, + 0x3F, 0xFF, 0xE0, 0x00, 0x0F, 0xC0, 0x00, 0xFF, 0xC0, 0x0F, 0xFF, 0x80, + 0x60, 0xFE, 0x03, 0x01, 0xFC, 0x08, 0x03, 0xF0, 0x00, 0x0F, 0xC0, 0x00, + 0x3F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0xFC, + 0x00, 0x07, 0xC0, 0x00, 0x3E, 0x00, 0x07, 0xF8, 0x00, 0x7F, 0xF0, 0x00, + 0x7F, 0xE0, 0x00, 0x3F, 0xC0, 0x00, 0x7F, 0x00, 0x01, 0xFC, 0x00, 0x03, + 0xF0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xE0, + 0x00, 0x0F, 0x80, 0x00, 0x3C, 0x1C, 0x01, 0xF0, 0xF8, 0x07, 0x83, 0xF0, + 0x3C, 0x0F, 0xE1, 0xE0, 0x1F, 0xFE, 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x00, + 0x07, 0x00, 0x00, 0x07, 0x80, 0x00, 0x07, 0xC0, 0x00, 0x07, 0xE0, 0x00, + 0x07, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x07, 0xFC, 0x00, + 0x06, 0xFC, 0x00, 0x06, 0x7E, 0x00, 0x06, 0x3F, 0x00, 0x06, 0x3F, 0x00, + 0x06, 0x1F, 0x80, 0x06, 0x0F, 0xC0, 0x06, 0x07, 0xE0, 0x03, 0x07, 0xE0, + 0x03, 0x03, 0xF0, 0x03, 0x01, 0xF8, 0x03, 0x01, 0xFC, 0x03, 0x00, 0xFC, + 0x03, 0x00, 0x7E, 0x03, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, + 0xF0, 0xFF, 0xFF, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x07, 0xE0, 0x00, 0x03, + 0xF0, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x3F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, 0x7F, 0xFE, 0x00, + 0x7F, 0xFC, 0x00, 0xFF, 0xFC, 0x00, 0xC0, 0x00, 0x01, 0x80, 0x00, 0x01, + 0x80, 0x00, 0x03, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x07, 0xFE, 0x00, 0x07, + 0xFF, 0x00, 0x07, 0xFF, 0x80, 0x0F, 0xFF, 0xC0, 0x00, 0xFF, 0xE0, 0x00, + 0x1F, 0xE0, 0x00, 0x0F, 0xF0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF0, 0x00, + 0x03, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, + 0x01, 0xE0, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x78, 0x03, 0xC0, 0xFC, + 0x07, 0x80, 0xFC, 0x0F, 0x00, 0xFE, 0x1E, 0x00, 0x7F, 0xF8, 0x00, 0x1F, + 0xC0, 0x00, 0x00, 0x00, 0x0E, 0x00, 0x01, 0xF8, 0x00, 0x0F, 0x80, 0x00, + 0x7E, 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x01, 0xFC, + 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0x3F, 0x80, 0x00, 0xFE, 0x00, + 0x01, 0xFF, 0xF0, 0x07, 0xFF, 0xF0, 0x0F, 0xE1, 0xF0, 0x3F, 0x81, 0xF0, + 0x7F, 0x03, 0xF0, 0xFC, 0x07, 0xE3, 0xF8, 0x0F, 0xC7, 0xF0, 0x1F, 0x8F, + 0xC0, 0x7F, 0x1F, 0x80, 0xFE, 0x3F, 0x01, 0xFC, 0x7C, 0x03, 0xF0, 0xF8, + 0x0F, 0xE1, 0xF0, 0x1F, 0xC1, 0xE0, 0x3F, 0x03, 0xC0, 0xFC, 0x07, 0x81, + 0xF0, 0x07, 0x87, 0xC0, 0x07, 0xFF, 0x00, 0x03, 0xF8, 0x00, 0x0F, 0xFF, + 0xFC, 0x1F, 0xFF, 0xF8, 0x3F, 0xFF, 0xE0, 0xFF, 0xFF, 0xC1, 0xFF, 0xFF, + 0x07, 0x00, 0x1C, 0x08, 0x00, 0x78, 0x30, 0x01, 0xE0, 0x40, 0x03, 0xC0, + 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, + 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x78, 0x00, 0x01, + 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x78, + 0x00, 0x01, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x1E, 0x00, + 0x00, 0x78, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x80, 0x00, + 0x1E, 0x00, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x03, 0xFE, 0x00, 0x3C, 0x78, + 0x03, 0xC1, 0xE0, 0x3C, 0x07, 0x81, 0xE0, 0x3C, 0x1F, 0x01, 0xE0, 0xF8, + 0x0F, 0x07, 0xC0, 0x78, 0x3F, 0x03, 0xC1, 0xF8, 0x3C, 0x0F, 0xE1, 0xE0, + 0x3F, 0x9E, 0x01, 0xFF, 0xC0, 0x07, 0xFC, 0x00, 0x3F, 0xC0, 0x00, 0xFF, + 0x00, 0x1F, 0xFC, 0x03, 0xCF, 0xF0, 0x3C, 0x3F, 0x83, 0xC0, 0xFC, 0x3C, + 0x03, 0xF1, 0xE0, 0x1F, 0x9E, 0x00, 0x7C, 0xF0, 0x03, 0xE7, 0x80, 0x1F, + 0x3C, 0x00, 0xF9, 0xE0, 0x07, 0x87, 0x00, 0x3C, 0x3C, 0x03, 0xC0, 0xF0, + 0x3C, 0x03, 0xC3, 0xC0, 0x07, 0xF0, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0xFF, + 0xE0, 0x03, 0xF1, 0xE0, 0x0F, 0xC1, 0xC0, 0x3F, 0x03, 0xC0, 0xFE, 0x07, + 0x81, 0xF8, 0x0F, 0x87, 0xF0, 0x1F, 0x0F, 0xC0, 0x3E, 0x3F, 0x80, 0xFC, + 0x7F, 0x01, 0xF8, 0xFC, 0x03, 0xF1, 0xF8, 0x07, 0xE3, 0xF0, 0x1F, 0xC7, + 0xE0, 0x3F, 0x8F, 0xC0, 0x7E, 0x0F, 0x81, 0xFC, 0x1F, 0x03, 0xF8, 0x1F, + 0x0F, 0xE0, 0x1F, 0xFF, 0xC0, 0x1F, 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x03, + 0xF8, 0x00, 0x0F, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x7E, 0x00, 0x01, 0xF8, + 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, + 0x1F, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x01, 0xE0, 0x1F, 0x81, 0xFE, 0x0F, + 0xF0, 0x7F, 0x81, 0xF8, 0x07, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x80, 0x7E, 0x07, 0xF8, 0x3F, + 0xC1, 0xFE, 0x07, 0xE0, 0x1E, 0x00, 0x00, 0x78, 0x01, 0xF8, 0x07, 0xF8, + 0x0F, 0xF0, 0x1F, 0xE0, 0x1F, 0x80, 0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x07, 0x80, + 0x1F, 0x80, 0x3F, 0x80, 0x7F, 0x00, 0xFE, 0x00, 0xFC, 0x00, 0xF8, 0x00, + 0xE0, 0x01, 0xC0, 0x07, 0x00, 0x0C, 0x00, 0x30, 0x01, 0xC0, 0x0E, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x07, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x7F, 0x00, 0x03, 0xFF, 0x00, 0x0F, 0xFC, 0x00, 0x3F, 0xF0, + 0x01, 0xFF, 0xC0, 0x07, 0xFE, 0x00, 0x1F, 0xF8, 0x00, 0x7F, 0xE0, 0x00, + 0xFF, 0x80, 0x00, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0xFF, 0xE0, 0x00, + 0x1F, 0xF8, 0x00, 0x07, 0xFE, 0x00, 0x01, 0xFF, 0xC0, 0x00, 0x3F, 0xF0, + 0x00, 0x0F, 0xFC, 0x00, 0x03, 0xFF, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x07, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0x80, 0x00, 0x00, 0xE0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFF, 0x00, 0x00, + 0xFF, 0xC0, 0x00, 0x3F, 0xF0, 0x00, 0x0F, 0xFC, 0x00, 0x03, 0xFF, 0x80, + 0x00, 0x7F, 0xE0, 0x00, 0x1F, 0xF8, 0x00, 0x07, 0xFF, 0x00, 0x00, 0xFF, + 0x00, 0x00, 0x3F, 0x00, 0x00, 0xFF, 0x00, 0x03, 0xFF, 0x00, 0x1F, 0xFC, + 0x00, 0x7F, 0xE0, 0x01, 0xFF, 0x80, 0x0F, 0xFE, 0x00, 0x3F, 0xF0, 0x00, + 0xFF, 0xC0, 0x00, 0xFF, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xE0, 0x00, 0x00, + 0x80, 0x00, 0x00, 0x01, 0xF8, 0x01, 0xFF, 0x80, 0xF1, 0xF0, 0x38, 0x3E, + 0x1E, 0x0F, 0xC7, 0xC3, 0xF1, 0xF0, 0xFC, 0x7C, 0x3F, 0x0E, 0x0F, 0xC0, + 0x07, 0xF0, 0x01, 0xF8, 0x00, 0xFC, 0x00, 0x3F, 0x00, 0x1F, 0x00, 0x07, + 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x00, 0x60, 0x00, 0x30, 0x00, 0x0C, 0x00, + 0x06, 0x00, 0x01, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x03, 0xC0, 0x01, 0xF8, 0x00, 0xFF, 0x00, 0x3F, 0xC0, 0x0F, 0xF0, + 0x01, 0xF8, 0x00, 0x3C, 0x00, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x1F, + 0xFF, 0xC0, 0x00, 0x3F, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x7C, + 0x00, 0x03, 0x80, 0x7C, 0x00, 0x00, 0xE0, 0x7C, 0x00, 0x00, 0x38, 0x3C, + 0x00, 0xF0, 0x4C, 0x3E, 0x00, 0xFD, 0xE7, 0x1E, 0x00, 0xF3, 0xF1, 0x9F, + 0x00, 0xF1, 0xF0, 0xEF, 0x80, 0xF0, 0x78, 0x3F, 0x80, 0xF0, 0x3C, 0x1F, + 0xC0, 0x78, 0x1E, 0x0F, 0xE0, 0x78, 0x1E, 0x07, 0xF0, 0x3C, 0x0F, 0x03, + 0xF8, 0x3E, 0x07, 0x81, 0xFC, 0x1E, 0x07, 0x81, 0xFE, 0x0F, 0x03, 0xC0, + 0xDF, 0x07, 0x83, 0xC0, 0x6F, 0x83, 0xC3, 0xE0, 0x63, 0xE1, 0xF3, 0xF0, + 0x71, 0xF0, 0x7E, 0x78, 0x70, 0xF8, 0x1E, 0x3F, 0xF0, 0x3E, 0x00, 0x07, + 0xE0, 0x0F, 0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x01, 0xF0, 0x00, + 0x00, 0x00, 0x7C, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x03, 0x80, 0x03, 0xF0, + 0x07, 0xC0, 0x00, 0x7F, 0xFF, 0x80, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x00, + 0x00, 0x06, 0x00, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x00, 0x38, 0x00, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, + 0x1F, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x03, + 0x7E, 0x00, 0x00, 0x06, 0xFC, 0x00, 0x00, 0x19, 0xF8, 0x00, 0x00, 0x63, + 0xF8, 0x00, 0x00, 0xC7, 0xF0, 0x00, 0x03, 0x07, 0xE0, 0x00, 0x06, 0x0F, + 0xC0, 0x00, 0x18, 0x1F, 0x80, 0x00, 0x60, 0x3F, 0x00, 0x00, 0xC0, 0x7F, + 0x00, 0x03, 0x00, 0xFE, 0x00, 0x0F, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0xF8, + 0x00, 0x60, 0x03, 0xF0, 0x00, 0xC0, 0x07, 0xE0, 0x03, 0x00, 0x0F, 0xE0, + 0x0E, 0x00, 0x1F, 0xC0, 0x18, 0x00, 0x3F, 0x80, 0x70, 0x00, 0x7F, 0x01, + 0xC0, 0x00, 0xFE, 0x03, 0x80, 0x01, 0xFE, 0x1F, 0x80, 0x07, 0xFE, 0x7F, + 0xC0, 0x3F, 0xFF, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0xFF, 0xFF, 0xE0, 0x00, + 0xFE, 0x1F, 0xE0, 0x01, 0xFC, 0x1F, 0xE0, 0x03, 0xF8, 0x1F, 0xE0, 0x0F, + 0xE0, 0x3F, 0xC0, 0x1F, 0xC0, 0x7F, 0x80, 0x3F, 0x80, 0xFF, 0x00, 0x7F, + 0x01, 0xFE, 0x01, 0xFC, 0x03, 0xF8, 0x03, 0xF8, 0x0F, 0xF0, 0x07, 0xF0, + 0x1F, 0xC0, 0x0F, 0xC0, 0x7F, 0x00, 0x3F, 0x87, 0xF0, 0x00, 0x7F, 0xFF, + 0x00, 0x00, 0xFE, 0x1F, 0xC0, 0x03, 0xF8, 0x0F, 0xE0, 0x07, 0xF0, 0x0F, + 0xE0, 0x0F, 0xE0, 0x1F, 0xC0, 0x1F, 0xC0, 0x3F, 0xC0, 0x7F, 0x00, 0x7F, + 0x80, 0xFE, 0x00, 0xFF, 0x01, 0xFC, 0x01, 0xFE, 0x03, 0xF0, 0x07, 0xFC, + 0x0F, 0xE0, 0x0F, 0xF0, 0x1F, 0xC0, 0x3F, 0xE0, 0x3F, 0x80, 0x7F, 0x80, + 0xFE, 0x01, 0xFE, 0x01, 0xFE, 0x0F, 0xF8, 0x07, 0xFF, 0xFF, 0xC0, 0x3F, + 0xFF, 0xFC, 0x00, 0x00, 0x00, 0x01, 0xFE, 0x08, 0x00, 0x7F, 0xFE, 0xC0, + 0x0F, 0xF0, 0x7E, 0x00, 0xFE, 0x01, 0xF0, 0x1F, 0xE0, 0x07, 0x01, 0xFE, + 0x00, 0x38, 0x1F, 0xE0, 0x00, 0xC0, 0xFE, 0x00, 0x06, 0x0F, 0xF0, 0x00, + 0x30, 0xFF, 0x00, 0x01, 0x07, 0xF8, 0x00, 0x08, 0x7F, 0x80, 0x00, 0x03, + 0xFC, 0x00, 0x00, 0x3F, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x0F, 0xF0, + 0x00, 0x00, 0xFF, 0x80, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, + 0x01, 0xFE, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x03, + 0xFC, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x03, 0xF8, + 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x60, 0x7F, 0x00, 0x06, 0x03, 0xFC, 0x00, + 0x70, 0x0F, 0xE0, 0x07, 0x00, 0x1F, 0xC0, 0xE0, 0x00, 0x7F, 0xFE, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x01, 0xFF, 0xFF, 0x80, 0x00, 0x3F, 0xFF, 0xFE, + 0x00, 0x00, 0xFE, 0x07, 0xF0, 0x00, 0x1F, 0xC0, 0x3F, 0x00, 0x03, 0xF8, + 0x07, 0xF0, 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x1F, 0xC0, 0x07, 0xF0, 0x03, + 0xF8, 0x00, 0xFE, 0x00, 0x7F, 0x00, 0x1F, 0xC0, 0x1F, 0xC0, 0x03, 0xFC, + 0x03, 0xF8, 0x00, 0x7F, 0x80, 0x7F, 0x00, 0x0F, 0xF0, 0x0F, 0xC0, 0x01, + 0xFE, 0x03, 0xF8, 0x00, 0x3F, 0xC0, 0x7F, 0x00, 0x07, 0xF8, 0x0F, 0xE0, + 0x01, 0xFF, 0x03, 0xF8, 0x00, 0x3F, 0xE0, 0x7F, 0x00, 0x07, 0xF8, 0x0F, + 0xE0, 0x00, 0xFF, 0x01, 0xFC, 0x00, 0x3F, 0xE0, 0x7F, 0x00, 0x07, 0xF8, + 0x0F, 0xE0, 0x01, 0xFF, 0x01, 0xFC, 0x00, 0x3F, 0xC0, 0x3F, 0x00, 0x0F, + 0xF0, 0x0F, 0xE0, 0x01, 0xFC, 0x01, 0xFC, 0x00, 0x7F, 0x00, 0x3F, 0x80, + 0x1F, 0xC0, 0x0F, 0xE0, 0x0F, 0xF0, 0x01, 0xFE, 0x07, 0xF8, 0x00, 0x7F, + 0xFF, 0xFC, 0x00, 0x3F, 0xFF, 0xF8, 0x00, 0x00, 0x01, 0xFF, 0xFF, 0xFF, + 0x00, 0x7F, 0xFF, 0xFF, 0x00, 0x3F, 0xC0, 0x7E, 0x00, 0x3F, 0x80, 0x1E, + 0x00, 0x3F, 0x80, 0x0E, 0x00, 0x7F, 0x00, 0x06, 0x00, 0x7F, 0x00, 0x04, + 0x00, 0x7F, 0x00, 0x04, 0x00, 0x7F, 0x00, 0x00, 0x00, 0xFE, 0x01, 0x80, + 0x00, 0xFE, 0x01, 0x00, 0x00, 0xFE, 0x03, 0x00, 0x00, 0xFC, 0x0F, 0x00, + 0x01, 0xFF, 0xFF, 0x00, 0x01, 0xFF, 0xFE, 0x00, 0x01, 0xFC, 0x3E, 0x00, + 0x03, 0xF8, 0x1E, 0x00, 0x03, 0xF8, 0x0C, 0x00, 0x03, 0xF8, 0x0C, 0x00, + 0x03, 0xF8, 0x0C, 0x00, 0x07, 0xF0, 0x08, 0x00, 0x07, 0xF0, 0x00, 0x08, + 0x07, 0xF0, 0x00, 0x18, 0x07, 0xE0, 0x00, 0x30, 0x0F, 0xE0, 0x00, 0x30, + 0x0F, 0xE0, 0x00, 0x70, 0x0F, 0xE0, 0x01, 0xE0, 0x1F, 0xC0, 0x07, 0xE0, + 0x1F, 0xE0, 0x3F, 0xE0, 0x3F, 0xFF, 0xFF, 0xE0, 0xFF, 0xFF, 0xFF, 0xC0, + 0x01, 0xFF, 0xFF, 0xFE, 0x00, 0xFF, 0xFF, 0xFC, 0x00, 0xFF, 0x03, 0xF0, + 0x01, 0xFC, 0x01, 0xE0, 0x03, 0xF8, 0x01, 0xC0, 0x0F, 0xE0, 0x01, 0x80, + 0x1F, 0xC0, 0x02, 0x00, 0x3F, 0x80, 0x04, 0x00, 0x7F, 0x00, 0x00, 0x01, + 0xFC, 0x03, 0x00, 0x03, 0xF8, 0x04, 0x00, 0x07, 0xF0, 0x18, 0x00, 0x0F, + 0xC0, 0xF0, 0x00, 0x3F, 0xFF, 0xE0, 0x00, 0x7F, 0xFF, 0x80, 0x00, 0xFE, + 0x1F, 0x00, 0x03, 0xF8, 0x1E, 0x00, 0x07, 0xF0, 0x18, 0x00, 0x0F, 0xE0, + 0x30, 0x00, 0x1F, 0xC0, 0x60, 0x00, 0x7F, 0x00, 0x80, 0x00, 0xFE, 0x01, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x0F, 0xE0, 0x00, + 0x00, 0x1F, 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0xFF, 0x00, 0x00, + 0x01, 0xFE, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x3F, 0xFF, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xFF, 0x02, 0x00, 0x0F, 0xFF, 0xEE, 0x00, 0x3F, 0xC0, + 0xFC, 0x00, 0x7F, 0x00, 0x7C, 0x01, 0xFE, 0x00, 0x3C, 0x03, 0xFC, 0x00, + 0x38, 0x07, 0xF8, 0x00, 0x18, 0x07, 0xF0, 0x00, 0x18, 0x0F, 0xF0, 0x00, + 0x10, 0x1F, 0xE0, 0x00, 0x10, 0x1F, 0xE0, 0x00, 0x00, 0x3F, 0xC0, 0x00, + 0x00, 0x3F, 0xC0, 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x00, 0x7F, 0x80, 0x00, + 0x00, 0x7F, 0x80, 0x00, 0x00, 0xFF, 0x80, 0x00, 0x00, 0xFF, 0x80, 0x1F, + 0xFF, 0xFF, 0x00, 0x07, 0xFC, 0xFF, 0x00, 0x03, 0xF8, 0xFF, 0x00, 0x03, + 0xF8, 0xFF, 0x00, 0x03, 0xF0, 0xFF, 0x00, 0x03, 0xF0, 0xFF, 0x00, 0x07, + 0xF0, 0x7F, 0x00, 0x07, 0xF0, 0x7F, 0x00, 0x07, 0xE0, 0x7F, 0x80, 0x07, + 0xE0, 0x3F, 0x80, 0x0F, 0xE0, 0x1F, 0xC0, 0x0F, 0xC0, 0x0F, 0xE0, 0x0F, + 0xC0, 0x07, 0xF0, 0x3F, 0x80, 0x01, 0xFF, 0xFE, 0x00, 0x00, 0x3F, 0xE0, + 0x00, 0x01, 0xFF, 0xFC, 0x7F, 0xFE, 0x00, 0xFF, 0xC0, 0x3F, 0xF0, 0x00, + 0xFE, 0x00, 0x3F, 0xC0, 0x01, 0xFC, 0x00, 0x7F, 0x00, 0x03, 0xF8, 0x00, + 0xFE, 0x00, 0x0F, 0xE0, 0x01, 0xFC, 0x00, 0x1F, 0xC0, 0x07, 0xF0, 0x00, + 0x3F, 0x80, 0x0F, 0xE0, 0x00, 0x7F, 0x00, 0x1F, 0xC0, 0x01, 0xFC, 0x00, + 0x7F, 0x00, 0x03, 0xF8, 0x00, 0xFE, 0x00, 0x07, 0xF0, 0x01, 0xFC, 0x00, + 0x0F, 0xC0, 0x03, 0xF8, 0x00, 0x3F, 0x80, 0x0F, 0xE0, 0x00, 0x7F, 0xFF, + 0xFF, 0xC0, 0x00, 0xFF, 0xFF, 0xFF, 0x80, 0x03, 0xF8, 0x00, 0x7F, 0x00, + 0x07, 0xF0, 0x01, 0xFC, 0x00, 0x0F, 0xE0, 0x03, 0xF8, 0x00, 0x1F, 0xC0, + 0x07, 0xF0, 0x00, 0x7F, 0x00, 0x1F, 0xC0, 0x00, 0xFE, 0x00, 0x3F, 0x80, + 0x01, 0xFC, 0x00, 0x7F, 0x00, 0x03, 0xF0, 0x00, 0xFE, 0x00, 0x0F, 0xE0, + 0x03, 0xF8, 0x00, 0x1F, 0xC0, 0x07, 0xF0, 0x00, 0x3F, 0x80, 0x0F, 0xE0, + 0x00, 0xFF, 0x00, 0x3F, 0xC0, 0x01, 0xFE, 0x00, 0x7F, 0x80, 0x07, 0xFC, + 0x01, 0xFF, 0x00, 0x3F, 0xFF, 0x1F, 0xFF, 0xC0, 0x00, 0x01, 0xFF, 0xF8, + 0x03, 0xFE, 0x00, 0x0F, 0xE0, 0x00, 0x7F, 0x00, 0x03, 0xF8, 0x00, 0x3F, + 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xE0, 0x00, 0x7E, 0x00, 0x07, 0xF0, 0x00, + 0x3F, 0x80, 0x01, 0xFC, 0x00, 0x0F, 0xC0, 0x00, 0xFE, 0x00, 0x07, 0xF0, + 0x00, 0x3F, 0x80, 0x03, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0xFE, 0x00, 0x07, + 0xE0, 0x00, 0x7F, 0x00, 0x03, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0xFC, 0x00, + 0x0F, 0xE0, 0x00, 0x7F, 0x00, 0x03, 0xF8, 0x00, 0x3F, 0xC0, 0x01, 0xFC, + 0x00, 0x1F, 0xF0, 0x03, 0xFF, 0xF0, 0x00, 0x00, 0x07, 0xFF, 0xE0, 0x00, + 0x3F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x0F, 0xE0, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x0F, 0xE0, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x3F, + 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, + 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x07, 0xF0, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x07, 0x03, 0xF0, 0x01, 0xF0, 0xFE, 0x00, + 0x3E, 0x1F, 0xC0, 0x07, 0xC3, 0xF0, 0x00, 0xF8, 0xFC, 0x00, 0x0F, 0x3F, + 0x80, 0x00, 0xFF, 0xC0, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x01, 0xFF, 0xF8, + 0xFF, 0xC0, 0x1F, 0xF8, 0x0F, 0xC0, 0x03, 0xF8, 0x01, 0xC0, 0x00, 0xFE, + 0x00, 0xE0, 0x00, 0x3F, 0x80, 0x70, 0x00, 0x1F, 0xC0, 0x38, 0x00, 0x07, + 0xF0, 0x1C, 0x00, 0x01, 0xFC, 0x0E, 0x00, 0x00, 0x7F, 0x07, 0x00, 0x00, + 0x3F, 0x83, 0x80, 0x00, 0x0F, 0xE1, 0xC0, 0x00, 0x03, 0xF8, 0xE0, 0x00, + 0x00, 0xFC, 0x60, 0x00, 0x00, 0x7F, 0x7C, 0x00, 0x00, 0x1F, 0xFF, 0x00, + 0x00, 0x07, 0xFF, 0xE0, 0x00, 0x03, 0xFB, 0xF8, 0x00, 0x00, 0xFE, 0x7F, + 0x00, 0x00, 0x3F, 0x9F, 0xC0, 0x00, 0x0F, 0xE3, 0xF8, 0x00, 0x07, 0xF0, + 0xFE, 0x00, 0x01, 0xFC, 0x1F, 0xC0, 0x00, 0x7F, 0x07, 0xF0, 0x00, 0x1F, + 0x80, 0xFE, 0x00, 0x0F, 0xE0, 0x3F, 0x80, 0x03, 0xF8, 0x0F, 0xE0, 0x00, + 0xFE, 0x01, 0xFC, 0x00, 0x7F, 0x00, 0x7F, 0x00, 0x1F, 0xE0, 0x0F, 0xE0, + 0x0F, 0xF8, 0x07, 0xFC, 0x0F, 0xFF, 0xC7, 0xFF, 0xC0, 0x01, 0xFF, 0xF8, + 0x00, 0x03, 0xFF, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x7F, 0x00, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x0F, + 0xE0, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x3F, 0x80, + 0x00, 0x01, 0xFC, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x00, + 0x07, 0xF0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x7F, 0x00, + 0x00, 0x03, 0xF8, 0x00, 0x04, 0x1F, 0xC0, 0x00, 0x60, 0xFC, 0x00, 0x06, + 0x0F, 0xE0, 0x00, 0x30, 0x7F, 0x00, 0x03, 0x83, 0xF8, 0x00, 0x7C, 0x3F, + 0x80, 0x0F, 0xC1, 0xFE, 0x03, 0xFE, 0x1F, 0xFF, 0xFF, 0xF3, 0xFF, 0xFF, + 0xFF, 0x00, 0x01, 0xFF, 0xC0, 0x00, 0x3F, 0xF0, 0x03, 0xFC, 0x00, 0x03, + 0xFC, 0x00, 0x3F, 0xC0, 0x00, 0x7F, 0x80, 0x03, 0xFC, 0x00, 0x0F, 0xF8, + 0x00, 0x3F, 0xC0, 0x00, 0xFF, 0x80, 0x03, 0xFC, 0x00, 0x1F, 0xF0, 0x00, + 0x6F, 0xC0, 0x03, 0xFF, 0x00, 0x06, 0xFC, 0x00, 0x37, 0xF0, 0x00, 0x6F, + 0xE0, 0x06, 0x7E, 0x00, 0x04, 0xFE, 0x00, 0xEF, 0xE0, 0x00, 0xCF, 0xE0, + 0x0C, 0xFE, 0x00, 0x0C, 0xFE, 0x01, 0x8F, 0xE0, 0x00, 0xCF, 0xE0, 0x38, + 0xFC, 0x00, 0x18, 0x7E, 0x03, 0x1F, 0xC0, 0x01, 0x87, 0xE0, 0x61, 0xFC, + 0x00, 0x18, 0x7E, 0x0E, 0x1F, 0xC0, 0x01, 0x87, 0xE0, 0xC3, 0xF8, 0x00, + 0x30, 0x7F, 0x18, 0x3F, 0x80, 0x03, 0x07, 0xF3, 0x83, 0xF8, 0x00, 0x30, + 0x7F, 0x30, 0x3F, 0x00, 0x06, 0x07, 0xF7, 0x07, 0xF0, 0x00, 0x60, 0x3F, + 0xE0, 0x7F, 0x00, 0x06, 0x03, 0xFC, 0x07, 0xF0, 0x00, 0xE0, 0x3F, 0xC0, + 0x7E, 0x00, 0x0C, 0x03, 0xF8, 0x0F, 0xE0, 0x00, 0xC0, 0x3F, 0x00, 0xFE, + 0x00, 0x0C, 0x03, 0xF0, 0x0F, 0xE0, 0x01, 0xC0, 0x3E, 0x01, 0xFC, 0x00, + 0x1C, 0x03, 0xC0, 0x1F, 0xC0, 0x07, 0xE0, 0x3C, 0x03, 0xFE, 0x00, 0xFF, + 0xC1, 0x81, 0xFF, 0xFC, 0x00, 0x00, 0x10, 0x00, 0x00, 0x00, 0x03, 0xFF, + 0x00, 0x1F, 0xF8, 0x03, 0xF8, 0x00, 0x3F, 0x00, 0x0F, 0xE0, 0x00, 0xF0, + 0x00, 0x7F, 0x00, 0x07, 0x00, 0x03, 0xFC, 0x00, 0x38, 0x00, 0x1F, 0xE0, + 0x01, 0x80, 0x01, 0xBF, 0x80, 0x0C, 0x00, 0x0D, 0xFC, 0x00, 0x60, 0x00, + 0x67, 0xF0, 0x07, 0x00, 0x02, 0x3F, 0x80, 0x30, 0x00, 0x30, 0xFE, 0x01, + 0x80, 0x01, 0x87, 0xF0, 0x0C, 0x00, 0x0C, 0x1F, 0xC0, 0xC0, 0x00, 0xC0, + 0xFE, 0x06, 0x00, 0x06, 0x07, 0xF8, 0x30, 0x00, 0x30, 0x1F, 0xC1, 0x80, + 0x01, 0x80, 0xFF, 0x18, 0x00, 0x18, 0x03, 0xF8, 0xC0, 0x00, 0xC0, 0x1F, + 0xC6, 0x00, 0x06, 0x00, 0x7F, 0x60, 0x00, 0x60, 0x03, 0xFB, 0x00, 0x03, + 0x00, 0x0F, 0xF8, 0x00, 0x18, 0x00, 0x7F, 0xC0, 0x01, 0xC0, 0x01, 0xFC, + 0x00, 0x0C, 0x00, 0x0F, 0xE0, 0x00, 0x60, 0x00, 0x3F, 0x00, 0x03, 0x00, + 0x01, 0xF0, 0x00, 0x38, 0x00, 0x07, 0x80, 0x01, 0xC0, 0x00, 0x3C, 0x00, + 0x3F, 0x00, 0x01, 0xE0, 0x03, 0xFF, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, + 0x30, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x0F, 0xFF, 0x80, 0x00, 0x7E, + 0x1F, 0x80, 0x01, 0xF0, 0x0F, 0x80, 0x0F, 0xC0, 0x1F, 0x80, 0x3F, 0x00, + 0x1F, 0x80, 0xFE, 0x00, 0x3F, 0x03, 0xF8, 0x00, 0x7E, 0x07, 0xF0, 0x00, + 0xFE, 0x1F, 0xC0, 0x01, 0xFC, 0x7F, 0x80, 0x03, 0xF8, 0xFE, 0x00, 0x07, + 0xF3, 0xFC, 0x00, 0x1F, 0xE7, 0xF0, 0x00, 0x3F, 0xDF, 0xE0, 0x00, 0x7F, + 0xBF, 0xC0, 0x00, 0xFE, 0x7F, 0x80, 0x03, 0xFC, 0xFE, 0x00, 0x07, 0xFB, + 0xFC, 0x00, 0x0F, 0xF7, 0xF8, 0x00, 0x3F, 0xCF, 0xF0, 0x00, 0x7F, 0x9F, + 0xC0, 0x00, 0xFE, 0x3F, 0x80, 0x03, 0xFC, 0x7F, 0x00, 0x07, 0xF0, 0xFE, + 0x00, 0x1F, 0xC0, 0xFC, 0x00, 0x3F, 0x81, 0xF8, 0x00, 0xFE, 0x03, 0xF0, + 0x03, 0xF8, 0x03, 0xF0, 0x07, 0xE0, 0x03, 0xE0, 0x1F, 0x00, 0x03, 0xE0, + 0xFC, 0x00, 0x03, 0xFF, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x01, 0xFF, + 0xFF, 0x80, 0x00, 0xFF, 0xFF, 0xE0, 0x00, 0xFE, 0x1F, 0xE0, 0x01, 0xFC, + 0x1F, 0xE0, 0x03, 0xF0, 0x1F, 0xC0, 0x0F, 0xE0, 0x3F, 0xC0, 0x1F, 0xC0, + 0x7F, 0x80, 0x3F, 0x80, 0xFF, 0x00, 0x7E, 0x01, 0xFE, 0x01, 0xFC, 0x03, + 0xFC, 0x03, 0xF8, 0x0F, 0xF8, 0x07, 0xF0, 0x1F, 0xE0, 0x0F, 0xC0, 0x7F, + 0x80, 0x3F, 0x81, 0xFE, 0x00, 0x7F, 0x07, 0xF8, 0x00, 0xFF, 0xFF, 0xC0, + 0x03, 0xFF, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, + 0x1F, 0x80, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x01, + 0xFC, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x0F, 0xE0, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x01, 0xFC, + 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x3F, 0xFF, 0x00, 0x00, 0x00, 0x00, + 0x00, 0xFE, 0x00, 0x00, 0x0F, 0xFF, 0x00, 0x00, 0x7E, 0x1F, 0x80, 0x01, + 0xF0, 0x0F, 0x80, 0x0F, 0xC0, 0x1F, 0x80, 0x3F, 0x80, 0x1F, 0x80, 0xFE, + 0x00, 0x3F, 0x03, 0xF8, 0x00, 0x7E, 0x07, 0xF0, 0x00, 0xFE, 0x1F, 0xC0, + 0x01, 0xFC, 0x7F, 0x80, 0x03, 0xF8, 0xFE, 0x00, 0x07, 0xF3, 0xFC, 0x00, + 0x1F, 0xE7, 0xF8, 0x00, 0x3F, 0xDF, 0xE0, 0x00, 0x7F, 0xBF, 0xC0, 0x00, + 0xFF, 0x7F, 0x80, 0x01, 0xFC, 0xFE, 0x00, 0x07, 0xFB, 0xFC, 0x00, 0x0F, + 0xF7, 0xF8, 0x00, 0x1F, 0xCF, 0xF0, 0x00, 0x7F, 0x9F, 0xC0, 0x00, 0xFE, + 0x3F, 0x80, 0x01, 0xFC, 0x7F, 0x00, 0x07, 0xF0, 0xFE, 0x00, 0x0F, 0xE1, + 0xFC, 0x00, 0x3F, 0x81, 0xF8, 0x00, 0x7E, 0x03, 0xF0, 0x01, 0xF8, 0x03, + 0xE0, 0x07, 0xE0, 0x07, 0xE0, 0x1F, 0x80, 0x03, 0xE0, 0x7E, 0x00, 0x03, + 0xF3, 0xF0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x06, + 0x00, 0x00, 0x00, 0x1C, 0x00, 0x00, 0xC0, 0x7F, 0xE0, 0x03, 0x03, 0xFF, + 0xF8, 0x1C, 0x0F, 0xFF, 0xFF, 0xF0, 0x3F, 0xFF, 0xFF, 0xC0, 0xE0, 0x3F, + 0xFF, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x01, 0xFF, 0xFF, 0xC0, 0x00, 0x7F, + 0xFF, 0xF8, 0x00, 0x3F, 0xC3, 0xFC, 0x00, 0x3F, 0x81, 0xFE, 0x00, 0x3F, + 0x80, 0xFF, 0x00, 0x7F, 0x80, 0xFF, 0x00, 0x7F, 0x00, 0xFF, 0x00, 0x7F, + 0x00, 0xFF, 0x00, 0x7F, 0x00, 0xFF, 0x00, 0xFF, 0x01, 0xFE, 0x00, 0xFE, + 0x01, 0xFE, 0x00, 0xFE, 0x03, 0xFC, 0x00, 0xFE, 0x07, 0xF8, 0x01, 0xFC, + 0x1F, 0xF0, 0x01, 0xFF, 0xFF, 0xC0, 0x01, 0xFF, 0xFE, 0x00, 0x03, 0xFD, + 0xFE, 0x00, 0x03, 0xF8, 0xFF, 0x00, 0x03, 0xF8, 0xFF, 0x00, 0x03, 0xF8, + 0xFF, 0x00, 0x07, 0xF8, 0x7F, 0x80, 0x07, 0xF0, 0x7F, 0x80, 0x07, 0xF0, + 0x3F, 0x80, 0x07, 0xF0, 0x3F, 0xC0, 0x0F, 0xE0, 0x3F, 0xC0, 0x0F, 0xE0, + 0x1F, 0xC0, 0x0F, 0xE0, 0x1F, 0xE0, 0x1F, 0xE0, 0x1F, 0xE0, 0x1F, 0xE0, + 0x0F, 0xF0, 0x3F, 0xF0, 0x0F, 0xF8, 0xFF, 0xFC, 0x0F, 0xFE, 0x00, 0x1F, + 0x83, 0x00, 0x7F, 0xF7, 0x00, 0xF8, 0x7E, 0x01, 0xE0, 0x1E, 0x03, 0xC0, + 0x0E, 0x03, 0xC0, 0x0E, 0x07, 0xC0, 0x0E, 0x07, 0xC0, 0x04, 0x07, 0xC0, + 0x04, 0x07, 0xE0, 0x04, 0x07, 0xF0, 0x00, 0x07, 0xF8, 0x00, 0x03, 0xFC, + 0x00, 0x03, 0xFF, 0x00, 0x01, 0xFF, 0x80, 0x00, 0xFF, 0xC0, 0x00, 0x7F, + 0xE0, 0x00, 0x3F, 0xE0, 0x00, 0x1F, 0xF0, 0x00, 0x0F, 0xF0, 0x00, 0x07, + 0xF8, 0x00, 0x03, 0xF8, 0x00, 0x01, 0xF8, 0x20, 0x00, 0xF8, 0x20, 0x00, + 0xF8, 0x20, 0x00, 0xF8, 0x70, 0x00, 0xF8, 0x70, 0x00, 0xF0, 0x78, 0x01, + 0xF0, 0x78, 0x03, 0xE0, 0x7E, 0x07, 0xC0, 0x47, 0xFF, 0x80, 0xC0, 0xFC, + 0x00, 0x3F, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xFC, 0xFE, 0x3F, 0x8F, 0x9E, + 0x07, 0xF0, 0xF3, 0x81, 0xFC, 0x0E, 0x60, 0x3F, 0x81, 0x98, 0x07, 0xF0, + 0x13, 0x00, 0xFC, 0x02, 0x00, 0x3F, 0x80, 0x40, 0x07, 0xF0, 0x00, 0x00, + 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, + 0x00, 0x1F, 0x80, 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, + 0xC0, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, + 0x03, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xF8, + 0x00, 0x00, 0x7E, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x3F, 0xFF, 0xC0, 0x00, 0x7F, 0xFF, + 0x03, 0xFF, 0x0F, 0xFC, 0x00, 0xFC, 0x07, 0xF0, 0x00, 0x38, 0x07, 0xF0, + 0x00, 0x38, 0x07, 0xF0, 0x00, 0x30, 0x0F, 0xE0, 0x00, 0x30, 0x0F, 0xE0, + 0x00, 0x70, 0x0F, 0xE0, 0x00, 0x60, 0x0F, 0xE0, 0x00, 0x60, 0x1F, 0xC0, + 0x00, 0xE0, 0x1F, 0xC0, 0x00, 0xC0, 0x1F, 0xC0, 0x00, 0xC0, 0x3F, 0x80, + 0x00, 0xC0, 0x3F, 0x80, 0x01, 0x80, 0x3F, 0x80, 0x01, 0x80, 0x3F, 0x80, + 0x01, 0x80, 0x7F, 0x00, 0x01, 0x80, 0x7F, 0x00, 0x03, 0x00, 0x7F, 0x00, + 0x03, 0x00, 0x7E, 0x00, 0x03, 0x00, 0xFE, 0x00, 0x06, 0x00, 0xFE, 0x00, + 0x06, 0x00, 0xFC, 0x00, 0x06, 0x00, 0xFC, 0x00, 0x0E, 0x00, 0xFC, 0x00, + 0x0C, 0x00, 0xFC, 0x00, 0x1C, 0x00, 0xFC, 0x00, 0x18, 0x00, 0x7E, 0x00, + 0x38, 0x00, 0x7E, 0x00, 0x70, 0x00, 0x3F, 0x81, 0xE0, 0x00, 0x0F, 0xFF, + 0x80, 0x00, 0x03, 0xFE, 0x00, 0x00, 0xFF, 0xFC, 0x03, 0xFE, 0x7F, 0xE0, + 0x01, 0xF8, 0x7F, 0x80, 0x01, 0xC0, 0xFF, 0x00, 0x03, 0x80, 0xFE, 0x00, + 0x0E, 0x01, 0xFC, 0x00, 0x18, 0x03, 0xF8, 0x00, 0x70, 0x07, 0xF0, 0x00, + 0xC0, 0x0F, 0xF0, 0x03, 0x80, 0x1F, 0xE0, 0x0E, 0x00, 0x1F, 0xC0, 0x18, + 0x00, 0x3F, 0x80, 0x70, 0x00, 0x7F, 0x00, 0xC0, 0x00, 0xFE, 0x03, 0x00, + 0x01, 0xFC, 0x0E, 0x00, 0x03, 0xF8, 0x18, 0x00, 0x07, 0xF8, 0x60, 0x00, + 0x07, 0xF1, 0xC0, 0x00, 0x0F, 0xE3, 0x00, 0x00, 0x1F, 0xCC, 0x00, 0x00, + 0x3F, 0xB8, 0x00, 0x00, 0x7F, 0x60, 0x00, 0x00, 0xFF, 0xC0, 0x00, 0x00, + 0xFF, 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x07, + 0xE0, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0x00, 0x30, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0xFF, 0xF8, + 0xFF, 0xF0, 0xFF, 0x9F, 0xF8, 0x1F, 0xE0, 0x0F, 0x87, 0xF8, 0x07, 0xE0, + 0x07, 0x03, 0xF8, 0x03, 0xF0, 0x03, 0x80, 0xFE, 0x01, 0xF8, 0x01, 0x80, + 0x7F, 0x00, 0xFC, 0x00, 0xC0, 0x3F, 0x80, 0x7F, 0x00, 0xC0, 0x1F, 0xC0, + 0x7F, 0x80, 0x60, 0x0F, 0xE0, 0x3F, 0xC0, 0x60, 0x07, 0xF0, 0x37, 0xE0, + 0x30, 0x03, 0xF8, 0x1B, 0xF0, 0x30, 0x00, 0xFC, 0x19, 0xF8, 0x18, 0x00, + 0x7E, 0x0C, 0xFE, 0x18, 0x00, 0x3F, 0x84, 0x7F, 0x0C, 0x00, 0x1F, 0xC6, + 0x3F, 0x8C, 0x00, 0x0F, 0xE2, 0x1F, 0xC6, 0x00, 0x07, 0xF3, 0x07, 0xE6, + 0x00, 0x03, 0xF9, 0x83, 0xF3, 0x00, 0x01, 0xFD, 0x81, 0xFB, 0x00, 0x00, + 0x7E, 0xC0, 0xFD, 0x80, 0x00, 0x3F, 0xC0, 0x7F, 0x80, 0x00, 0x1F, 0xE0, + 0x3F, 0xC0, 0x00, 0x0F, 0xE0, 0x1F, 0xC0, 0x00, 0x07, 0xF0, 0x0F, 0xE0, + 0x00, 0x03, 0xF0, 0x07, 0xE0, 0x00, 0x01, 0xF8, 0x01, 0xF0, 0x00, 0x00, + 0x78, 0x00, 0xF0, 0x00, 0x00, 0x3C, 0x00, 0x78, 0x00, 0x00, 0x1C, 0x00, + 0x38, 0x00, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x00, 0x06, 0x00, 0x0C, 0x00, + 0x00, 0x03, 0x00, 0x06, 0x00, 0x00, 0x03, 0xFF, 0xF0, 0xFF, 0xC0, 0x3F, + 0xE0, 0x0F, 0xC0, 0x03, 0xF8, 0x01, 0xE0, 0x00, 0xFE, 0x00, 0xE0, 0x00, + 0x3F, 0x80, 0x70, 0x00, 0x07, 0xE0, 0x18, 0x00, 0x01, 0xFC, 0x0C, 0x00, + 0x00, 0x7F, 0x06, 0x00, 0x00, 0x0F, 0xC3, 0x00, 0x00, 0x03, 0xF9, 0x80, + 0x00, 0x00, 0xFE, 0xC0, 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x07, 0xF8, + 0x00, 0x00, 0x01, 0xFC, 0x00, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x00, 0x0F, + 0xC0, 0x00, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x00, + 0xFF, 0x80, 0x00, 0x00, 0x77, 0xF0, 0x00, 0x00, 0x39, 0xFC, 0x00, 0x00, + 0x1C, 0x3F, 0x00, 0x00, 0x06, 0x0F, 0xE0, 0x00, 0x03, 0x03, 0xF8, 0x00, + 0x01, 0x80, 0x7E, 0x00, 0x00, 0xE0, 0x1F, 0xC0, 0x00, 0x70, 0x07, 0xF0, + 0x00, 0x38, 0x01, 0xFC, 0x00, 0x1E, 0x00, 0x7F, 0x80, 0x1F, 0xC0, 0x1F, + 0xF0, 0x0F, 0xFC, 0x3F, 0xFF, 0x80, 0xFF, 0xF8, 0x3F, 0xF3, 0xFC, 0x00, + 0xFC, 0x1F, 0xC0, 0x07, 0x81, 0xFC, 0x00, 0x70, 0x0F, 0xC0, 0x0E, 0x00, + 0xFE, 0x00, 0xC0, 0x0F, 0xE0, 0x1C, 0x00, 0x7E, 0x03, 0x80, 0x07, 0xF0, + 0x30, 0x00, 0x7F, 0x06, 0x00, 0x03, 0xF0, 0xE0, 0x00, 0x3F, 0x8C, 0x00, + 0x03, 0xF9, 0x80, 0x00, 0x1F, 0xB0, 0x00, 0x01, 0xFF, 0x00, 0x00, 0x1F, + 0xE0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x1F, 0x80, 0x00, 0x03, 0xF8, 0x00, 0x00, 0x3F, 0x80, 0x00, 0x03, + 0xF8, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x7F, 0x00, + 0x00, 0x07, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x01, + 0xFF, 0x00, 0x00, 0xFF, 0xFE, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xF0, 0x3F, + 0xFF, 0xFF, 0x03, 0xF8, 0x0F, 0xF0, 0x7C, 0x01, 0xFE, 0x07, 0x80, 0x3F, + 0xC0, 0x70, 0x03, 0xF8, 0x06, 0x00, 0x7F, 0x80, 0xC0, 0x0F, 0xF0, 0x08, + 0x01, 0xFE, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x7F, + 0x80, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, 0xE0, 0x00, + 0x03, 0xFC, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x07, 0xF8, 0x00, 0x00, 0xFF, + 0x00, 0x00, 0x1F, 0xE0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0x3F, 0xC0, 0x00, + 0x07, 0xF8, 0x00, 0xC0, 0xFF, 0x00, 0x0C, 0x1F, 0xE0, 0x01, 0x81, 0xFE, + 0x00, 0x38, 0x3F, 0xC0, 0x07, 0x87, 0xF8, 0x01, 0xF0, 0xFF, 0x00, 0xFF, + 0x0F, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x7F, 0xE0, 0x0F, + 0xFC, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, + 0x00, 0x07, 0x80, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF0, + 0x00, 0x1E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1E, 0x00, 0x03, 0xC0, + 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x1F, 0x00, + 0x03, 0xE0, 0x00, 0x78, 0x00, 0x0F, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, + 0x0F, 0x00, 0x01, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xE0, 0x00, + 0x3C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xFE, 0x01, + 0xFF, 0xC0, 0x00, 0xF0, 0x07, 0x80, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x1C, + 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xE0, + 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x07, 0x00, 0x3C, 0x01, 0xE0, 0x0F, 0x00, + 0x3C, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x01, 0xE0, 0x0F, 0x00, 0x78, 0x01, + 0xC0, 0x0F, 0x00, 0x78, 0x03, 0xC0, 0x0F, 0x00, 0x78, 0x00, 0x7F, 0xE0, + 0x0F, 0xFC, 0x00, 0x0F, 0x80, 0x01, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, + 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, + 0x07, 0x80, 0x01, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF0, 0x00, + 0x3E, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x1E, 0x00, 0x07, 0xC0, 0x00, + 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xC0, 0x00, 0xF8, 0x00, 0x1F, 0x00, 0x03, + 0xE0, 0x00, 0x78, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x0F, + 0x00, 0x01, 0xE0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, 0xE0, 0x07, 0xFC, + 0x01, 0xFF, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0x00, 0x7F, 0x00, + 0x03, 0xF8, 0x00, 0x3F, 0xC0, 0x01, 0xEF, 0x00, 0x1E, 0x78, 0x00, 0xF1, + 0xE0, 0x0F, 0x0F, 0x00, 0x78, 0x3C, 0x07, 0xC1, 0xE0, 0x3C, 0x07, 0x83, + 0xE0, 0x3C, 0x1E, 0x00, 0xF1, 0xF0, 0x07, 0x8F, 0x00, 0x1E, 0xF8, 0x00, + 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x70, 0x3E, + 0x0F, 0x83, 0xF0, 0x3E, 0x07, 0x80, 0xF0, 0x0E, 0x01, 0xC0, 0x00, 0x3C, + 0x0C, 0x03, 0xF9, 0xF0, 0x1F, 0x3F, 0x80, 0xF8, 0x7E, 0x07, 0xC1, 0xF8, + 0x3F, 0x07, 0xC0, 0xF8, 0x1F, 0x07, 0xE0, 0x7C, 0x3F, 0x01, 0xF0, 0xFC, + 0x0F, 0x87, 0xE0, 0x3E, 0x1F, 0x80, 0xF8, 0x7E, 0x03, 0xC3, 0xF8, 0x1F, + 0x0F, 0xC0, 0x7C, 0x3F, 0x03, 0xF0, 0xFC, 0x0F, 0x83, 0xF0, 0x7E, 0x3F, + 0xC2, 0xF8, 0xBF, 0x9B, 0xE4, 0x7F, 0xCF, 0xE0, 0xFE, 0x3F, 0x01, 0xE0, + 0x78, 0x00, 0x00, 0x7C, 0x00, 0x3F, 0xF0, 0x00, 0x1F, 0x80, 0x00, 0x7E, + 0x00, 0x01, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x00, 0x00, 0x7C, 0x00, + 0x03, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x3E, 0x3E, 0x01, 0xF9, 0xFC, 0x07, + 0xEF, 0xF8, 0x1F, 0x47, 0xF0, 0x7E, 0x0F, 0xC3, 0xF8, 0x3F, 0x0F, 0xC0, + 0xFC, 0x3F, 0x03, 0xF1, 0xF8, 0x0F, 0xC7, 0xE0, 0x3F, 0x1F, 0x01, 0xF8, + 0x7C, 0x07, 0xE3, 0xF0, 0x1F, 0x8F, 0xC0, 0xFC, 0x3E, 0x03, 0xF1, 0xF8, + 0x0F, 0x87, 0xE0, 0x7C, 0x1F, 0x03, 0xE0, 0xFC, 0x0F, 0x03, 0xF0, 0x78, + 0x0F, 0xC7, 0xC0, 0x1F, 0xFE, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x3F, 0x00, + 0x3F, 0xE0, 0x1E, 0x3C, 0x0F, 0x0F, 0x07, 0x87, 0xC3, 0xE1, 0xF1, 0xF0, + 0x38, 0xFC, 0x00, 0x3E, 0x00, 0x1F, 0x80, 0x07, 0xE0, 0x01, 0xF8, 0x00, + 0xFC, 0x00, 0x3F, 0x00, 0x0F, 0xC0, 0x03, 0xF0, 0x00, 0xFC, 0x03, 0x3F, + 0x00, 0xCF, 0xE0, 0x61, 0xFC, 0x70, 0x3F, 0xF8, 0x07, 0xFC, 0x00, 0xFC, + 0x00, 0x00, 0x00, 0x00, 0x80, 0x00, 0x0F, 0xC0, 0x00, 0x7F, 0xE0, 0x00, + 0x07, 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x01, 0xF8, 0x00, 0x00, 0xFC, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x1F, 0x80, + 0x07, 0x9F, 0x80, 0x0F, 0xFF, 0xC0, 0x0F, 0x9F, 0xE0, 0x0F, 0x87, 0xF0, + 0x0F, 0x83, 0xF0, 0x0F, 0xC1, 0xF8, 0x07, 0xC0, 0xFC, 0x07, 0xE0, 0x7C, + 0x07, 0xE0, 0x7E, 0x03, 0xF0, 0x3F, 0x03, 0xF0, 0x1F, 0x81, 0xF8, 0x0F, + 0x80, 0xFC, 0x0F, 0xC0, 0xFE, 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0x3F, 0x03, + 0xF0, 0x1F, 0x83, 0xF8, 0x0F, 0xC1, 0xF8, 0xC7, 0xE1, 0xFC, 0xC3, 0xF9, + 0xBE, 0xC0, 0xFF, 0x9F, 0xC0, 0x7F, 0x8F, 0xC0, 0x0F, 0x83, 0xC0, 0x00, + 0x00, 0x3F, 0x00, 0x3F, 0xE0, 0x1E, 0x3C, 0x0F, 0x0F, 0x07, 0x83, 0xC3, + 0xE0, 0xF1, 0xF0, 0x3C, 0xFC, 0x1E, 0x3F, 0x0F, 0x9F, 0x83, 0xC7, 0xE3, + 0xE1, 0xFB, 0xE0, 0xFF, 0xE0, 0x3F, 0xC0, 0x0F, 0xC0, 0x03, 0xF0, 0x00, + 0xFC, 0x03, 0x3F, 0x01, 0x8F, 0xC0, 0xC1, 0xF8, 0x70, 0x7F, 0xF8, 0x07, + 0xFC, 0x00, 0xFC, 0x00, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x03, 0xCE, 0x00, + 0x00, 0x78, 0xF0, 0x00, 0x0F, 0x8F, 0x00, 0x00, 0xF0, 0xF0, 0x00, 0x1F, + 0x06, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x03, 0xFF, 0xC0, 0x00, 0x3F, + 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x01, + 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x3F, 0x00, + 0x00, 0x03, 0xF0, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x07, 0xC0, + 0x00, 0x00, 0xFC, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x01, 0xF0, 0x00, 0x06, 0x1F, 0x00, 0x00, 0xF1, 0xE0, + 0x00, 0x0F, 0x3E, 0x00, 0x00, 0xF3, 0xC0, 0x00, 0x07, 0xF8, 0x00, 0x00, + 0x3E, 0x00, 0x00, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x7F, 0xF0, 0x00, 0x7E, + 0x3F, 0xE0, 0x7C, 0x0F, 0xF0, 0x7E, 0x07, 0xC0, 0x7E, 0x03, 0xE0, 0x3F, + 0x01, 0xF0, 0x1F, 0x01, 0xF8, 0x0F, 0x80, 0xFC, 0x07, 0xC0, 0xFC, 0x01, + 0xE0, 0xFC, 0x00, 0x78, 0xFC, 0x00, 0x1F, 0xFC, 0x00, 0x0F, 0xF0, 0x00, + 0x1C, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x0F, 0xF8, 0x00, + 0x07, 0xFF, 0x80, 0x01, 0xFF, 0xF8, 0x00, 0x7F, 0xFE, 0x00, 0x77, 0xFF, + 0x80, 0xF0, 0x7F, 0xC0, 0xF0, 0x07, 0xE0, 0xF0, 0x01, 0xF0, 0x78, 0x00, + 0xF8, 0x3C, 0x00, 0x78, 0x1F, 0x00, 0x7C, 0x07, 0xC0, 0x78, 0x01, 0xFF, + 0xF8, 0x00, 0x1F, 0xE0, 0x00, 0x00, 0x04, 0x00, 0x01, 0xF8, 0x00, 0x1F, + 0xF0, 0x00, 0x07, 0xE0, 0x00, 0x0F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x7E, + 0x00, 0x00, 0xFC, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x0F, 0xC0, + 0x00, 0x1F, 0x87, 0xC0, 0x3E, 0x1F, 0xC0, 0xFC, 0x7F, 0x81, 0xF9, 0x9F, + 0x03, 0xE6, 0x3E, 0x07, 0xD8, 0x7C, 0x1F, 0xA0, 0xF8, 0x3F, 0x83, 0xF0, + 0x7F, 0x07, 0xE0, 0xFC, 0x0F, 0xC3, 0xF8, 0x3F, 0x07, 0xE0, 0x7E, 0x0F, + 0xC0, 0xFC, 0x3F, 0x03, 0xF0, 0x7E, 0x07, 0xE0, 0xFC, 0x0F, 0xC1, 0xF0, + 0x3F, 0x17, 0xE0, 0x7E, 0x6F, 0xC0, 0xF9, 0x9F, 0x01, 0xF6, 0x3E, 0x03, + 0xF8, 0xFC, 0x07, 0xF1, 0xC0, 0x07, 0x80, 0x01, 0xE0, 0x3F, 0x03, 0xF0, + 0x3F, 0x03, 0xF0, 0x1E, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0xC7, + 0xFC, 0x1F, 0xC0, 0xF8, 0x0F, 0x81, 0xF8, 0x1F, 0x81, 0xF0, 0x1F, 0x03, + 0xF0, 0x3E, 0x03, 0xE0, 0x3E, 0x07, 0xE0, 0x7C, 0x07, 0xC0, 0xFC, 0x2F, + 0x84, 0xF8, 0xCF, 0x98, 0xFF, 0x0F, 0xE0, 0x78, 0x00, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xFC, 0x00, + 0x01, 0xE0, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x01, 0x00, 0x00, 0xFC, 0x00, 0x1F, 0xF0, 0x00, 0x1F, 0xC0, + 0x00, 0x3E, 0x00, 0x01, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x80, 0x00, + 0x7C, 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xF8, + 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x7E, 0x00, 0x01, 0xF0, 0x00, + 0x0F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xE0, 0x00, 0x1F, + 0x80, 0x00, 0x7E, 0x00, 0x01, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x3F, 0x00, + 0x60, 0xF8, 0x03, 0xC3, 0xC0, 0x0F, 0x1F, 0x00, 0x3C, 0xF8, 0x00, 0x7F, + 0xC0, 0x00, 0xFC, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0xFC, 0x00, 0x07, + 0xFC, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xF8, 0x00, 0x01, + 0xF8, 0x00, 0x01, 0xF8, 0x00, 0x01, 0xF0, 0x00, 0x01, 0xF0, 0x00, 0x03, + 0xF0, 0x00, 0x03, 0xF0, 0x00, 0x03, 0xE3, 0xFF, 0x03, 0xE0, 0xFC, 0x07, + 0xE0, 0xF0, 0x07, 0xE0, 0xE0, 0x07, 0xC1, 0xC0, 0x0F, 0xC3, 0x80, 0x0F, + 0xC7, 0x00, 0x0F, 0x8E, 0x00, 0x0F, 0xBE, 0x00, 0x1F, 0xFE, 0x00, 0x1F, + 0xFE, 0x00, 0x1F, 0xFE, 0x00, 0x1F, 0x3E, 0x00, 0x3F, 0x3F, 0x00, 0x3F, + 0x1F, 0x00, 0x3E, 0x1F, 0x00, 0x7E, 0x1F, 0x04, 0x7E, 0x1F, 0x8C, 0x7E, + 0x0F, 0x98, 0x7C, 0x0F, 0xF0, 0xFC, 0x07, 0xE0, 0xE0, 0x03, 0xC0, 0x00, + 0x08, 0x0F, 0xC7, 0xFE, 0x07, 0xF0, 0x3F, 0x01, 0xF8, 0x0F, 0xC0, 0x7C, + 0x07, 0xE0, 0x3F, 0x01, 0xF8, 0x0F, 0x80, 0x7C, 0x07, 0xE0, 0x3E, 0x01, + 0xF0, 0x1F, 0x80, 0xFC, 0x07, 0xC0, 0x3E, 0x03, 0xF0, 0x1F, 0x80, 0xF8, + 0x0F, 0xC0, 0x7E, 0x03, 0xE0, 0x1F, 0x00, 0xF8, 0x8F, 0x8C, 0x7C, 0x43, + 0xE4, 0x1F, 0xE0, 0xFE, 0x03, 0xC0, 0x00, 0x00, 0x70, 0x78, 0x0F, 0x83, + 0xFE, 0x3F, 0x87, 0xF8, 0x1F, 0xCF, 0xF1, 0xFF, 0x03, 0xF1, 0x3E, 0x73, + 0xE0, 0x7E, 0x47, 0xD8, 0x7C, 0x0F, 0xD0, 0xFB, 0x1F, 0x81, 0xF4, 0x3E, + 0xC3, 0xF0, 0x3E, 0x87, 0xF0, 0x7C, 0x0F, 0xE0, 0xFE, 0x1F, 0x81, 0xF4, + 0x1F, 0x83, 0xF0, 0x3F, 0x07, 0xE0, 0x7C, 0x07, 0xE0, 0xFC, 0x1F, 0x81, + 0xF8, 0x1F, 0x83, 0xF0, 0x3F, 0x07, 0xE0, 0x7C, 0x07, 0xE0, 0xFC, 0x0F, + 0x80, 0xF8, 0x1F, 0x03, 0xF0, 0x3F, 0x07, 0xE0, 0x7E, 0x07, 0xE0, 0xFC, + 0x0F, 0x88, 0xF8, 0x1F, 0x81, 0xF3, 0x3F, 0x03, 0xE0, 0x3E, 0x47, 0xE0, + 0xFC, 0x07, 0xF0, 0xFC, 0x1F, 0x80, 0xFE, 0x18, 0x00, 0x00, 0x0F, 0x00, + 0x00, 0x70, 0xF8, 0x7F, 0xC3, 0xF8, 0x1F, 0x8F, 0xF0, 0x3F, 0x33, 0xE0, + 0x7C, 0x87, 0xC1, 0xF9, 0x0F, 0x83, 0xF4, 0x1F, 0x07, 0xD0, 0x3E, 0x0F, + 0xE0, 0xFC, 0x3F, 0x81, 0xF8, 0x7F, 0x03, 0xE0, 0xFC, 0x0F, 0xC1, 0xF8, + 0x1F, 0x87, 0xE0, 0x3E, 0x0F, 0xC0, 0xFC, 0x1F, 0x81, 0xF0, 0x3E, 0x03, + 0xE0, 0xFC, 0x0F, 0xC9, 0xF8, 0x1F, 0x33, 0xE0, 0x3E, 0x47, 0xC0, 0x7F, + 0x1F, 0x80, 0xFE, 0x38, 0x00, 0xF0, 0x00, 0x00, 0x3F, 0x00, 0x0E, 0x38, + 0x03, 0xC1, 0xC0, 0x78, 0x1E, 0x0F, 0x81, 0xF0, 0xF0, 0x1F, 0x1F, 0x01, + 0xF3, 0xE0, 0x1F, 0x3E, 0x03, 0xF7, 0xC0, 0x3F, 0x7C, 0x03, 0xF7, 0xC0, + 0x3E, 0xFC, 0x03, 0xEF, 0xC0, 0x7E, 0xF8, 0x07, 0xCF, 0x80, 0x7C, 0xF8, + 0x0F, 0x8F, 0x80, 0xF8, 0xF8, 0x1F, 0x07, 0x81, 0xE0, 0x78, 0x3C, 0x03, + 0xC7, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0x0F, 0x1F, 0x00, 0x3F, 0xE7, 0xF8, + 0x01, 0xF9, 0xFF, 0x00, 0x1F, 0x47, 0xF0, 0x07, 0xF0, 0x7E, 0x00, 0xFE, + 0x0F, 0xC0, 0x1F, 0x81, 0xF8, 0x03, 0xF0, 0x3F, 0x00, 0xFC, 0x07, 0xE0, + 0x1F, 0x81, 0xFC, 0x03, 0xE0, 0x3F, 0x00, 0x7C, 0x07, 0xE0, 0x1F, 0x81, + 0xFC, 0x03, 0xF0, 0x3F, 0x00, 0x7C, 0x07, 0xE0, 0x0F, 0x81, 0xF8, 0x03, + 0xF0, 0x3E, 0x00, 0x7E, 0x0F, 0xC0, 0x0F, 0x81, 0xF0, 0x01, 0xF0, 0x7C, + 0x00, 0x7F, 0x1F, 0x00, 0x0F, 0xFF, 0xC0, 0x01, 0xF3, 0xE0, 0x00, 0x3E, + 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x3E, 0x00, 0x00, + 0x0F, 0xC0, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x3F, 0xFC, + 0x00, 0x00, 0x00, 0x3E, 0x00, 0x03, 0xF9, 0xF0, 0x1F, 0x1F, 0xC0, 0xF8, + 0x7E, 0x07, 0xC1, 0xF8, 0x3F, 0x07, 0xE0, 0xF8, 0x1F, 0x87, 0xE0, 0x7C, + 0x3F, 0x01, 0xF0, 0xFC, 0x0F, 0xC7, 0xE0, 0x3E, 0x1F, 0x80, 0xF8, 0x7E, + 0x07, 0xE3, 0xF0, 0x1F, 0x8F, 0xC0, 0x7C, 0x3F, 0x03, 0xF0, 0xFC, 0x0F, + 0xC3, 0xF0, 0x7E, 0x0F, 0xC3, 0xF8, 0x3F, 0x9B, 0xE0, 0x7F, 0xDF, 0x01, + 0xFE, 0x7C, 0x01, 0xF1, 0xF0, 0x00, 0x0F, 0xC0, 0x00, 0x3E, 0x00, 0x00, + 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x7C, 0x00, 0x03, 0xF8, + 0x00, 0x7F, 0xF8, 0x00, 0x00, 0x71, 0xE1, 0xFF, 0x3E, 0x07, 0xE7, 0xF0, + 0x7E, 0xFF, 0x07, 0xE9, 0xE0, 0x7D, 0x0E, 0x07, 0xD0, 0x00, 0xFE, 0x00, + 0x0F, 0xE0, 0x00, 0xFC, 0x00, 0x0F, 0xC0, 0x01, 0xFC, 0x00, 0x1F, 0x80, + 0x01, 0xF8, 0x00, 0x1F, 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x03, 0xF0, + 0x00, 0x7E, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x07, 0xC0, 0x00, 0x01, + 0xF1, 0x07, 0xFF, 0x0F, 0x0F, 0x0E, 0x07, 0x1E, 0x06, 0x1E, 0x06, 0x1F, + 0x02, 0x1F, 0x02, 0x1F, 0x80, 0x0F, 0xC0, 0x0F, 0xE0, 0x0F, 0xF0, 0x07, + 0xF8, 0x03, 0xF8, 0x01, 0xFC, 0x00, 0xFC, 0x40, 0x7C, 0x40, 0x7C, 0x60, + 0x3C, 0xE0, 0x38, 0xF0, 0x38, 0xF8, 0xF0, 0xDF, 0xC0, 0x00, 0x20, 0x03, + 0x00, 0x38, 0x03, 0x80, 0x3C, 0x03, 0xE0, 0x7F, 0x07, 0xFF, 0x3F, 0xF8, + 0x7C, 0x07, 0xE0, 0x3F, 0x01, 0xF0, 0x0F, 0x80, 0xFC, 0x07, 0xC0, 0x3E, + 0x03, 0xF0, 0x1F, 0x80, 0xF8, 0x07, 0xC0, 0x7E, 0x03, 0xF1, 0x1F, 0x08, + 0xF8, 0x87, 0xC8, 0x3F, 0xC1, 0xFC, 0x07, 0x80, 0x00, 0x00, 0x40, 0x00, + 0x1F, 0x03, 0xF7, 0xF8, 0x0F, 0x87, 0xE0, 0x3E, 0x1F, 0x81, 0xF8, 0x7E, + 0x07, 0xC1, 0xF0, 0x1F, 0x07, 0xC0, 0xFC, 0x3F, 0x03, 0xE0, 0xF8, 0x0F, + 0x83, 0xE0, 0x7E, 0x0F, 0x81, 0xF8, 0x7E, 0x0F, 0xC1, 0xF0, 0x3F, 0x07, + 0xC1, 0xFC, 0x1F, 0x07, 0xE0, 0xF8, 0x2F, 0x83, 0xE1, 0x3C, 0x6F, 0x8D, + 0xF1, 0x3E, 0x67, 0xC8, 0xFF, 0x1F, 0xE3, 0xF8, 0x7F, 0x07, 0xC0, 0xF0, + 0x00, 0x06, 0x07, 0x1F, 0x07, 0xBF, 0x83, 0xE7, 0xC1, 0xF3, 0xE0, 0xF9, + 0xF8, 0x3C, 0x7C, 0x0C, 0x3E, 0x06, 0x1F, 0x03, 0x0F, 0x83, 0x07, 0xC1, + 0x83, 0xE1, 0x81, 0xF1, 0x80, 0xF9, 0x80, 0x7C, 0xC0, 0x3E, 0xC0, 0x1F, + 0xC0, 0x0F, 0xC0, 0x07, 0xC0, 0x03, 0xC0, 0x01, 0xC0, 0x00, 0xC0, 0x00, + 0x40, 0x00, 0x06, 0x01, 0x81, 0xC7, 0xC0, 0x30, 0x7F, 0xF8, 0x0E, 0x0F, + 0x9F, 0x01, 0xC1, 0xF3, 0xE0, 0x78, 0x3E, 0x7C, 0x1F, 0x03, 0xCF, 0xC3, + 0xE0, 0x30, 0xF8, 0xFC, 0x06, 0x1F, 0x1F, 0xC0, 0x83, 0xE7, 0xF8, 0x30, + 0x7C, 0xFF, 0x04, 0x0F, 0xB7, 0xE1, 0x81, 0xF6, 0xFC, 0x60, 0x3F, 0x8F, + 0x98, 0x07, 0xE1, 0xF3, 0x00, 0xFC, 0x3E, 0xC0, 0x1F, 0x07, 0xF0, 0x03, + 0xE0, 0xFC, 0x00, 0x78, 0x1F, 0x80, 0x0F, 0x03, 0xE0, 0x01, 0xC0, 0x78, + 0x00, 0x30, 0x0E, 0x00, 0x06, 0x01, 0x80, 0x00, 0x00, 0xF0, 0x1E, 0x0F, + 0xF0, 0x3E, 0x01, 0xF8, 0x7F, 0x01, 0xF8, 0xFF, 0x00, 0xF9, 0x8E, 0x00, + 0xFB, 0x00, 0x00, 0xFF, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x7C, 0x00, 0x00, + 0x7C, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0xFE, 0x00, 0x01, 0xBF, 0x00, 0x01, + 0xBF, 0x08, 0x73, 0x1F, 0x18, 0xFF, 0x1F, 0x30, 0xFE, 0x1F, 0xE0, 0xFC, + 0x0F, 0xC0, 0x78, 0x07, 0x80, 0x00, 0x30, 0x1C, 0x0F, 0xF0, 0x7C, 0x07, + 0xE0, 0xF8, 0x0F, 0xC1, 0xF0, 0x0F, 0xC1, 0xE0, 0x1F, 0x81, 0xC0, 0x3F, + 0x03, 0x00, 0x3E, 0x06, 0x00, 0x7E, 0x08, 0x00, 0xFC, 0x30, 0x01, 0xF8, + 0x60, 0x01, 0xF1, 0x80, 0x03, 0xE3, 0x00, 0x07, 0xCC, 0x00, 0x0F, 0xD8, + 0x00, 0x1F, 0xE0, 0x00, 0x1F, 0xC0, 0x00, 0x3F, 0x00, 0x00, 0x7E, 0x00, + 0x00, 0xF8, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x07, 0x00, 0x00, + 0x0C, 0x00, 0x00, 0x18, 0x00, 0x00, 0x60, 0x01, 0xC1, 0x80, 0x07, 0xE6, + 0x00, 0x0F, 0xF8, 0x00, 0x1F, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0x00, 0x07, + 0xFF, 0xE1, 0xFF, 0xF8, 0x3F, 0xFF, 0x07, 0xFF, 0xC0, 0x80, 0x70, 0x30, + 0x1C, 0x04, 0x07, 0x00, 0x00, 0xC0, 0x00, 0x38, 0x00, 0x0E, 0x00, 0x03, + 0x80, 0x00, 0x60, 0x00, 0x18, 0x00, 0x06, 0x00, 0x01, 0xC0, 0x00, 0x30, + 0x00, 0x0C, 0x00, 0x03, 0xE0, 0x00, 0xFE, 0x00, 0x1F, 0xE0, 0xC7, 0xFC, + 0x3D, 0xCF, 0xC7, 0x90, 0xF8, 0xF0, 0x07, 0x9C, 0x00, 0x3E, 0x00, 0x00, + 0x01, 0xF0, 0x00, 0xFC, 0x00, 0x1F, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, + 0x07, 0xC0, 0x00, 0x78, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, 0x80, + 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x03, 0xE0, + 0x00, 0x3E, 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x0F, 0xC0, + 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, + 0x80, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x03, + 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, + 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7E, 0x00, + 0x03, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, + 0x3E, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xE0, + 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x7C, 0x00, 0x07, 0xC0, 0x00, 0x7C, + 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, 0x0F, + 0x80, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x00, + 0xF8, 0x00, 0x03, 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x03, 0xE0, 0x00, + 0x7C, 0x00, 0x07, 0xC0, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x00, 0xF8, 0x00, + 0x0F, 0x80, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, + 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x07, 0xC0, 0x00, 0x7C, 0x00, 0x0F, 0x80, + 0x03, 0xF0, 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x03, 0xFF, 0x01, 0x3F, + 0xFE, 0x1D, 0xFF, 0xFF, 0xFE, 0x0F, 0xFF, 0x00, 0x1F, 0xF0, 0x00, 0x1F, + 0x00 }; + +const GFXglyph FreeSerifBoldItalic24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 12, 0, 1 }, // 0x20 ' ' + { 0, 15, 33, 18, 3, -31 }, // 0x21 '!' + { 62, 19, 13, 26, 6, -31 }, // 0x22 '"' + { 93, 27, 33, 23, -2, -32 }, // 0x23 '#' + { 205, 24, 39, 24, -1, -33 }, // 0x24 '$' + { 322, 35, 32, 39, 2, -30 }, // 0x25 '%' + { 462, 33, 33, 37, 0, -31 }, // 0x26 '&' + { 599, 7, 13, 13, 6, -31 }, // 0x27 ''' + { 611, 14, 41, 16, 1, -31 }, // 0x28 '(' + { 683, 14, 41, 16, -2, -31 }, // 0x29 ')' + { 755, 19, 20, 23, 3, -31 }, // 0x2A '*' + { 803, 22, 23, 27, 2, -22 }, // 0x2B '+' + { 867, 10, 15, 12, -3, -5 }, // 0x2C ',' + { 886, 12, 5, 16, 0, -12 }, // 0x2D '-' + { 894, 8, 7, 12, 0, -5 }, // 0x2E '.' + { 901, 19, 33, 16, 0, -31 }, // 0x2F '/' + { 980, 22, 33, 23, 1, -31 }, // 0x30 '0' + { 1071, 20, 32, 23, 0, -31 }, // 0x31 '1' + { 1151, 22, 32, 23, 1, -31 }, // 0x32 '2' + { 1239, 22, 33, 24, 0, -31 }, // 0x33 '3' + { 1330, 25, 32, 23, 0, -31 }, // 0x34 '4' + { 1430, 24, 32, 24, 0, -30 }, // 0x35 '5' + { 1526, 23, 32, 24, 1, -30 }, // 0x36 '6' + { 1618, 23, 31, 23, 3, -30 }, // 0x37 '7' + { 1708, 21, 33, 23, 1, -31 }, // 0x38 '8' + { 1795, 23, 33, 23, 0, -31 }, // 0x39 '9' + { 1890, 13, 22, 12, 0, -20 }, // 0x3A ':' + { 1926, 15, 30, 12, -2, -20 }, // 0x3B ';' + { 1983, 24, 25, 27, 1, -23 }, // 0x3C '<' + { 2058, 24, 14, 27, 3, -18 }, // 0x3D '=' + { 2100, 24, 25, 27, 3, -23 }, // 0x3E '>' + { 2175, 18, 33, 24, 4, -31 }, // 0x3F '?' + { 2250, 33, 33, 39, 3, -31 }, // 0x40 '@' + { 2387, 31, 32, 33, 0, -31 }, // 0x41 'A' + { 2511, 31, 31, 30, 0, -30 }, // 0x42 'B' + { 2632, 29, 33, 29, 2, -31 }, // 0x43 'C' + { 2752, 35, 31, 34, 0, -30 }, // 0x44 'D' + { 2888, 32, 31, 30, 0, -30 }, // 0x45 'E' + { 3012, 31, 31, 29, 0, -30 }, // 0x46 'F' + { 3133, 32, 33, 33, 2, -31 }, // 0x47 'G' + { 3265, 39, 31, 35, 0, -30 }, // 0x48 'H' + { 3417, 21, 31, 18, 0, -30 }, // 0x49 'I' + { 3499, 27, 36, 23, 0, -30 }, // 0x4A 'J' + { 3621, 34, 31, 31, 0, -30 }, // 0x4B 'K' + { 3753, 29, 31, 29, 0, -30 }, // 0x4C 'L' + { 3866, 44, 32, 41, 0, -30 }, // 0x4D 'M' + { 4042, 37, 32, 33, 0, -30 }, // 0x4E 'N' + { 4190, 31, 33, 32, 2, -31 }, // 0x4F 'O' + { 4318, 31, 31, 28, 0, -30 }, // 0x50 'P' + { 4439, 31, 42, 32, 2, -31 }, // 0x51 'Q' + { 4602, 32, 31, 31, 0, -30 }, // 0x52 'R' + { 4726, 24, 33, 24, 0, -31 }, // 0x53 'S' + { 4825, 27, 31, 28, 4, -30 }, // 0x54 'T' + { 4930, 32, 32, 34, 5, -30 }, // 0x55 'U' + { 5058, 31, 32, 33, 6, -30 }, // 0x56 'V' + { 5182, 41, 32, 44, 6, -30 }, // 0x57 'W' + { 5346, 34, 31, 33, 0, -30 }, // 0x58 'X' + { 5478, 28, 31, 30, 6, -30 }, // 0x59 'Y' + { 5587, 28, 31, 26, 0, -30 }, // 0x5A 'Z' + { 5696, 19, 38, 16, -2, -30 }, // 0x5B '[' + { 5787, 13, 33, 19, 6, -31 }, // 0x5C '\' + { 5841, 19, 38, 16, -3, -30 }, // 0x5D ']' + { 5932, 21, 17, 27, 3, -30 }, // 0x5E '^' + { 5977, 24, 3, 23, 0, 5 }, // 0x5F '_' + { 5986, 10, 9, 16, 4, -32 }, // 0x60 '`' + { 5998, 22, 23, 24, 1, -21 }, // 0x61 'a' + { 6062, 22, 33, 23, 1, -31 }, // 0x62 'b' + { 6153, 18, 23, 20, 1, -21 }, // 0x63 'c' + { 6205, 25, 34, 24, 1, -32 }, // 0x64 'd' + { 6312, 18, 23, 20, 1, -21 }, // 0x65 'e' + { 6364, 28, 41, 23, -4, -31 }, // 0x66 'f' + { 6508, 25, 31, 23, -1, -21 }, // 0x67 'g' + { 6605, 23, 34, 26, 1, -32 }, // 0x68 'h' + { 6703, 12, 33, 14, 2, -31 }, // 0x69 'i' + { 6753, 22, 42, 16, -4, -31 }, // 0x6A 'j' + { 6869, 24, 34, 24, 1, -32 }, // 0x6B 'k' + { 6971, 13, 34, 14, 2, -32 }, // 0x6C 'l' + { 7027, 35, 23, 36, 0, -21 }, // 0x6D 'm' + { 7128, 23, 23, 25, 0, -21 }, // 0x6E 'n' + { 7195, 20, 23, 22, 1, -21 }, // 0x6F 'o' + { 7253, 27, 31, 23, -4, -21 }, // 0x70 'p' + { 7358, 22, 31, 23, 1, -21 }, // 0x71 'q' + { 7444, 20, 22, 19, 0, -21 }, // 0x72 'r' + { 7499, 16, 23, 17, 0, -21 }, // 0x73 's' + { 7545, 13, 29, 13, 2, -27 }, // 0x74 't' + { 7593, 22, 23, 25, 2, -21 }, // 0x75 'u' + { 7657, 17, 23, 21, 3, -21 }, // 0x76 'v' + { 7706, 27, 23, 31, 3, -21 }, // 0x77 'w' + { 7784, 24, 23, 22, -1, -21 }, // 0x78 'x' + { 7853, 23, 31, 20, -3, -21 }, // 0x79 'y' + { 7943, 19, 25, 19, 0, -20 }, // 0x7A 'z' + { 8003, 20, 41, 16, 0, -31 }, // 0x7B '{' + { 8106, 4, 33, 13, 5, -31 }, // 0x7C '|' + { 8123, 20, 41, 16, -6, -31 }, // 0x7D '}' + { 8226, 21, 7, 27, 3, -14 } }; // 0x7E '~' + +const GFXfont FreeSerifBoldItalic24pt7b PROGMEM = { + (uint8_t *)FreeSerifBoldItalic24pt7bBitmaps, + (GFXglyph *)FreeSerifBoldItalic24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 8917 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic9pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic9pt7b.h new file mode 100644 index 0000000..47711ee --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifBoldItalic9pt7b.h @@ -0,0 +1,215 @@ +const uint8_t FreeSerifBoldItalic9pt7bBitmaps[] PROGMEM = { + 0x0C, 0x31, 0xC6, 0x18, 0x41, 0x08, 0x20, 0x0E, 0x38, 0xE0, 0xCF, 0x38, + 0xA2, 0x88, 0x02, 0x40, 0xC8, 0x13, 0x06, 0x43, 0xFC, 0x32, 0x06, 0x40, + 0x98, 0x7F, 0x84, 0xC0, 0x90, 0x32, 0x04, 0xC0, 0x01, 0x01, 0xF0, 0x4B, + 0x99, 0x33, 0x24, 0x78, 0x07, 0x80, 0x38, 0x0B, 0x89, 0x31, 0x26, 0x64, + 0xC7, 0x30, 0x3C, 0x04, 0x00, 0x38, 0x41, 0x9F, 0x06, 0x48, 0x31, 0x60, + 0xCD, 0x03, 0x2C, 0x07, 0x27, 0x81, 0x39, 0x05, 0xC4, 0x26, 0x10, 0x98, + 0x84, 0x66, 0x10, 0xE0, 0x03, 0x80, 0x22, 0x03, 0x10, 0x19, 0x00, 0xF0, + 0x0F, 0x3C, 0xF8, 0xCC, 0xC4, 0xE7, 0x47, 0x3E, 0x38, 0xE1, 0xE7, 0x97, + 0xCF, 0x00, 0xFA, 0x80, 0x08, 0x88, 0x84, 0x62, 0x10, 0x84, 0x21, 0x08, + 0x41, 0x00, 0x20, 0x84, 0x10, 0x84, 0x21, 0x08, 0xC6, 0x23, 0x11, 0x00, + 0x18, 0x18, 0xD6, 0x38, 0x18, 0xF7, 0x18, 0x18, 0x08, 0x04, 0x02, 0x01, + 0x0F, 0xF8, 0x40, 0x20, 0x10, 0x08, 0x00, 0x6D, 0x95, 0x00, 0xFF, 0xC0, + 0xFF, 0x80, 0x06, 0x0C, 0x30, 0x60, 0x83, 0x04, 0x18, 0x20, 0xC1, 0x06, + 0x00, 0x0F, 0x0C, 0x8C, 0x6E, 0x37, 0x1B, 0x1F, 0x8F, 0xC7, 0xC7, 0x63, + 0xB1, 0x89, 0x83, 0x80, 0x06, 0x1E, 0x0E, 0x0E, 0x0C, 0x0C, 0x1C, 0x18, + 0x18, 0x18, 0x38, 0x38, 0xFC, 0x1F, 0x13, 0xD0, 0xE0, 0x70, 0x38, 0x38, + 0x18, 0x18, 0x18, 0x08, 0x08, 0x4F, 0xCF, 0xE0, 0x1F, 0x11, 0xC0, 0xE0, + 0x60, 0xC1, 0xF0, 0x38, 0x0C, 0x06, 0x03, 0x01, 0x19, 0x8F, 0x00, 0x00, + 0x80, 0xC0, 0xE1, 0xE0, 0xB0, 0x98, 0x9C, 0x8C, 0xFF, 0x07, 0x03, 0x01, + 0x80, 0x0F, 0x88, 0x08, 0x07, 0x83, 0xE0, 0x78, 0x1C, 0x06, 0x03, 0x01, + 0x80, 0x9C, 0x87, 0x80, 0x03, 0x87, 0x07, 0x07, 0x07, 0x03, 0xE3, 0x99, + 0xCC, 0xC6, 0x63, 0x33, 0x89, 0x87, 0x80, 0x3F, 0xBF, 0x90, 0x80, 0xC0, + 0x40, 0x60, 0x20, 0x30, 0x30, 0x10, 0x18, 0x08, 0x00, 0x1E, 0x13, 0x31, + 0x31, 0x3A, 0x1C, 0x1C, 0x6E, 0xC6, 0xC6, 0xC6, 0x44, 0x38, 0x0E, 0x1C, + 0x8C, 0x6C, 0x36, 0x3B, 0x1D, 0x8E, 0x7E, 0x0E, 0x07, 0x07, 0x0E, 0x0C, + 0x00, 0x39, 0xCE, 0x00, 0x03, 0x9C, 0xE0, 0x39, 0xCE, 0x00, 0x01, 0x8C, + 0x22, 0x20, 0x00, 0x01, 0xC3, 0xC7, 0x8E, 0x06, 0x01, 0xE0, 0x3C, 0x07, + 0x80, 0x40, 0xFF, 0x80, 0x00, 0x00, 0x0F, 0xF8, 0x00, 0x60, 0x1E, 0x03, + 0xC0, 0x78, 0x1C, 0x3C, 0x78, 0xF0, 0x40, 0x00, 0x1C, 0x27, 0x37, 0x07, + 0x0E, 0x1C, 0x30, 0x60, 0x40, 0x00, 0xE0, 0xE0, 0xE0, 0x0F, 0x80, 0xC3, + 0x08, 0x04, 0xC3, 0x3C, 0x24, 0xE2, 0x27, 0x33, 0x39, 0x11, 0xC9, 0x93, + 0x77, 0x18, 0x00, 0x70, 0x40, 0xFC, 0x00, 0x00, 0x80, 0x18, 0x01, 0x80, + 0x38, 0x05, 0x80, 0x5C, 0x09, 0xC1, 0x1C, 0x1F, 0xC2, 0x0C, 0x20, 0xC4, + 0x0E, 0xF3, 0xF0, 0x3F, 0xE0, 0xC7, 0x0C, 0x71, 0xC7, 0x1C, 0xE1, 0xF0, + 0x39, 0xC3, 0x8E, 0x38, 0xE3, 0x0E, 0x71, 0xE7, 0x1C, 0xFF, 0x00, 0x07, + 0xD1, 0xC7, 0x38, 0x27, 0x02, 0x70, 0x0F, 0x00, 0xE0, 0x0E, 0x00, 0xE0, + 0x0E, 0x00, 0x60, 0x87, 0x18, 0x1E, 0x00, 0x3F, 0xE0, 0x30, 0xE0, 0xC1, + 0x87, 0x07, 0x1C, 0x1C, 0x60, 0x73, 0x81, 0xCE, 0x07, 0x38, 0x38, 0xC0, + 0xE7, 0x07, 0x1C, 0x78, 0xFF, 0x80, 0x1F, 0xF8, 0x61, 0xC3, 0x04, 0x38, + 0x81, 0xCC, 0x0F, 0xE0, 0xE2, 0x07, 0x10, 0x38, 0x81, 0x81, 0x1C, 0x18, + 0xE3, 0x8F, 0xFC, 0x00, 0x3F, 0xF8, 0x61, 0xC3, 0x04, 0x38, 0x81, 0xCC, + 0x0F, 0xE0, 0xE2, 0x07, 0x10, 0x38, 0x81, 0x80, 0x1C, 0x00, 0xE0, 0x0F, + 0x80, 0x00, 0x07, 0x91, 0xC7, 0x38, 0x27, 0x00, 0x70, 0x0F, 0x00, 0xE1, + 0xFE, 0x0E, 0xE0, 0xCE, 0x0C, 0x60, 0xC7, 0x1C, 0x1F, 0x00, 0x1F, 0x7E, + 0x1C, 0x38, 0x30, 0x60, 0xE1, 0xC1, 0xC3, 0x83, 0x06, 0x0F, 0xFC, 0x1C, + 0x38, 0x38, 0x70, 0x60, 0xC1, 0xC3, 0x83, 0x87, 0x0F, 0x9F, 0x00, 0x3F, + 0x0C, 0x0C, 0x1C, 0x1C, 0x18, 0x38, 0x38, 0x38, 0x30, 0x70, 0x70, 0xF8, + 0x07, 0xC0, 0xE0, 0x38, 0x0C, 0x07, 0x01, 0xC0, 0x70, 0x18, 0x0E, 0x03, + 0x80, 0xC3, 0x30, 0xDC, 0x1E, 0x00, 0x1F, 0x78, 0x71, 0x83, 0x18, 0x39, + 0x81, 0xD0, 0x0D, 0x00, 0xFC, 0x07, 0x60, 0x3B, 0x81, 0x8C, 0x1C, 0x70, + 0xE1, 0x8F, 0xBE, 0x00, 0x1F, 0x00, 0xC0, 0x0C, 0x01, 0xC0, 0x1C, 0x01, + 0x80, 0x38, 0x03, 0x80, 0x38, 0x03, 0x01, 0x70, 0x37, 0x0E, 0xFF, 0xE0, + 0x1E, 0x07, 0x87, 0x07, 0x83, 0x83, 0x82, 0xC3, 0xC1, 0x62, 0xE0, 0xB1, + 0x70, 0x99, 0x30, 0x4D, 0xB8, 0x27, 0x9C, 0x13, 0x8C, 0x11, 0xC6, 0x0C, + 0xC7, 0x0F, 0x47, 0xC0, 0x3C, 0x3C, 0x38, 0x20, 0xE0, 0x85, 0xC4, 0x13, + 0x10, 0x4E, 0x42, 0x3A, 0x08, 0x78, 0x21, 0xE0, 0x83, 0x84, 0x0C, 0x18, + 0x10, 0x00, 0x40, 0x07, 0xC1, 0xCE, 0x38, 0x73, 0x87, 0x70, 0x77, 0x07, + 0xF0, 0xFE, 0x0E, 0xE0, 0xEE, 0x1C, 0xE1, 0xC6, 0x38, 0x3E, 0x00, 0x3F, + 0xC0, 0xC7, 0x0C, 0x71, 0xC7, 0x1C, 0x71, 0x8E, 0x3F, 0xC3, 0x80, 0x30, + 0x03, 0x00, 0x70, 0x07, 0x00, 0xF8, 0x00, 0x07, 0xC0, 0xCE, 0x38, 0x73, + 0x87, 0x70, 0x77, 0x07, 0xF0, 0x7E, 0x0E, 0xE0, 0xEE, 0x0C, 0xE1, 0xC6, + 0x38, 0x36, 0x01, 0x80, 0x3C, 0x2D, 0xFC, 0x3F, 0xC0, 0xE7, 0x0C, 0x71, + 0xC7, 0x1C, 0x71, 0x8E, 0x3F, 0x83, 0xB8, 0x3B, 0x83, 0x3C, 0x71, 0xC7, + 0x1C, 0xF9, 0xF0, 0x0C, 0x89, 0x8C, 0x46, 0x23, 0x80, 0xE0, 0x78, 0x0E, + 0x03, 0x21, 0x90, 0xCC, 0xC9, 0xC0, 0x7F, 0xE9, 0xDF, 0x31, 0x4E, 0x21, + 0xC0, 0x38, 0x06, 0x01, 0xC0, 0x38, 0x06, 0x00, 0xC0, 0x38, 0x0F, 0xC0, + 0x7C, 0xF3, 0x82, 0x30, 0x27, 0x04, 0x70, 0x46, 0x04, 0xE0, 0x4E, 0x08, + 0xE0, 0x8E, 0x08, 0xE1, 0x0F, 0x30, 0x3C, 0x00, 0xFC, 0x73, 0x82, 0x38, + 0x23, 0x84, 0x38, 0x83, 0x90, 0x39, 0x01, 0xA0, 0x1C, 0x01, 0xC0, 0x18, + 0x01, 0x00, 0xF9, 0xF7, 0x30, 0xE2, 0x30, 0xC2, 0x38, 0xC4, 0x3B, 0xC4, + 0x3A, 0xE8, 0x3C, 0xE8, 0x3C, 0xF0, 0x18, 0xF0, 0x18, 0x60, 0x10, 0x60, + 0x10, 0x40, 0x3F, 0x78, 0x61, 0x83, 0x98, 0x1D, 0x00, 0x70, 0x03, 0x80, + 0x1C, 0x01, 0x60, 0x0B, 0x80, 0x9C, 0x08, 0x60, 0xC3, 0x8F, 0x7E, 0x00, + 0xF9, 0xE6, 0x18, 0xC2, 0x1C, 0x81, 0xA0, 0x34, 0x07, 0x00, 0xC0, 0x18, + 0x07, 0x00, 0xE0, 0x1C, 0x0F, 0xC0, 0x3F, 0xE6, 0x19, 0x87, 0x21, 0xC0, + 0x30, 0x0E, 0x03, 0x80, 0x60, 0x1C, 0x07, 0x05, 0xC1, 0x38, 0xEF, 0xFC, + 0x0E, 0x08, 0x18, 0x18, 0x18, 0x10, 0x30, 0x30, 0x30, 0x20, 0x60, 0x60, + 0x60, 0x40, 0xF0, 0xC6, 0x10, 0xC6, 0x10, 0x86, 0x30, 0x86, 0x30, 0x1E, + 0x0C, 0x18, 0x20, 0xC1, 0x83, 0x04, 0x18, 0x30, 0x60, 0x83, 0x06, 0x3C, + 0x00, 0x18, 0x1C, 0x34, 0x26, 0x66, 0x43, 0xC3, 0xFF, 0x80, 0xC6, 0x30, + 0x0D, 0x9D, 0x8C, 0xCC, 0x6E, 0x26, 0x33, 0x19, 0xBE, 0x66, 0x00, 0x00, + 0x78, 0x18, 0x30, 0x30, 0x3E, 0x73, 0x63, 0x63, 0x63, 0xC6, 0xC6, 0xCC, + 0x70, 0x0F, 0x3B, 0x70, 0x70, 0xE0, 0xE0, 0xE2, 0xE4, 0x78, 0x00, 0x00, + 0xF0, 0x1C, 0x06, 0x01, 0x83, 0xE3, 0x30, 0xCC, 0x63, 0x19, 0xCC, 0x63, + 0x38, 0xCF, 0x1D, 0x80, 0x0E, 0x75, 0xCB, 0xBE, 0xDE, 0x38, 0x72, 0x78, + 0x00, 0xE0, 0x34, 0x0C, 0x01, 0x80, 0x30, 0x1F, 0x01, 0x80, 0x30, 0x06, + 0x01, 0xC0, 0x30, 0x06, 0x00, 0xC0, 0x30, 0x06, 0x04, 0x80, 0xE0, 0x00, + 0x1C, 0x19, 0xD8, 0xCC, 0x66, 0x60, 0xE1, 0x80, 0xF0, 0x7E, 0x43, 0x21, + 0x8F, 0x00, 0x00, 0x1E, 0x07, 0x03, 0x01, 0x80, 0xD8, 0xFC, 0x76, 0x33, + 0x19, 0x99, 0xCC, 0xD6, 0x77, 0x30, 0x39, 0xC0, 0x0F, 0x31, 0x8C, 0xC6, + 0x31, 0xAE, 0x00, 0x03, 0x81, 0xC0, 0x00, 0x00, 0xE0, 0x30, 0x18, 0x18, + 0x0C, 0x06, 0x03, 0x03, 0x01, 0x80, 0xC2, 0xC1, 0xC0, 0x00, 0x0F, 0x00, + 0xC0, 0x60, 0x18, 0x06, 0xF3, 0x90, 0xC8, 0x34, 0x0F, 0x06, 0xC1, 0x98, + 0x66, 0xB9, 0xC0, 0x03, 0xCC, 0x63, 0x39, 0x8C, 0x66, 0x31, 0x8E, 0x70, + 0x7B, 0x99, 0xAF, 0xCE, 0x66, 0x63, 0x67, 0x33, 0x31, 0x99, 0x8C, 0xCC, + 0xE7, 0xC6, 0x30, 0x73, 0x7F, 0x73, 0x73, 0x63, 0x67, 0xE6, 0xC7, 0xC6, + 0x1E, 0x33, 0x63, 0x63, 0xC3, 0xC6, 0xC6, 0xCC, 0x78, 0x1D, 0xC3, 0xB1, + 0xCC, 0x63, 0x19, 0xCE, 0x63, 0x18, 0xCC, 0x3E, 0x1C, 0x06, 0x03, 0xE0, + 0x0D, 0x99, 0x8C, 0xCC, 0x6E, 0x76, 0x33, 0x19, 0x9C, 0x7C, 0x06, 0x07, + 0x07, 0xC0, 0x76, 0x3A, 0x30, 0x70, 0x60, 0x60, 0x60, 0xE0, 0x3D, 0x14, + 0x58, 0x38, 0x60, 0xA2, 0xF0, 0x08, 0xCC, 0xF6, 0x31, 0x98, 0xC6, 0x35, + 0xC0, 0xE3, 0x63, 0x66, 0x66, 0x66, 0xCC, 0xCC, 0xFE, 0xEC, 0xE6, 0xCD, + 0x8B, 0x26, 0x8E, 0x18, 0x20, 0xE4, 0xD9, 0x36, 0xE5, 0xDA, 0x77, 0x19, + 0xC6, 0x61, 0x10, 0x39, 0xC7, 0xB0, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xE1, + 0x5A, 0x67, 0x00, 0x39, 0x8C, 0xC3, 0x21, 0xA0, 0xD0, 0x68, 0x38, 0x0C, + 0x04, 0x04, 0x14, 0x0C, 0x00, 0x3E, 0x46, 0x0C, 0x08, 0x10, 0x20, 0x70, + 0x1A, 0x0E, 0x03, 0x0E, 0x0C, 0x0C, 0x08, 0x18, 0x18, 0x10, 0x60, 0x30, + 0x30, 0x30, 0x60, 0x60, 0x60, 0x30, 0xFF, 0xF0, 0x0C, 0x06, 0x06, 0x06, + 0x04, 0x0C, 0x0C, 0x0C, 0x06, 0x18, 0x18, 0x18, 0x30, 0x30, 0x30, 0xE0, + 0x71, 0x8F }; + +const GFXglyph FreeSerifBoldItalic9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 6, 13, 7, 1, -11 }, // 0x21 '!' + { 10, 6, 5, 10, 3, -11 }, // 0x22 '"' + { 14, 11, 13, 9, -1, -12 }, // 0x23 '#' + { 32, 11, 15, 9, -1, -12 }, // 0x24 '$' + { 53, 14, 13, 15, 1, -11 }, // 0x25 '%' + { 76, 13, 13, 14, 0, -11 }, // 0x26 '&' + { 98, 2, 5, 5, 3, -11 }, // 0x27 ''' + { 100, 5, 16, 6, 1, -11 }, // 0x28 '(' + { 110, 5, 16, 6, -1, -11 }, // 0x29 ')' + { 120, 8, 8, 9, 1, -11 }, // 0x2A '*' + { 128, 9, 9, 10, 0, -8 }, // 0x2B '+' + { 139, 3, 6, 5, -1, -2 }, // 0x2C ',' + { 142, 5, 2, 6, 0, -4 }, // 0x2D '-' + { 144, 3, 3, 4, 0, -1 }, // 0x2E '.' + { 146, 7, 12, 6, 0, -11 }, // 0x2F '/' + { 157, 9, 13, 9, 0, -11 }, // 0x30 '0' + { 172, 8, 13, 9, 0, -11 }, // 0x31 '1' + { 185, 9, 13, 9, 0, -11 }, // 0x32 '2' + { 200, 9, 13, 9, 0, -11 }, // 0x33 '3' + { 215, 9, 12, 9, 0, -11 }, // 0x34 '4' + { 229, 9, 13, 9, 0, -11 }, // 0x35 '5' + { 244, 9, 13, 9, 1, -11 }, // 0x36 '6' + { 259, 9, 12, 9, 1, -11 }, // 0x37 '7' + { 273, 8, 13, 9, 0, -11 }, // 0x38 '8' + { 286, 9, 13, 9, 0, -11 }, // 0x39 '9' + { 301, 5, 9, 5, 0, -7 }, // 0x3A ':' + { 307, 5, 11, 5, 0, -7 }, // 0x3B ';' + { 314, 9, 10, 10, 1, -9 }, // 0x3C '<' + { 326, 9, 5, 10, 1, -6 }, // 0x3D '=' + { 332, 9, 10, 10, 1, -9 }, // 0x3E '>' + { 344, 8, 13, 9, 1, -11 }, // 0x3F '?' + { 357, 13, 13, 15, 1, -12 }, // 0x40 '@' + { 379, 12, 13, 13, 0, -11 }, // 0x41 'A' + { 399, 12, 13, 12, 0, -11 }, // 0x42 'B' + { 419, 12, 13, 11, 1, -11 }, // 0x43 'C' + { 439, 14, 13, 13, 0, -11 }, // 0x44 'D' + { 462, 13, 13, 11, 0, -11 }, // 0x45 'E' + { 484, 13, 13, 11, 0, -11 }, // 0x46 'F' + { 506, 12, 13, 13, 1, -11 }, // 0x47 'G' + { 526, 15, 13, 14, 0, -11 }, // 0x48 'H' + { 551, 8, 13, 7, 0, -11 }, // 0x49 'I' + { 564, 10, 14, 9, 0, -11 }, // 0x4A 'J' + { 582, 13, 13, 12, 0, -11 }, // 0x4B 'K' + { 604, 12, 13, 11, 0, -11 }, // 0x4C 'L' + { 624, 17, 13, 16, 0, -11 }, // 0x4D 'M' + { 652, 14, 13, 13, 0, -11 }, // 0x4E 'N' + { 675, 12, 13, 12, 1, -11 }, // 0x4F 'O' + { 695, 12, 13, 11, 0, -11 }, // 0x50 'P' + { 715, 12, 16, 12, 1, -11 }, // 0x51 'Q' + { 739, 12, 13, 12, 0, -11 }, // 0x52 'R' + { 759, 9, 13, 9, 0, -11 }, // 0x53 'S' + { 774, 11, 13, 11, 2, -11 }, // 0x54 'T' + { 792, 12, 13, 13, 2, -11 }, // 0x55 'U' + { 812, 12, 12, 13, 2, -11 }, // 0x56 'V' + { 830, 16, 12, 17, 2, -11 }, // 0x57 'W' + { 854, 13, 13, 13, 0, -11 }, // 0x58 'X' + { 876, 11, 13, 11, 2, -11 }, // 0x59 'Y' + { 894, 11, 13, 10, 0, -11 }, // 0x5A 'Z' + { 912, 8, 15, 6, -1, -11 }, // 0x5B '[' + { 927, 5, 12, 7, 2, -11 }, // 0x5C '\' + { 935, 7, 15, 6, -1, -11 }, // 0x5D ']' + { 949, 8, 7, 10, 1, -11 }, // 0x5E '^' + { 956, 9, 1, 9, 0, 3 }, // 0x5F '_' + { 958, 4, 3, 6, 2, -11 }, // 0x60 '`' + { 960, 9, 9, 9, 0, -7 }, // 0x61 'a' + { 971, 8, 14, 9, 0, -12 }, // 0x62 'b' + { 985, 8, 9, 8, 0, -7 }, // 0x63 'c' + { 994, 10, 14, 9, 0, -12 }, // 0x64 'd' + { 1012, 7, 9, 7, 0, -7 }, // 0x65 'e' + { 1020, 11, 17, 9, -2, -12 }, // 0x66 'f' + { 1044, 9, 12, 9, 0, -7 }, // 0x67 'g' + { 1058, 9, 14, 10, 0, -12 }, // 0x68 'h' + { 1074, 5, 13, 5, 1, -11 }, // 0x69 'i' + { 1083, 9, 16, 6, -1, -11 }, // 0x6A 'j' + { 1101, 10, 14, 9, 0, -12 }, // 0x6B 'k' + { 1119, 5, 14, 5, 1, -12 }, // 0x6C 'l' + { 1128, 13, 9, 14, 0, -7 }, // 0x6D 'm' + { 1143, 8, 9, 9, 0, -7 }, // 0x6E 'n' + { 1152, 8, 9, 9, 0, -7 }, // 0x6F 'o' + { 1161, 10, 12, 9, -2, -7 }, // 0x70 'p' + { 1176, 9, 12, 9, 0, -7 }, // 0x71 'q' + { 1190, 8, 8, 7, 0, -7 }, // 0x72 'r' + { 1198, 6, 9, 6, 0, -7 }, // 0x73 's' + { 1205, 5, 12, 5, 1, -10 }, // 0x74 't' + { 1213, 8, 9, 10, 1, -7 }, // 0x75 'u' + { 1222, 7, 8, 8, 1, -7 }, // 0x76 'v' + { 1229, 10, 8, 12, 1, -7 }, // 0x77 'w' + { 1239, 10, 9, 9, -1, -7 }, // 0x78 'x' + { 1251, 9, 12, 8, -1, -7 }, // 0x79 'y' + { 1265, 8, 9, 7, 0, -7 }, // 0x7A 'z' + { 1274, 8, 16, 6, 0, -12 }, // 0x7B '{' + { 1290, 1, 12, 5, 2, -11 }, // 0x7C '|' + { 1292, 8, 16, 6, -2, -12 }, // 0x7D '}' + { 1308, 8, 2, 10, 1, -4 } }; // 0x7E '~' + +const GFXfont FreeSerifBoldItalic9pt7b PROGMEM = { + (uint8_t *)FreeSerifBoldItalic9pt7bBitmaps, + (GFXglyph *)FreeSerifBoldItalic9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 1982 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic12pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic12pt7b.h new file mode 100644 index 0000000..52332a7 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic12pt7b.h @@ -0,0 +1,271 @@ +const uint8_t FreeSerifItalic12pt7bBitmaps[] PROGMEM = { + 0x0C, 0x31, 0xC6, 0x18, 0x43, 0x0C, 0x20, 0x84, 0x10, 0x03, 0x0C, 0x30, + 0x66, 0xCD, 0x12, 0x24, 0x51, 0x00, 0x03, 0x10, 0x11, 0x80, 0x8C, 0x0C, + 0x40, 0x46, 0x1F, 0xFC, 0x21, 0x01, 0x18, 0x18, 0x80, 0x84, 0x3F, 0xF8, + 0x62, 0x02, 0x30, 0x31, 0x01, 0x08, 0x08, 0xC0, 0x00, 0x40, 0x08, 0x07, + 0xC0, 0xCA, 0x18, 0xA1, 0x92, 0x19, 0x01, 0xD0, 0x0F, 0x00, 0x78, 0x03, + 0xC0, 0x2E, 0x02, 0x64, 0x46, 0x44, 0x64, 0x46, 0x64, 0xC1, 0xF0, 0x08, + 0x00, 0x80, 0x00, 0x08, 0x0F, 0x0C, 0x0C, 0x7C, 0x0C, 0x22, 0x06, 0x12, + 0x06, 0x09, 0x03, 0x09, 0x01, 0x84, 0x80, 0xC4, 0x8F, 0x3C, 0x4C, 0x40, + 0x4C, 0x20, 0x4E, 0x10, 0x26, 0x08, 0x23, 0x08, 0x11, 0x84, 0x10, 0xC4, + 0x08, 0x3C, 0x00, 0x00, 0xE0, 0x02, 0x60, 0x0C, 0xC0, 0x19, 0x80, 0x36, + 0x00, 0x70, 0x00, 0xC0, 0x07, 0x9F, 0x33, 0x08, 0xC3, 0x13, 0x06, 0x46, + 0x0D, 0x0C, 0x0C, 0x18, 0x1C, 0x1C, 0x5C, 0x9F, 0x1E, 0xFA, 0xA0, 0x02, + 0x08, 0x20, 0xC3, 0x06, 0x18, 0x30, 0xE1, 0x83, 0x06, 0x0C, 0x18, 0x30, + 0x60, 0x40, 0x80, 0x81, 0x00, 0x08, 0x10, 0x10, 0x20, 0x40, 0xC1, 0x83, + 0x06, 0x0C, 0x18, 0x70, 0xC1, 0x83, 0x0C, 0x10, 0x41, 0x04, 0x00, 0x18, + 0x18, 0x18, 0x93, 0x74, 0x38, 0xD7, 0x93, 0x18, 0x18, 0x04, 0x00, 0x80, + 0x10, 0x02, 0x00, 0x41, 0xFF, 0xC1, 0x00, 0x20, 0x04, 0x00, 0x80, 0x10, + 0x00, 0x6C, 0x95, 0x00, 0xF8, 0xFC, 0x00, 0x40, 0x18, 0x02, 0x00, 0xC0, + 0x30, 0x06, 0x01, 0x80, 0x20, 0x0C, 0x01, 0x00, 0x60, 0x18, 0x03, 0x00, + 0xC0, 0x10, 0x06, 0x00, 0x07, 0x81, 0x98, 0x61, 0x18, 0x33, 0x06, 0xC0, + 0xD8, 0x1B, 0x03, 0xE0, 0xF8, 0x1F, 0x03, 0x60, 0x6C, 0x19, 0x83, 0x10, + 0xC3, 0x30, 0x3C, 0x00, 0x01, 0x87, 0xC0, 0xC0, 0x60, 0x30, 0x18, 0x18, + 0x0C, 0x06, 0x07, 0x03, 0x01, 0x80, 0xC0, 0xC0, 0x60, 0x30, 0xFE, 0x00, + 0x0F, 0x0C, 0x64, 0x0C, 0x03, 0x00, 0xC0, 0x20, 0x18, 0x0C, 0x02, 0x01, + 0x00, 0x80, 0x40, 0x20, 0x10, 0x2F, 0xF0, 0x07, 0x86, 0x30, 0x0C, 0x03, + 0x01, 0x81, 0x81, 0xF0, 0x1E, 0x03, 0x80, 0x60, 0x18, 0x06, 0x01, 0x00, + 0xCC, 0x63, 0xE0, 0x00, 0x20, 0x0C, 0x03, 0x80, 0xA0, 0x2C, 0x09, 0x82, + 0x30, 0x84, 0x31, 0x8C, 0x33, 0x06, 0x7F, 0xE0, 0x30, 0x06, 0x00, 0x80, + 0x30, 0x03, 0xE1, 0x80, 0x20, 0x06, 0x00, 0xF0, 0x0F, 0x00, 0x60, 0x06, + 0x00, 0xC0, 0x18, 0x03, 0x00, 0x40, 0x18, 0x02, 0x30, 0x87, 0xE0, 0x00, + 0x70, 0x3C, 0x07, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x7F, 0x07, 0x18, 0x60, + 0xCE, 0x0C, 0xC0, 0xCC, 0x0C, 0xC0, 0xCC, 0x18, 0x41, 0x86, 0x30, 0x3E, + 0x00, 0x7F, 0xF0, 0x18, 0x03, 0x00, 0xC0, 0x10, 0x06, 0x01, 0x80, 0x30, + 0x0C, 0x01, 0x00, 0x60, 0x08, 0x03, 0x00, 0xC0, 0x10, 0x06, 0x00, 0x0F, + 0x83, 0x18, 0xC1, 0x98, 0x33, 0x06, 0x71, 0x87, 0x60, 0x70, 0x17, 0x0C, + 0x71, 0x07, 0x60, 0x6C, 0x0D, 0x81, 0xB0, 0x63, 0x1C, 0x3E, 0x00, 0x07, + 0x83, 0x18, 0xC1, 0x18, 0x36, 0x06, 0xC0, 0xD8, 0x1B, 0x07, 0x60, 0xE6, + 0x38, 0x7F, 0x00, 0xC0, 0x30, 0x0C, 0x07, 0x03, 0xC0, 0xC0, 0x00, 0x33, + 0x30, 0x00, 0x00, 0xCC, 0xC0, 0x18, 0xC6, 0x00, 0x00, 0x00, 0x03, 0x18, + 0x44, 0x40, 0x00, 0x00, 0x03, 0x00, 0xF0, 0x38, 0x1E, 0x07, 0x80, 0xE0, + 0x0F, 0x00, 0x1C, 0x00, 0x78, 0x01, 0xE0, 0x07, 0x00, 0x10, 0xFF, 0xF0, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x0F, 0xFF, 0x00, 0x0C, 0x00, 0xF0, 0x01, + 0xC0, 0x07, 0x80, 0x1E, 0x00, 0x70, 0x0F, 0x03, 0xC1, 0xE0, 0x78, 0x0E, + 0x00, 0x80, 0x00, 0x3E, 0x21, 0x90, 0x60, 0x30, 0x38, 0x38, 0x30, 0x30, + 0x20, 0x20, 0x10, 0x00, 0x00, 0x06, 0x03, 0x01, 0x80, 0x07, 0xE0, 0x1C, + 0x18, 0x30, 0x04, 0x60, 0x02, 0x61, 0xDA, 0xC3, 0x31, 0xC6, 0x31, 0xC4, + 0x31, 0xCC, 0x31, 0xCC, 0x21, 0xCC, 0x62, 0x6C, 0xE4, 0x67, 0x38, 0x30, + 0x00, 0x1C, 0x08, 0x07, 0xF0, 0x00, 0x20, 0x00, 0xC0, 0x03, 0x80, 0x0B, + 0x00, 0x16, 0x00, 0x4E, 0x00, 0x9C, 0x02, 0x18, 0x08, 0x30, 0x1F, 0xE0, + 0x40, 0xC1, 0x81, 0xC2, 0x03, 0x8C, 0x07, 0x3C, 0x1F, 0x80, 0x1F, 0xF0, + 0x1C, 0x60, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x38, 0x60, 0xC3, 0x03, 0xF0, + 0x1C, 0x30, 0x60, 0x61, 0x81, 0x86, 0x06, 0x38, 0x18, 0xC0, 0xC3, 0x06, + 0x3F, 0xF0, 0x01, 0xF9, 0x06, 0x0F, 0x1C, 0x06, 0x38, 0x02, 0x30, 0x02, + 0x60, 0x00, 0x60, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0xC0, 0x00, + 0xC0, 0x00, 0xC0, 0x08, 0x60, 0x10, 0x30, 0x60, 0x1F, 0x80, 0x1F, 0xF0, + 0x07, 0x0C, 0x06, 0x06, 0x06, 0x06, 0x06, 0x03, 0x0E, 0x03, 0x0C, 0x03, + 0x0C, 0x03, 0x1C, 0x03, 0x1C, 0x07, 0x18, 0x06, 0x18, 0x06, 0x38, 0x0C, + 0x30, 0x18, 0x30, 0x70, 0xFF, 0x80, 0x1F, 0xFF, 0x07, 0x07, 0x06, 0x02, + 0x06, 0x02, 0x06, 0x00, 0x0E, 0x10, 0x0C, 0x30, 0x0F, 0xF0, 0x1C, 0x20, + 0x18, 0x20, 0x18, 0x00, 0x18, 0x00, 0x38, 0x04, 0x30, 0x08, 0x30, 0x38, + 0xFF, 0xF8, 0x1F, 0xFF, 0x07, 0x07, 0x07, 0x02, 0x06, 0x02, 0x06, 0x00, + 0x0E, 0x10, 0x0C, 0x30, 0x0F, 0xF0, 0x1C, 0x20, 0x1C, 0x20, 0x18, 0x00, + 0x18, 0x00, 0x38, 0x00, 0x30, 0x00, 0x30, 0x00, 0xFC, 0x00, 0x01, 0xF1, + 0x06, 0x0F, 0x18, 0x07, 0x38, 0x02, 0x30, 0x02, 0x60, 0x00, 0x60, 0x00, + 0xE0, 0x00, 0xC0, 0x7F, 0xC0, 0x1C, 0xC0, 0x1C, 0xC0, 0x18, 0xC0, 0x18, + 0x60, 0x18, 0x30, 0x38, 0x0F, 0xC0, 0x1F, 0xC7, 0xE0, 0xE0, 0x70, 0x18, + 0x0E, 0x03, 0x01, 0x80, 0x60, 0x30, 0x1C, 0x0E, 0x03, 0x01, 0x80, 0x7F, + 0xF0, 0x1C, 0x06, 0x03, 0x01, 0xC0, 0x60, 0x30, 0x0C, 0x06, 0x03, 0x81, + 0xC0, 0x60, 0x38, 0x0C, 0x06, 0x07, 0xE3, 0xF0, 0x1F, 0x83, 0x81, 0x80, + 0xC0, 0x60, 0x70, 0x30, 0x18, 0x1C, 0x0C, 0x06, 0x03, 0x03, 0x81, 0x80, + 0xC1, 0xF8, 0x03, 0xF0, 0x0C, 0x00, 0xC0, 0x1C, 0x01, 0x80, 0x18, 0x03, + 0x80, 0x30, 0x03, 0x00, 0x30, 0x07, 0x00, 0x60, 0x06, 0x0C, 0xE0, 0xCC, + 0x07, 0x80, 0x1F, 0xCF, 0x83, 0x83, 0x81, 0x81, 0x00, 0xC3, 0x00, 0x62, + 0x00, 0x72, 0x00, 0x36, 0x00, 0x1E, 0x00, 0x1D, 0x80, 0x0C, 0xE0, 0x06, + 0x30, 0x03, 0x1C, 0x03, 0x87, 0x01, 0x81, 0x80, 0xC0, 0xE1, 0xF9, 0xFC, + 0x1F, 0xC0, 0x1C, 0x00, 0x60, 0x01, 0x80, 0x06, 0x00, 0x38, 0x00, 0xC0, + 0x03, 0x00, 0x1C, 0x00, 0x60, 0x01, 0x80, 0x06, 0x00, 0x38, 0x0C, 0xC0, + 0x23, 0x03, 0xBF, 0xFE, 0x0F, 0x00, 0x78, 0x38, 0x07, 0x81, 0xC0, 0x38, + 0x0E, 0x02, 0xC0, 0x70, 0x3E, 0x05, 0xC1, 0x70, 0x2E, 0x13, 0x01, 0x31, + 0x98, 0x11, 0x89, 0xC0, 0x8C, 0x8C, 0x04, 0x6C, 0x60, 0x23, 0x43, 0x02, + 0x1C, 0x38, 0x10, 0xE1, 0x81, 0x86, 0x1C, 0x1F, 0x23, 0xF8, 0x1E, 0x07, + 0xC1, 0xC0, 0x60, 0x70, 0x10, 0x1C, 0x0C, 0x05, 0x82, 0x02, 0x60, 0x80, + 0x9C, 0x60, 0x23, 0x10, 0x10, 0xC4, 0x04, 0x19, 0x01, 0x06, 0xC0, 0x40, + 0xE0, 0x20, 0x38, 0x08, 0x0E, 0x06, 0x01, 0x03, 0xE0, 0x40, 0x01, 0xF0, + 0x0C, 0x10, 0x30, 0x10, 0xC0, 0x33, 0x00, 0x6E, 0x00, 0xD8, 0x01, 0xF0, + 0x03, 0xC0, 0x0D, 0x80, 0x1B, 0x00, 0x76, 0x00, 0xCC, 0x03, 0x08, 0x0C, + 0x18, 0x70, 0x0F, 0x80, 0x1F, 0xF0, 0x1C, 0x60, 0x60, 0xC1, 0x83, 0x06, + 0x0C, 0x38, 0x30, 0xC1, 0x83, 0x0E, 0x1F, 0xE0, 0x60, 0x01, 0x80, 0x06, + 0x00, 0x38, 0x00, 0xC0, 0x03, 0x00, 0x3F, 0x00, 0x01, 0xF0, 0x06, 0x10, + 0x30, 0x30, 0xC0, 0x33, 0x00, 0x66, 0x00, 0xD8, 0x01, 0xB0, 0x03, 0xE0, + 0x0F, 0x80, 0x1B, 0x00, 0x36, 0x00, 0xCC, 0x03, 0x98, 0x06, 0x18, 0x18, + 0x18, 0xC0, 0x0E, 0x00, 0x20, 0x01, 0xF8, 0x36, 0x7F, 0x80, 0x1F, 0xF0, + 0x1C, 0x60, 0x60, 0xC1, 0x83, 0x06, 0x0C, 0x38, 0x70, 0xC3, 0x83, 0xF8, + 0x1D, 0xC0, 0x63, 0x01, 0x8C, 0x06, 0x18, 0x38, 0x60, 0xC1, 0xC3, 0x03, + 0x3F, 0x0F, 0x07, 0x90, 0xC7, 0x18, 0x21, 0x82, 0x18, 0x01, 0xC0, 0x0E, + 0x00, 0x70, 0x03, 0x80, 0x1C, 0x00, 0xC4, 0x0C, 0x40, 0xC6, 0x08, 0xE1, + 0x89, 0xE0, 0x7F, 0xFE, 0xC7, 0x1D, 0x0C, 0x14, 0x18, 0x20, 0x70, 0x00, + 0xE0, 0x01, 0x80, 0x03, 0x00, 0x0E, 0x00, 0x18, 0x00, 0x30, 0x00, 0x60, + 0x01, 0xC0, 0x03, 0x00, 0x0E, 0x00, 0x7F, 0x80, 0x7E, 0x1F, 0x38, 0x0C, + 0x38, 0x0C, 0x30, 0x08, 0x30, 0x08, 0x70, 0x08, 0x70, 0x10, 0x60, 0x10, + 0x60, 0x10, 0xE0, 0x10, 0xC0, 0x20, 0xC0, 0x20, 0xC0, 0x60, 0xC0, 0x40, + 0x61, 0x80, 0x3F, 0x00, 0xFC, 0x3E, 0xE0, 0x18, 0xC0, 0x21, 0x80, 0xC3, + 0x81, 0x07, 0x04, 0x0E, 0x08, 0x0C, 0x20, 0x18, 0x80, 0x31, 0x00, 0x64, + 0x00, 0xF0, 0x01, 0xE0, 0x01, 0x80, 0x02, 0x00, 0x04, 0x00, 0xFD, 0xF8, + 0xF7, 0x07, 0x06, 0x30, 0x60, 0x63, 0x07, 0x04, 0x30, 0x70, 0x83, 0x8F, + 0x08, 0x38, 0xB1, 0x03, 0x93, 0x10, 0x19, 0x32, 0x01, 0xA3, 0x20, 0x1A, + 0x34, 0x01, 0xC3, 0x40, 0x1C, 0x38, 0x01, 0x83, 0x00, 0x18, 0x30, 0x01, + 0x02, 0x00, 0x1F, 0x9F, 0x0E, 0x06, 0x06, 0x04, 0x07, 0x08, 0x03, 0x10, + 0x03, 0x20, 0x03, 0xC0, 0x01, 0x80, 0x01, 0xC0, 0x03, 0xC0, 0x06, 0xE0, + 0x0C, 0x60, 0x18, 0x60, 0x30, 0x70, 0x70, 0x78, 0xF8, 0xFC, 0xFC, 0xFB, + 0x81, 0x8C, 0x08, 0x60, 0x83, 0x8C, 0x0C, 0xC0, 0x64, 0x03, 0xC0, 0x0C, + 0x00, 0xE0, 0x07, 0x00, 0x30, 0x01, 0x80, 0x1C, 0x00, 0xC0, 0x1F, 0xC0, + 0x1F, 0xFE, 0x30, 0x38, 0xC0, 0xF1, 0x01, 0xC0, 0x07, 0x00, 0x1C, 0x00, + 0x70, 0x01, 0xE0, 0x03, 0x80, 0x0E, 0x00, 0x38, 0x00, 0xE0, 0x01, 0xC0, + 0x47, 0x01, 0x1C, 0x06, 0x7F, 0xF8, 0x07, 0x04, 0x08, 0x08, 0x08, 0x18, + 0x10, 0x10, 0x10, 0x20, 0x20, 0x20, 0x20, 0x40, 0x40, 0x40, 0x80, 0x80, + 0x80, 0xE0, 0xC0, 0xC0, 0x40, 0x60, 0x20, 0x30, 0x30, 0x18, 0x18, 0x08, + 0x0C, 0x04, 0x06, 0x06, 0x03, 0x03, 0x0E, 0x04, 0x08, 0x10, 0x60, 0x81, + 0x02, 0x04, 0x18, 0x20, 0x40, 0x81, 0x02, 0x08, 0x10, 0x20, 0x47, 0x80, + 0x0C, 0x03, 0x81, 0xE0, 0x4C, 0x33, 0x08, 0x66, 0x19, 0x03, 0xC0, 0xC0, + 0xFF, 0xF0, 0xCE, 0x63, 0x07, 0xA0, 0xCE, 0x18, 0x63, 0x04, 0x60, 0xC6, + 0x0C, 0xC0, 0xCC, 0x18, 0xC3, 0x8C, 0x5A, 0x79, 0xC0, 0x38, 0x06, 0x01, + 0x80, 0x40, 0x30, 0x0C, 0xE3, 0xCC, 0xC3, 0x70, 0xD8, 0x36, 0x19, 0x06, + 0xC3, 0x30, 0x8C, 0xC3, 0xE0, 0x0F, 0x0C, 0xCC, 0x6C, 0x06, 0x06, 0x03, + 0x01, 0x80, 0xC0, 0x73, 0x1E, 0x00, 0x00, 0x70, 0x01, 0x80, 0x0C, 0x00, + 0x60, 0x02, 0x03, 0xF0, 0x31, 0x83, 0x08, 0x30, 0xC3, 0x06, 0x18, 0x31, + 0x81, 0x8C, 0x18, 0x61, 0xCB, 0x16, 0x8F, 0x38, 0x07, 0x19, 0x31, 0x63, + 0x62, 0xEC, 0xD0, 0xC0, 0xC0, 0xE6, 0x78, 0x00, 0x38, 0x01, 0x30, 0x0C, + 0x00, 0x20, 0x01, 0x80, 0x06, 0x00, 0xFE, 0x00, 0x40, 0x03, 0x00, 0x0C, + 0x00, 0x30, 0x00, 0x80, 0x06, 0x00, 0x18, 0x00, 0x60, 0x01, 0x80, 0x04, + 0x00, 0x30, 0x00, 0xC0, 0x02, 0x00, 0x90, 0x03, 0x80, 0x00, 0x07, 0xC0, + 0xC7, 0x18, 0x61, 0x86, 0x18, 0xE1, 0x8C, 0x07, 0x80, 0x80, 0x1C, 0x00, + 0xF0, 0x33, 0x84, 0x18, 0x80, 0x88, 0x08, 0x61, 0x03, 0xE0, 0x1C, 0x00, + 0xC0, 0x0C, 0x00, 0xC0, 0x18, 0x01, 0x8E, 0x1B, 0x61, 0xC6, 0x38, 0x63, + 0x8C, 0x30, 0xC3, 0x0C, 0x60, 0xC6, 0x1A, 0x61, 0xA4, 0x1C, 0x18, 0xC6, + 0x00, 0x0B, 0xC6, 0x23, 0x18, 0x8C, 0x63, 0x5C, 0x01, 0x80, 0xC0, 0x60, + 0x00, 0x00, 0x0C, 0x1E, 0x02, 0x03, 0x01, 0x80, 0xC0, 0x40, 0x60, 0x30, + 0x18, 0x08, 0x0C, 0x06, 0x02, 0x1B, 0x0F, 0x00, 0x1C, 0x01, 0x80, 0x30, + 0x06, 0x01, 0x80, 0x33, 0xC6, 0x30, 0x88, 0x32, 0x06, 0x80, 0xF0, 0x1B, + 0x06, 0x60, 0xC4, 0x18, 0xD2, 0x0C, 0x3C, 0x61, 0x86, 0x18, 0xC3, 0x0C, + 0x21, 0x86, 0x18, 0x43, 0x2D, 0x38, 0x78, 0xE7, 0x0D, 0xB5, 0x8D, 0x1C, + 0xC7, 0x0C, 0x63, 0x8E, 0x31, 0x86, 0x30, 0xC3, 0x18, 0xC1, 0x0C, 0x61, + 0x84, 0xB0, 0xC6, 0xB0, 0x63, 0x80, 0x78, 0xE1, 0xB6, 0x14, 0x63, 0x84, + 0x38, 0xC3, 0x0C, 0x70, 0x86, 0x18, 0x61, 0x96, 0x1A, 0xC1, 0xC0, 0x0F, + 0x06, 0x63, 0x0D, 0x83, 0x60, 0xF0, 0x3C, 0x1B, 0x06, 0xC3, 0x39, 0x87, + 0x80, 0x1E, 0xF0, 0x39, 0xC1, 0x86, 0x0C, 0x30, 0xC1, 0x86, 0x0C, 0x30, + 0xC3, 0x06, 0x18, 0x60, 0xC6, 0x07, 0xC0, 0x60, 0x03, 0x00, 0x18, 0x00, + 0xC0, 0x1F, 0x00, 0x07, 0x81, 0x9C, 0x63, 0x98, 0x76, 0x0C, 0xC1, 0xB0, + 0x76, 0x0E, 0xC3, 0x98, 0xB1, 0xE6, 0x00, 0x80, 0x30, 0x06, 0x00, 0xC0, + 0xFC, 0x79, 0x8F, 0xC5, 0x07, 0x03, 0x01, 0x80, 0xC0, 0xC0, 0x60, 0x30, + 0x10, 0x00, 0x1E, 0x98, 0xCC, 0x27, 0x11, 0x80, 0xE0, 0x39, 0x0C, 0x86, + 0x62, 0x2E, 0x00, 0x08, 0x67, 0xCC, 0x30, 0xC6, 0x18, 0x61, 0x8C, 0x34, + 0xE0, 0xF0, 0xCC, 0x19, 0x83, 0x30, 0xC6, 0x18, 0x87, 0x31, 0x66, 0x3C, + 0xCB, 0x1A, 0x6B, 0x8E, 0x00, 0x70, 0xCC, 0x33, 0x04, 0xC2, 0x18, 0x86, + 0x41, 0x90, 0x68, 0x1C, 0x06, 0x01, 0x00, 0x61, 0x0F, 0x84, 0x36, 0x30, + 0xDC, 0xC1, 0x35, 0x08, 0xD4, 0x23, 0x91, 0x0E, 0x48, 0x30, 0xE0, 0xC3, + 0x02, 0x08, 0x00, 0x0C, 0x63, 0x4A, 0x07, 0x00, 0x70, 0x06, 0x00, 0x20, + 0x07, 0x00, 0xB0, 0x0B, 0x21, 0x14, 0xE1, 0x80, 0x38, 0x63, 0x0C, 0x30, + 0x86, 0x10, 0xC4, 0x0C, 0x81, 0xA0, 0x34, 0x07, 0x00, 0x60, 0x08, 0x02, + 0x00, 0x40, 0x10, 0x04, 0x07, 0x00, 0x1F, 0x90, 0x80, 0x80, 0xC0, 0xC0, + 0x40, 0x60, 0x60, 0x60, 0x38, 0x3E, 0x03, 0xA0, 0x60, 0x00, 0x83, 0x81, + 0x01, 0x80, 0xC0, 0x40, 0x60, 0x30, 0x10, 0x10, 0x1C, 0x06, 0x03, 0x03, + 0x01, 0x80, 0xC0, 0x40, 0x60, 0x30, 0x18, 0x07, 0x00, 0xFF, 0xFF, 0x07, + 0x00, 0xC0, 0x60, 0x30, 0x10, 0x18, 0x0C, 0x06, 0x06, 0x03, 0x01, 0x80, + 0x60, 0x40, 0x60, 0x30, 0x10, 0x18, 0x0C, 0x06, 0x06, 0x06, 0x00, 0x78, + 0x18, 0x8C, 0x0F, 0x00 }; + +const GFXglyph FreeSerifItalic12pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 6, 0, 1 }, // 0x20 ' ' + { 0, 6, 16, 8, 1, -15 }, // 0x21 '!' + { 12, 7, 6, 8, 3, -15 }, // 0x22 '"' + { 18, 13, 16, 12, 0, -15 }, // 0x23 '#' + { 44, 12, 20, 12, 0, -17 }, // 0x24 '$' + { 74, 17, 17, 20, 2, -16 }, // 0x25 '%' + { 111, 15, 16, 19, 2, -15 }, // 0x26 '&' + { 141, 2, 6, 5, 4, -15 }, // 0x27 ''' + { 143, 7, 20, 8, 1, -15 }, // 0x28 '(' + { 161, 7, 20, 8, 0, -15 }, // 0x29 ')' + { 179, 8, 10, 12, 4, -15 }, // 0x2A '*' + { 189, 11, 11, 16, 2, -10 }, // 0x2B '+' + { 205, 3, 6, 6, 0, -2 }, // 0x2C ',' + { 208, 5, 1, 8, 1, -5 }, // 0x2D '-' + { 209, 2, 3, 6, 1, -2 }, // 0x2E '.' + { 210, 11, 16, 7, 0, -15 }, // 0x2F '/' + { 232, 11, 17, 12, 1, -16 }, // 0x30 '0' + { 256, 9, 17, 12, 1, -16 }, // 0x31 '1' + { 276, 10, 15, 12, 1, -14 }, // 0x32 '2' + { 295, 10, 16, 12, 1, -15 }, // 0x33 '3' + { 315, 11, 16, 12, 0, -15 }, // 0x34 '4' + { 337, 11, 16, 12, 0, -15 }, // 0x35 '5' + { 359, 12, 17, 12, 1, -16 }, // 0x36 '6' + { 385, 11, 16, 12, 2, -15 }, // 0x37 '7' + { 407, 11, 17, 12, 1, -16 }, // 0x38 '8' + { 431, 11, 17, 12, 1, -16 }, // 0x39 '9' + { 455, 4, 11, 6, 1, -10 }, // 0x3A ':' + { 461, 5, 14, 6, 0, -10 }, // 0x3B ';' + { 470, 12, 13, 14, 1, -12 }, // 0x3C '<' + { 490, 12, 6, 16, 2, -8 }, // 0x3D '=' + { 499, 12, 13, 14, 2, -12 }, // 0x3E '>' + { 519, 9, 16, 11, 3, -15 }, // 0x3F '?' + { 537, 16, 16, 19, 2, -15 }, // 0x40 '@' + { 569, 15, 15, 16, 0, -14 }, // 0x41 'A' + { 598, 14, 16, 14, 0, -15 }, // 0x42 'B' + { 626, 16, 16, 15, 1, -15 }, // 0x43 'C' + { 658, 16, 16, 17, 0, -15 }, // 0x44 'D' + { 690, 16, 16, 14, 0, -15 }, // 0x45 'E' + { 722, 16, 16, 14, 0, -15 }, // 0x46 'F' + { 754, 16, 16, 17, 1, -15 }, // 0x47 'G' + { 786, 19, 16, 17, 0, -15 }, // 0x48 'H' + { 824, 9, 16, 8, 0, -15 }, // 0x49 'I' + { 842, 12, 16, 10, 0, -15 }, // 0x4A 'J' + { 866, 17, 16, 15, 0, -15 }, // 0x4B 'K' + { 900, 14, 16, 14, 0, -15 }, // 0x4C 'L' + { 928, 21, 16, 20, 0, -15 }, // 0x4D 'M' + { 970, 18, 16, 16, 0, -15 }, // 0x4E 'N' + { 1006, 15, 16, 16, 1, -15 }, // 0x4F 'O' + { 1036, 14, 16, 14, 0, -15 }, // 0x50 'P' + { 1064, 15, 20, 16, 1, -15 }, // 0x51 'Q' + { 1102, 14, 16, 15, 0, -15 }, // 0x52 'R' + { 1130, 12, 16, 11, 0, -15 }, // 0x53 'S' + { 1154, 15, 16, 14, 2, -15 }, // 0x54 'T' + { 1184, 16, 16, 17, 3, -15 }, // 0x55 'U' + { 1216, 15, 16, 16, 3, -15 }, // 0x56 'V' + { 1246, 20, 16, 21, 3, -15 }, // 0x57 'W' + { 1286, 16, 16, 16, 0, -15 }, // 0x58 'X' + { 1318, 13, 16, 14, 3, -15 }, // 0x59 'Y' + { 1344, 15, 16, 14, 0, -15 }, // 0x5A 'Z' + { 1374, 8, 20, 9, 1, -15 }, // 0x5B '[' + { 1394, 8, 16, 12, 3, -15 }, // 0x5C '\' + { 1410, 7, 20, 9, 1, -15 }, // 0x5D ']' + { 1428, 10, 9, 10, 0, -15 }, // 0x5E '^' + { 1440, 12, 1, 12, 0, 3 }, // 0x5F '_' + { 1442, 4, 4, 6, 3, -15 }, // 0x60 '`' + { 1444, 12, 11, 12, 0, -10 }, // 0x61 'a' + { 1461, 10, 16, 11, 1, -15 }, // 0x62 'b' + { 1481, 9, 11, 10, 1, -10 }, // 0x63 'c' + { 1494, 13, 16, 12, 0, -15 }, // 0x64 'd' + { 1520, 8, 11, 10, 1, -10 }, // 0x65 'e' + { 1531, 14, 22, 10, -2, -16 }, // 0x66 'f' + { 1570, 12, 16, 11, -1, -10 }, // 0x67 'g' + { 1594, 12, 16, 12, 0, -15 }, // 0x68 'h' + { 1618, 5, 16, 6, 1, -15 }, // 0x69 'i' + { 1628, 9, 21, 7, -2, -15 }, // 0x6A 'j' + { 1652, 11, 16, 11, 0, -15 }, // 0x6B 'k' + { 1674, 6, 16, 6, 1, -15 }, // 0x6C 'l' + { 1686, 17, 11, 17, 0, -10 }, // 0x6D 'm' + { 1710, 12, 11, 12, 0, -10 }, // 0x6E 'n' + { 1727, 10, 11, 11, 1, -10 }, // 0x6F 'o' + { 1741, 13, 16, 11, -2, -10 }, // 0x70 'p' + { 1767, 11, 16, 12, 0, -10 }, // 0x71 'q' + { 1789, 9, 11, 9, 0, -10 }, // 0x72 'r' + { 1802, 9, 11, 8, 0, -10 }, // 0x73 's' + { 1815, 6, 13, 6, 1, -12 }, // 0x74 't' + { 1825, 11, 11, 12, 1, -10 }, // 0x75 'u' + { 1841, 10, 11, 11, 1, -10 }, // 0x76 'v' + { 1855, 14, 11, 16, 2, -10 }, // 0x77 'w' + { 1875, 12, 11, 10, -1, -10 }, // 0x78 'x' + { 1892, 11, 16, 11, 0, -10 }, // 0x79 'y' + { 1914, 9, 13, 9, 0, -10 }, // 0x7A 'z' + { 1929, 9, 21, 10, 1, -16 }, // 0x7B '{' + { 1953, 1, 16, 7, 3, -15 }, // 0x7C '|' + { 1955, 9, 21, 10, 0, -16 }, // 0x7D '}' + { 1979, 11, 3, 13, 1, -6 } }; // 0x7E '~' + +const GFXfont FreeSerifItalic12pt7b PROGMEM = { + (uint8_t *)FreeSerifItalic12pt7bBitmaps, + (GFXglyph *)FreeSerifItalic12pt7bGlyphs, + 0x20, 0x7E, 29 }; + +// Approx. 2656 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic18pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic18pt7b.h new file mode 100644 index 0000000..666ae7e --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic18pt7b.h @@ -0,0 +1,450 @@ +const uint8_t FreeSerifItalic18pt7bBitmaps[] PROGMEM = { + 0x01, 0xC0, 0xF0, 0x3C, 0x0F, 0x03, 0x81, 0xE0, 0x70, 0x1C, 0x06, 0x01, + 0x80, 0xC0, 0x30, 0x0C, 0x02, 0x01, 0x80, 0x40, 0x10, 0x00, 0x00, 0x01, + 0x80, 0xF0, 0x3C, 0x06, 0x00, 0x38, 0x77, 0x8F, 0x78, 0xF7, 0x0E, 0x60, + 0xE6, 0x0C, 0xC1, 0x8C, 0x18, 0x81, 0x00, 0x00, 0x60, 0xC0, 0x0C, 0x38, + 0x03, 0x86, 0x00, 0x60, 0xC0, 0x0C, 0x38, 0x03, 0x06, 0x00, 0x60, 0xC0, + 0xFF, 0xFF, 0x1F, 0xFF, 0xE0, 0x61, 0xC0, 0x1C, 0x30, 0x03, 0x06, 0x00, + 0x61, 0xC0, 0x18, 0x30, 0x3F, 0xFF, 0xC7, 0xFF, 0xF8, 0x18, 0x30, 0x03, + 0x0E, 0x00, 0xE1, 0x80, 0x18, 0x30, 0x03, 0x0C, 0x00, 0xC1, 0x80, 0x18, + 0x70, 0x00, 0x00, 0x08, 0x00, 0x30, 0x00, 0x40, 0x0F, 0xC0, 0x61, 0xE1, + 0x86, 0xC6, 0x0D, 0x8C, 0x1A, 0x18, 0x24, 0x38, 0xC0, 0x39, 0x80, 0x7F, + 0x00, 0x7E, 0x00, 0x3E, 0x00, 0x3E, 0x00, 0x7C, 0x00, 0xDC, 0x03, 0x38, + 0x06, 0x32, 0x0C, 0x64, 0x18, 0xDC, 0x71, 0xB8, 0xC6, 0x39, 0x8C, 0x3F, + 0x30, 0x1F, 0x80, 0x18, 0x00, 0x30, 0x00, 0x60, 0x00, 0x07, 0x80, 0x60, + 0x0F, 0xE0, 0xE0, 0x0F, 0x0F, 0xB0, 0x0E, 0x04, 0x30, 0x07, 0x02, 0x18, + 0x07, 0x01, 0x18, 0x03, 0x00, 0x8C, 0x01, 0x80, 0x8C, 0x00, 0xC0, 0x4C, + 0x00, 0x60, 0x66, 0x1F, 0x30, 0x66, 0x1F, 0xCC, 0x63, 0x1C, 0x67, 0xE3, + 0x1C, 0x19, 0xE1, 0x1C, 0x04, 0x01, 0x8C, 0x02, 0x00, 0x8E, 0x01, 0x00, + 0xC7, 0x00, 0x80, 0xC3, 0x00, 0x80, 0x61, 0x80, 0xC0, 0x60, 0xC0, 0xC0, + 0x20, 0x70, 0xE0, 0x30, 0x1F, 0xC0, 0x10, 0x07, 0xC0, 0x00, 0x1E, 0x00, + 0x00, 0xFC, 0x00, 0x07, 0x18, 0x00, 0x18, 0x60, 0x00, 0xE1, 0x80, 0x03, + 0x8C, 0x00, 0x0E, 0x60, 0x00, 0x3B, 0x00, 0x00, 0xF0, 0x00, 0x07, 0x80, + 0x00, 0x7F, 0x1F, 0xC3, 0x3C, 0x1C, 0x38, 0x70, 0x61, 0xE1, 0xE3, 0x87, + 0x07, 0x8C, 0x3C, 0x0F, 0x60, 0xF0, 0x3D, 0x03, 0xC0, 0x78, 0x0F, 0x01, + 0xE0, 0x3E, 0x07, 0xC0, 0x7C, 0x77, 0x84, 0xFF, 0x8F, 0xE1, 0xF8, 0x0F, + 0x00, 0x3B, 0xDE, 0xE7, 0x33, 0x18, 0x80, 0x00, 0x80, 0x80, 0x80, 0x80, + 0xC0, 0xC0, 0xE0, 0x60, 0x70, 0x38, 0x18, 0x0C, 0x0E, 0x07, 0x03, 0x01, + 0x80, 0xC0, 0x60, 0x30, 0x18, 0x0C, 0x06, 0x01, 0x00, 0x80, 0x40, 0x30, + 0x08, 0x04, 0x02, 0x00, 0x04, 0x01, 0x00, 0x80, 0x60, 0x10, 0x08, 0x04, + 0x03, 0x01, 0x80, 0xC0, 0x60, 0x30, 0x18, 0x0C, 0x0E, 0x07, 0x03, 0x81, + 0x80, 0xC0, 0xE0, 0x60, 0x30, 0x30, 0x18, 0x18, 0x08, 0x08, 0x08, 0x08, + 0x00, 0x06, 0x00, 0x60, 0x06, 0x0C, 0x43, 0xE4, 0xF1, 0x58, 0x0E, 0x00, + 0xF0, 0x74, 0xEE, 0x47, 0xC4, 0x30, 0x60, 0x06, 0x00, 0x60, 0x01, 0x80, + 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, + 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xFF, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, + 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x01, 0x80, 0x31, 0xCE, + 0x31, 0x08, 0x98, 0xFF, 0xFF, 0x6F, 0xF6, 0x00, 0x06, 0x00, 0x0E, 0x00, + 0x0C, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x30, 0x00, 0x70, 0x00, 0x60, 0x00, + 0xE0, 0x00, 0xC0, 0x01, 0xC0, 0x03, 0x80, 0x03, 0x00, 0x07, 0x00, 0x06, + 0x00, 0x0E, 0x00, 0x0C, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x30, 0x00, 0x70, + 0x00, 0x60, 0x00, 0xE0, 0x00, 0x00, 0x78, 0x00, 0xC3, 0x00, 0xC1, 0xC0, + 0xC0, 0x60, 0xE0, 0x30, 0xE0, 0x1C, 0x70, 0x0E, 0x70, 0x07, 0x38, 0x03, + 0xBC, 0x01, 0xDC, 0x01, 0xEE, 0x00, 0xFF, 0x00, 0x7F, 0x80, 0x3B, 0x80, + 0x1D, 0xC0, 0x1E, 0xE0, 0x0E, 0x70, 0x0F, 0x38, 0x07, 0x1C, 0x07, 0x06, + 0x03, 0x83, 0x83, 0x80, 0xC3, 0x00, 0x1F, 0x00, 0x00, 0xF0, 0x7F, 0x00, + 0x70, 0x07, 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0E, 0x01, 0xC0, 0x1C, 0x01, + 0xC0, 0x38, 0x03, 0x80, 0x38, 0x03, 0x80, 0x70, 0x07, 0x00, 0x70, 0x0E, + 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x1E, 0x0F, 0xF8, 0x01, 0xF0, 0x07, 0xFC, + 0x0C, 0x3E, 0x10, 0x1F, 0x20, 0x0F, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0F, + 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x38, 0x00, 0x30, 0x00, 0x70, 0x00, 0xE0, + 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0E, 0x00, 0x1C, 0x00, 0x38, 0x04, + 0x30, 0x0C, 0x7F, 0xF8, 0xFF, 0xF0, 0x00, 0x7C, 0x00, 0xFF, 0x00, 0xC3, + 0xC0, 0x80, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1C, 0x00, 0x1C, 0x00, + 0x38, 0x00, 0xF0, 0x03, 0xFC, 0x00, 0x1F, 0x00, 0x03, 0xC0, 0x01, 0xE0, + 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x06, 0x00, 0x07, + 0x00, 0x03, 0x07, 0x87, 0x03, 0xFF, 0x00, 0xFC, 0x00, 0x00, 0x01, 0x80, + 0x01, 0x80, 0x01, 0xC0, 0x01, 0xE0, 0x01, 0xF0, 0x01, 0xB0, 0x01, 0xB8, + 0x01, 0x9C, 0x01, 0x8C, 0x00, 0x86, 0x00, 0x87, 0x00, 0x83, 0x80, 0x81, + 0x80, 0x81, 0xC0, 0xC0, 0xE0, 0xC0, 0x70, 0xFF, 0xFF, 0x7F, 0xFF, 0x00, + 0x1C, 0x00, 0x0C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x03, 0x80, 0x01, 0x80, + 0x01, 0xFF, 0x01, 0xFF, 0x02, 0x00, 0x02, 0x00, 0x06, 0x00, 0x07, 0x00, + 0x0F, 0xC0, 0x0F, 0xF0, 0x00, 0xF8, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x1C, + 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x0C, 0x00, 0x08, 0x00, 0x18, + 0x00, 0x30, 0x00, 0x30, 0x70, 0xE0, 0xFF, 0x80, 0x7E, 0x00, 0x00, 0x03, + 0x80, 0x1F, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x38, 0x00, 0x38, 0x00, 0x38, + 0x00, 0x3C, 0x00, 0x3D, 0xF0, 0x1F, 0xFE, 0x1F, 0x0F, 0x8E, 0x03, 0xC7, + 0x00, 0xF7, 0x00, 0x7B, 0x80, 0x3D, 0x80, 0x1E, 0xC0, 0x0F, 0x60, 0x0F, + 0xB0, 0x07, 0x98, 0x03, 0xC4, 0x03, 0xC3, 0x03, 0xC0, 0xC3, 0x80, 0x1F, + 0x00, 0x3F, 0xFF, 0x7F, 0xFE, 0x40, 0x0E, 0x80, 0x0C, 0x00, 0x18, 0x00, + 0x18, 0x00, 0x30, 0x00, 0x70, 0x00, 0x60, 0x00, 0xC0, 0x01, 0xC0, 0x01, + 0x80, 0x03, 0x80, 0x03, 0x00, 0x06, 0x00, 0x0E, 0x00, 0x0C, 0x00, 0x1C, + 0x00, 0x18, 0x00, 0x30, 0x00, 0x70, 0x00, 0x60, 0x00, 0xE0, 0x00, 0x00, + 0xF8, 0x03, 0x0E, 0x06, 0x06, 0x0C, 0x03, 0x0C, 0x03, 0x0C, 0x03, 0x0C, + 0x03, 0x0E, 0x06, 0x07, 0x8E, 0x07, 0xD8, 0x03, 0xE0, 0x07, 0xF0, 0x1C, + 0xF8, 0x30, 0x3C, 0x60, 0x1C, 0x60, 0x0E, 0xC0, 0x06, 0xC0, 0x06, 0xC0, + 0x06, 0xC0, 0x06, 0xE0, 0x0C, 0x60, 0x18, 0x38, 0x30, 0x0F, 0xC0, 0x01, + 0xF8, 0x07, 0x8C, 0x0E, 0x06, 0x1E, 0x02, 0x3C, 0x03, 0x3C, 0x03, 0x78, + 0x03, 0x78, 0x03, 0x78, 0x03, 0x78, 0x07, 0x78, 0x07, 0x78, 0x07, 0x3C, + 0x0E, 0x3E, 0x1E, 0x1F, 0xEE, 0x07, 0x9C, 0x00, 0x38, 0x00, 0x78, 0x00, + 0x70, 0x01, 0xE0, 0x03, 0xC0, 0x0F, 0x00, 0x3C, 0x00, 0xE0, 0x00, 0x0C, + 0x3C, 0x78, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0x0F, 0x1E, 0x18, + 0x00, 0x07, 0x03, 0xC1, 0xE0, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x02, 0x03, 0x81, 0xC0, 0xE0, 0x30, 0x10, 0x10, 0x10, 0x00, 0x00, + 0x00, 0x00, 0xC0, 0x01, 0xF0, 0x01, 0xF8, 0x01, 0xF8, 0x01, 0xF0, 0x01, + 0xF0, 0x03, 0xF0, 0x03, 0xF0, 0x00, 0xF0, 0x00, 0x3E, 0x00, 0x07, 0xE0, + 0x00, 0x7E, 0x00, 0x03, 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xF0, 0x00, 0x3F, + 0x00, 0x03, 0xC0, 0x00, 0x10, 0xFF, 0xFF, 0xFF, 0xFF, 0xF0, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xFF, + 0xFF, 0xC0, 0xC0, 0x00, 0x3C, 0x00, 0x07, 0xE0, 0x00, 0x7E, 0x00, 0x07, + 0xE0, 0x00, 0x3E, 0x00, 0x03, 0xE0, 0x00, 0x3F, 0x00, 0x03, 0xC0, 0x01, + 0xF0, 0x01, 0xF8, 0x01, 0xF8, 0x01, 0xF0, 0x01, 0xF0, 0x03, 0xF0, 0x03, + 0xF0, 0x00, 0xF0, 0x00, 0x20, 0x00, 0x00, 0x0F, 0x81, 0x86, 0x30, 0x33, + 0x03, 0x30, 0x30, 0x03, 0x00, 0x60, 0x0E, 0x01, 0xC0, 0x38, 0x06, 0x00, + 0xC0, 0x08, 0x01, 0x00, 0x10, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, + 0x00, 0xF0, 0x0F, 0x00, 0x60, 0x00, 0x00, 0x7F, 0x00, 0x03, 0xFF, 0xE0, + 0x07, 0x80, 0xF0, 0x0E, 0x00, 0x38, 0x1C, 0x00, 0x0C, 0x38, 0x0E, 0x06, + 0x70, 0x3F, 0xE2, 0x70, 0x71, 0xE3, 0xF0, 0x60, 0xE1, 0xE0, 0xC0, 0xC1, + 0xE0, 0xC0, 0xC1, 0xE1, 0x81, 0xC1, 0xE1, 0x81, 0xC1, 0xE1, 0x81, 0x82, + 0xE1, 0x83, 0x82, 0x71, 0x83, 0x86, 0x71, 0xC7, 0x8C, 0x38, 0xF9, 0xF8, + 0x3C, 0xF0, 0xF0, 0x1E, 0x00, 0x00, 0x0F, 0x80, 0x30, 0x03, 0xFF, 0xE0, + 0x00, 0x7F, 0x00, 0x00, 0x03, 0x00, 0x00, 0x18, 0x00, 0x01, 0xC0, 0x00, + 0x1E, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x5E, 0x00, 0x04, 0xF0, + 0x00, 0x63, 0x80, 0x02, 0x1C, 0x00, 0x20, 0xE0, 0x01, 0x07, 0x00, 0x10, + 0x3C, 0x01, 0xFF, 0xE0, 0x0F, 0xFF, 0x00, 0xC0, 0x38, 0x04, 0x01, 0xC0, + 0x60, 0x0E, 0x06, 0x00, 0x78, 0x30, 0x03, 0xC3, 0x00, 0x1E, 0x38, 0x00, + 0xFB, 0xF0, 0x1F, 0xE0, 0x07, 0xFF, 0x80, 0x0F, 0xFF, 0x00, 0x78, 0x3C, + 0x03, 0xC0, 0xF0, 0x1E, 0x07, 0x80, 0xE0, 0x3C, 0x07, 0x01, 0xE0, 0x78, + 0x1E, 0x03, 0x83, 0xE0, 0x1F, 0xF8, 0x01, 0xFF, 0xC0, 0x0F, 0x0F, 0x00, + 0x70, 0x3C, 0x03, 0x80, 0xF0, 0x3C, 0x07, 0x81, 0xC0, 0x3C, 0x0E, 0x01, + 0xE0, 0xF0, 0x0F, 0x07, 0x80, 0xF0, 0x38, 0x0F, 0x81, 0xC1, 0xF8, 0x1F, + 0xFF, 0x83, 0xFF, 0xE0, 0x00, 0x00, 0x3F, 0x08, 0x07, 0xFF, 0xC0, 0xF8, + 0x3E, 0x0F, 0x00, 0x70, 0xF0, 0x03, 0x8F, 0x00, 0x08, 0xF0, 0x00, 0x47, + 0x80, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x01, 0xE0, 0x00, + 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xF0, + 0x00, 0x03, 0x80, 0x02, 0x1E, 0x00, 0x20, 0x78, 0x02, 0x03, 0xE0, 0x60, + 0x07, 0xFE, 0x00, 0x0F, 0xC0, 0x00, 0x07, 0xFF, 0xC0, 0x00, 0xFF, 0xFC, + 0x00, 0x78, 0x1F, 0x00, 0x3C, 0x03, 0xC0, 0x1E, 0x00, 0xF0, 0x0E, 0x00, + 0x78, 0x07, 0x00, 0x1E, 0x07, 0x80, 0x0F, 0x03, 0x80, 0x07, 0x81, 0xC0, + 0x03, 0xC1, 0xE0, 0x01, 0xE0, 0xF0, 0x00, 0xF0, 0x70, 0x00, 0x78, 0x38, + 0x00, 0x78, 0x3C, 0x00, 0x3C, 0x1E, 0x00, 0x3E, 0x0E, 0x00, 0x1E, 0x0F, + 0x00, 0x1E, 0x07, 0x80, 0x1E, 0x03, 0x80, 0x3E, 0x01, 0xC0, 0x7E, 0x01, + 0xFF, 0xFC, 0x03, 0xFF, 0xF0, 0x00, 0x07, 0xFF, 0xFC, 0x07, 0xFF, 0xF0, + 0x1E, 0x01, 0xC0, 0x78, 0x02, 0x01, 0xE0, 0x08, 0x07, 0x00, 0x00, 0x1C, + 0x08, 0x00, 0xF0, 0x60, 0x03, 0x83, 0x80, 0x0F, 0xFC, 0x00, 0x7F, 0xF0, + 0x01, 0xE0, 0xC0, 0x07, 0x03, 0x00, 0x1C, 0x08, 0x00, 0xF0, 0x20, 0x03, + 0x80, 0x00, 0x0E, 0x00, 0x00, 0x78, 0x00, 0x81, 0xE0, 0x06, 0x07, 0x00, + 0x38, 0x1C, 0x03, 0xC0, 0xFF, 0xFF, 0x0F, 0xFF, 0xFC, 0x00, 0x07, 0xFF, + 0xFC, 0x07, 0xFF, 0xF0, 0x1E, 0x01, 0xC0, 0x78, 0x02, 0x01, 0xE0, 0x08, + 0x07, 0x00, 0x20, 0x1C, 0x00, 0x00, 0xF0, 0x20, 0x03, 0x81, 0x80, 0x0E, + 0x0C, 0x00, 0x7F, 0xF0, 0x01, 0xFF, 0xC0, 0x07, 0x03, 0x00, 0x1C, 0x0C, + 0x00, 0xF0, 0x20, 0x03, 0xC0, 0x00, 0x0E, 0x00, 0x00, 0x78, 0x00, 0x01, + 0xE0, 0x00, 0x07, 0x00, 0x00, 0x1C, 0x00, 0x00, 0xF8, 0x00, 0x0F, 0xF8, + 0x00, 0x00, 0x00, 0x3F, 0x02, 0x01, 0xFF, 0x88, 0x0F, 0x81, 0xF0, 0x3C, + 0x01, 0xE0, 0xF0, 0x01, 0xC3, 0xC0, 0x01, 0x0F, 0x80, 0x02, 0x1E, 0x00, + 0x00, 0x7C, 0x00, 0x00, 0xF0, 0x00, 0x01, 0xE0, 0x00, 0x07, 0xC0, 0x00, + 0x0F, 0x00, 0x3F, 0xFE, 0x00, 0x1E, 0x3C, 0x00, 0x38, 0x78, 0x00, 0x70, + 0xF0, 0x00, 0xE0, 0xE0, 0x01, 0xC1, 0xE0, 0x07, 0x01, 0xE0, 0x0E, 0x01, + 0xF0, 0x3C, 0x01, 0xFF, 0xF0, 0x00, 0xFF, 0x00, 0x00, 0x07, 0xFC, 0x3F, + 0xE0, 0x3E, 0x00, 0xF0, 0x07, 0x80, 0x1C, 0x00, 0xF0, 0x03, 0x80, 0x1C, + 0x00, 0xF0, 0x03, 0x80, 0x1E, 0x00, 0x70, 0x03, 0x80, 0x1E, 0x00, 0x70, + 0x03, 0x80, 0x1E, 0x00, 0x70, 0x03, 0x80, 0x1F, 0xFF, 0xF0, 0x03, 0xFF, + 0xFE, 0x00, 0x70, 0x03, 0xC0, 0x0E, 0x00, 0x70, 0x03, 0xC0, 0x0E, 0x00, + 0x70, 0x03, 0xC0, 0x0E, 0x00, 0x78, 0x03, 0xC0, 0x0E, 0x00, 0x78, 0x01, + 0xC0, 0x0E, 0x00, 0x78, 0x01, 0xC0, 0x0E, 0x00, 0x78, 0x03, 0xE0, 0x3F, + 0xE1, 0xFF, 0x00, 0x07, 0xFC, 0x07, 0xC0, 0x1E, 0x00, 0x78, 0x01, 0xC0, + 0x07, 0x00, 0x1C, 0x00, 0xF0, 0x03, 0x80, 0x0E, 0x00, 0x78, 0x01, 0xE0, + 0x07, 0x00, 0x1C, 0x00, 0xF0, 0x03, 0x80, 0x0E, 0x00, 0x78, 0x01, 0xE0, + 0x07, 0x00, 0x1C, 0x00, 0xF0, 0x0F, 0xF8, 0x00, 0x00, 0xFF, 0x80, 0x0F, + 0x00, 0x07, 0x80, 0x03, 0x80, 0x01, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, + 0x70, 0x00, 0x38, 0x00, 0x3C, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x0F, 0x00, + 0x07, 0x80, 0x03, 0x80, 0x01, 0xC0, 0x01, 0xE0, 0x00, 0xE0, 0x00, 0x70, + 0x1E, 0x78, 0x0F, 0x38, 0x07, 0xF8, 0x01, 0xF0, 0x00, 0x07, 0xFC, 0x7F, + 0x80, 0xF8, 0x0F, 0x00, 0x38, 0x07, 0x00, 0x3C, 0x07, 0x00, 0x1C, 0x06, + 0x00, 0x0E, 0x06, 0x00, 0x07, 0x0C, 0x00, 0x07, 0x8C, 0x00, 0x03, 0x9C, + 0x00, 0x01, 0xD8, 0x00, 0x01, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x73, + 0x80, 0x00, 0x39, 0xE0, 0x00, 0x3C, 0x78, 0x00, 0x1C, 0x1C, 0x00, 0x0E, + 0x0F, 0x00, 0x07, 0x03, 0x80, 0x07, 0x81, 0xE0, 0x03, 0x80, 0x70, 0x01, + 0xC0, 0x3C, 0x01, 0xE0, 0x1F, 0x03, 0xFE, 0x3F, 0xE0, 0x07, 0xFC, 0x00, + 0x1F, 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, + 0x01, 0xC0, 0x00, 0x3C, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x07, 0x80, + 0x00, 0x78, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x0F, 0x00, 0x00, 0xE0, + 0x00, 0x0E, 0x00, 0x11, 0xE0, 0x03, 0x1E, 0x00, 0x61, 0xC0, 0x06, 0x1C, + 0x01, 0xE3, 0xFF, 0xFC, 0xFF, 0xFF, 0xC0, 0x07, 0xF0, 0x00, 0x7E, 0x03, + 0xE0, 0x01, 0xF0, 0x03, 0xC0, 0x03, 0xE0, 0x07, 0x80, 0x0F, 0x80, 0x1F, + 0x00, 0x37, 0x00, 0x2E, 0x00, 0x5E, 0x00, 0x5C, 0x01, 0xB8, 0x01, 0xB8, + 0x06, 0x70, 0x02, 0x78, 0x09, 0xE0, 0x04, 0x70, 0x33, 0xC0, 0x08, 0xE0, + 0xC7, 0x00, 0x31, 0xC1, 0x0E, 0x00, 0x43, 0x86, 0x3C, 0x00, 0x87, 0x18, + 0x70, 0x03, 0x0E, 0x20, 0xE0, 0x06, 0x1C, 0xC3, 0xC0, 0x08, 0x3B, 0x07, + 0x80, 0x10, 0x7C, 0x0E, 0x00, 0x60, 0x78, 0x1C, 0x00, 0x80, 0xE0, 0x78, + 0x03, 0x01, 0x80, 0xF0, 0x07, 0x03, 0x03, 0xE0, 0x3F, 0x84, 0x1F, 0xF0, + 0x00, 0x07, 0xC0, 0x3F, 0xC0, 0x78, 0x03, 0xE0, 0x0E, 0x00, 0x70, 0x03, + 0xC0, 0x18, 0x01, 0xF0, 0x0E, 0x00, 0x6C, 0x03, 0x00, 0x1B, 0x80, 0xC0, + 0x0C, 0xE0, 0x30, 0x03, 0x18, 0x1C, 0x00, 0xC7, 0x06, 0x00, 0x30, 0xC1, + 0x80, 0x18, 0x38, 0xE0, 0x06, 0x06, 0x30, 0x01, 0x81, 0x8C, 0x00, 0xC0, + 0x73, 0x00, 0x30, 0x0D, 0xC0, 0x0C, 0x03, 0xE0, 0x03, 0x00, 0x78, 0x01, + 0x80, 0x1E, 0x00, 0x60, 0x07, 0x00, 0x38, 0x00, 0xC0, 0x0E, 0x00, 0x30, + 0x0F, 0xE0, 0x04, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0xFF, 0xE0, 0x07, 0xC1, + 0xE0, 0x1E, 0x01, 0xE0, 0x78, 0x01, 0xC1, 0xE0, 0x03, 0xC7, 0x80, 0x07, + 0x9F, 0x00, 0x0F, 0x3C, 0x00, 0x1E, 0xF8, 0x00, 0x3D, 0xE0, 0x00, 0xFF, + 0xC0, 0x01, 0xEF, 0x80, 0x03, 0xDE, 0x00, 0x0F, 0xBC, 0x00, 0x1E, 0x78, + 0x00, 0x7C, 0xF0, 0x00, 0xF1, 0xE0, 0x03, 0xC1, 0xC0, 0x0F, 0x03, 0xC0, + 0x3C, 0x03, 0xC1, 0xF0, 0x03, 0xFF, 0x80, 0x01, 0xFC, 0x00, 0x00, 0x07, + 0xFF, 0xC0, 0x07, 0xFF, 0xC0, 0x0E, 0x0F, 0x80, 0x78, 0x1F, 0x01, 0xC0, + 0x3C, 0x07, 0x00, 0xF0, 0x1C, 0x03, 0xC0, 0xF0, 0x0F, 0x03, 0x80, 0x78, + 0x0E, 0x01, 0xE0, 0x78, 0x1F, 0x01, 0xFF, 0xF8, 0x07, 0x7F, 0x00, 0x1C, + 0x00, 0x00, 0xF0, 0x00, 0x03, 0x80, 0x00, 0x0E, 0x00, 0x00, 0x78, 0x00, + 0x01, 0xE0, 0x00, 0x07, 0x00, 0x00, 0x1C, 0x00, 0x00, 0xF0, 0x00, 0x0F, + 0xF0, 0x00, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0xFF, 0xE0, 0x03, 0xC1, 0xE0, + 0x1E, 0x01, 0xC0, 0x78, 0x03, 0xC1, 0xE0, 0x03, 0x87, 0x80, 0x07, 0x8F, + 0x00, 0x0F, 0x3C, 0x00, 0x1E, 0x78, 0x00, 0x3D, 0xE0, 0x00, 0x7B, 0xC0, + 0x01, 0xFF, 0x80, 0x03, 0xDE, 0x00, 0x07, 0xBC, 0x00, 0x1F, 0x78, 0x00, + 0x3C, 0xF0, 0x00, 0xF1, 0xE0, 0x01, 0xE3, 0xC0, 0x07, 0x83, 0x80, 0x1E, + 0x07, 0x80, 0x78, 0x07, 0x01, 0xC0, 0x03, 0xDE, 0x00, 0x01, 0xC0, 0x00, + 0x06, 0x00, 0x00, 0x18, 0x00, 0x10, 0x7F, 0xC0, 0xC3, 0xFF, 0xFF, 0x08, + 0x07, 0xF0, 0x00, 0x07, 0xFF, 0x80, 0x0F, 0xFF, 0x00, 0x78, 0x3C, 0x03, + 0xC0, 0xF0, 0x1E, 0x07, 0x80, 0xE0, 0x3C, 0x07, 0x01, 0xE0, 0x78, 0x1E, + 0x03, 0x83, 0xF0, 0x1F, 0xFE, 0x01, 0xFF, 0xC0, 0x0F, 0x38, 0x00, 0x71, + 0xE0, 0x03, 0x87, 0x00, 0x3C, 0x38, 0x01, 0xC1, 0xE0, 0x0E, 0x07, 0x00, + 0xF0, 0x3C, 0x07, 0x81, 0xE0, 0x38, 0x07, 0x01, 0xC0, 0x3C, 0x1E, 0x00, + 0xF3, 0xFC, 0x07, 0xC0, 0x00, 0xF8, 0x81, 0xFF, 0xC1, 0xE1, 0xE1, 0xE0, + 0x70, 0xF0, 0x10, 0x78, 0x08, 0x3C, 0x00, 0x1F, 0x00, 0x07, 0x80, 0x01, + 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0xF8, + 0x80, 0x3C, 0x40, 0x1E, 0x20, 0x0F, 0x38, 0x07, 0x9E, 0x07, 0x8F, 0x87, + 0x84, 0x7F, 0xC2, 0x0F, 0x80, 0x3F, 0xFF, 0xF7, 0xFF, 0xFF, 0x70, 0x78, + 0x76, 0x07, 0x02, 0xC0, 0x70, 0x28, 0x0F, 0x02, 0x00, 0xF0, 0x00, 0x0E, + 0x00, 0x01, 0xE0, 0x00, 0x1E, 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x03, + 0xC0, 0x00, 0x3C, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x07, 0x80, 0x00, + 0x70, 0x00, 0x07, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x01, 0xF0, 0x00, + 0xFF, 0xE0, 0x00, 0x7F, 0xE0, 0xFE, 0x3F, 0x00, 0x78, 0x3C, 0x00, 0x60, + 0xF0, 0x01, 0x81, 0xE0, 0x03, 0x03, 0xC0, 0x06, 0x07, 0x00, 0x08, 0x1E, + 0x00, 0x30, 0x3C, 0x00, 0x60, 0x70, 0x00, 0x81, 0xE0, 0x01, 0x03, 0xC0, + 0x06, 0x07, 0x80, 0x0C, 0x0E, 0x00, 0x10, 0x3C, 0x00, 0x60, 0x78, 0x00, + 0xC0, 0xF0, 0x01, 0x01, 0xE0, 0x06, 0x03, 0xC0, 0x08, 0x03, 0xC0, 0x30, + 0x07, 0xC1, 0xC0, 0x07, 0xFF, 0x00, 0x03, 0xF8, 0x00, 0x00, 0xFF, 0x01, + 0xFB, 0xE0, 0x07, 0x8E, 0x00, 0x18, 0x78, 0x01, 0x83, 0xC0, 0x0C, 0x1E, + 0x00, 0xC0, 0xF0, 0x06, 0x03, 0x80, 0x60, 0x1C, 0x02, 0x00, 0xE0, 0x30, + 0x07, 0x83, 0x00, 0x3C, 0x10, 0x01, 0xE1, 0x80, 0x07, 0x08, 0x00, 0x38, + 0x80, 0x01, 0xC4, 0x00, 0x0E, 0x40, 0x00, 0x7C, 0x00, 0x03, 0xE0, 0x00, + 0x0E, 0x00, 0x00, 0x70, 0x00, 0x03, 0x00, 0x00, 0x10, 0x00, 0x00, 0xFF, + 0x3F, 0xC3, 0xFB, 0xE0, 0x78, 0x07, 0x8E, 0x03, 0xC0, 0x18, 0x78, 0x0E, + 0x01, 0x83, 0xC0, 0x70, 0x0C, 0x1E, 0x03, 0x80, 0x40, 0xF0, 0x3C, 0x06, + 0x03, 0x81, 0xE0, 0x60, 0x1C, 0x17, 0x83, 0x00, 0xE0, 0xBC, 0x30, 0x07, + 0x09, 0xE1, 0x00, 0x38, 0x47, 0x18, 0x01, 0xE4, 0x38, 0x80, 0x0F, 0x21, + 0xCC, 0x00, 0x7A, 0x0E, 0x40, 0x01, 0xD0, 0x76, 0x00, 0x0F, 0x03, 0xA0, + 0x00, 0x78, 0x1F, 0x00, 0x03, 0x80, 0xF0, 0x00, 0x1C, 0x07, 0x00, 0x00, + 0xC0, 0x38, 0x00, 0x06, 0x00, 0x80, 0x00, 0x20, 0x04, 0x00, 0x00, 0x0F, + 0xF8, 0x7F, 0x03, 0xE0, 0x3E, 0x01, 0xC0, 0x18, 0x01, 0xE0, 0x30, 0x01, + 0xE0, 0x60, 0x00, 0xE0, 0xC0, 0x00, 0xF1, 0xC0, 0x00, 0x71, 0x80, 0x00, + 0x7B, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x3C, 0x00, 0x00, 0x7E, 0x00, 0x00, 0xCE, 0x00, 0x01, 0x8F, 0x00, 0x01, + 0x07, 0x00, 0x03, 0x07, 0x00, 0x06, 0x07, 0x80, 0x0C, 0x03, 0x80, 0x18, + 0x03, 0xC0, 0x78, 0x03, 0xE0, 0xFE, 0x1F, 0xF8, 0xFF, 0x87, 0xE7, 0xC0, + 0x38, 0x70, 0x06, 0x0E, 0x01, 0x81, 0xE0, 0x30, 0x1C, 0x0C, 0x03, 0x83, + 0x00, 0x78, 0xC0, 0x07, 0x30, 0x00, 0xE4, 0x00, 0x1D, 0x80, 0x03, 0xE0, + 0x00, 0x38, 0x00, 0x0F, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x07, 0x00, + 0x01, 0xE0, 0x00, 0x38, 0x00, 0x07, 0x00, 0x01, 0xE0, 0x00, 0x7C, 0x00, + 0x3F, 0xF0, 0x00, 0x07, 0xFF, 0xFC, 0x3F, 0xFF, 0xE0, 0xE0, 0x0F, 0x82, + 0x00, 0x3C, 0x18, 0x01, 0xE0, 0x40, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, + 0xC0, 0x00, 0x0E, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, + 0x00, 0xF0, 0x00, 0x07, 0x80, 0x00, 0x1C, 0x00, 0x00, 0xF0, 0x00, 0x07, + 0x80, 0x00, 0x3C, 0x00, 0xC1, 0xE0, 0x02, 0x0F, 0x00, 0x18, 0x38, 0x01, + 0xE1, 0xFF, 0xFF, 0x0F, 0xFF, 0xFC, 0x00, 0x01, 0xF8, 0x0C, 0x00, 0xC0, + 0x06, 0x00, 0x30, 0x01, 0x80, 0x18, 0x00, 0xC0, 0x06, 0x00, 0x30, 0x03, + 0x00, 0x18, 0x00, 0xC0, 0x06, 0x00, 0x60, 0x03, 0x00, 0x18, 0x01, 0xC0, + 0x0C, 0x00, 0x60, 0x03, 0x00, 0x30, 0x01, 0x80, 0x0C, 0x00, 0x60, 0x06, + 0x00, 0x30, 0x01, 0xF8, 0x00, 0xE0, 0x0E, 0x00, 0x60, 0x07, 0x00, 0x30, + 0x03, 0x80, 0x18, 0x01, 0xC0, 0x0C, 0x00, 0xC0, 0x0E, 0x00, 0x60, 0x07, + 0x00, 0x30, 0x03, 0x80, 0x18, 0x01, 0xC0, 0x0C, 0x00, 0xC0, 0x0E, 0x00, + 0x60, 0x07, 0x00, 0x30, 0x03, 0xF0, 0x06, 0x00, 0x60, 0x06, 0x00, 0x60, + 0x0E, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x01, 0x80, 0x18, 0x01, 0x80, + 0x18, 0x03, 0x00, 0x30, 0x03, 0x00, 0x30, 0x03, 0x00, 0x60, 0x06, 0x00, + 0x60, 0x06, 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x0F, 0xC0, 0x03, 0x80, + 0x07, 0x00, 0x1F, 0x00, 0x36, 0x00, 0xCE, 0x01, 0x8C, 0x06, 0x1C, 0x0C, + 0x18, 0x38, 0x38, 0x60, 0x31, 0xC0, 0x73, 0x00, 0x6E, 0x00, 0xE0, 0xFF, + 0xFF, 0xFF, 0xFF, 0xF0, 0xE3, 0x8F, 0x0E, 0x18, 0x30, 0x01, 0xEC, 0x0E, + 0x58, 0x30, 0x70, 0xE0, 0xC3, 0x81, 0x86, 0x07, 0x1C, 0x0C, 0x38, 0x18, + 0xE0, 0x71, 0xC0, 0xE3, 0x83, 0x87, 0x0B, 0x2F, 0x36, 0xCF, 0xCF, 0x1F, + 0x1C, 0x00, 0x03, 0x00, 0x1F, 0x00, 0x07, 0x00, 0x07, 0x00, 0x06, 0x00, + 0x0E, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x0C, 0x00, 0x1C, 0x7C, 0x1C, 0xFE, + 0x19, 0x8F, 0x1A, 0x07, 0x3C, 0x07, 0x38, 0x07, 0x38, 0x07, 0x70, 0x0E, + 0x70, 0x0E, 0x70, 0x1C, 0x60, 0x18, 0xE0, 0x30, 0xE0, 0x60, 0xE1, 0xC0, + 0x3F, 0x00, 0x01, 0xF0, 0x38, 0xC3, 0x8E, 0x78, 0x73, 0x80, 0x3C, 0x01, + 0xC0, 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x47, 0x84, 0x3F, + 0xC0, 0x7C, 0x00, 0x00, 0x01, 0x80, 0x07, 0xC0, 0x00, 0xE0, 0x00, 0x60, + 0x00, 0x30, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0C, 0x00, 0x06, 0x00, 0xF7, + 0x01, 0xC7, 0x81, 0xC3, 0x81, 0xC1, 0xC1, 0xE0, 0xE0, 0xE0, 0x60, 0xF0, + 0x30, 0x78, 0x38, 0x78, 0x18, 0x3C, 0x0C, 0x1E, 0x0C, 0x0F, 0x0E, 0x27, + 0xCB, 0x21, 0xF9, 0xE0, 0x78, 0xE0, 0x00, 0xF0, 0x1C, 0xC3, 0x86, 0x38, + 0x33, 0xC3, 0x1C, 0x31, 0xE3, 0x1F, 0xE0, 0xF0, 0x07, 0x80, 0x3C, 0x01, + 0xE0, 0x47, 0x84, 0x3F, 0xC0, 0x7C, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x33, + 0x00, 0x06, 0x30, 0x00, 0xC0, 0x00, 0x0C, 0x00, 0x01, 0xC0, 0x00, 0x18, + 0x00, 0x01, 0x80, 0x00, 0x38, 0x00, 0x3F, 0xF8, 0x03, 0xFF, 0x80, 0x03, + 0x00, 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x06, 0x00, 0x00, + 0x60, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x0C, 0x00, 0x00, 0xC0, 0x00, + 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x18, 0x00, 0x01, 0x80, 0x00, 0x18, 0x00, + 0x03, 0x00, 0x00, 0x30, 0x00, 0xC6, 0x00, 0x0C, 0xC0, 0x00, 0x78, 0x00, + 0x00, 0x01, 0xF8, 0x07, 0x1F, 0x0E, 0x0F, 0x0C, 0x0E, 0x18, 0x0E, 0x18, + 0x0E, 0x18, 0x1E, 0x18, 0x3C, 0x0C, 0x78, 0x07, 0xE0, 0x08, 0x00, 0x18, + 0x00, 0x1E, 0x00, 0x0F, 0xE0, 0x13, 0xF0, 0x60, 0x78, 0xC0, 0x38, 0xC0, + 0x18, 0xC0, 0x18, 0xC0, 0x30, 0x60, 0x60, 0x3F, 0x80, 0x03, 0x00, 0x1F, + 0x00, 0x07, 0x00, 0x07, 0x00, 0x06, 0x00, 0x06, 0x00, 0x0E, 0x00, 0x0E, + 0x00, 0x0C, 0x00, 0x1C, 0x38, 0x1C, 0x7C, 0x1C, 0xCC, 0x19, 0x0C, 0x3A, + 0x0C, 0x3C, 0x1C, 0x3C, 0x18, 0x38, 0x18, 0x70, 0x38, 0x70, 0x38, 0x70, + 0x30, 0x60, 0x72, 0xE0, 0x76, 0xE0, 0x7C, 0xC0, 0x70, 0x03, 0x03, 0xC1, + 0xE0, 0x60, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x7E, 0x0F, 0x03, 0x81, 0x81, + 0xC0, 0xE0, 0x70, 0x30, 0x38, 0x1C, 0x1C, 0x4C, 0x47, 0xC3, 0xC0, 0x00, + 0x0C, 0x00, 0x3C, 0x00, 0x78, 0x00, 0x60, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x18, 0x03, 0xF0, 0x00, 0xE0, 0x01, 0x80, 0x03, 0x00, + 0x0E, 0x00, 0x1C, 0x00, 0x30, 0x00, 0x60, 0x01, 0xC0, 0x03, 0x80, 0x06, + 0x00, 0x0C, 0x00, 0x38, 0x00, 0x70, 0x00, 0xC0, 0x03, 0x80, 0x06, 0x00, + 0x0C, 0x06, 0x30, 0x0C, 0xC0, 0x0F, 0x00, 0x00, 0x03, 0x00, 0x3E, 0x00, + 0x1C, 0x00, 0x38, 0x00, 0x60, 0x01, 0xC0, 0x03, 0x80, 0x07, 0x00, 0x0C, + 0x00, 0x38, 0xFC, 0x70, 0x60, 0xE1, 0x81, 0x86, 0x07, 0x10, 0x0E, 0x40, + 0x1B, 0x80, 0x3F, 0x00, 0xE7, 0x01, 0xCE, 0x03, 0x0C, 0x06, 0x1C, 0x5C, + 0x1D, 0x38, 0x3E, 0x60, 0x38, 0x03, 0x1F, 0x07, 0x07, 0x06, 0x0E, 0x0E, + 0x0E, 0x0C, 0x1C, 0x1C, 0x18, 0x38, 0x38, 0x38, 0x30, 0x70, 0x70, 0x70, + 0x64, 0xE4, 0xE8, 0xF0, 0xE0, 0x00, 0x06, 0x18, 0x1E, 0x3E, 0x3C, 0x3F, + 0x0E, 0x4C, 0x47, 0x0C, 0x8C, 0x8E, 0x1D, 0x0D, 0x0E, 0x1E, 0x1A, 0x0E, + 0x1C, 0x1E, 0x0C, 0x3C, 0x1C, 0x1C, 0x38, 0x38, 0x1C, 0x38, 0x38, 0x1C, + 0x30, 0x38, 0x18, 0x70, 0x30, 0x39, 0x70, 0x70, 0x32, 0x60, 0x70, 0x3C, + 0x60, 0x60, 0x38, 0x06, 0x0E, 0x1F, 0x1F, 0x83, 0x99, 0xC1, 0x98, 0xC1, + 0xD8, 0xE0, 0xE8, 0x70, 0x78, 0x30, 0x38, 0x38, 0x3C, 0x1C, 0x1C, 0x0E, + 0x0E, 0x06, 0x0E, 0x03, 0x17, 0x01, 0xB3, 0x80, 0xF1, 0x80, 0x70, 0x01, + 0xF0, 0x0E, 0x38, 0x38, 0x30, 0xE0, 0x73, 0x80, 0xEE, 0x01, 0xDC, 0x03, + 0xF8, 0x0F, 0xE0, 0x1D, 0xC0, 0x3B, 0x80, 0xE7, 0x03, 0x8E, 0x06, 0x0E, + 0x38, 0x07, 0xC0, 0x00, 0x00, 0xE7, 0xC0, 0x7C, 0xFE, 0x01, 0xD1, 0xF0, + 0x1E, 0x0F, 0x01, 0xC0, 0xF0, 0x38, 0x0F, 0x03, 0x80, 0xF0, 0x38, 0x0E, + 0x03, 0x01, 0xE0, 0x70, 0x1C, 0x07, 0x03, 0xC0, 0x60, 0x78, 0x06, 0x0F, + 0x00, 0xE1, 0xC0, 0x0F, 0xF0, 0x00, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xC0, + 0x00, 0x1C, 0x00, 0x01, 0x80, 0x00, 0x38, 0x00, 0x0F, 0xF0, 0x00, 0x00, + 0xF7, 0x03, 0xCE, 0x0F, 0x06, 0x1E, 0x06, 0x1C, 0x04, 0x3C, 0x04, 0x78, + 0x04, 0x78, 0x0C, 0xF0, 0x08, 0xF0, 0x18, 0xF0, 0x38, 0xF0, 0xF0, 0xF9, + 0x70, 0x7E, 0x70, 0x3C, 0x70, 0x00, 0x60, 0x00, 0xE0, 0x00, 0xE0, 0x00, + 0xC0, 0x01, 0xC0, 0x01, 0xC0, 0x0F, 0xF0, 0x7C, 0x70, 0xE7, 0xC7, 0x4C, + 0x34, 0x01, 0xA0, 0x1E, 0x00, 0xF0, 0x07, 0x00, 0x78, 0x03, 0x80, 0x1C, + 0x00, 0xC0, 0x0E, 0x00, 0x70, 0x03, 0x80, 0x00, 0x07, 0x88, 0x63, 0x86, + 0x0C, 0x30, 0x21, 0xC1, 0x0E, 0x00, 0x38, 0x00, 0xE0, 0x03, 0x80, 0x1C, + 0x10, 0x60, 0x83, 0x06, 0x18, 0x71, 0x82, 0x78, 0x00, 0x02, 0x03, 0x03, + 0x07, 0xF7, 0xF8, 0xE0, 0x60, 0x70, 0x38, 0x1C, 0x0C, 0x0E, 0x07, 0x03, + 0x01, 0x91, 0xC8, 0xF8, 0x78, 0x00, 0x1C, 0x0D, 0xF8, 0x38, 0x60, 0x70, + 0xC1, 0xC3, 0x83, 0x87, 0x07, 0x0C, 0x1E, 0x38, 0x78, 0x70, 0xB0, 0xE2, + 0x61, 0x8D, 0xC7, 0x33, 0x2C, 0xC6, 0x5F, 0x0F, 0x38, 0x1C, 0x00, 0x18, + 0x1B, 0xE0, 0x73, 0x81, 0xC6, 0x03, 0x18, 0x0C, 0x70, 0x21, 0xC1, 0x83, + 0x0C, 0x0C, 0x20, 0x31, 0x00, 0xC8, 0x03, 0x40, 0x0E, 0x00, 0x30, 0x00, + 0x80, 0x00, 0x18, 0x04, 0x1B, 0xE0, 0x30, 0x71, 0x80, 0xC1, 0xC6, 0x07, + 0x01, 0x1C, 0x2C, 0x08, 0x70, 0xB0, 0x20, 0xC4, 0xC1, 0x03, 0x21, 0x84, + 0x0D, 0x86, 0x20, 0x34, 0x19, 0x00, 0xE0, 0x68, 0x03, 0x81, 0xA0, 0x0C, + 0x07, 0x00, 0x30, 0x18, 0x00, 0x80, 0x40, 0x00, 0x03, 0x07, 0x0F, 0x8F, + 0x13, 0x93, 0x01, 0xB0, 0x01, 0xE0, 0x01, 0xC0, 0x00, 0xC0, 0x00, 0xC0, + 0x01, 0xC0, 0x03, 0xE0, 0x02, 0x60, 0x04, 0x62, 0x08, 0x64, 0xF0, 0x7C, + 0xE0, 0x30, 0x06, 0x06, 0x3F, 0x07, 0x07, 0x07, 0x07, 0x03, 0x03, 0x81, + 0x03, 0x82, 0x01, 0x82, 0x01, 0xC4, 0x01, 0xC4, 0x01, 0xC8, 0x00, 0xC8, + 0x00, 0xD0, 0x00, 0xF0, 0x00, 0xE0, 0x00, 0xC0, 0x00, 0xC0, 0x00, 0x80, + 0x01, 0x00, 0x02, 0x00, 0x04, 0x00, 0x78, 0x00, 0x70, 0x00, 0x1F, 0xFC, + 0x7F, 0xE1, 0x01, 0x08, 0x08, 0x00, 0x40, 0x02, 0x00, 0x10, 0x00, 0x80, + 0x06, 0x00, 0x10, 0x00, 0x80, 0x04, 0x00, 0x38, 0x01, 0xF0, 0x0B, 0xE0, + 0x01, 0xC6, 0x03, 0x98, 0x03, 0x80, 0x00, 0x70, 0x0C, 0x01, 0x80, 0x38, + 0x03, 0x80, 0x30, 0x07, 0x00, 0x70, 0x07, 0x00, 0x60, 0x0E, 0x00, 0xE0, + 0x0C, 0x01, 0xC0, 0x1C, 0x07, 0x80, 0x30, 0x04, 0x00, 0x20, 0x03, 0x00, + 0x30, 0x07, 0x00, 0x70, 0x06, 0x00, 0x60, 0x0E, 0x00, 0xE0, 0x0C, 0x00, + 0xC0, 0x07, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFC, 0x00, 0xC0, 0x06, + 0x00, 0x30, 0x03, 0x00, 0x30, 0x03, 0x00, 0x70, 0x07, 0x00, 0x70, 0x06, + 0x00, 0xE0, 0x0E, 0x00, 0xE0, 0x0C, 0x00, 0x40, 0x04, 0x00, 0xC0, 0x1E, + 0x03, 0x80, 0x38, 0x03, 0x00, 0x70, 0x07, 0x00, 0x70, 0x06, 0x00, 0xE0, + 0x0E, 0x00, 0xC0, 0x1C, 0x01, 0x80, 0x70, 0x00, 0x1E, 0x00, 0x3F, 0xE1, + 0xF8, 0x7F, 0xC0, 0x07, 0x80 }; + +const GFXglyph FreeSerifItalic18pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 9, 0, 1 }, // 0x20 ' ' + { 0, 10, 23, 12, 1, -22 }, // 0x21 '!' + { 29, 12, 9, 12, 4, -22 }, // 0x22 '"' + { 43, 19, 23, 17, 0, -22 }, // 0x23 '#' + { 98, 15, 29, 17, 1, -25 }, // 0x24 '$' + { 153, 25, 23, 29, 3, -22 }, // 0x25 '%' + { 225, 22, 23, 27, 3, -22 }, // 0x26 '&' + { 289, 5, 9, 7, 4, -22 }, // 0x27 ''' + { 295, 9, 29, 12, 1, -22 }, // 0x28 '(' + { 328, 9, 29, 12, 1, -22 }, // 0x29 ')' + { 361, 12, 14, 18, 5, -22 }, // 0x2A '*' + { 382, 16, 18, 24, 4, -17 }, // 0x2B '+' + { 418, 5, 8, 9, -1, -2 }, // 0x2C ',' + { 423, 8, 2, 12, 2, -8 }, // 0x2D '-' + { 425, 4, 4, 9, 1, -3 }, // 0x2E '.' + { 427, 16, 23, 10, 0, -22 }, // 0x2F '/' + { 473, 17, 24, 17, 1, -23 }, // 0x30 '0' + { 524, 12, 24, 17, 2, -23 }, // 0x31 '1' + { 560, 16, 23, 17, 1, -22 }, // 0x32 '2' + { 606, 17, 24, 18, 0, -23 }, // 0x33 '3' + { 657, 17, 24, 17, 0, -23 }, // 0x34 '4' + { 708, 16, 23, 18, 0, -22 }, // 0x35 '5' + { 754, 17, 24, 18, 1, -23 }, // 0x36 '6' + { 805, 16, 23, 17, 3, -22 }, // 0x37 '7' + { 851, 16, 24, 18, 1, -23 }, // 0x38 '8' + { 899, 16, 24, 17, 1, -23 }, // 0x39 '9' + { 947, 7, 15, 9, 2, -14 }, // 0x3A ':' + { 961, 9, 20, 9, 1, -14 }, // 0x3B ';' + { 984, 18, 18, 20, 2, -17 }, // 0x3C '<' + { 1025, 18, 9, 23, 3, -12 }, // 0x3D '=' + { 1046, 18, 18, 20, 2, -17 }, // 0x3E '>' + { 1087, 12, 23, 16, 4, -22 }, // 0x3F '?' + { 1122, 24, 23, 27, 2, -22 }, // 0x40 '@' + { 1191, 21, 23, 23, 0, -22 }, // 0x41 'A' + { 1252, 21, 23, 21, 0, -22 }, // 0x42 'B' + { 1313, 21, 23, 21, 2, -22 }, // 0x43 'C' + { 1374, 25, 23, 25, 0, -22 }, // 0x44 'D' + { 1446, 22, 23, 20, 0, -22 }, // 0x45 'E' + { 1510, 22, 23, 20, 0, -22 }, // 0x46 'F' + { 1574, 23, 23, 24, 2, -22 }, // 0x47 'G' + { 1641, 27, 23, 25, 0, -22 }, // 0x48 'H' + { 1719, 14, 23, 11, 0, -22 }, // 0x49 'I' + { 1760, 17, 23, 15, 0, -22 }, // 0x4A 'J' + { 1809, 25, 23, 22, 0, -22 }, // 0x4B 'K' + { 1881, 20, 23, 20, 0, -22 }, // 0x4C 'L' + { 1939, 31, 23, 29, 0, -22 }, // 0x4D 'M' + { 2029, 26, 23, 24, 0, -22 }, // 0x4E 'N' + { 2104, 23, 23, 23, 1, -22 }, // 0x4F 'O' + { 2171, 22, 23, 20, 0, -22 }, // 0x50 'P' + { 2235, 23, 29, 23, 1, -22 }, // 0x51 'Q' + { 2319, 21, 23, 22, 0, -22 }, // 0x52 'R' + { 2380, 17, 23, 16, 0, -22 }, // 0x53 'S' + { 2429, 20, 23, 21, 3, -22 }, // 0x54 'T' + { 2487, 23, 23, 25, 4, -22 }, // 0x55 'U' + { 2554, 21, 23, 23, 5, -22 }, // 0x56 'V' + { 2615, 29, 23, 31, 5, -22 }, // 0x57 'W' + { 2699, 24, 23, 23, 0, -22 }, // 0x58 'X' + { 2768, 19, 23, 21, 4, -22 }, // 0x59 'Y' + { 2823, 22, 23, 20, 0, -22 }, // 0x5A 'Z' + { 2887, 13, 28, 14, 1, -22 }, // 0x5B '[' + { 2933, 12, 23, 17, 4, -22 }, // 0x5C '\' + { 2968, 12, 28, 14, 1, -22 }, // 0x5D ']' + { 3010, 15, 13, 15, 0, -22 }, // 0x5E '^' + { 3035, 18, 2, 17, 0, 3 }, // 0x5F '_' + { 3040, 6, 6, 9, 5, -22 }, // 0x60 '`' + { 3045, 15, 15, 17, 1, -14 }, // 0x61 'a' + { 3074, 16, 24, 17, 1, -23 }, // 0x62 'b' + { 3122, 13, 15, 14, 1, -14 }, // 0x63 'c' + { 3147, 17, 24, 18, 1, -23 }, // 0x64 'd' + { 3198, 13, 15, 14, 1, -14 }, // 0x65 'e' + { 3223, 20, 31, 15, -3, -23 }, // 0x66 'f' + { 3301, 16, 22, 15, -1, -14 }, // 0x67 'g' + { 3345, 16, 24, 17, 1, -23 }, // 0x68 'h' + { 3393, 9, 23, 9, 1, -22 }, // 0x69 'i' + { 3419, 15, 30, 10, -3, -22 }, // 0x6A 'j' + { 3476, 15, 24, 16, 1, -23 }, // 0x6B 'k' + { 3521, 8, 25, 9, 1, -23 }, // 0x6C 'l' + { 3546, 24, 15, 25, 0, -14 }, // 0x6D 'm' + { 3591, 17, 15, 17, 0, -14 }, // 0x6E 'n' + { 3623, 15, 15, 17, 1, -14 }, // 0x6F 'o' + { 3652, 20, 22, 16, -3, -14 }, // 0x70 'p' + { 3707, 16, 22, 17, 1, -14 }, // 0x71 'q' + { 3751, 13, 15, 13, 1, -14 }, // 0x72 'r' + { 3776, 13, 15, 12, 0, -14 }, // 0x73 's' + { 3801, 9, 18, 8, 1, -17 }, // 0x74 't' + { 3822, 15, 15, 17, 1, -14 }, // 0x75 'u' + { 3851, 14, 15, 16, 2, -14 }, // 0x76 'v' + { 3878, 22, 15, 24, 1, -14 }, // 0x77 'w' + { 3920, 16, 15, 15, -1, -14 }, // 0x78 'x' + { 3950, 16, 22, 16, 0, -14 }, // 0x79 'y' + { 3994, 14, 18, 14, 0, -14 }, // 0x7A 'z' + { 4026, 12, 30, 14, 2, -23 }, // 0x7B '{' + { 4071, 2, 23, 10, 4, -22 }, // 0x7C '|' + { 4077, 12, 31, 14, 0, -24 }, // 0x7D '}' + { 4124, 17, 4, 19, 1, -10 } }; // 0x7E '~' + +const GFXfont FreeSerifItalic18pt7b PROGMEM = { + (uint8_t *)FreeSerifItalic18pt7bBitmaps, + (GFXglyph *)FreeSerifItalic18pt7bGlyphs, + 0x20, 0x7E, 42 }; + +// Approx. 4805 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic24pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic24pt7b.h new file mode 100644 index 0000000..75da1e0 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic24pt7b.h @@ -0,0 +1,737 @@ +const uint8_t FreeSerifItalic24pt7bBitmaps[] PROGMEM = { + 0x00, 0xF0, 0x0F, 0x00, 0xF0, 0x0F, 0x01, 0xF0, 0x1E, 0x01, 0xE0, 0x1C, + 0x01, 0xC0, 0x3C, 0x03, 0x80, 0x38, 0x03, 0x80, 0x30, 0x07, 0x00, 0x60, + 0x06, 0x00, 0x60, 0x04, 0x00, 0x40, 0x0C, 0x00, 0x80, 0x08, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x07, 0x00, 0xF8, 0x0F, 0x80, 0xF8, 0x07, 0x00, + 0x38, 0x1D, 0xE0, 0x77, 0x83, 0xDC, 0x0E, 0x70, 0x39, 0xC1, 0xEE, 0x07, + 0x38, 0x1C, 0xC0, 0x63, 0x01, 0x8C, 0x06, 0x20, 0x10, 0x00, 0x06, 0x03, + 0x00, 0x07, 0x03, 0x80, 0x03, 0x81, 0xC0, 0x03, 0x81, 0xC0, 0x01, 0xC0, + 0xE0, 0x00, 0xE0, 0x70, 0x00, 0xE0, 0x70, 0x00, 0x70, 0x38, 0x00, 0x30, + 0x18, 0x00, 0x38, 0x1C, 0x03, 0xFF, 0xFF, 0xE1, 0xFF, 0xFF, 0xF0, 0x0E, + 0x07, 0x00, 0x06, 0x03, 0x00, 0x07, 0x03, 0x80, 0x03, 0x81, 0xC0, 0x03, + 0x81, 0xC0, 0x01, 0xC0, 0xE0, 0x00, 0xE0, 0x70, 0x1F, 0xFF, 0xFF, 0x8F, + 0xFF, 0xFF, 0x80, 0x70, 0x38, 0x00, 0x38, 0x1C, 0x00, 0x1C, 0x0C, 0x00, + 0x1C, 0x0E, 0x00, 0x0E, 0x07, 0x00, 0x0E, 0x07, 0x00, 0x07, 0x03, 0x80, + 0x03, 0x81, 0xC0, 0x03, 0x81, 0xC0, 0x01, 0xC0, 0xE0, 0x00, 0x00, 0x01, + 0x00, 0x00, 0x18, 0x00, 0x00, 0xC0, 0x00, 0xFF, 0x80, 0x1C, 0x2F, 0x01, + 0x83, 0x3C, 0x1C, 0x18, 0xE1, 0xC0, 0xC3, 0x0E, 0x06, 0x18, 0x70, 0x60, + 0x83, 0x83, 0x04, 0x1E, 0x18, 0x00, 0xF8, 0xC0, 0x03, 0xEC, 0x00, 0x0F, + 0xE0, 0x00, 0x3F, 0x00, 0x00, 0xFC, 0x00, 0x03, 0xF0, 0x00, 0x0F, 0xC0, + 0x00, 0x7F, 0x00, 0x03, 0x7C, 0x00, 0x19, 0xE0, 0x01, 0x87, 0x80, 0x0C, + 0x3C, 0x00, 0x60, 0xE2, 0x03, 0x07, 0x10, 0x30, 0x39, 0x81, 0x81, 0xCE, + 0x0C, 0x0C, 0x70, 0x60, 0xE3, 0xC6, 0x06, 0x0F, 0x30, 0x60, 0x1F, 0x9E, + 0x00, 0x3F, 0x80, 0x00, 0xC0, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, + 0x80, 0x00, 0x01, 0xF0, 0x00, 0xC0, 0x03, 0xFE, 0x01, 0xE0, 0x03, 0xC7, + 0x83, 0xE0, 0x03, 0xC0, 0x7F, 0x60, 0x03, 0xC0, 0x20, 0x70, 0x01, 0xC0, + 0x10, 0x30, 0x01, 0xE0, 0x08, 0x38, 0x00, 0xE0, 0x04, 0x18, 0x00, 0xF0, + 0x02, 0x1C, 0x00, 0x70, 0x02, 0x0C, 0x00, 0x38, 0x01, 0x0E, 0x00, 0x1C, + 0x01, 0x8E, 0x00, 0x0E, 0x00, 0x86, 0x00, 0x07, 0x00, 0x87, 0x03, 0xE1, + 0x80, 0xC3, 0x07, 0xFC, 0xE1, 0xC3, 0x87, 0xC6, 0x3F, 0x81, 0x87, 0x81, + 0x8F, 0x81, 0xC7, 0x80, 0x40, 0x00, 0xC3, 0xC0, 0x20, 0x00, 0xE3, 0xC0, + 0x10, 0x00, 0x61, 0xC0, 0x08, 0x00, 0x61, 0xE0, 0x04, 0x00, 0x70, 0xF0, + 0x06, 0x00, 0x30, 0x70, 0x02, 0x00, 0x38, 0x38, 0x03, 0x00, 0x18, 0x1C, + 0x01, 0x00, 0x1C, 0x0E, 0x01, 0x80, 0x0C, 0x07, 0x01, 0x80, 0x0E, 0x01, + 0xC3, 0x80, 0x06, 0x00, 0x7F, 0x80, 0x06, 0x00, 0x1F, 0x00, 0x07, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x71, + 0xC0, 0x00, 0x01, 0xC3, 0x80, 0x00, 0x0E, 0x0E, 0x00, 0x00, 0x38, 0x38, + 0x00, 0x01, 0xE0, 0xE0, 0x00, 0x07, 0x87, 0x00, 0x00, 0x1E, 0x18, 0x00, + 0x00, 0x78, 0xC0, 0x00, 0x01, 0xE6, 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x00, 0x78, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x7F, + 0xC1, 0xFE, 0x03, 0x9F, 0x03, 0xE0, 0x3C, 0x3C, 0x07, 0x01, 0xE0, 0xF8, + 0x1C, 0x0F, 0x03, 0xE0, 0xE0, 0x7C, 0x07, 0x83, 0x01, 0xE0, 0x1F, 0x1C, + 0x07, 0x80, 0x7C, 0x60, 0x3E, 0x00, 0xFB, 0x00, 0xF8, 0x03, 0xFC, 0x03, + 0xE0, 0x07, 0xE0, 0x0F, 0x80, 0x1F, 0x00, 0x3F, 0x00, 0x3E, 0x00, 0x7C, + 0x00, 0xFC, 0x01, 0xF8, 0x0F, 0xF0, 0x03, 0xF0, 0xF3, 0xF0, 0x87, 0xFF, + 0x07, 0xFC, 0x07, 0xF0, 0x07, 0xC0, 0x39, 0xDE, 0xE7, 0x3B, 0x9C, 0xC6, + 0x31, 0x00, 0x00, 0x10, 0x01, 0x00, 0x18, 0x01, 0x80, 0x18, 0x01, 0x80, + 0x1C, 0x00, 0xC0, 0x0E, 0x00, 0xE0, 0x07, 0x00, 0x78, 0x03, 0x80, 0x3C, + 0x01, 0xE0, 0x0E, 0x00, 0x70, 0x07, 0x80, 0x3C, 0x01, 0xE0, 0x0E, 0x00, + 0x70, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x0E, + 0x00, 0x30, 0x01, 0x80, 0x0C, 0x00, 0x60, 0x01, 0x80, 0x0C, 0x00, 0x60, + 0x01, 0x00, 0x0C, 0x00, 0x20, 0x00, 0x00, 0x80, 0x06, 0x00, 0x10, 0x00, + 0x80, 0x06, 0x00, 0x30, 0x00, 0xC0, 0x06, 0x00, 0x30, 0x01, 0x80, 0x0C, + 0x00, 0x70, 0x03, 0x80, 0x1C, 0x00, 0xE0, 0x07, 0x00, 0x38, 0x01, 0xC0, + 0x1E, 0x00, 0xF0, 0x07, 0x80, 0x3C, 0x01, 0xC0, 0x1E, 0x00, 0xF0, 0x07, + 0x80, 0x38, 0x03, 0xC0, 0x1C, 0x00, 0xE0, 0x0E, 0x00, 0x60, 0x07, 0x00, + 0x30, 0x03, 0x00, 0x30, 0x03, 0x00, 0x10, 0x01, 0x00, 0x00, 0x01, 0x00, + 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, 0xE1, 0x07, 0xE1, 0x0F, + 0xF1, 0x1F, 0x19, 0x30, 0x07, 0xC0, 0x03, 0x80, 0x0D, 0x60, 0x79, 0x3C, + 0xF1, 0x1F, 0xE1, 0x0F, 0xE1, 0x07, 0x03, 0x80, 0x03, 0x80, 0x03, 0x80, + 0x03, 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, 0x00, 0xE0, 0x00, 0x01, + 0xC0, 0x00, 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, + 0x00, 0x00, 0x38, 0x00, 0x00, 0x70, 0x03, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xE0, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x00, + 0x00, 0x38, 0x00, 0x00, 0x70, 0x00, 0x00, 0xE0, 0x00, 0x01, 0xC0, 0x00, + 0x03, 0x80, 0x00, 0x07, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x1C, 0x7C, 0xF9, + 0xF1, 0xE1, 0xC3, 0x0C, 0x10, 0xC1, 0x00, 0x7F, 0xFF, 0xFF, 0xFF, 0x00, + 0x77, 0xFF, 0xF7, 0x00, 0x00, 0x00, 0x78, 0x00, 0x03, 0x80, 0x00, 0x3C, + 0x00, 0x01, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, 0x00, + 0xF0, 0x00, 0x07, 0x00, 0x00, 0x78, 0x00, 0x03, 0x80, 0x00, 0x3C, 0x00, + 0x01, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x70, + 0x00, 0x07, 0x80, 0x00, 0x38, 0x00, 0x03, 0x80, 0x00, 0x3C, 0x00, 0x01, + 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x70, 0x00, + 0x07, 0x80, 0x00, 0x38, 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xE0, + 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x00, 0x1F, 0x80, 0x03, 0x86, + 0x00, 0x30, 0x18, 0x03, 0x00, 0xC0, 0x38, 0x03, 0x03, 0x80, 0x18, 0x38, + 0x00, 0xC1, 0xC0, 0x07, 0x1C, 0x00, 0x38, 0xE0, 0x01, 0xCF, 0x00, 0x0E, + 0x70, 0x00, 0x77, 0x80, 0x07, 0xBC, 0x00, 0x3D, 0xE0, 0x01, 0xEE, 0x00, + 0x0F, 0xF0, 0x00, 0x77, 0x80, 0x07, 0xBC, 0x00, 0x3D, 0xC0, 0x01, 0xCE, + 0x00, 0x1E, 0x70, 0x00, 0xF3, 0x80, 0x07, 0x1C, 0x00, 0x78, 0xE0, 0x03, + 0x83, 0x00, 0x38, 0x18, 0x03, 0x80, 0xE0, 0x18, 0x03, 0x01, 0x80, 0x0C, + 0x38, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x00, 0x80, 0x1F, 0xC0, 0x3F, 0xE0, + 0x01, 0xF0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1C, 0x00, 0x1E, + 0x00, 0x0F, 0x00, 0x07, 0x80, 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x00, + 0xF0, 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x1E, 0x00, + 0x0F, 0x00, 0x07, 0x80, 0x07, 0x80, 0x03, 0xC0, 0x01, 0xE0, 0x01, 0xE0, + 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x3C, 0x00, 0x3F, 0x01, 0xFF, + 0xF0, 0x00, 0x3F, 0x00, 0x07, 0xFE, 0x00, 0x7F, 0xF8, 0x07, 0x07, 0xE0, + 0x60, 0x1F, 0x06, 0x00, 0x7C, 0x20, 0x01, 0xE0, 0x00, 0x0F, 0x00, 0x00, + 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x01, 0xE0, 0x00, 0x0E, 0x00, + 0x00, 0xF0, 0x00, 0x07, 0x00, 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0x70, + 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, 0x03, 0x00, 0x00, 0x30, 0x00, 0x03, + 0x00, 0x00, 0x30, 0x00, 0x03, 0x00, 0x00, 0x30, 0x01, 0x03, 0x00, 0x08, + 0x30, 0x00, 0xC3, 0xFF, 0xFC, 0x3F, 0xFF, 0xE3, 0xFF, 0xFE, 0x00, 0x00, + 0x0F, 0xC0, 0x00, 0xFF, 0xC0, 0x06, 0x0F, 0x80, 0x30, 0x1E, 0x01, 0x80, + 0x3C, 0x00, 0x00, 0xF0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x78, + 0x00, 0x01, 0xE0, 0x00, 0x0E, 0x00, 0x00, 0xF0, 0x00, 0x0E, 0x00, 0x01, + 0xF8, 0x00, 0x3F, 0xF8, 0x00, 0x0F, 0xF0, 0x00, 0x07, 0xC0, 0x00, 0x0F, + 0x80, 0x00, 0x3E, 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x07, 0x80, + 0x00, 0x1E, 0x00, 0x00, 0x70, 0x00, 0x01, 0xC0, 0x00, 0x07, 0x00, 0x00, + 0x38, 0x00, 0x00, 0xC0, 0x70, 0x06, 0x03, 0xF8, 0x70, 0x07, 0xFF, 0x00, + 0x0F, 0xF0, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x70, 0x00, 0x03, 0xC0, + 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xE0, 0x00, 0x37, 0x80, 0x00, + 0xDC, 0x00, 0x06, 0x70, 0x00, 0x33, 0xC0, 0x01, 0x8F, 0x00, 0x0C, 0x38, + 0x00, 0x60, 0xE0, 0x03, 0x07, 0x80, 0x18, 0x1E, 0x00, 0xC0, 0x70, 0x06, + 0x03, 0xC0, 0x30, 0x0F, 0x01, 0x80, 0x38, 0x0C, 0x00, 0xE0, 0x70, 0x07, + 0x81, 0xFF, 0xFF, 0xEF, 0xFF, 0xFF, 0xBF, 0xFF, 0xFE, 0x00, 0x0F, 0x00, + 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x80, 0x00, 0x1E, 0x00, 0x00, + 0x70, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x00, 0x00, 0x3F, 0xFC, 0x00, 0xFF, + 0xF0, 0x07, 0xFF, 0x80, 0x10, 0x00, 0x00, 0x40, 0x00, 0x02, 0x00, 0x00, + 0x08, 0x00, 0x00, 0x70, 0x00, 0x01, 0xF8, 0x00, 0x0F, 0xF0, 0x00, 0x3F, + 0xF0, 0x00, 0x1F, 0xE0, 0x00, 0x1F, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3C, + 0x00, 0x00, 0x78, 0x00, 0x01, 0xE0, 0x00, 0x03, 0x80, 0x00, 0x0E, 0x00, + 0x00, 0x38, 0x00, 0x00, 0xE0, 0x00, 0x03, 0x80, 0x00, 0x0C, 0x00, 0x00, + 0x70, 0x00, 0x01, 0xC0, 0x00, 0x06, 0x00, 0x00, 0x30, 0x00, 0x01, 0x80, + 0x70, 0x0E, 0x03, 0xF0, 0xE0, 0x07, 0xFF, 0x00, 0x0F, 0xE0, 0x00, 0x00, + 0x00, 0x0E, 0x00, 0x01, 0xF0, 0x00, 0x1F, 0x00, 0x00, 0xF8, 0x00, 0x03, + 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x7C, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xC0, + 0x00, 0x0F, 0x80, 0x00, 0x3E, 0x00, 0x00, 0xF9, 0xF8, 0x01, 0xFF, 0xFC, + 0x07, 0xE0, 0x7C, 0x0F, 0x80, 0x7C, 0x3E, 0x00, 0x78, 0x78, 0x00, 0x78, + 0xF0, 0x00, 0xF3, 0xC0, 0x01, 0xE7, 0x80, 0x03, 0xCF, 0x00, 0x07, 0x9C, + 0x00, 0x0F, 0x38, 0x00, 0x3E, 0x70, 0x00, 0x78, 0xE0, 0x00, 0xF1, 0xC0, + 0x03, 0xC1, 0x80, 0x07, 0x83, 0x00, 0x1E, 0x03, 0x00, 0x38, 0x06, 0x01, + 0xE0, 0x03, 0x07, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0xFF, 0xF9, 0xFF, 0xFF, + 0xCF, 0xFF, 0xFC, 0xE0, 0x00, 0xCC, 0x00, 0x0E, 0x40, 0x00, 0x60, 0x00, + 0x07, 0x00, 0x00, 0x70, 0x00, 0x03, 0x80, 0x00, 0x38, 0x00, 0x01, 0x80, + 0x00, 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x0E, 0x00, 0x00, 0xE0, 0x00, 0x07, + 0x00, 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0x38, 0x00, 0x03, 0x80, 0x00, + 0x1C, 0x00, 0x01, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x0E, 0x00, + 0x00, 0x70, 0x00, 0x07, 0x00, 0x00, 0x78, 0x00, 0x03, 0x80, 0x00, 0x38, + 0x00, 0x01, 0xC0, 0x00, 0x1C, 0x00, 0x00, 0x00, 0x3F, 0x80, 0x03, 0x83, + 0x80, 0x1C, 0x03, 0x00, 0xE0, 0x0E, 0x07, 0x00, 0x1C, 0x1C, 0x00, 0x70, + 0x70, 0x01, 0xC1, 0xC0, 0x07, 0x07, 0x80, 0x1C, 0x1E, 0x00, 0xE0, 0x3C, + 0x07, 0x80, 0xFC, 0x38, 0x01, 0xFB, 0xC0, 0x03, 0xF8, 0x00, 0x0F, 0xE0, + 0x00, 0x7F, 0xC0, 0x07, 0x1F, 0x80, 0x78, 0x3F, 0x03, 0x80, 0x7C, 0x1E, + 0x00, 0xF8, 0x70, 0x01, 0xE3, 0x80, 0x03, 0xCE, 0x00, 0x07, 0x38, 0x00, + 0x1C, 0xE0, 0x00, 0x73, 0x80, 0x01, 0xCE, 0x00, 0x06, 0x1C, 0x00, 0x38, + 0x70, 0x01, 0xC0, 0xE0, 0x0E, 0x01, 0xE0, 0xE0, 0x01, 0xFE, 0x00, 0x00, + 0x1F, 0x80, 0x03, 0xC3, 0x00, 0x1C, 0x02, 0x00, 0xE0, 0x0C, 0x07, 0x00, + 0x18, 0x3C, 0x00, 0x60, 0xE0, 0x01, 0xC7, 0x80, 0x07, 0x1E, 0x00, 0x1C, + 0xF0, 0x00, 0x73, 0xC0, 0x01, 0xCF, 0x00, 0x07, 0x3C, 0x00, 0x3C, 0xF0, + 0x00, 0xF3, 0xC0, 0x03, 0xCF, 0x00, 0x1E, 0x1E, 0x00, 0x78, 0x7C, 0x03, + 0xE0, 0xF8, 0x3F, 0x01, 0xFF, 0xBC, 0x03, 0xF1, 0xE0, 0x00, 0x0F, 0x80, + 0x00, 0x3C, 0x00, 0x01, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x7C, 0x00, 0x03, + 0xE0, 0x00, 0x1F, 0x00, 0x00, 0xF0, 0x00, 0x0F, 0x80, 0x00, 0x78, 0x00, + 0x0F, 0x80, 0x00, 0xE0, 0x00, 0x00, 0x07, 0x07, 0xC3, 0xE1, 0xF0, 0x70, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x38, 0x3E, 0x1F, 0x0F, 0x83, 0x80, 0x01, 0xC0, 0x7C, 0x0F, 0x81, + 0xF0, 0x1C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x18, 0x07, 0x80, 0xF8, 0x1F, 0x01, 0xE0, + 0x1C, 0x03, 0x00, 0xC0, 0x18, 0x04, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x0C, 0x00, 0x00, 0xF8, 0x00, 0x07, 0xF0, 0x00, 0x3F, 0xC0, + 0x01, 0xFC, 0x00, 0x0F, 0xE0, 0x00, 0xFF, 0x00, 0x07, 0xF8, 0x00, 0x3F, + 0xC0, 0x01, 0xFC, 0x00, 0x07, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x1F, 0x80, + 0x00, 0x3F, 0xC0, 0x00, 0x1F, 0xE0, 0x00, 0x07, 0xF0, 0x00, 0x03, 0xF8, + 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x7F, 0x80, 0x00, 0x1F, + 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x07, 0x00, 0x00, 0x02, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0x80, 0x00, 0x00, + 0xE0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x3F, 0x80, 0x00, + 0x0F, 0xF0, 0x00, 0x03, 0xFC, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x07, 0xF0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x7F, 0x00, 0x00, 0x1F, + 0x00, 0x00, 0x3F, 0x00, 0x00, 0xFE, 0x00, 0x07, 0xF8, 0x00, 0x1F, 0xE0, + 0x00, 0x7F, 0x80, 0x01, 0xFC, 0x00, 0x07, 0xF0, 0x00, 0x3F, 0xC0, 0x00, + 0xFF, 0x00, 0x00, 0xFC, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x80, 0x00, 0x00, + 0x03, 0xF0, 0x06, 0x1C, 0x0C, 0x0E, 0x1C, 0x06, 0x1C, 0x07, 0x1C, 0x07, + 0x1C, 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x0E, 0x00, 0x1E, 0x00, 0x3C, + 0x00, 0x38, 0x00, 0x70, 0x00, 0xE0, 0x01, 0xC0, 0x03, 0x80, 0x03, 0x00, + 0x06, 0x00, 0x04, 0x00, 0x08, 0x00, 0x08, 0x00, 0x08, 0x00, 0x10, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x70, 0x00, 0xF8, 0x00, + 0xF8, 0x00, 0xF8, 0x00, 0x70, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x1F, + 0xFF, 0x80, 0x00, 0x3F, 0x01, 0xF0, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x7C, + 0x00, 0x07, 0x80, 0x7C, 0x00, 0x00, 0xE0, 0x3C, 0x00, 0x00, 0x38, 0x3C, + 0x00, 0x00, 0x0C, 0x3C, 0x00, 0x78, 0x07, 0x1E, 0x00, 0xFE, 0xE1, 0x9E, + 0x00, 0xF1, 0xF0, 0xEF, 0x00, 0xE0, 0xF0, 0x37, 0x80, 0xE0, 0x38, 0x1F, + 0x80, 0x70, 0x1C, 0x0F, 0xC0, 0x70, 0x1E, 0x07, 0xE0, 0x38, 0x0F, 0x03, + 0xF0, 0x18, 0x07, 0x01, 0xF8, 0x1C, 0x03, 0x80, 0xFC, 0x0E, 0x01, 0xC0, + 0xDE, 0x07, 0x01, 0xE0, 0x6F, 0x03, 0x80, 0xE0, 0x73, 0xC1, 0xC0, 0xF0, + 0x31, 0xE0, 0xF0, 0xF8, 0x30, 0xF0, 0x38, 0xDC, 0x30, 0x3C, 0x1F, 0xC7, + 0xF0, 0x0E, 0x07, 0x81, 0xF0, 0x07, 0x80, 0x00, 0x00, 0x01, 0xE0, 0x00, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x01, 0x00, 0x03, 0xF0, + 0x0F, 0x80, 0x00, 0x7F, 0xFF, 0x00, 0x00, 0x07, 0xFC, 0x00, 0x00, 0x00, + 0x00, 0x18, 0x00, 0x00, 0x01, 0xC0, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x00, + 0xF0, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x03, 0xF0, + 0x00, 0x00, 0x37, 0x80, 0x00, 0x03, 0x3C, 0x00, 0x00, 0x19, 0xE0, 0x00, + 0x01, 0x8F, 0x80, 0x00, 0x08, 0x7C, 0x00, 0x00, 0xC3, 0xE0, 0x00, 0x0C, + 0x0F, 0x00, 0x00, 0x60, 0x78, 0x00, 0x06, 0x03, 0xC0, 0x00, 0x20, 0x1F, + 0x00, 0x03, 0x00, 0xF8, 0x00, 0x3F, 0xFF, 0xC0, 0x01, 0xFF, 0xFE, 0x00, + 0x18, 0x00, 0xF0, 0x00, 0xC0, 0x07, 0x80, 0x0C, 0x00, 0x3E, 0x00, 0xE0, + 0x01, 0xF0, 0x06, 0x00, 0x0F, 0x80, 0x70, 0x00, 0x3C, 0x03, 0x00, 0x01, + 0xE0, 0x38, 0x00, 0x0F, 0x83, 0xC0, 0x00, 0x7C, 0x3E, 0x00, 0x07, 0xF3, + 0xFC, 0x01, 0xFF, 0xE0, 0x03, 0xFF, 0xFE, 0x00, 0x07, 0xFF, 0xF8, 0x00, + 0x3E, 0x07, 0xC0, 0x03, 0xE0, 0x3E, 0x00, 0x3E, 0x01, 0xF0, 0x03, 0xC0, + 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x78, 0x01, 0xF0, + 0x07, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x7C, 0x00, 0xF0, + 0x3F, 0x00, 0x1F, 0xFF, 0x80, 0x01, 0xFF, 0xFC, 0x00, 0x1F, 0x07, 0xE0, + 0x01, 0xE0, 0x1F, 0x00, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x07, 0xC0, 0x3C, + 0x00, 0x7C, 0x03, 0xC0, 0x07, 0xC0, 0x7C, 0x00, 0x7C, 0x07, 0xC0, 0x07, + 0xC0, 0x78, 0x00, 0x7C, 0x0F, 0x80, 0x0F, 0x80, 0xF8, 0x00, 0xF8, 0x0F, + 0x00, 0x1F, 0x00, 0xF0, 0x03, 0xE0, 0x1F, 0x81, 0xFC, 0x03, 0xFF, 0xFF, + 0x80, 0xFF, 0xFF, 0xC0, 0x00, 0x00, 0x01, 0xFE, 0x04, 0x00, 0x3F, 0xFF, + 0xE0, 0x03, 0xF0, 0x1F, 0x80, 0x1F, 0x00, 0x3E, 0x00, 0xF0, 0x00, 0x78, + 0x0F, 0x80, 0x00, 0xE0, 0x3C, 0x00, 0x03, 0x81, 0xF0, 0x00, 0x04, 0x0F, + 0x80, 0x00, 0x10, 0x7C, 0x00, 0x00, 0x41, 0xF0, 0x00, 0x00, 0x0F, 0x80, + 0x00, 0x00, 0x3E, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x07, 0xC0, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x03, + 0xE0, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x00, 0xF8, + 0x00, 0x00, 0x01, 0xF0, 0x00, 0x02, 0x07, 0xC0, 0x00, 0x18, 0x0F, 0x80, + 0x00, 0xC0, 0x3E, 0x00, 0x06, 0x00, 0x7C, 0x00, 0x70, 0x00, 0xFC, 0x07, + 0x00, 0x00, 0xFF, 0xF8, 0x00, 0x00, 0xFF, 0x00, 0x00, 0x03, 0xFF, 0xFF, + 0x00, 0x00, 0x3F, 0xFF, 0xE0, 0x00, 0x0F, 0xC0, 0xFC, 0x00, 0x07, 0xC0, + 0x1F, 0x00, 0x03, 0xE0, 0x07, 0xC0, 0x01, 0xE0, 0x01, 0xF0, 0x01, 0xF0, + 0x00, 0x7C, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x7C, 0x00, 0x0F, 0x00, 0x3C, + 0x00, 0x07, 0xC0, 0x3E, 0x00, 0x03, 0xE0, 0x1F, 0x00, 0x01, 0xF0, 0x0F, + 0x00, 0x00, 0xF8, 0x0F, 0x80, 0x00, 0x7C, 0x07, 0xC0, 0x00, 0x3E, 0x03, + 0xE0, 0x00, 0x1F, 0x01, 0xE0, 0x00, 0x1F, 0x81, 0xF0, 0x00, 0x0F, 0x80, + 0xF8, 0x00, 0x07, 0xC0, 0x78, 0x00, 0x03, 0xE0, 0x3C, 0x00, 0x03, 0xE0, + 0x3E, 0x00, 0x01, 0xF0, 0x1F, 0x00, 0x01, 0xF0, 0x0F, 0x00, 0x01, 0xF0, + 0x0F, 0x80, 0x01, 0xF8, 0x07, 0xC0, 0x01, 0xF0, 0x03, 0xE0, 0x01, 0xF0, + 0x01, 0xE0, 0x03, 0xF0, 0x01, 0xF8, 0x0F, 0xE0, 0x01, 0xFF, 0xFF, 0xC0, + 0x03, 0xFF, 0xFE, 0x00, 0x00, 0x03, 0xFF, 0xFF, 0xF8, 0x03, 0xFF, 0xFF, + 0xC0, 0x0F, 0x80, 0x1E, 0x00, 0x7C, 0x00, 0x30, 0x03, 0xE0, 0x01, 0x00, + 0x1E, 0x00, 0x08, 0x01, 0xF0, 0x00, 0x40, 0x0F, 0x80, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x03, 0xC0, 0x10, 0x00, 0x3E, 0x01, 0x80, 0x01, 0xF0, 0x08, + 0x00, 0x0F, 0x01, 0xC0, 0x00, 0xFF, 0xFE, 0x00, 0x07, 0xFF, 0xF0, 0x00, + 0x3E, 0x07, 0x00, 0x01, 0xE0, 0x18, 0x00, 0x1F, 0x00, 0xC0, 0x00, 0xF8, + 0x04, 0x00, 0x07, 0x80, 0x20, 0x00, 0x3C, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x08, 0x0F, 0x80, 0x00, 0xC0, + 0x7C, 0x00, 0x0E, 0x03, 0xC0, 0x00, 0xE0, 0x1E, 0x00, 0x0F, 0x01, 0xF8, + 0x03, 0xF8, 0x1F, 0xFF, 0xFF, 0x83, 0xFF, 0xFF, 0xFC, 0x00, 0x03, 0xFF, + 0xFF, 0xF8, 0x03, 0xFF, 0xFF, 0xC0, 0x0F, 0x80, 0x1E, 0x00, 0x7C, 0x00, + 0x30, 0x03, 0xE0, 0x01, 0x00, 0x1E, 0x00, 0x08, 0x01, 0xF0, 0x00, 0x40, + 0x0F, 0x80, 0x02, 0x00, 0x7C, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x3E, + 0x00, 0x80, 0x01, 0xF0, 0x0C, 0x00, 0x0F, 0x00, 0xC0, 0x00, 0xF8, 0x0E, + 0x00, 0x07, 0xFF, 0xF0, 0x00, 0x3F, 0xFF, 0x00, 0x01, 0xE0, 0x18, 0x00, + 0x1F, 0x00, 0xC0, 0x00, 0xF8, 0x06, 0x00, 0x07, 0xC0, 0x20, 0x00, 0x3C, + 0x01, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0x0F, 0x80, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xFF, + 0xC0, 0x00, 0x00, 0x00, 0x01, 0xFE, 0x02, 0x00, 0x1F, 0xFF, 0x8C, 0x00, + 0xFC, 0x07, 0xF8, 0x03, 0xE0, 0x03, 0xF0, 0x0F, 0x00, 0x03, 0xC0, 0x3C, + 0x00, 0x03, 0x80, 0xF0, 0x00, 0x07, 0x03, 0xC0, 0x00, 0x0E, 0x0F, 0x80, + 0x00, 0x08, 0x3E, 0x00, 0x00, 0x10, 0x7C, 0x00, 0x00, 0x01, 0xF0, 0x00, + 0x00, 0x03, 0xE0, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x3F, + 0xFF, 0xE0, 0x00, 0x0F, 0xE7, 0xC0, 0x00, 0x0F, 0x0F, 0x80, 0x00, 0x1E, + 0x1F, 0x00, 0x00, 0x7C, 0x3E, 0x00, 0x00, 0xF0, 0x7C, 0x00, 0x01, 0xE0, + 0x78, 0x00, 0x03, 0xC0, 0xF8, 0x00, 0x0F, 0x01, 0xF0, 0x00, 0x1E, 0x01, + 0xF0, 0x00, 0x3C, 0x01, 0xE0, 0x00, 0xF8, 0x01, 0xF0, 0x03, 0xE0, 0x01, + 0xF8, 0x0F, 0x80, 0x00, 0xFF, 0xFC, 0x00, 0x00, 0x7F, 0xC0, 0x00, 0x03, + 0xFF, 0xE0, 0x7F, 0xF0, 0x07, 0xF8, 0x01, 0xFC, 0x00, 0x3E, 0x00, 0x0F, + 0x80, 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, + 0x00, 0xF0, 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, + 0x78, 0x00, 0x1E, 0x00, 0x07, 0x80, 0x01, 0xE0, 0x00, 0xF8, 0x00, 0x3E, + 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, 0x00, + 0x03, 0xC0, 0x01, 0xFF, 0xFF, 0xFC, 0x00, 0x1F, 0xFF, 0xFF, 0x80, 0x01, + 0xE0, 0x00, 0x78, 0x00, 0x3E, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF8, + 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x00, 0x7C, 0x00, + 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xF0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x0F, + 0x80, 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x03, 0xC0, + 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x03, 0xF8, 0x00, + 0xFE, 0x00, 0xFF, 0xE0, 0x7F, 0xFC, 0x00, 0x01, 0xFF, 0xC0, 0x1F, 0xE0, + 0x03, 0xE0, 0x00, 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x07, 0xC0, 0x01, + 0xF0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF0, + 0x00, 0x7C, 0x00, 0x1F, 0x00, 0x07, 0xC0, 0x01, 0xE0, 0x00, 0xF8, 0x00, + 0x3E, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x01, 0xF0, 0x00, 0x7C, 0x00, 0x1E, + 0x00, 0x0F, 0x80, 0x03, 0xE0, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x1F, 0x00, + 0x0F, 0xE0, 0x0F, 0xFE, 0x00, 0x00, 0x1F, 0xFE, 0x00, 0x07, 0xF0, 0x00, + 0x07, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1E, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0xF8, 0x00, 0x01, 0xE0, 0x00, 0x03, 0xC0, 0x00, 0x0F, 0x80, 0x00, 0x1F, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x78, 0x00, 0x01, 0xF0, 0x00, 0x03, 0xE0, + 0x00, 0x07, 0x80, 0x00, 0x1F, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x78, 0x00, + 0x00, 0xF0, 0x00, 0x03, 0xE0, 0x00, 0x07, 0xC0, 0x00, 0x0F, 0x00, 0x00, + 0x1E, 0x00, 0x00, 0x7C, 0x00, 0x00, 0xF0, 0x01, 0xC1, 0xE0, 0x07, 0xC7, + 0x80, 0x0F, 0x8F, 0x00, 0x1F, 0x3C, 0x00, 0x1F, 0xF0, 0x00, 0x0F, 0x80, + 0x00, 0x01, 0xFF, 0xE1, 0xFF, 0x80, 0x3F, 0xC0, 0x1F, 0x80, 0x0F, 0x80, + 0x0F, 0x00, 0x07, 0xC0, 0x0F, 0x00, 0x03, 0xC0, 0x0F, 0x00, 0x01, 0xE0, + 0x0E, 0x00, 0x01, 0xF0, 0x0E, 0x00, 0x00, 0xF8, 0x0E, 0x00, 0x00, 0x78, + 0x1C, 0x00, 0x00, 0x3C, 0x1C, 0x00, 0x00, 0x3E, 0x3C, 0x00, 0x00, 0x1F, + 0x38, 0x00, 0x00, 0x0F, 0x38, 0x00, 0x00, 0x07, 0xF8, 0x00, 0x00, 0x07, + 0xFE, 0x00, 0x00, 0x03, 0xDF, 0x00, 0x00, 0x01, 0xE7, 0xC0, 0x00, 0x01, + 0xF3, 0xE0, 0x00, 0x00, 0xF8, 0xF8, 0x00, 0x00, 0x78, 0x3C, 0x00, 0x00, + 0x3C, 0x1F, 0x00, 0x00, 0x3E, 0x07, 0xC0, 0x00, 0x1F, 0x03, 0xE0, 0x00, + 0x0F, 0x00, 0xF8, 0x00, 0x0F, 0x80, 0x3C, 0x00, 0x07, 0xC0, 0x1F, 0x00, + 0x03, 0xC0, 0x07, 0x80, 0x01, 0xE0, 0x03, 0xE0, 0x01, 0xF0, 0x01, 0xF8, + 0x01, 0xFC, 0x01, 0xFE, 0x03, 0xFF, 0xC3, 0xFF, 0xE0, 0x03, 0xFF, 0xE0, + 0x00, 0x0F, 0xF0, 0x00, 0x00, 0xFC, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, + 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, + 0x00, 0x78, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, + 0x00, 0x00, 0x0F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, + 0x0F, 0x80, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x80, + 0x00, 0x01, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x01, + 0xF0, 0x00, 0x08, 0x3C, 0x00, 0x03, 0x0F, 0x80, 0x00, 0x41, 0xF0, 0x00, + 0x18, 0x3C, 0x00, 0x07, 0x07, 0x80, 0x01, 0xC1, 0xF8, 0x01, 0xF8, 0x7F, + 0xFF, 0xFF, 0x3F, 0xFF, 0xFF, 0xC0, 0x01, 0xFF, 0x00, 0x00, 0x3F, 0xC0, + 0x0F, 0xC0, 0x00, 0x1F, 0xC0, 0x01, 0xF0, 0x00, 0x0F, 0xE0, 0x00, 0xFC, + 0x00, 0x03, 0xF0, 0x00, 0x3F, 0x00, 0x01, 0xFC, 0x00, 0x0F, 0xC0, 0x00, + 0xFF, 0x00, 0x02, 0xF0, 0x00, 0x37, 0x80, 0x01, 0xBC, 0x00, 0x19, 0xE0, + 0x00, 0x6F, 0x80, 0x0E, 0xF8, 0x00, 0x1B, 0xE0, 0x03, 0x3E, 0x00, 0x04, + 0x78, 0x01, 0x8F, 0x00, 0x03, 0x1E, 0x00, 0xE7, 0xC0, 0x00, 0xC7, 0x80, + 0x31, 0xF0, 0x00, 0x21, 0xE0, 0x18, 0x78, 0x00, 0x18, 0x78, 0x0E, 0x1E, + 0x00, 0x06, 0x1E, 0x03, 0x0F, 0x80, 0x01, 0x87, 0x81, 0x83, 0xE0, 0x00, + 0x41, 0xF0, 0xE0, 0xF0, 0x00, 0x30, 0x7C, 0x30, 0x3C, 0x00, 0x0C, 0x0F, + 0x18, 0x1F, 0x00, 0x03, 0x03, 0xCE, 0x07, 0xC0, 0x01, 0x80, 0xF3, 0x01, + 0xE0, 0x00, 0x60, 0x3D, 0x80, 0xF8, 0x00, 0x18, 0x0F, 0xE0, 0x3E, 0x00, + 0x0C, 0x03, 0xF0, 0x0F, 0x00, 0x03, 0x00, 0xF8, 0x03, 0xC0, 0x00, 0xC0, + 0x3E, 0x01, 0xF0, 0x00, 0x70, 0x0F, 0x00, 0x7C, 0x00, 0x1C, 0x01, 0x80, + 0x3F, 0x00, 0x0F, 0x80, 0x60, 0x1F, 0xC0, 0x0F, 0xF8, 0x10, 0x1F, 0xFE, + 0x00, 0x03, 0xFC, 0x00, 0x3F, 0xE0, 0x1F, 0xC0, 0x01, 0xF8, 0x00, 0xF8, + 0x00, 0x1C, 0x00, 0x1F, 0x00, 0x03, 0x80, 0x03, 0xF0, 0x00, 0x60, 0x00, + 0x7E, 0x00, 0x0C, 0x00, 0x0B, 0xE0, 0x03, 0x80, 0x03, 0x7C, 0x00, 0x60, + 0x00, 0x67, 0x80, 0x0C, 0x00, 0x0C, 0xF8, 0x03, 0x80, 0x03, 0x0F, 0x00, + 0x70, 0x00, 0x61, 0xF0, 0x0C, 0x00, 0x0C, 0x3E, 0x01, 0x80, 0x01, 0x83, + 0xC0, 0x70, 0x00, 0x60, 0x7C, 0x0C, 0x00, 0x0C, 0x07, 0x81, 0x80, 0x01, + 0x80, 0xF8, 0x30, 0x00, 0x60, 0x0F, 0x0E, 0x00, 0x0C, 0x01, 0xE1, 0x80, + 0x01, 0x80, 0x3E, 0x30, 0x00, 0x30, 0x03, 0xCE, 0x00, 0x0C, 0x00, 0x7D, + 0x80, 0x01, 0x80, 0x07, 0xB0, 0x00, 0x30, 0x00, 0xF6, 0x00, 0x0E, 0x00, + 0x1F, 0xC0, 0x01, 0x80, 0x01, 0xF0, 0x00, 0x30, 0x00, 0x3E, 0x00, 0x0E, + 0x00, 0x03, 0xC0, 0x01, 0xC0, 0x00, 0x70, 0x00, 0x7C, 0x00, 0x06, 0x00, + 0x3F, 0xE0, 0x00, 0xC0, 0x00, 0x00, 0x00, 0x18, 0x00, 0x00, 0x00, 0xFE, + 0x00, 0x00, 0x1F, 0xFE, 0x00, 0x01, 0xF0, 0x7C, 0x00, 0x0F, 0x00, 0x78, + 0x00, 0x78, 0x00, 0xF0, 0x07, 0xC0, 0x03, 0xE0, 0x3E, 0x00, 0x07, 0x81, + 0xF0, 0x00, 0x1E, 0x07, 0xC0, 0x00, 0x7C, 0x3E, 0x00, 0x01, 0xF1, 0xF0, + 0x00, 0x07, 0xC7, 0xC0, 0x00, 0x1F, 0x3F, 0x00, 0x00, 0x7C, 0xF8, 0x00, + 0x01, 0xF7, 0xE0, 0x00, 0x0F, 0xDF, 0x00, 0x00, 0x3F, 0x7C, 0x00, 0x00, + 0xFB, 0xF0, 0x00, 0x07, 0xEF, 0xC0, 0x00, 0x1F, 0xBE, 0x00, 0x00, 0x7C, + 0xF8, 0x00, 0x03, 0xF3, 0xE0, 0x00, 0x0F, 0x8F, 0x80, 0x00, 0x3E, 0x3E, + 0x00, 0x01, 0xF0, 0xF8, 0x00, 0x0F, 0x81, 0xE0, 0x00, 0x3E, 0x07, 0x80, + 0x01, 0xF0, 0x1F, 0x00, 0x0F, 0x80, 0x3C, 0x00, 0x7C, 0x00, 0x78, 0x03, + 0xC0, 0x00, 0xF8, 0x3E, 0x00, 0x01, 0xFF, 0xE0, 0x00, 0x01, 0xFC, 0x00, + 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x0F, 0x81, 0xF8, + 0x00, 0x7C, 0x03, 0xE0, 0x03, 0xE0, 0x1F, 0x00, 0x1E, 0x00, 0x7C, 0x01, + 0xF0, 0x03, 0xE0, 0x0F, 0x80, 0x1F, 0x00, 0x78, 0x00, 0xF8, 0x03, 0xC0, + 0x07, 0xC0, 0x3E, 0x00, 0x3C, 0x01, 0xF0, 0x03, 0xE0, 0x0F, 0x00, 0x3E, + 0x00, 0xF8, 0x03, 0xF0, 0x07, 0xC0, 0x7E, 0x00, 0x3F, 0xFF, 0xE0, 0x01, + 0xEF, 0xF8, 0x00, 0x1F, 0x00, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x07, 0x80, + 0x00, 0x00, 0x3C, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x00, 0xF0, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x03, + 0xC0, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x01, 0xF0, 0x00, 0x00, 0x1F, 0xC0, + 0x00, 0x03, 0xFF, 0x80, 0x00, 0x00, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1F, + 0xFE, 0x00, 0x00, 0xF0, 0x7C, 0x00, 0x0F, 0x00, 0x78, 0x00, 0x78, 0x00, + 0xF0, 0x03, 0xC0, 0x03, 0xE0, 0x1E, 0x00, 0x07, 0x80, 0xF0, 0x00, 0x1E, + 0x07, 0xC0, 0x00, 0x7C, 0x3E, 0x00, 0x01, 0xF1, 0xF8, 0x00, 0x07, 0xC7, + 0xC0, 0x00, 0x1F, 0x3F, 0x00, 0x00, 0x7C, 0xF8, 0x00, 0x01, 0xF7, 0xE0, + 0x00, 0x0F, 0xDF, 0x80, 0x00, 0x3F, 0x7C, 0x00, 0x00, 0xFB, 0xF0, 0x00, + 0x03, 0xEF, 0xC0, 0x00, 0x1F, 0xBE, 0x00, 0x00, 0x7C, 0xF8, 0x00, 0x01, + 0xF3, 0xE0, 0x00, 0x0F, 0x8F, 0x80, 0x00, 0x3E, 0x3E, 0x00, 0x01, 0xF0, + 0xF8, 0x00, 0x07, 0xC3, 0xE0, 0x00, 0x3E, 0x07, 0x80, 0x01, 0xF0, 0x1F, + 0x00, 0x07, 0x80, 0x3C, 0x00, 0x3C, 0x00, 0xF8, 0x01, 0xE0, 0x01, 0xE0, + 0x1E, 0x00, 0x01, 0xF3, 0xE0, 0x00, 0x01, 0xFE, 0x00, 0x00, 0x03, 0x00, + 0x00, 0x00, 0x18, 0x00, 0x00, 0x01, 0xC0, 0x00, 0x04, 0x0F, 0xF0, 0x00, + 0x60, 0x7F, 0xFC, 0x07, 0x03, 0xFF, 0xFF, 0xF8, 0x38, 0x1F, 0xFF, 0x80, + 0x00, 0x07, 0xF8, 0x00, 0x03, 0xFF, 0xFE, 0x00, 0x07, 0xFF, 0xF8, 0x00, + 0x3E, 0x0F, 0xC0, 0x03, 0xE0, 0x3E, 0x00, 0x3E, 0x01, 0xF0, 0x03, 0xC0, + 0x1F, 0x00, 0x7C, 0x01, 0xF0, 0x07, 0xC0, 0x1F, 0x00, 0x78, 0x01, 0xF0, + 0x07, 0x80, 0x3E, 0x00, 0xF8, 0x03, 0xE0, 0x0F, 0x80, 0x7C, 0x00, 0xF0, + 0x1F, 0x80, 0x1F, 0xFF, 0xE0, 0x01, 0xFF, 0xF0, 0x00, 0x1E, 0x1E, 0x00, + 0x01, 0xE1, 0xE0, 0x00, 0x3E, 0x1F, 0x00, 0x03, 0xE0, 0xF0, 0x00, 0x3C, + 0x0F, 0x00, 0x03, 0xC0, 0xF8, 0x00, 0x7C, 0x07, 0x80, 0x07, 0xC0, 0x7C, + 0x00, 0x78, 0x03, 0xC0, 0x0F, 0x80, 0x3C, 0x00, 0xF8, 0x03, 0xE0, 0x0F, + 0x00, 0x1E, 0x00, 0xF0, 0x01, 0xE0, 0x1F, 0x00, 0x1F, 0x03, 0xF8, 0x00, + 0xF8, 0xFF, 0xE0, 0x0F, 0xE0, 0x00, 0x3F, 0x06, 0x01, 0xFF, 0xDC, 0x07, + 0xC1, 0xF0, 0x1E, 0x01, 0xE0, 0x3C, 0x01, 0xC0, 0xF0, 0x03, 0x81, 0xE0, + 0x03, 0x03, 0xC0, 0x04, 0x07, 0x80, 0x08, 0x0F, 0x80, 0x00, 0x1F, 0x00, + 0x00, 0x1F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, + 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x3F, 0x00, + 0x00, 0x3E, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x7C, 0x08, 0x00, 0x78, 0x10, + 0x00, 0xF0, 0x20, 0x01, 0xE0, 0xC0, 0x03, 0xC1, 0x80, 0x07, 0x83, 0x80, + 0x1E, 0x07, 0x00, 0x3C, 0x0F, 0x00, 0xF0, 0x1F, 0x87, 0xC0, 0x23, 0xFF, + 0x00, 0x81, 0xF8, 0x00, 0x3F, 0xFF, 0xFF, 0xE7, 0xFF, 0xFF, 0xFD, 0xF0, + 0x3E, 0x07, 0xB8, 0x07, 0xC0, 0x76, 0x00, 0xF8, 0x04, 0x80, 0x3E, 0x00, + 0xB0, 0x07, 0xC0, 0x14, 0x00, 0xF8, 0x02, 0x00, 0x1E, 0x00, 0x00, 0x07, + 0xC0, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xC0, 0x00, + 0x00, 0xF8, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0xF8, + 0x00, 0x00, 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, + 0x1F, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x0F, 0x00, + 0x00, 0x03, 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x03, + 0xE0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x3F, 0xC0, 0x00, 0x3F, 0xFF, 0x00, + 0x00, 0x7F, 0xFE, 0x03, 0xFE, 0x1F, 0xE0, 0x01, 0xF8, 0x1F, 0x80, 0x01, + 0xC0, 0x3E, 0x00, 0x03, 0x80, 0x7C, 0x00, 0x07, 0x00, 0xF8, 0x00, 0x0C, + 0x03, 0xE0, 0x00, 0x18, 0x07, 0xC0, 0x00, 0x70, 0x0F, 0x80, 0x00, 0xC0, + 0x1F, 0x00, 0x01, 0x80, 0x7C, 0x00, 0x03, 0x00, 0xF8, 0x00, 0x0E, 0x01, + 0xF0, 0x00, 0x18, 0x07, 0xC0, 0x00, 0x30, 0x0F, 0x80, 0x00, 0x60, 0x1F, + 0x00, 0x01, 0x80, 0x3E, 0x00, 0x03, 0x00, 0xF8, 0x00, 0x06, 0x01, 0xF0, + 0x00, 0x18, 0x03, 0xE0, 0x00, 0x30, 0x07, 0xC0, 0x00, 0x60, 0x1F, 0x00, + 0x00, 0xC0, 0x3E, 0x00, 0x03, 0x00, 0x7C, 0x00, 0x06, 0x00, 0xF8, 0x00, + 0x18, 0x01, 0xF0, 0x00, 0x30, 0x03, 0xE0, 0x00, 0xC0, 0x03, 0xE0, 0x03, + 0x80, 0x03, 0xE0, 0x0E, 0x00, 0x03, 0xF0, 0x78, 0x00, 0x03, 0xFF, 0xC0, + 0x00, 0x01, 0xFE, 0x00, 0x00, 0xFF, 0xE0, 0x0F, 0xF9, 0xFC, 0x00, 0x1F, + 0x07, 0xC0, 0x00, 0x78, 0x3E, 0x00, 0x03, 0x81, 0xF0, 0x00, 0x18, 0x0F, + 0x80, 0x01, 0xC0, 0x7C, 0x00, 0x0C, 0x01, 0xE0, 0x00, 0xC0, 0x0F, 0x80, + 0x06, 0x00, 0x7C, 0x00, 0x60, 0x03, 0xE0, 0x07, 0x00, 0x1F, 0x00, 0x30, + 0x00, 0xF8, 0x03, 0x00, 0x03, 0xC0, 0x18, 0x00, 0x1E, 0x01, 0x80, 0x00, + 0xF8, 0x1C, 0x00, 0x07, 0xC0, 0xC0, 0x00, 0x3E, 0x0C, 0x00, 0x01, 0xF0, + 0x60, 0x00, 0x07, 0x86, 0x00, 0x00, 0x3C, 0x30, 0x00, 0x01, 0xE3, 0x00, + 0x00, 0x0F, 0xB0, 0x00, 0x00, 0x7D, 0x80, 0x00, 0x03, 0xF8, 0x00, 0x00, + 0x0F, 0xC0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x1E, + 0x00, 0x00, 0x00, 0xE0, 0x00, 0x00, 0x07, 0x00, 0x00, 0x00, 0x10, 0x00, + 0x00, 0xFF, 0xE3, 0xFF, 0x81, 0xFE, 0x7F, 0x01, 0xFC, 0x00, 0xF8, 0x7C, + 0x01, 0xF0, 0x00, 0xE0, 0xF8, 0x03, 0xE0, 0x01, 0x81, 0xF0, 0x03, 0xC0, + 0x07, 0x03, 0xE0, 0x07, 0x80, 0x0C, 0x03, 0xC0, 0x0F, 0x00, 0x18, 0x07, + 0x80, 0x1E, 0x00, 0x60, 0x0F, 0x00, 0x7E, 0x00, 0xC0, 0x1F, 0x00, 0xFC, + 0x03, 0x00, 0x3E, 0x03, 0xF8, 0x06, 0x00, 0x7C, 0x05, 0xF0, 0x18, 0x00, + 0xF8, 0x1B, 0xE0, 0x30, 0x01, 0xF0, 0x33, 0xC0, 0xC0, 0x01, 0xE0, 0xC7, + 0x83, 0x80, 0x03, 0xC1, 0x8F, 0x06, 0x00, 0x07, 0x86, 0x1E, 0x1C, 0x00, + 0x0F, 0x0C, 0x3C, 0x30, 0x00, 0x1F, 0x30, 0x7C, 0xE0, 0x00, 0x3E, 0x60, + 0xF9, 0x80, 0x00, 0x7D, 0x81, 0xF7, 0x00, 0x00, 0xFB, 0x03, 0xEC, 0x00, + 0x01, 0xFC, 0x03, 0xF8, 0x00, 0x01, 0xF8, 0x07, 0xE0, 0x00, 0x03, 0xE0, + 0x0F, 0x80, 0x00, 0x07, 0xC0, 0x1F, 0x00, 0x00, 0x0F, 0x00, 0x3C, 0x00, + 0x00, 0x1E, 0x00, 0x78, 0x00, 0x00, 0x38, 0x00, 0xE0, 0x00, 0x00, 0x70, + 0x01, 0xC0, 0x00, 0x00, 0xC0, 0x03, 0x00, 0x00, 0x00, 0x80, 0x06, 0x00, + 0x00, 0x07, 0xFF, 0x83, 0xFF, 0x01, 0xFE, 0x00, 0xFE, 0x00, 0x7C, 0x00, + 0x78, 0x00, 0x7C, 0x00, 0x70, 0x00, 0x3C, 0x00, 0xE0, 0x00, 0x3E, 0x01, + 0xC0, 0x00, 0x3E, 0x01, 0x80, 0x00, 0x1F, 0x03, 0x00, 0x00, 0x1F, 0x07, + 0x00, 0x00, 0x0F, 0x0E, 0x00, 0x00, 0x0F, 0x9C, 0x00, 0x00, 0x0F, 0xB8, + 0x00, 0x00, 0x07, 0xF0, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x03, 0xC0, + 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x07, 0xF0, + 0x00, 0x00, 0x0F, 0xF0, 0x00, 0x00, 0x1C, 0xF0, 0x00, 0x00, 0x38, 0xF8, + 0x00, 0x00, 0x30, 0xF8, 0x00, 0x00, 0x60, 0x7C, 0x00, 0x00, 0xC0, 0x7C, + 0x00, 0x01, 0xC0, 0x3C, 0x00, 0x03, 0x80, 0x3E, 0x00, 0x07, 0x00, 0x3E, + 0x00, 0x0E, 0x00, 0x1F, 0x00, 0x1E, 0x00, 0x1F, 0x00, 0x7F, 0x00, 0x3F, + 0xC0, 0xFF, 0xC1, 0xFF, 0xF0, 0x7F, 0xF0, 0x7F, 0xC7, 0xF0, 0x03, 0xE0, + 0xF8, 0x00, 0x70, 0x3E, 0x00, 0x38, 0x07, 0x80, 0x0C, 0x01, 0xE0, 0x07, + 0x00, 0x7C, 0x03, 0x80, 0x1F, 0x00, 0xC0, 0x03, 0xC0, 0x60, 0x00, 0xF0, + 0x30, 0x00, 0x3E, 0x1C, 0x00, 0x07, 0x8E, 0x00, 0x01, 0xE3, 0x00, 0x00, + 0x7D, 0x80, 0x00, 0x1F, 0xC0, 0x00, 0x03, 0xF0, 0x00, 0x00, 0xF8, 0x00, + 0x00, 0x3C, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x01, 0xF0, + 0x00, 0x00, 0x78, 0x00, 0x00, 0x3E, 0x00, 0x00, 0x0F, 0x80, 0x00, 0x03, + 0xC0, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x7C, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x0F, 0xC0, 0x00, 0x07, 0xF0, 0x00, 0x0F, 0xFF, 0xC0, 0x00, 0x03, 0xFF, + 0xFF, 0xF8, 0x1F, 0xFF, 0xFF, 0x81, 0xF0, 0x00, 0xFC, 0x0E, 0x00, 0x0F, + 0xC0, 0x60, 0x00, 0xFC, 0x06, 0x00, 0x0F, 0xC0, 0x20, 0x00, 0x7C, 0x00, + 0x00, 0x07, 0xE0, 0x00, 0x00, 0x7E, 0x00, 0x00, 0x07, 0xE0, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x03, 0xE0, 0x00, 0x00, 0x3F, 0x00, 0x00, 0x03, 0xF0, + 0x00, 0x00, 0x3F, 0x00, 0x00, 0x03, 0xF0, 0x00, 0x00, 0x1F, 0x00, 0x00, + 0x01, 0xF8, 0x00, 0x00, 0x1F, 0x80, 0x00, 0x01, 0xF8, 0x00, 0x00, 0x1F, + 0x80, 0x00, 0x00, 0xF8, 0x00, 0x00, 0x0F, 0xC0, 0x00, 0x00, 0xFC, 0x00, + 0x08, 0x0F, 0xC0, 0x00, 0x80, 0xFC, 0x00, 0x0C, 0x07, 0xC0, 0x00, 0x60, + 0x7E, 0x00, 0x07, 0x07, 0xE0, 0x01, 0xF0, 0x7F, 0xFF, 0xFF, 0x83, 0xFF, + 0xFF, 0xFC, 0x00, 0x00, 0x3F, 0x80, 0x3C, 0x00, 0x1C, 0x00, 0x0E, 0x00, + 0x07, 0x00, 0x07, 0x00, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0xE0, + 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, + 0x00, 0x03, 0x80, 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, + 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x07, 0x00, + 0x03, 0x80, 0x01, 0xC0, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x38, + 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x07, 0x80, 0x03, + 0xFC, 0x00, 0xF0, 0x00, 0x38, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x03, 0x80, + 0x01, 0xE0, 0x00, 0x70, 0x00, 0x3C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x03, + 0xC0, 0x00, 0xE0, 0x00, 0x78, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x03, 0x80, + 0x01, 0xC0, 0x00, 0xF0, 0x00, 0x38, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x03, + 0x80, 0x01, 0xE0, 0x00, 0x70, 0x00, 0x3C, 0x00, 0x0E, 0x00, 0x07, 0x00, + 0x03, 0xC0, 0x00, 0xE0, 0x00, 0x78, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, + 0x80, 0x00, 0xFF, 0x80, 0x07, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0xF0, + 0x00, 0x70, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x0E, 0x00, 0x07, + 0x00, 0x03, 0x80, 0x01, 0xC0, 0x01, 0xE0, 0x00, 0xE0, 0x00, 0x70, 0x00, + 0x38, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x03, 0x80, + 0x03, 0x80, 0x01, 0xC0, 0x00, 0xE0, 0x00, 0x70, 0x00, 0x78, 0x00, 0x38, + 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x07, 0x00, 0x03, 0x80, 0x01, + 0xC0, 0x00, 0xE0, 0x00, 0xF0, 0x00, 0x70, 0x00, 0x38, 0x03, 0xFC, 0x00, + 0x00, 0xF0, 0x00, 0x0F, 0x00, 0x01, 0xF8, 0x00, 0x1F, 0x80, 0x03, 0xBC, + 0x00, 0x39, 0xC0, 0x07, 0x1E, 0x00, 0x70, 0xE0, 0x0E, 0x0F, 0x00, 0xE0, + 0x70, 0x1E, 0x07, 0x81, 0xC0, 0x38, 0x3C, 0x03, 0xC3, 0x80, 0x1C, 0x78, + 0x01, 0xE7, 0x00, 0x0E, 0xF0, 0x00, 0xF0, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0x60, 0xF0, 0xF8, 0x78, 0x3C, 0x1E, 0x0E, 0x07, 0x00, 0x1E, 0x70, + 0x03, 0x0B, 0x80, 0x70, 0x3C, 0x07, 0x01, 0xE0, 0x70, 0x0E, 0x07, 0x00, + 0x70, 0x78, 0x03, 0x83, 0x80, 0x38, 0x3C, 0x01, 0xC1, 0xC0, 0x0E, 0x1E, + 0x00, 0xF0, 0xF0, 0x07, 0x0F, 0x00, 0x78, 0x78, 0x03, 0xC3, 0xC0, 0x3E, + 0x1E, 0x01, 0x70, 0xF0, 0x17, 0x0F, 0x81, 0x38, 0xBE, 0x11, 0xC8, 0xFF, + 0x0F, 0x83, 0xF0, 0x70, 0x00, 0x00, 0xF0, 0x00, 0x7F, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00, + 0x78, 0x00, 0x03, 0x80, 0x00, 0x1C, 0x00, 0x01, 0xE0, 0x00, 0x0F, 0x0F, + 0x80, 0x71, 0xFE, 0x03, 0x98, 0xF8, 0x3D, 0x03, 0xE1, 0xE8, 0x0F, 0x0E, + 0x80, 0x78, 0x78, 0x03, 0xC7, 0xC0, 0x1E, 0x3C, 0x00, 0xF1, 0xE0, 0x0F, + 0x1E, 0x00, 0x78, 0xF0, 0x03, 0xC7, 0x80, 0x3C, 0x38, 0x01, 0xE3, 0xC0, + 0x1E, 0x1E, 0x00, 0xE0, 0xE0, 0x0E, 0x07, 0x00, 0xF0, 0x78, 0x07, 0x03, + 0xC0, 0xE0, 0x0F, 0x0E, 0x00, 0x1F, 0x80, 0x00, 0x00, 0x3F, 0x00, 0x38, + 0x60, 0x38, 0x1C, 0x1C, 0x0F, 0x0E, 0x03, 0x87, 0x80, 0x03, 0xC0, 0x00, + 0xE0, 0x00, 0x78, 0x00, 0x1E, 0x00, 0x07, 0x00, 0x03, 0xC0, 0x00, 0xF0, + 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, 0x00, 0xF0, 0x02, 0x3E, 0x01, + 0x87, 0x80, 0xC1, 0xF0, 0x60, 0x3F, 0xF0, 0x03, 0xF0, 0x00, 0x00, 0x00, + 0x0E, 0x00, 0x00, 0xFE, 0x00, 0x00, 0x1E, 0x00, 0x00, 0x1E, 0x00, 0x00, + 0x1C, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x3C, 0x00, 0x00, + 0x38, 0x00, 0x00, 0x38, 0x00, 0x00, 0x78, 0x00, 0x1E, 0x78, 0x00, 0x71, + 0x70, 0x00, 0xC1, 0x70, 0x03, 0x80, 0xF0, 0x07, 0x80, 0xE0, 0x07, 0x01, + 0xE0, 0x0E, 0x01, 0xE0, 0x1E, 0x01, 0xE0, 0x3C, 0x01, 0xC0, 0x3C, 0x01, + 0xC0, 0x78, 0x03, 0xC0, 0x78, 0x03, 0xC0, 0x78, 0x03, 0x80, 0xF0, 0x07, + 0x80, 0xF0, 0x07, 0x80, 0xF0, 0x0F, 0x80, 0xF0, 0x0F, 0x00, 0xF0, 0x17, + 0x08, 0xF0, 0x27, 0x10, 0x78, 0x47, 0x20, 0x7F, 0x87, 0xC0, 0x1E, 0x07, + 0x00, 0x00, 0x1F, 0x00, 0x1C, 0xF0, 0x1C, 0x1C, 0x0E, 0x07, 0x07, 0x01, + 0xC3, 0xC0, 0xF1, 0xE0, 0x38, 0x70, 0x1C, 0x3C, 0x0E, 0x1F, 0x0F, 0x07, + 0x8F, 0x01, 0xFE, 0x00, 0xF0, 0x00, 0x3C, 0x00, 0x0F, 0x00, 0x03, 0xC0, + 0x00, 0xF0, 0x01, 0x3C, 0x00, 0xC7, 0x80, 0x61, 0xF0, 0x60, 0x3F, 0xF0, + 0x03, 0xE0, 0x00, 0x00, 0x00, 0x07, 0xC0, 0x00, 0x03, 0x1C, 0x00, 0x00, + 0xC3, 0x80, 0x00, 0x38, 0x70, 0x00, 0x06, 0x00, 0x00, 0x01, 0xC0, 0x00, + 0x00, 0x30, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x01, 0xC0, 0x00, 0x00, 0x78, + 0x00, 0x00, 0x0E, 0x00, 0x00, 0x01, 0xC0, 0x00, 0x07, 0xFF, 0xC0, 0x00, + 0xFF, 0xF8, 0x00, 0x01, 0xE0, 0x00, 0x00, 0x38, 0x00, 0x00, 0x07, 0x00, + 0x00, 0x01, 0xE0, 0x00, 0x00, 0x3C, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, + 0xE0, 0x00, 0x00, 0x1C, 0x00, 0x00, 0x07, 0x80, 0x00, 0x00, 0xF0, 0x00, + 0x00, 0x1C, 0x00, 0x00, 0x03, 0x80, 0x00, 0x00, 0xF0, 0x00, 0x00, 0x1E, + 0x00, 0x00, 0x03, 0x80, 0x00, 0x00, 0x70, 0x00, 0x00, 0x0E, 0x00, 0x00, + 0x03, 0xC0, 0x00, 0x00, 0x70, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x01, 0xC0, + 0x00, 0x00, 0x70, 0x00, 0x00, 0x0E, 0x00, 0x00, 0x01, 0x80, 0x00, 0x38, + 0x60, 0x00, 0x07, 0x0C, 0x00, 0x00, 0xE3, 0x00, 0x00, 0x0F, 0x80, 0x00, + 0x00, 0x00, 0x3F, 0x00, 0x07, 0x0E, 0x00, 0x70, 0x3E, 0x07, 0x01, 0xF0, + 0x70, 0x0E, 0x07, 0x80, 0x70, 0x3C, 0x03, 0x81, 0xC0, 0x1C, 0x0E, 0x01, + 0xE0, 0x70, 0x0E, 0x03, 0x80, 0xF0, 0x0E, 0x0F, 0x00, 0x30, 0xE0, 0x00, + 0xFE, 0x00, 0x0C, 0x00, 0x00, 0xC0, 0x00, 0x0E, 0x00, 0x00, 0x7E, 0x00, + 0x03, 0xFE, 0x00, 0x0F, 0xFC, 0x00, 0x8F, 0xF0, 0x18, 0x0F, 0xC1, 0x80, + 0x1F, 0x18, 0x00, 0x78, 0xC0, 0x01, 0xC6, 0x00, 0x0E, 0x30, 0x00, 0x61, + 0xC0, 0x07, 0x06, 0x00, 0x70, 0x1C, 0x0E, 0x00, 0x3F, 0xC0, 0x00, 0x00, + 0xF0, 0x00, 0x7F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, + 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1C, + 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x03, 0x80, 0x78, 0x7E, 0x03, 0x86, 0x70, + 0x3C, 0x43, 0x81, 0xE4, 0x1C, 0x0E, 0x40, 0xE0, 0x74, 0x0E, 0x07, 0xA0, + 0x70, 0x3E, 0x03, 0x81, 0xE0, 0x1C, 0x0F, 0x00, 0xE0, 0xF0, 0x0E, 0x07, + 0x80, 0x70, 0x38, 0x03, 0x81, 0xC0, 0x1C, 0x1E, 0x00, 0xC2, 0xF0, 0x0E, + 0x27, 0x00, 0x73, 0x38, 0x03, 0x93, 0xC0, 0x1F, 0x1E, 0x00, 0xE0, 0x03, + 0x81, 0xF0, 0x7C, 0x1F, 0x03, 0x80, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x71, 0xFC, 0x1F, 0x07, 0x81, 0xE0, 0x78, 0x1C, 0x07, 0x03, 0xC0, 0xF0, + 0x38, 0x0E, 0x07, 0x81, 0xE0, 0x70, 0x1C, 0x0F, 0x03, 0x84, 0xE2, 0x39, + 0x0F, 0x81, 0xC0, 0x00, 0x01, 0xC0, 0x00, 0x7C, 0x00, 0x0F, 0x80, 0x01, + 0xF0, 0x00, 0x1C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x0E, 0x00, 0x3F, 0xC0, 0x00, 0xF0, 0x00, 0x1E, + 0x00, 0x03, 0xC0, 0x00, 0x78, 0x00, 0x0E, 0x00, 0x03, 0xC0, 0x00, 0x78, + 0x00, 0x0F, 0x00, 0x01, 0xC0, 0x00, 0x38, 0x00, 0x0F, 0x00, 0x01, 0xE0, + 0x00, 0x38, 0x00, 0x07, 0x00, 0x01, 0xE0, 0x00, 0x38, 0x00, 0x07, 0x00, + 0x00, 0xE0, 0x00, 0x3C, 0x00, 0x07, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x00, + 0x07, 0x00, 0x00, 0xE0, 0x00, 0x1C, 0x01, 0xC7, 0x00, 0x38, 0xC0, 0x07, + 0x30, 0x00, 0x7C, 0x00, 0x00, 0x00, 0xF0, 0x00, 0x7F, 0x00, 0x00, 0x78, + 0x00, 0x03, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0xE0, 0x00, 0x07, 0x00, 0x00, + 0x78, 0x00, 0x03, 0xC0, 0x00, 0x1C, 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, + 0x00, 0x70, 0xFF, 0x83, 0x80, 0xF0, 0x3C, 0x06, 0x01, 0xE0, 0x60, 0x0E, + 0x06, 0x00, 0x70, 0xE0, 0x07, 0x8C, 0x00, 0x3C, 0xC0, 0x01, 0xCC, 0x00, + 0x0F, 0xF0, 0x00, 0xFF, 0x80, 0x07, 0x9E, 0x00, 0x38, 0xF0, 0x01, 0xC3, + 0x80, 0x1E, 0x1E, 0x00, 0xF0, 0x70, 0x07, 0x03, 0xC2, 0x78, 0x0E, 0x13, + 0xC0, 0x79, 0x1E, 0x01, 0xF0, 0x00, 0x07, 0x00, 0x00, 0xE1, 0xFC, 0x0F, + 0x80, 0xE0, 0x3C, 0x07, 0x80, 0xF0, 0x1C, 0x07, 0x80, 0xF0, 0x1E, 0x03, + 0x80, 0xF0, 0x1E, 0x03, 0xC0, 0x70, 0x1E, 0x03, 0xC0, 0x78, 0x0E, 0x03, + 0xC0, 0x78, 0x0E, 0x01, 0xC0, 0x78, 0x0F, 0x01, 0xC0, 0x38, 0x4F, 0x11, + 0xE4, 0x39, 0x07, 0xC0, 0x70, 0x00, 0x07, 0x81, 0xC0, 0x78, 0xFE, 0x0F, + 0xC1, 0xF8, 0x3C, 0x33, 0x84, 0x70, 0x78, 0x87, 0x10, 0xE0, 0xF2, 0x0E, + 0x41, 0xC1, 0xC8, 0x39, 0x07, 0x87, 0xA0, 0x74, 0x0F, 0x0F, 0x40, 0xE8, + 0x1E, 0x1F, 0x01, 0xE0, 0x38, 0x3C, 0x07, 0xC0, 0xF0, 0xF8, 0x0F, 0x01, + 0xE1, 0xE0, 0x1E, 0x03, 0xC3, 0xC0, 0x38, 0x07, 0x07, 0x00, 0xF0, 0x1E, + 0x1E, 0x01, 0xE0, 0x3C, 0x3C, 0x03, 0x80, 0x79, 0x70, 0x07, 0x00, 0xE2, + 0xE0, 0x1E, 0x03, 0x8B, 0xC0, 0x3C, 0x07, 0x27, 0x80, 0x70, 0x0F, 0x8E, + 0x00, 0xE0, 0x1E, 0x00, 0x07, 0x81, 0xE3, 0xFC, 0x3F, 0x83, 0xC2, 0x3C, + 0x1E, 0x21, 0xE0, 0xF2, 0x0F, 0x07, 0x20, 0x70, 0x39, 0x07, 0x83, 0xD0, + 0x3C, 0x1F, 0x01, 0xE0, 0xE8, 0x0E, 0x0F, 0x80, 0xF0, 0x78, 0x07, 0x83, + 0xC0, 0x38, 0x1C, 0x01, 0xC1, 0xE0, 0x1E, 0x0F, 0x00, 0xF1, 0x70, 0x07, + 0x0B, 0x80, 0x38, 0xBC, 0x01, 0xC9, 0xE0, 0x0F, 0x8E, 0x00, 0x38, 0x00, + 0x00, 0x1F, 0x80, 0x07, 0x8F, 0x00, 0x70, 0x3C, 0x07, 0x00, 0xE0, 0x70, + 0x07, 0x87, 0x80, 0x3C, 0x78, 0x01, 0xE7, 0x80, 0x0F, 0x3C, 0x00, 0x7B, + 0xC0, 0x03, 0xDE, 0x00, 0x3D, 0xF0, 0x01, 0xEF, 0x80, 0x0F, 0x78, 0x00, + 0xF3, 0xC0, 0x07, 0x9E, 0x00, 0x78, 0xF0, 0x03, 0x87, 0x80, 0x38, 0x1C, + 0x03, 0x80, 0xF0, 0x38, 0x03, 0xC3, 0x00, 0x07, 0xE0, 0x00, 0x00, 0x3C, + 0x3F, 0x00, 0x7F, 0x8F, 0xF0, 0x01, 0xF7, 0x3F, 0x00, 0x1D, 0x83, 0xF0, + 0x07, 0xA0, 0x3E, 0x00, 0xF8, 0x07, 0xC0, 0x1E, 0x00, 0xF8, 0x03, 0xC0, + 0x1F, 0x00, 0xF0, 0x03, 0xE0, 0x1E, 0x00, 0x7C, 0x03, 0xC0, 0x1F, 0x00, + 0x70, 0x03, 0xE0, 0x1E, 0x00, 0x78, 0x03, 0xC0, 0x1F, 0x00, 0x70, 0x03, + 0xC0, 0x0E, 0x00, 0xF8, 0x03, 0xC0, 0x1E, 0x00, 0x78, 0x07, 0x80, 0x0F, + 0x01, 0xE0, 0x01, 0xE0, 0x70, 0x00, 0x7C, 0x3C, 0x00, 0x0F, 0x7C, 0x00, + 0x01, 0xC0, 0x00, 0x00, 0x78, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x01, 0xE0, + 0x00, 0x00, 0x38, 0x00, 0x00, 0x0F, 0x00, 0x00, 0x01, 0xE0, 0x00, 0x00, + 0x7E, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x03, 0x8D, + 0xC0, 0x38, 0x2E, 0x07, 0x80, 0xF0, 0x78, 0x07, 0x03, 0x80, 0x38, 0x38, + 0x03, 0xC3, 0xC0, 0x1E, 0x3C, 0x00, 0xE1, 0xE0, 0x07, 0x1E, 0x00, 0x78, + 0xF0, 0x03, 0x87, 0x80, 0x3C, 0x78, 0x01, 0xE3, 0xC0, 0x1F, 0x1E, 0x01, + 0x70, 0xF0, 0x17, 0x87, 0x80, 0xBC, 0x3C, 0x09, 0xC0, 0xF1, 0x8E, 0x07, + 0xF8, 0xF0, 0x1F, 0x07, 0x80, 0x00, 0x38, 0x00, 0x03, 0xC0, 0x00, 0x1E, + 0x00, 0x00, 0xE0, 0x00, 0x0F, 0x00, 0x00, 0x78, 0x00, 0x03, 0xC0, 0x00, + 0x3E, 0x00, 0x0F, 0xFE, 0x00, 0x07, 0x87, 0x3F, 0x87, 0xC3, 0xC7, 0xE1, + 0xE6, 0xF0, 0xF6, 0x00, 0x72, 0x00, 0x3A, 0x00, 0x1D, 0x00, 0x1F, 0x00, + 0x0E, 0x80, 0x07, 0x80, 0x03, 0xC0, 0x03, 0xC0, 0x01, 0xE0, 0x00, 0xF0, + 0x00, 0xF0, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1C, 0x00, 0x1E, 0x00, 0x0F, + 0x00, 0x00, 0x01, 0xF8, 0x81, 0x87, 0xC1, 0x80, 0xE1, 0xC0, 0x60, 0xE0, + 0x10, 0x70, 0x08, 0x3C, 0x04, 0x1F, 0x00, 0x07, 0xC0, 0x03, 0xE0, 0x00, + 0xF8, 0x00, 0x3E, 0x00, 0x0F, 0x00, 0x03, 0xC1, 0x01, 0xE0, 0x80, 0x70, + 0x40, 0x38, 0x30, 0x1C, 0x38, 0x0C, 0x1C, 0x0E, 0x0F, 0x0E, 0x04, 0x7C, + 0x00, 0x00, 0xC0, 0x18, 0x03, 0x80, 0x78, 0x1F, 0x03, 0xFF, 0x7F, 0xF0, + 0xF0, 0x0E, 0x00, 0xE0, 0x1E, 0x01, 0xE0, 0x1C, 0x01, 0xC0, 0x3C, 0x03, + 0xC0, 0x38, 0x03, 0x80, 0x78, 0x07, 0x80, 0x70, 0x8F, 0x10, 0xF1, 0x0F, + 0x20, 0xFC, 0x07, 0x80, 0x00, 0x00, 0x00, 0xF0, 0x0E, 0x7F, 0x00, 0xE0, + 0xF0, 0x1E, 0x0E, 0x01, 0xE1, 0xE0, 0x3C, 0x1E, 0x03, 0xC1, 0xE0, 0x3C, + 0x1C, 0x07, 0xC3, 0xC0, 0x78, 0x3C, 0x0F, 0x83, 0xC0, 0xB8, 0x38, 0x1F, + 0x87, 0x83, 0x70, 0x78, 0x27, 0x07, 0x86, 0x70, 0x70, 0xC7, 0x1F, 0x08, + 0xE1, 0xE1, 0x0E, 0x2E, 0x60, 0xE4, 0xFC, 0x0F, 0x87, 0x00, 0x70, 0x1C, + 0x03, 0xBF, 0x00, 0xF1, 0xE0, 0x3C, 0x78, 0x07, 0x1E, 0x00, 0xC3, 0x80, + 0x30, 0xE0, 0x08, 0x38, 0x06, 0x0E, 0x01, 0x03, 0x80, 0xC0, 0xF0, 0x20, + 0x3C, 0x10, 0x07, 0x04, 0x01, 0xC2, 0x00, 0x71, 0x00, 0x1C, 0xC0, 0x07, + 0x60, 0x01, 0xF0, 0x00, 0x78, 0x00, 0x1C, 0x00, 0x06, 0x00, 0x01, 0x00, + 0x00, 0x0C, 0x00, 0x40, 0x3B, 0xF8, 0x01, 0x00, 0xF1, 0xE0, 0x0C, 0x03, + 0xC3, 0x80, 0x78, 0x07, 0x0E, 0x01, 0xE0, 0x0C, 0x38, 0x0F, 0x80, 0x20, + 0xE0, 0x6E, 0x00, 0x83, 0x81, 0x38, 0x04, 0x0F, 0x0C, 0xE0, 0x10, 0x1C, + 0x23, 0x80, 0x80, 0x71, 0x8E, 0x06, 0x01, 0xCC, 0x38, 0x10, 0x07, 0x20, + 0xE0, 0x80, 0x1D, 0x83, 0x86, 0x00, 0x7C, 0x07, 0x30, 0x01, 0xF0, 0x1C, + 0x80, 0x07, 0x80, 0x74, 0x00, 0x1E, 0x01, 0xF0, 0x00, 0x70, 0x07, 0x80, + 0x01, 0xC0, 0x1C, 0x00, 0x06, 0x00, 0x60, 0x00, 0x10, 0x01, 0x00, 0x00, + 0x00, 0xE0, 0x38, 0x1F, 0x81, 0xF0, 0x8F, 0x09, 0x80, 0x3C, 0x40, 0x00, + 0x72, 0x00, 0x01, 0xD0, 0x00, 0x07, 0xC0, 0x00, 0x1E, 0x00, 0x00, 0x38, + 0x00, 0x00, 0xE0, 0x00, 0x03, 0x80, 0x00, 0x0F, 0x00, 0x00, 0x7C, 0x00, + 0x01, 0x70, 0x00, 0x09, 0xC0, 0x00, 0x67, 0x00, 0x01, 0x1E, 0x10, 0x08, + 0x38, 0x40, 0x40, 0xE2, 0x39, 0x03, 0xD0, 0xF8, 0x0F, 0x83, 0xC0, 0x1C, + 0x00, 0x07, 0x80, 0x33, 0xFC, 0x03, 0xC1, 0xE0, 0x1E, 0x07, 0x80, 0x70, + 0x3C, 0x01, 0x80, 0xE0, 0x0C, 0x07, 0x80, 0x40, 0x3C, 0x02, 0x00, 0xE0, + 0x20, 0x07, 0x81, 0x00, 0x3C, 0x18, 0x01, 0xE0, 0x80, 0x07, 0x0C, 0x00, + 0x38, 0x40, 0x01, 0xE4, 0x00, 0x0F, 0x60, 0x00, 0x3A, 0x00, 0x01, 0xF0, + 0x00, 0x0F, 0x00, 0x00, 0x70, 0x00, 0x03, 0x80, 0x00, 0x18, 0x00, 0x00, + 0x80, 0x00, 0x0C, 0x00, 0x00, 0x40, 0x00, 0x04, 0x00, 0x00, 0x40, 0x00, + 0x04, 0x00, 0x0E, 0x40, 0x00, 0x7C, 0x00, 0x03, 0xC0, 0x00, 0x00, 0x0F, + 0xFF, 0x87, 0xFF, 0x82, 0x00, 0x83, 0x00, 0xC1, 0x00, 0xC0, 0x00, 0xC0, + 0x00, 0xC0, 0x00, 0x60, 0x00, 0x60, 0x00, 0x60, 0x00, 0x60, 0x00, 0x20, + 0x00, 0x30, 0x00, 0x30, 0x00, 0x30, 0x00, 0x30, 0x00, 0x18, 0x00, 0x1E, + 0x00, 0x1F, 0xC0, 0x1F, 0xF0, 0xE8, 0xFC, 0x70, 0x1E, 0x38, 0x03, 0x88, + 0x00, 0x78, 0x00, 0x0F, 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x0E, 0x00, 0x0F, + 0x00, 0x07, 0x80, 0x03, 0x80, 0x01, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, + 0x70, 0x00, 0x78, 0x00, 0x3C, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x0F, 0x00, + 0x07, 0x80, 0x07, 0x80, 0x03, 0xC0, 0x07, 0xC0, 0x07, 0xC0, 0x00, 0x80, + 0x00, 0x60, 0x00, 0x38, 0x00, 0x1C, 0x00, 0x0E, 0x00, 0x0F, 0x00, 0x07, + 0x80, 0x03, 0x80, 0x01, 0xC0, 0x01, 0xE0, 0x00, 0xF0, 0x00, 0x70, 0x00, + 0x38, 0x00, 0x3C, 0x00, 0x1E, 0x00, 0x0E, 0x00, 0x07, 0x00, 0x01, 0x80, + 0x00, 0x70, 0x00, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xFF, 0xFF, 0xFF, 0xE0, 0x00, 0x18, 0x00, 0x0E, 0x00, 0x06, 0x00, 0x07, + 0x00, 0x07, 0x00, 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x0F, 0x00, 0x0E, + 0x00, 0x0E, 0x00, 0x1E, 0x00, 0x1E, 0x00, 0x1C, 0x00, 0x1C, 0x00, 0x3C, + 0x00, 0x3C, 0x00, 0x38, 0x00, 0x38, 0x00, 0x18, 0x00, 0x08, 0x00, 0x1C, + 0x00, 0x7E, 0x00, 0x78, 0x00, 0xF0, 0x00, 0xE0, 0x01, 0xE0, 0x01, 0xE0, + 0x01, 0xC0, 0x01, 0xC0, 0x03, 0xC0, 0x03, 0x80, 0x03, 0x80, 0x07, 0x80, + 0x07, 0x80, 0x07, 0x00, 0x07, 0x00, 0x0F, 0x00, 0x0E, 0x00, 0x1C, 0x00, + 0xF8, 0x00, 0x1F, 0x80, 0x00, 0xFF, 0x80, 0xC7, 0xFF, 0x87, 0xBC, 0x3F, + 0xFE, 0x60, 0x3F, 0xF0, 0x00, 0x1F, 0x00 }; + +const GFXglyph FreeSerifItalic24pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 12, 0, 1 }, // 0x20 ' ' + { 0, 12, 32, 16, 2, -30 }, // 0x21 '!' + { 48, 14, 12, 16, 6, -31 }, // 0x22 '"' + { 69, 25, 31, 23, 0, -30 }, // 0x23 '#' + { 166, 21, 38, 24, 2, -33 }, // 0x24 '$' + { 266, 33, 32, 39, 4, -30 }, // 0x25 '%' + { 398, 30, 33, 37, 4, -31 }, // 0x26 '&' + { 522, 5, 12, 9, 6, -31 }, // 0x27 ''' + { 530, 13, 39, 16, 2, -30 }, // 0x28 '(' + { 594, 13, 39, 16, 0, -30 }, // 0x29 ')' + { 658, 16, 20, 23, 7, -31 }, // 0x2A '*' + { 698, 23, 23, 32, 4, -22 }, // 0x2B '+' + { 765, 7, 11, 12, -1, -4 }, // 0x2C ',' + { 775, 11, 3, 16, 2, -11 }, // 0x2D '-' + { 780, 5, 5, 12, 1, -3 }, // 0x2E '.' + { 784, 21, 33, 14, 0, -31 }, // 0x2F '/' + { 871, 21, 31, 23, 2, -30 }, // 0x30 '0' + { 953, 17, 32, 23, 2, -31 }, // 0x31 '1' + { 1021, 21, 31, 24, 0, -30 }, // 0x32 '2' + { 1103, 22, 32, 23, 0, -31 }, // 0x33 '3' + { 1191, 22, 32, 23, 0, -31 }, // 0x34 '4' + { 1279, 22, 32, 24, 0, -31 }, // 0x35 '5' + { 1367, 23, 32, 23, 1, -31 }, // 0x36 '6' + { 1459, 21, 32, 23, 4, -31 }, // 0x37 '7' + { 1543, 22, 32, 23, 1, -31 }, // 0x38 '8' + { 1631, 22, 33, 23, 1, -31 }, // 0x39 '9' + { 1722, 9, 22, 12, 2, -20 }, // 0x3A ':' + { 1747, 11, 27, 12, 1, -20 }, // 0x3B ';' + { 1785, 23, 25, 27, 3, -24 }, // 0x3C '<' + { 1857, 24, 12, 31, 4, -17 }, // 0x3D '=' + { 1893, 24, 25, 27, 3, -24 }, // 0x3E '>' + { 1968, 16, 33, 21, 6, -31 }, // 0x3F '?' + { 2034, 33, 33, 37, 3, -31 }, // 0x40 '@' + { 2171, 29, 31, 31, 0, -30 }, // 0x41 'A' + { 2284, 28, 31, 28, 0, -30 }, // 0x42 'B' + { 2393, 30, 33, 29, 2, -31 }, // 0x43 'C' + { 2517, 33, 31, 33, 0, -30 }, // 0x44 'D' + { 2645, 29, 31, 27, 0, -30 }, // 0x45 'E' + { 2758, 29, 31, 27, 0, -30 }, // 0x46 'F' + { 2871, 31, 33, 32, 2, -31 }, // 0x47 'G' + { 2999, 36, 31, 33, 0, -30 }, // 0x48 'H' + { 3139, 18, 31, 15, 0, -30 }, // 0x49 'I' + { 3209, 23, 32, 20, 0, -30 }, // 0x4A 'J' + { 3301, 33, 31, 30, 0, -30 }, // 0x4B 'K' + { 3429, 27, 31, 27, 0, -30 }, // 0x4C 'L' + { 3534, 42, 31, 39, 0, -30 }, // 0x4D 'M' + { 3697, 35, 32, 32, 0, -30 }, // 0x4E 'N' + { 3837, 30, 33, 31, 2, -31 }, // 0x4F 'O' + { 3961, 29, 31, 27, 0, -30 }, // 0x50 'P' + { 4074, 30, 41, 31, 2, -31 }, // 0x51 'Q' + { 4228, 28, 31, 29, 0, -30 }, // 0x52 'R' + { 4337, 23, 33, 21, 0, -31 }, // 0x53 'S' + { 4432, 27, 31, 28, 4, -30 }, // 0x54 'T' + { 4537, 31, 32, 33, 5, -30 }, // 0x55 'U' + { 4661, 29, 32, 31, 6, -30 }, // 0x56 'V' + { 4777, 39, 32, 42, 6, -30 }, // 0x57 'W' + { 4933, 32, 31, 31, 0, -30 }, // 0x58 'X' + { 5057, 26, 31, 28, 5, -30 }, // 0x59 'Y' + { 5158, 29, 31, 26, 0, -30 }, // 0x5A 'Z' + { 5271, 17, 39, 18, 1, -31 }, // 0x5B '[' + { 5354, 17, 33, 23, 5, -31 }, // 0x5C '\' + { 5425, 17, 39, 18, 1, -31 }, // 0x5D ']' + { 5508, 20, 17, 20, 0, -31 }, // 0x5E '^' + { 5551, 24, 2, 23, 0, 5 }, // 0x5F '_' + { 5557, 8, 8, 12, 6, -31 }, // 0x60 '`' + { 5565, 21, 21, 23, 1, -20 }, // 0x61 'a' + { 5621, 21, 33, 22, 1, -31 }, // 0x62 'b' + { 5708, 18, 22, 19, 1, -20 }, // 0x63 'c' + { 5758, 24, 33, 23, 1, -31 }, // 0x64 'd' + { 5857, 18, 22, 19, 1, -20 }, // 0x65 'e' + { 5907, 27, 42, 20, -4, -31 }, // 0x66 'f' + { 6049, 21, 31, 21, -1, -20 }, // 0x67 'g' + { 6131, 21, 32, 23, 1, -31 }, // 0x68 'h' + { 6215, 10, 32, 12, 2, -30 }, // 0x69 'i' + { 6255, 19, 41, 13, -3, -30 }, // 0x6A 'j' + { 6353, 21, 33, 21, 1, -31 }, // 0x6B 'k' + { 6440, 11, 33, 12, 2, -31 }, // 0x6C 'l' + { 6486, 31, 21, 34, 1, -20 }, // 0x6D 'm' + { 6568, 21, 21, 23, 1, -20 }, // 0x6E 'n' + { 6624, 21, 22, 22, 1, -20 }, // 0x6F 'o' + { 6682, 27, 31, 22, -4, -20 }, // 0x70 'p' + { 6787, 21, 31, 23, 1, -20 }, // 0x71 'q' + { 6869, 17, 21, 17, 1, -20 }, // 0x72 'r' + { 6914, 17, 22, 16, 0, -20 }, // 0x73 's' + { 6961, 12, 26, 11, 1, -24 }, // 0x74 't' + { 7000, 20, 22, 23, 1, -20 }, // 0x75 'u' + { 7055, 18, 22, 21, 3, -20 }, // 0x76 'v' + { 7105, 30, 22, 32, 2, -20 }, // 0x77 'w' + { 7188, 22, 22, 20, -1, -20 }, // 0x78 'x' + { 7249, 21, 31, 22, 1, -20 }, // 0x79 'y' + { 7331, 17, 24, 18, 0, -19 }, // 0x7A 'z' + { 7382, 17, 40, 19, 2, -31 }, // 0x7B '{' + { 7467, 3, 33, 13, 5, -31 }, // 0x7C '|' + { 7480, 16, 41, 19, 0, -32 }, // 0x7D '}' + { 7562, 22, 6, 25, 2, -14 } }; // 0x7E '~' + +const GFXfont FreeSerifItalic24pt7b PROGMEM = { + (uint8_t *)FreeSerifItalic24pt7bBitmaps, + (GFXglyph *)FreeSerifItalic24pt7bGlyphs, + 0x20, 0x7E, 56 }; + +// Approx. 8251 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic9pt7b.h b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic9pt7b.h new file mode 100644 index 0000000..34e6b8d --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/FreeSerifItalic9pt7b.h @@ -0,0 +1,202 @@ +const uint8_t FreeSerifItalic9pt7bBitmaps[] PROGMEM = { + 0x11, 0x12, 0x22, 0x24, 0x40, 0x0C, 0xDE, 0xE5, 0x40, 0x04, 0x82, 0x20, + 0x98, 0x24, 0x7F, 0xC4, 0x82, 0x23, 0xFC, 0x24, 0x11, 0x04, 0x83, 0x20, + 0x1C, 0x1B, 0x99, 0x4D, 0x26, 0x81, 0xC0, 0x70, 0x1C, 0x13, 0x49, 0xA4, + 0xDA, 0xC7, 0xC1, 0x00, 0x80, 0x1C, 0x61, 0xCF, 0x0E, 0x28, 0x30, 0xA0, + 0xC5, 0x03, 0x34, 0xE7, 0xAE, 0x40, 0xB1, 0x05, 0x84, 0x26, 0x20, 0x99, + 0x84, 0x3C, 0x03, 0x80, 0x6C, 0x06, 0xC0, 0x78, 0x06, 0x01, 0xEF, 0x66, + 0x24, 0x24, 0xC3, 0x8C, 0x10, 0xE3, 0x87, 0xCE, 0xFA, 0x08, 0x21, 0x08, + 0x61, 0x8C, 0x30, 0xC3, 0x0C, 0x30, 0x41, 0x02, 0x00, 0x10, 0x40, 0x82, + 0x0C, 0x30, 0xC3, 0x0C, 0x61, 0x84, 0x21, 0x08, 0x00, 0x30, 0xCA, 0x5E, + 0x6A, 0x93, 0x08, 0x08, 0x04, 0x02, 0x01, 0x0F, 0xF8, 0x40, 0x20, 0x10, + 0x08, 0x00, 0x56, 0xF0, 0xF0, 0x03, 0x02, 0x06, 0x04, 0x08, 0x08, 0x10, + 0x30, 0x20, 0x60, 0x40, 0xC0, 0x0E, 0x0C, 0x8C, 0x6C, 0x36, 0x1F, 0x0F, + 0x07, 0x87, 0xC3, 0x61, 0xB1, 0x88, 0x83, 0x80, 0x04, 0x70, 0xC3, 0x08, + 0x21, 0x86, 0x10, 0x43, 0x08, 0xF8, 0x1C, 0x67, 0x83, 0x03, 0x02, 0x06, + 0x0C, 0x08, 0x10, 0x20, 0x42, 0xFC, 0x0F, 0x08, 0xC0, 0x60, 0xC1, 0xE0, + 0x38, 0x0C, 0x06, 0x03, 0x01, 0x01, 0x1F, 0x00, 0x01, 0x01, 0x81, 0x41, + 0x61, 0x21, 0x11, 0x18, 0x88, 0xFF, 0x02, 0x03, 0x01, 0x00, 0x0F, 0x84, + 0x04, 0x03, 0x80, 0x60, 0x18, 0x0C, 0x06, 0x03, 0x03, 0x03, 0x1E, 0x00, + 0x01, 0x83, 0x87, 0x07, 0x03, 0x03, 0x73, 0xCD, 0x86, 0xC3, 0x61, 0xB1, + 0x88, 0xC3, 0xC0, 0x7F, 0x40, 0x80, 0x80, 0x40, 0x40, 0x60, 0x20, 0x20, + 0x10, 0x10, 0x18, 0x08, 0x00, 0x1E, 0x19, 0xCC, 0x66, 0x33, 0xB0, 0xE0, + 0x50, 0xCC, 0xC3, 0x61, 0xB0, 0xCC, 0xC3, 0xC0, 0x0E, 0x19, 0x8C, 0x6C, + 0x36, 0x1B, 0x0D, 0x86, 0xE6, 0x3F, 0x03, 0x03, 0x06, 0x0C, 0x00, 0x33, + 0x00, 0x00, 0xCC, 0x33, 0x00, 0x00, 0x44, 0x48, 0x01, 0x83, 0x86, 0x1C, + 0x0C, 0x03, 0x80, 0x30, 0x07, 0x00, 0x80, 0xFF, 0x80, 0x00, 0x00, 0x0F, + 0xF8, 0xC0, 0x1C, 0x03, 0x80, 0x70, 0x18, 0x38, 0x70, 0xC0, 0x80, 0x00, + 0x3C, 0x8C, 0x18, 0x30, 0xC3, 0x0C, 0x20, 0x40, 0x80, 0x06, 0x00, 0x0F, + 0xC0, 0xC3, 0x0C, 0x04, 0xC7, 0xBC, 0x64, 0xE2, 0x27, 0x31, 0x39, 0x91, + 0xCC, 0x93, 0x3B, 0x0E, 0x00, 0x1F, 0x80, 0x01, 0x00, 0x60, 0x14, 0x04, + 0xC0, 0x98, 0x23, 0x07, 0xE1, 0x04, 0x20, 0x88, 0x1B, 0x8F, 0x80, 0x3F, + 0xC1, 0x8C, 0x21, 0x8C, 0x31, 0x8C, 0x3E, 0x04, 0x61, 0x86, 0x30, 0xC4, + 0x19, 0x86, 0x7F, 0x80, 0x07, 0x91, 0x86, 0x30, 0x26, 0x02, 0x60, 0x0C, + 0x00, 0xC0, 0x0C, 0x00, 0xC0, 0x0C, 0x00, 0x61, 0x83, 0xE0, 0x3F, 0xC0, + 0x63, 0x82, 0x0C, 0x30, 0x31, 0x81, 0x8C, 0x0C, 0x40, 0x66, 0x07, 0x30, + 0x31, 0x03, 0x18, 0x71, 0xFE, 0x00, 0x3F, 0xF0, 0xC2, 0x08, 0x21, 0x80, + 0x19, 0x81, 0xF8, 0x11, 0x03, 0x10, 0x30, 0x02, 0x04, 0x60, 0x8F, 0xF8, + 0x3F, 0xF0, 0xC2, 0x08, 0x21, 0x80, 0x19, 0x81, 0xF8, 0x11, 0x03, 0x10, + 0x30, 0x02, 0x00, 0x60, 0x0F, 0x80, 0x07, 0x91, 0x87, 0x30, 0x26, 0x02, + 0x60, 0x0C, 0x00, 0xC1, 0xFC, 0x0C, 0xC0, 0xCC, 0x0C, 0x60, 0x83, 0xF0, + 0x3E, 0x3C, 0x30, 0x60, 0x81, 0x06, 0x0C, 0x18, 0x30, 0x7F, 0x81, 0x06, + 0x0C, 0x18, 0x30, 0x60, 0x81, 0x06, 0x0C, 0x3C, 0x78, 0x1E, 0x18, 0x20, + 0xC1, 0x83, 0x04, 0x18, 0x30, 0x41, 0x87, 0x80, 0x0F, 0x81, 0x80, 0x80, + 0xC0, 0x60, 0x20, 0x30, 0x18, 0x0C, 0x04, 0x36, 0x1E, 0x00, 0x3E, 0x78, + 0x61, 0x82, 0x10, 0x31, 0x01, 0xB0, 0x0E, 0x00, 0x58, 0x06, 0x60, 0x33, + 0x01, 0x0C, 0x18, 0x61, 0xE7, 0xC0, 0x3E, 0x01, 0x80, 0x20, 0x0C, 0x01, + 0x80, 0x30, 0x04, 0x01, 0x80, 0x30, 0x04, 0x0D, 0x83, 0x7F, 0xE0, 0x1C, + 0x07, 0x0C, 0x0E, 0x0C, 0x14, 0x14, 0x1C, 0x14, 0x2C, 0x16, 0x4C, 0x26, + 0x48, 0x26, 0x98, 0x27, 0x18, 0x27, 0x10, 0x42, 0x30, 0xF4, 0x7C, 0x38, + 0x78, 0x60, 0x83, 0x04, 0x2C, 0x41, 0x22, 0x09, 0x10, 0x4D, 0x84, 0x28, + 0x21, 0x41, 0x06, 0x10, 0x21, 0xE1, 0x00, 0x07, 0x83, 0x18, 0xC1, 0xB0, + 0x36, 0x07, 0xC0, 0xF0, 0x3E, 0x06, 0xC0, 0xD8, 0x31, 0x8C, 0x1E, 0x00, + 0x3F, 0xC1, 0x9C, 0x21, 0x8C, 0x31, 0x86, 0x31, 0x87, 0xE1, 0x80, 0x30, + 0x04, 0x01, 0x80, 0x78, 0x00, 0x07, 0x83, 0x18, 0xC1, 0x98, 0x36, 0x07, + 0xC0, 0xF0, 0x1E, 0x06, 0xC0, 0xD8, 0x31, 0x04, 0x13, 0x01, 0x80, 0x70, + 0xB7, 0xE0, 0x3F, 0xC1, 0x8C, 0x21, 0x8C, 0x31, 0x8C, 0x3F, 0x04, 0xC1, + 0x98, 0x31, 0x84, 0x31, 0x86, 0x78, 0x70, 0x1E, 0x4C, 0x63, 0x08, 0xC0, + 0x38, 0x07, 0x00, 0x60, 0x0C, 0x43, 0x10, 0xC6, 0x62, 0x70, 0x7F, 0xE9, + 0x8E, 0x31, 0x04, 0x01, 0x80, 0x30, 0x06, 0x00, 0x80, 0x30, 0x06, 0x00, + 0x80, 0x7E, 0x00, 0x7C, 0xF3, 0x02, 0x30, 0x46, 0x04, 0x60, 0x46, 0x04, + 0x40, 0x8C, 0x08, 0xC0, 0x8C, 0x10, 0xE3, 0x03, 0xC0, 0xF8, 0xEC, 0x0C, + 0x81, 0x18, 0x43, 0x08, 0x62, 0x0C, 0x81, 0x90, 0x14, 0x03, 0x00, 0x60, + 0x08, 0x00, 0xFB, 0xCE, 0x43, 0x0C, 0x86, 0x11, 0x8C, 0x43, 0x38, 0x86, + 0xB2, 0x0D, 0x24, 0x1C, 0x50, 0x38, 0xA0, 0x21, 0x80, 0x42, 0x01, 0x04, + 0x00, 0x3E, 0x71, 0x82, 0x0C, 0x40, 0xC8, 0x07, 0x00, 0x60, 0x06, 0x00, + 0xB0, 0x13, 0x02, 0x18, 0x61, 0x8F, 0x3E, 0xF9, 0xC8, 0x23, 0x10, 0xC8, + 0x34, 0x05, 0x01, 0x80, 0x40, 0x30, 0x0C, 0x03, 0x03, 0xE0, 0x3F, 0xE4, + 0x19, 0x03, 0x00, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0x40, 0x18, 0x06, 0x05, + 0x81, 0x7F, 0xE0, 0x0E, 0x10, 0x20, 0x81, 0x02, 0x04, 0x10, 0x20, 0x40, + 0x82, 0x04, 0x08, 0x1C, 0x00, 0x81, 0x04, 0x18, 0x20, 0xC1, 0x04, 0x08, + 0x20, 0x41, 0x38, 0x20, 0x82, 0x08, 0x41, 0x04, 0x10, 0xC2, 0x08, 0x20, + 0x8C, 0x00, 0x18, 0x18, 0x2C, 0x24, 0x46, 0x42, 0x83, 0xFF, 0x80, 0xD8, + 0x80, 0x1F, 0x98, 0x98, 0x4C, 0x2C, 0x36, 0x33, 0x3A, 0xEE, 0x38, 0x08, + 0x04, 0x02, 0x03, 0x71, 0xCC, 0xC6, 0xC3, 0x63, 0x21, 0x93, 0x8F, 0x00, + 0x1F, 0x33, 0x60, 0xC0, 0xC0, 0xC0, 0xC4, 0x78, 0x01, 0x80, 0x40, 0x60, + 0x20, 0xF1, 0x89, 0x8C, 0xC4, 0xC2, 0x63, 0x33, 0xAE, 0xE0, 0x0E, 0x65, + 0x8B, 0x2F, 0x98, 0x31, 0x3C, 0x01, 0xE0, 0x40, 0x08, 0x02, 0x00, 0x40, + 0x3E, 0x03, 0x00, 0x40, 0x08, 0x01, 0x00, 0x60, 0x0C, 0x01, 0x00, 0x20, + 0x04, 0x01, 0x00, 0xC0, 0x00, 0x1E, 0x19, 0xD8, 0xCC, 0xE1, 0xC3, 0x01, + 0xE0, 0xBC, 0x82, 0x41, 0x31, 0x0F, 0x00, 0x38, 0x08, 0x04, 0x02, 0x03, + 0x39, 0x6C, 0xC6, 0x46, 0x63, 0x21, 0x11, 0xB8, 0xE0, 0x30, 0x00, 0xE2, + 0x44, 0xC8, 0xCE, 0x06, 0x00, 0x00, 0x00, 0xC0, 0x83, 0x04, 0x08, 0x10, + 0x60, 0x81, 0x02, 0x04, 0x70, 0x38, 0x10, 0x10, 0x10, 0x37, 0x22, 0x24, + 0x38, 0x78, 0x48, 0x4D, 0xC6, 0x73, 0x32, 0x26, 0x64, 0x4C, 0xDE, 0x77, + 0x39, 0x5E, 0xCC, 0xCC, 0xCE, 0x66, 0x62, 0x22, 0x11, 0x11, 0xB9, 0x8E, + 0x77, 0x3B, 0x33, 0x62, 0x62, 0x42, 0x4D, 0xCE, 0x0F, 0x18, 0xD8, 0x7C, + 0x3C, 0x3E, 0x1B, 0x18, 0xF0, 0x3B, 0x87, 0x31, 0x8C, 0x43, 0x31, 0x88, + 0x62, 0x30, 0xF0, 0x60, 0x10, 0x04, 0x03, 0x80, 0x0F, 0x18, 0x98, 0x4C, + 0x2C, 0x26, 0x33, 0x38, 0xEC, 0x04, 0x02, 0x03, 0x03, 0xC0, 0x76, 0x50, + 0xC1, 0x06, 0x08, 0x10, 0x60, 0x1A, 0x6C, 0xC8, 0xC0, 0xD1, 0xB3, 0x5C, + 0x23, 0xC8, 0xC4, 0x21, 0x18, 0xE0, 0xC3, 0x42, 0x42, 0xC6, 0x86, 0x8C, + 0x9D, 0xEE, 0x62, 0xC4, 0x89, 0xA3, 0x47, 0x0C, 0x10, 0xE2, 0x2C, 0x44, + 0xD8, 0x9D, 0x23, 0xA4, 0x65, 0x0C, 0xC1, 0x10, 0x19, 0x95, 0x43, 0x01, + 0x80, 0xC0, 0xA0, 0x91, 0x8E, 0x70, 0x88, 0x46, 0x23, 0x20, 0x90, 0x50, + 0x28, 0x18, 0x08, 0x08, 0x08, 0x18, 0x00, 0x3F, 0x42, 0x04, 0x08, 0x10, + 0x20, 0x40, 0x72, 0x0E, 0x08, 0x61, 0x04, 0x30, 0x86, 0x08, 0x61, 0x04, + 0x30, 0xC3, 0x8F, 0x00, 0xFF, 0xF0, 0x1E, 0x0C, 0x10, 0x20, 0xC1, 0x82, + 0x04, 0x1C, 0x30, 0x40, 0x83, 0x04, 0x08, 0x20, 0x60, 0x99, 0x8E }; + +const GFXglyph FreeSerifItalic9pt7bGlyphs[] PROGMEM = { + { 0, 0, 0, 5, 0, 1 }, // 0x20 ' ' + { 0, 4, 12, 6, 1, -11 }, // 0x21 '!' + { 6, 5, 4, 6, 3, -11 }, // 0x22 '"' + { 9, 10, 12, 9, 0, -11 }, // 0x23 '#' + { 24, 9, 15, 9, 1, -12 }, // 0x24 '$' + { 41, 14, 12, 15, 1, -11 }, // 0x25 '%' + { 62, 12, 12, 14, 1, -11 }, // 0x26 '&' + { 80, 2, 4, 4, 3, -11 }, // 0x27 ''' + { 81, 6, 15, 6, 1, -11 }, // 0x28 '(' + { 93, 6, 15, 6, 0, -11 }, // 0x29 ')' + { 105, 6, 8, 9, 3, -11 }, // 0x2A '*' + { 111, 9, 9, 12, 1, -8 }, // 0x2B '+' + { 122, 2, 4, 5, 0, -1 }, // 0x2C ',' + { 123, 4, 1, 6, 1, -3 }, // 0x2D '-' + { 124, 2, 2, 5, 0, -1 }, // 0x2E '.' + { 125, 8, 12, 5, 0, -11 }, // 0x2F '/' + { 137, 9, 13, 9, 1, -12 }, // 0x30 '0' + { 152, 6, 13, 9, 1, -12 }, // 0x31 '1' + { 162, 8, 12, 9, 1, -11 }, // 0x32 '2' + { 174, 9, 12, 9, 0, -11 }, // 0x33 '3' + { 188, 9, 12, 9, 0, -11 }, // 0x34 '4' + { 202, 9, 12, 9, 0, -11 }, // 0x35 '5' + { 216, 9, 13, 9, 1, -12 }, // 0x36 '6' + { 231, 9, 12, 9, 1, -11 }, // 0x37 '7' + { 245, 9, 13, 9, 1, -12 }, // 0x38 '8' + { 260, 9, 13, 9, 0, -12 }, // 0x39 '9' + { 275, 4, 8, 4, 1, -7 }, // 0x3A ':' + { 279, 4, 10, 4, 1, -7 }, // 0x3B ';' + { 284, 9, 9, 10, 1, -8 }, // 0x3C '<' + { 295, 9, 5, 12, 2, -6 }, // 0x3D '=' + { 301, 9, 9, 10, 1, -8 }, // 0x3E '>' + { 312, 7, 12, 8, 2, -11 }, // 0x3F '?' + { 323, 13, 12, 14, 1, -11 }, // 0x40 '@' + { 343, 11, 11, 12, 0, -10 }, // 0x41 'A' + { 359, 11, 12, 11, 0, -11 }, // 0x42 'B' + { 376, 12, 12, 11, 1, -11 }, // 0x43 'C' + { 394, 13, 12, 13, 0, -11 }, // 0x44 'D' + { 414, 12, 12, 10, 0, -11 }, // 0x45 'E' + { 432, 12, 12, 10, 0, -11 }, // 0x46 'F' + { 450, 12, 12, 12, 1, -11 }, // 0x47 'G' + { 468, 14, 12, 13, 0, -11 }, // 0x48 'H' + { 489, 7, 12, 6, 0, -11 }, // 0x49 'I' + { 500, 9, 12, 8, 0, -11 }, // 0x4A 'J' + { 514, 13, 12, 12, 0, -11 }, // 0x4B 'K' + { 534, 11, 12, 10, 0, -11 }, // 0x4C 'L' + { 551, 16, 12, 15, 0, -11 }, // 0x4D 'M' + { 575, 13, 12, 12, 0, -11 }, // 0x4E 'N' + { 595, 11, 12, 12, 1, -11 }, // 0x4F 'O' + { 612, 11, 12, 10, 0, -11 }, // 0x50 'P' + { 629, 11, 15, 12, 1, -11 }, // 0x51 'Q' + { 650, 11, 12, 11, 0, -11 }, // 0x52 'R' + { 667, 10, 12, 8, 0, -11 }, // 0x53 'S' + { 682, 11, 12, 11, 2, -11 }, // 0x54 'T' + { 699, 12, 12, 13, 2, -11 }, // 0x55 'U' + { 717, 11, 12, 12, 2, -11 }, // 0x56 'V' + { 734, 15, 12, 16, 2, -11 }, // 0x57 'W' + { 757, 12, 12, 12, 0, -11 }, // 0x58 'X' + { 775, 10, 12, 11, 2, -11 }, // 0x59 'Y' + { 790, 11, 12, 10, 0, -11 }, // 0x5A 'Z' + { 807, 7, 15, 7, 0, -11 }, // 0x5B '[' + { 821, 6, 12, 9, 2, -11 }, // 0x5C '\' + { 830, 6, 15, 7, 1, -11 }, // 0x5D ']' + { 842, 8, 7, 8, 0, -11 }, // 0x5E '^' + { 849, 9, 1, 9, 0, 2 }, // 0x5F '_' + { 851, 3, 3, 5, 2, -11 }, // 0x60 '`' + { 853, 9, 8, 9, 0, -7 }, // 0x61 'a' + { 862, 9, 12, 9, 0, -11 }, // 0x62 'b' + { 876, 8, 8, 7, 0, -7 }, // 0x63 'c' + { 884, 9, 12, 9, 0, -11 }, // 0x64 'd' + { 898, 7, 8, 7, 0, -7 }, // 0x65 'e' + { 905, 11, 17, 8, -1, -12 }, // 0x66 'f' + { 929, 9, 12, 8, 0, -7 }, // 0x67 'g' + { 943, 9, 12, 9, 0, -11 }, // 0x68 'h' + { 957, 4, 12, 4, 1, -11 }, // 0x69 'i' + { 963, 7, 16, 5, -1, -11 }, // 0x6A 'j' + { 977, 8, 12, 8, 0, -11 }, // 0x6B 'k' + { 989, 4, 12, 5, 1, -11 }, // 0x6C 'l' + { 995, 13, 8, 13, 0, -7 }, // 0x6D 'm' + { 1008, 8, 8, 9, 0, -7 }, // 0x6E 'n' + { 1016, 9, 8, 9, 0, -7 }, // 0x6F 'o' + { 1025, 10, 12, 8, -1, -7 }, // 0x70 'p' + { 1040, 9, 12, 9, 0, -7 }, // 0x71 'q' + { 1054, 7, 8, 7, 0, -7 }, // 0x72 'r' + { 1061, 7, 8, 6, 0, -7 }, // 0x73 's' + { 1068, 5, 9, 4, 0, -8 }, // 0x74 't' + { 1074, 8, 8, 9, 1, -7 }, // 0x75 'u' + { 1082, 7, 8, 8, 1, -7 }, // 0x76 'v' + { 1089, 11, 8, 12, 1, -7 }, // 0x77 'w' + { 1100, 9, 8, 8, -1, -7 }, // 0x78 'x' + { 1109, 9, 12, 9, 0, -7 }, // 0x79 'y' + { 1123, 8, 9, 7, 0, -7 }, // 0x7A 'z' + { 1132, 6, 15, 7, 1, -11 }, // 0x7B '{' + { 1144, 1, 12, 5, 2, -11 }, // 0x7C '|' + { 1146, 7, 16, 7, 0, -12 }, // 0x7D '}' + { 1160, 8, 3, 10, 1, -5 } }; // 0x7E '~' + +const GFXfont FreeSerifItalic9pt7b PROGMEM = { + (uint8_t *)FreeSerifItalic9pt7bBitmaps, + (GFXglyph *)FreeSerifItalic9pt7bGlyphs, + 0x20, 0x7E, 22 }; + +// Approx. 1835 bytes diff --git a/libraries/Adafruit-GFX-Library-master/Fonts/TomThumb.h b/libraries/Adafruit-GFX-Library-master/Fonts/TomThumb.h new file mode 100644 index 0000000..dad420d --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/Fonts/TomThumb.h @@ -0,0 +1,474 @@ +/** +** The original 3x5 font is licensed under the 3-clause BSD license: +** +** Copyright 1999 Brian J. Swetland +** Copyright 1999 Vassilii Khachaturov +** Portions (of vt100.c/vt100.h) copyright Dan Marks +** +** All rights reserved. +** +** Redistribution and use in source and binary forms, with or without +** modification, are permitted provided that the following conditions +** are met: +** 1. Redistributions of source code must retain the above copyright +** notice, this list of conditions, and the following disclaimer. +** 2. Redistributions in binary form must reproduce the above copyright +** notice, this list of conditions, and the following disclaimer in the +** documentation and/or other materials provided with the distribution. +** 3. The name of the authors may not be used to endorse or promote products +** derived from this software without specific prior written permission. +** +** THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR +** IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES +** OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. +** IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, +** INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT +** NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +** DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +** THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +** (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF +** THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +** +** Modifications to Tom Thumb for improved readability are from Robey Pointer, +** see: +** http://robey.lag.net/2010/01/23/tiny-monospace-font.html +** +** The original author does not have any objection to relicensing of Robey +** Pointer's modifications (in this file) in a more permissive license. See +** the discussion at the above blog, and also here: +** http://opengameart.org/forumtopic/how-to-submit-art-using-the-3-clause-bsd-license +** +** Feb 21, 2016: Conversion from Linux BDF --> Adafruit GFX font, +** with the help of this Python script: +** https://gist.github.com/skelliam/322d421f028545f16f6d +** William Skellenger (williamj@skellenger.net) +** Twitter: @skelliam +** +*/ + +#define TOMTHUMB_USE_EXTENDED 0 + +const uint8_t TomThumbBitmaps[] PROGMEM = { + 0x00, /* 0x20 space */ + 0x80, 0x80, 0x80, 0x00, 0x80, /* 0x21 exclam */ + 0xA0, 0xA0, /* 0x22 quotedbl */ + 0xA0, 0xE0, 0xA0, 0xE0, 0xA0, /* 0x23 numbersign */ + 0x60, 0xC0, 0x60, 0xC0, 0x40, /* 0x24 dollar */ + 0x80, 0x20, 0x40, 0x80, 0x20, /* 0x25 percent */ + 0xC0, 0xC0, 0xE0, 0xA0, 0x60, /* 0x26 ampersand */ + 0x80, 0x80, /* 0x27 quotesingle */ + 0x40, 0x80, 0x80, 0x80, 0x40, /* 0x28 parenleft */ + 0x80, 0x40, 0x40, 0x40, 0x80, /* 0x29 parenright */ + 0xA0, 0x40, 0xA0, /* 0x2A asterisk */ + 0x40, 0xE0, 0x40, /* 0x2B plus */ + 0x40, 0x80, /* 0x2C comma */ + 0xE0, /* 0x2D hyphen */ + 0x80, /* 0x2E period */ + 0x20, 0x20, 0x40, 0x80, 0x80, /* 0x2F slash */ + 0x60, 0xA0, 0xA0, 0xA0, 0xC0, /* 0x30 zero */ + 0x40, 0xC0, 0x40, 0x40, 0x40, /* 0x31 one */ + 0xC0, 0x20, 0x40, 0x80, 0xE0, /* 0x32 two */ + 0xC0, 0x20, 0x40, 0x20, 0xC0, /* 0x33 three */ + 0xA0, 0xA0, 0xE0, 0x20, 0x20, /* 0x34 four */ + 0xE0, 0x80, 0xC0, 0x20, 0xC0, /* 0x35 five */ + 0x60, 0x80, 0xE0, 0xA0, 0xE0, /* 0x36 six */ + 0xE0, 0x20, 0x40, 0x80, 0x80, /* 0x37 seven */ + 0xE0, 0xA0, 0xE0, 0xA0, 0xE0, /* 0x38 eight */ + 0xE0, 0xA0, 0xE0, 0x20, 0xC0, /* 0x39 nine */ + 0x80, 0x00, 0x80, /* 0x3A colon */ + 0x40, 0x00, 0x40, 0x80, /* 0x3B semicolon */ + 0x20, 0x40, 0x80, 0x40, 0x20, /* 0x3C less */ + 0xE0, 0x00, 0xE0, /* 0x3D equal */ + 0x80, 0x40, 0x20, 0x40, 0x80, /* 0x3E greater */ + 0xE0, 0x20, 0x40, 0x00, 0x40, /* 0x3F question */ + 0x40, 0xA0, 0xE0, 0x80, 0x60, /* 0x40 at */ + 0x40, 0xA0, 0xE0, 0xA0, 0xA0, /* 0x41 A */ + 0xC0, 0xA0, 0xC0, 0xA0, 0xC0, /* 0x42 B */ + 0x60, 0x80, 0x80, 0x80, 0x60, /* 0x43 C */ + 0xC0, 0xA0, 0xA0, 0xA0, 0xC0, /* 0x44 D */ + 0xE0, 0x80, 0xE0, 0x80, 0xE0, /* 0x45 E */ + 0xE0, 0x80, 0xE0, 0x80, 0x80, /* 0x46 F */ + 0x60, 0x80, 0xE0, 0xA0, 0x60, /* 0x47 G */ + 0xA0, 0xA0, 0xE0, 0xA0, 0xA0, /* 0x48 H */ + 0xE0, 0x40, 0x40, 0x40, 0xE0, /* 0x49 I */ + 0x20, 0x20, 0x20, 0xA0, 0x40, /* 0x4A J */ + 0xA0, 0xA0, 0xC0, 0xA0, 0xA0, /* 0x4B K */ + 0x80, 0x80, 0x80, 0x80, 0xE0, /* 0x4C L */ + 0xA0, 0xE0, 0xE0, 0xA0, 0xA0, /* 0x4D M */ + 0xA0, 0xE0, 0xE0, 0xE0, 0xA0, /* 0x4E N */ + 0x40, 0xA0, 0xA0, 0xA0, 0x40, /* 0x4F O */ + 0xC0, 0xA0, 0xC0, 0x80, 0x80, /* 0x50 P */ + 0x40, 0xA0, 0xA0, 0xE0, 0x60, /* 0x51 Q */ + 0xC0, 0xA0, 0xE0, 0xC0, 0xA0, /* 0x52 R */ + 0x60, 0x80, 0x40, 0x20, 0xC0, /* 0x53 S */ + 0xE0, 0x40, 0x40, 0x40, 0x40, /* 0x54 T */ + 0xA0, 0xA0, 0xA0, 0xA0, 0x60, /* 0x55 U */ + 0xA0, 0xA0, 0xA0, 0x40, 0x40, /* 0x56 V */ + 0xA0, 0xA0, 0xE0, 0xE0, 0xA0, /* 0x57 W */ + 0xA0, 0xA0, 0x40, 0xA0, 0xA0, /* 0x58 X */ + 0xA0, 0xA0, 0x40, 0x40, 0x40, /* 0x59 Y */ + 0xE0, 0x20, 0x40, 0x80, 0xE0, /* 0x5A Z */ + 0xE0, 0x80, 0x80, 0x80, 0xE0, /* 0x5B bracketleft */ + 0x80, 0x40, 0x20, /* 0x5C backslash */ + 0xE0, 0x20, 0x20, 0x20, 0xE0, /* 0x5D bracketright */ + 0x40, 0xA0, /* 0x5E asciicircum */ + 0xE0, /* 0x5F underscore */ + 0x80, 0x40, /* 0x60 grave */ + 0xC0, 0x60, 0xA0, 0xE0, /* 0x61 a */ + 0x80, 0xC0, 0xA0, 0xA0, 0xC0, /* 0x62 b */ + 0x60, 0x80, 0x80, 0x60, /* 0x63 c */ + 0x20, 0x60, 0xA0, 0xA0, 0x60, /* 0x64 d */ + 0x60, 0xA0, 0xC0, 0x60, /* 0x65 e */ + 0x20, 0x40, 0xE0, 0x40, 0x40, /* 0x66 f */ + 0x60, 0xA0, 0xE0, 0x20, 0x40, /* 0x67 g */ + 0x80, 0xC0, 0xA0, 0xA0, 0xA0, /* 0x68 h */ + 0x80, 0x00, 0x80, 0x80, 0x80, /* 0x69 i */ + 0x20, 0x00, 0x20, 0x20, 0xA0, 0x40, /* 0x6A j */ + 0x80, 0xA0, 0xC0, 0xC0, 0xA0, /* 0x6B k */ + 0xC0, 0x40, 0x40, 0x40, 0xE0, /* 0x6C l */ + 0xE0, 0xE0, 0xE0, 0xA0, /* 0x6D m */ + 0xC0, 0xA0, 0xA0, 0xA0, /* 0x6E n */ + 0x40, 0xA0, 0xA0, 0x40, /* 0x6F o */ + 0xC0, 0xA0, 0xA0, 0xC0, 0x80, /* 0x70 p */ + 0x60, 0xA0, 0xA0, 0x60, 0x20, /* 0x71 q */ + 0x60, 0x80, 0x80, 0x80, /* 0x72 r */ + 0x60, 0xC0, 0x60, 0xC0, /* 0x73 s */ + 0x40, 0xE0, 0x40, 0x40, 0x60, /* 0x74 t */ + 0xA0, 0xA0, 0xA0, 0x60, /* 0x75 u */ + 0xA0, 0xA0, 0xE0, 0x40, /* 0x76 v */ + 0xA0, 0xE0, 0xE0, 0xE0, /* 0x77 w */ + 0xA0, 0x40, 0x40, 0xA0, /* 0x78 x */ + 0xA0, 0xA0, 0x60, 0x20, 0x40, /* 0x79 y */ + 0xE0, 0x60, 0xC0, 0xE0, /* 0x7A z */ + 0x60, 0x40, 0x80, 0x40, 0x60, /* 0x7B braceleft */ + 0x80, 0x80, 0x00, 0x80, 0x80, /* 0x7C bar */ + 0xC0, 0x40, 0x20, 0x40, 0xC0, /* 0x7D braceright */ + 0x60, 0xC0, /* 0x7E asciitilde */ +#if (TOMTHUMB_USE_EXTENDED) + 0x80, 0x00, 0x80, 0x80, 0x80, /* 0xA1 exclamdown */ + 0x40, 0xE0, 0x80, 0xE0, 0x40, /* 0xA2 cent */ + 0x60, 0x40, 0xE0, 0x40, 0xE0, /* 0xA3 sterling */ + 0xA0, 0x40, 0xE0, 0x40, 0xA0, /* 0xA4 currency */ + 0xA0, 0xA0, 0x40, 0xE0, 0x40, /* 0xA5 yen */ + 0x80, 0x80, 0x00, 0x80, 0x80, /* 0xA6 brokenbar */ + 0x60, 0x40, 0xA0, 0x40, 0xC0, /* 0xA7 section */ + 0xA0, /* 0xA8 dieresis */ + 0x60, 0x80, 0x60, /* 0xA9 copyright */ + 0x60, 0xA0, 0xE0, 0x00, 0xE0, /* 0xAA ordfeminine */ + 0x40, 0x80, 0x40, /* 0xAB guillemotleft */ + 0xE0, 0x20, /* 0xAC logicalnot */ + 0xC0, /* 0xAD softhyphen */ + 0xC0, 0xC0, 0xA0, /* 0xAE registered */ + 0xE0, /* 0xAF macron */ + 0x40, 0xA0, 0x40, /* 0xB0 degree */ + 0x40, 0xE0, 0x40, 0x00, 0xE0, /* 0xB1 plusminus */ + 0xC0, 0x40, 0x60, /* 0xB2 twosuperior */ + 0xE0, 0x60, 0xE0, /* 0xB3 threesuperior */ + 0x40, 0x80, /* 0xB4 acute */ + 0xA0, 0xA0, 0xA0, 0xC0, 0x80, /* 0xB5 mu */ + 0x60, 0xA0, 0x60, 0x60, 0x60, /* 0xB6 paragraph */ + 0xE0, 0xE0, 0xE0, /* 0xB7 periodcentered */ + 0x40, 0x20, 0xC0, /* 0xB8 cedilla */ + 0x80, 0x80, 0x80, /* 0xB9 onesuperior */ + 0x40, 0xA0, 0x40, 0x00, 0xE0, /* 0xBA ordmasculine */ + 0x80, 0x40, 0x80, /* 0xBB guillemotright */ + 0x80, 0x80, 0x00, 0x60, 0x20, /* 0xBC onequarter */ + 0x80, 0x80, 0x00, 0xC0, 0x60, /* 0xBD onehalf */ + 0xC0, 0xC0, 0x00, 0x60, 0x20, /* 0xBE threequarters */ + 0x40, 0x00, 0x40, 0x80, 0xE0, /* 0xBF questiondown */ + 0x40, 0x20, 0x40, 0xE0, 0xA0, /* 0xC0 Agrave */ + 0x40, 0x80, 0x40, 0xE0, 0xA0, /* 0xC1 Aacute */ + 0xE0, 0x00, 0x40, 0xE0, 0xA0, /* 0xC2 Acircumflex */ + 0x60, 0xC0, 0x40, 0xE0, 0xA0, /* 0xC3 Atilde */ + 0xA0, 0x40, 0xA0, 0xE0, 0xA0, /* 0xC4 Adieresis */ + 0xC0, 0xC0, 0xA0, 0xE0, 0xA0, /* 0xC5 Aring */ + 0x60, 0xC0, 0xE0, 0xC0, 0xE0, /* 0xC6 AE */ + 0x60, 0x80, 0x80, 0x60, 0x20, 0x40, /* 0xC7 Ccedilla */ + 0x40, 0x20, 0xE0, 0xC0, 0xE0, /* 0xC8 Egrave */ + 0x40, 0x80, 0xE0, 0xC0, 0xE0, /* 0xC9 Eacute */ + 0xE0, 0x00, 0xE0, 0xC0, 0xE0, /* 0xCA Ecircumflex */ + 0xA0, 0x00, 0xE0, 0xC0, 0xE0, /* 0xCB Edieresis */ + 0x40, 0x20, 0xE0, 0x40, 0xE0, /* 0xCC Igrave */ + 0x40, 0x80, 0xE0, 0x40, 0xE0, /* 0xCD Iacute */ + 0xE0, 0x00, 0xE0, 0x40, 0xE0, /* 0xCE Icircumflex */ + 0xA0, 0x00, 0xE0, 0x40, 0xE0, /* 0xCF Idieresis */ + 0xC0, 0xA0, 0xE0, 0xA0, 0xC0, /* 0xD0 Eth */ + 0xC0, 0x60, 0xA0, 0xE0, 0xA0, /* 0xD1 Ntilde */ + 0x40, 0x20, 0xE0, 0xA0, 0xE0, /* 0xD2 Ograve */ + 0x40, 0x80, 0xE0, 0xA0, 0xE0, /* 0xD3 Oacute */ + 0xE0, 0x00, 0xE0, 0xA0, 0xE0, /* 0xD4 Ocircumflex */ + 0xC0, 0x60, 0xE0, 0xA0, 0xE0, /* 0xD5 Otilde */ + 0xA0, 0x00, 0xE0, 0xA0, 0xE0, /* 0xD6 Odieresis */ + 0xA0, 0x40, 0xA0, /* 0xD7 multiply */ + 0x60, 0xA0, 0xE0, 0xA0, 0xC0, /* 0xD8 Oslash */ + 0x80, 0x40, 0xA0, 0xA0, 0xE0, /* 0xD9 Ugrave */ + 0x20, 0x40, 0xA0, 0xA0, 0xE0, /* 0xDA Uacute */ + 0xE0, 0x00, 0xA0, 0xA0, 0xE0, /* 0xDB Ucircumflex */ + 0xA0, 0x00, 0xA0, 0xA0, 0xE0, /* 0xDC Udieresis */ + 0x20, 0x40, 0xA0, 0xE0, 0x40, /* 0xDD Yacute */ + 0x80, 0xE0, 0xA0, 0xE0, 0x80, /* 0xDE Thorn */ + 0x60, 0xA0, 0xC0, 0xA0, 0xC0, 0x80, /* 0xDF germandbls */ + 0x40, 0x20, 0x60, 0xA0, 0xE0, /* 0xE0 agrave */ + 0x40, 0x80, 0x60, 0xA0, 0xE0, /* 0xE1 aacute */ + 0xE0, 0x00, 0x60, 0xA0, 0xE0, /* 0xE2 acircumflex */ + 0x60, 0xC0, 0x60, 0xA0, 0xE0, /* 0xE3 atilde */ + 0xA0, 0x00, 0x60, 0xA0, 0xE0, /* 0xE4 adieresis */ + 0x60, 0x60, 0x60, 0xA0, 0xE0, /* 0xE5 aring */ + 0x60, 0xE0, 0xE0, 0xC0, /* 0xE6 ae */ + 0x60, 0x80, 0x60, 0x20, 0x40, /* 0xE7 ccedilla */ + 0x40, 0x20, 0x60, 0xE0, 0x60, /* 0xE8 egrave */ + 0x40, 0x80, 0x60, 0xE0, 0x60, /* 0xE9 eacute */ + 0xE0, 0x00, 0x60, 0xE0, 0x60, /* 0xEA ecircumflex */ + 0xA0, 0x00, 0x60, 0xE0, 0x60, /* 0xEB edieresis */ + 0x80, 0x40, 0x80, 0x80, 0x80, /* 0xEC igrave */ + 0x40, 0x80, 0x40, 0x40, 0x40, /* 0xED iacute */ + 0xE0, 0x00, 0x40, 0x40, 0x40, /* 0xEE icircumflex */ + 0xA0, 0x00, 0x40, 0x40, 0x40, /* 0xEF idieresis */ + 0x60, 0xC0, 0x60, 0xA0, 0x60, /* 0xF0 eth */ + 0xC0, 0x60, 0xC0, 0xA0, 0xA0, /* 0xF1 ntilde */ + 0x40, 0x20, 0x40, 0xA0, 0x40, /* 0xF2 ograve */ + 0x40, 0x80, 0x40, 0xA0, 0x40, /* 0xF3 oacute */ + 0xE0, 0x00, 0x40, 0xA0, 0x40, /* 0xF4 ocircumflex */ + 0xC0, 0x60, 0x40, 0xA0, 0x40, /* 0xF5 otilde */ + 0xA0, 0x00, 0x40, 0xA0, 0x40, /* 0xF6 odieresis */ + 0x40, 0x00, 0xE0, 0x00, 0x40, /* 0xF7 divide */ + 0x60, 0xE0, 0xA0, 0xC0, /* 0xF8 oslash */ + 0x80, 0x40, 0xA0, 0xA0, 0x60, /* 0xF9 ugrave */ + 0x20, 0x40, 0xA0, 0xA0, 0x60, /* 0xFA uacute */ + 0xE0, 0x00, 0xA0, 0xA0, 0x60, /* 0xFB ucircumflex */ + 0xA0, 0x00, 0xA0, 0xA0, 0x60, /* 0xFC udieresis */ + 0x20, 0x40, 0xA0, 0x60, 0x20, 0x40, /* 0xFD yacute */ + 0x80, 0xC0, 0xA0, 0xC0, 0x80, /* 0xFE thorn */ + 0xA0, 0x00, 0xA0, 0x60, 0x20, 0x40, /* 0xFF ydieresis */ + 0x00, /* 0x11D gcircumflex */ + 0x60, 0xC0, 0xE0, 0xC0, 0x60, /* 0x152 OE */ + 0x60, 0xE0, 0xC0, 0xE0, /* 0x153 oe */ + 0xA0, 0x60, 0xC0, 0x60, 0xC0, /* 0x160 Scaron */ + 0xA0, 0x60, 0xC0, 0x60, 0xC0, /* 0x161 scaron */ + 0xA0, 0x00, 0xA0, 0x40, 0x40, /* 0x178 Ydieresis */ + 0xA0, 0xE0, 0x60, 0xC0, 0xE0, /* 0x17D Zcaron */ + 0xA0, 0xE0, 0x60, 0xC0, 0xE0, /* 0x17E zcaron */ + 0x00, /* 0xEA4 uni0EA4 */ + 0x00, /* 0x13A0 uni13A0 */ + 0x80, /* 0x2022 bullet */ + 0xA0, /* 0x2026 ellipsis */ + 0x60, 0xE0, 0xE0, 0xC0, 0x60, /* 0x20AC Euro */ + 0xE0, 0xA0, 0xA0, 0xA0, 0xE0, /* 0xFFFD uniFFFD */ +#endif /* (TOMTHUMB_USE_EXTENDED) */ + }; + + +/* {offset, width, height, advance cursor, x offset, y offset} */ +const GFXglyph TomThumbGlyphs[] PROGMEM = { + { 0, 8, 1, 2, 0, -5 }, /* 0x20 space */ + { 1, 8, 5, 2, 0, -5 }, /* 0x21 exclam */ + { 6, 8, 2, 4, 0, -5 }, /* 0x22 quotedbl */ + { 8, 8, 5, 4, 0, -5 }, /* 0x23 numbersign */ + { 13, 8, 5, 4, 0, -5 }, /* 0x24 dollar */ + { 18, 8, 5, 4, 0, -5 }, /* 0x25 percent */ + { 23, 8, 5, 4, 0, -5 }, /* 0x26 ampersand */ + { 28, 8, 2, 2, 0, -5 }, /* 0x27 quotesingle */ + { 30, 8, 5, 3, 0, -5 }, /* 0x28 parenleft */ + { 35, 8, 5, 3, 0, -5 }, /* 0x29 parenright */ + { 40, 8, 3, 4, 0, -5 }, /* 0x2A asterisk */ + { 43, 8, 3, 4, 0, -4 }, /* 0x2B plus */ + { 46, 8, 2, 3, 0, -2 }, /* 0x2C comma */ + { 48, 8, 1, 4, 0, -3 }, /* 0x2D hyphen */ + { 49, 8, 1, 2, 0, -1 }, /* 0x2E period */ + { 50, 8, 5, 4, 0, -5 }, /* 0x2F slash */ + { 55, 8, 5, 4, 0, -5 }, /* 0x30 zero */ + { 60, 8, 5, 3, 0, -5 }, /* 0x31 one */ + { 65, 8, 5, 4, 0, -5 }, /* 0x32 two */ + { 70, 8, 5, 4, 0, -5 }, /* 0x33 three */ + { 75, 8, 5, 4, 0, -5 }, /* 0x34 four */ + { 80, 8, 5, 4, 0, -5 }, /* 0x35 five */ + { 85, 8, 5, 4, 0, -5 }, /* 0x36 six */ + { 90, 8, 5, 4, 0, -5 }, /* 0x37 seven */ + { 95, 8, 5, 4, 0, -5 }, /* 0x38 eight */ + { 100, 8, 5, 4, 0, -5 }, /* 0x39 nine */ + { 105, 8, 3, 2, 0, -4 }, /* 0x3A colon */ + { 108, 8, 4, 3, 0, -4 }, /* 0x3B semicolon */ + { 112, 8, 5, 4, 0, -5 }, /* 0x3C less */ + { 117, 8, 3, 4, 0, -4 }, /* 0x3D equal */ + { 120, 8, 5, 4, 0, -5 }, /* 0x3E greater */ + { 125, 8, 5, 4, 0, -5 }, /* 0x3F question */ + { 130, 8, 5, 4, 0, -5 }, /* 0x40 at */ + { 135, 8, 5, 4, 0, -5 }, /* 0x41 A */ + { 140, 8, 5, 4, 0, -5 }, /* 0x42 B */ + { 145, 8, 5, 4, 0, -5 }, /* 0x43 C */ + { 150, 8, 5, 4, 0, -5 }, /* 0x44 D */ + { 155, 8, 5, 4, 0, -5 }, /* 0x45 E */ + { 160, 8, 5, 4, 0, -5 }, /* 0x46 F */ + { 165, 8, 5, 4, 0, -5 }, /* 0x47 G */ + { 170, 8, 5, 4, 0, -5 }, /* 0x48 H */ + { 175, 8, 5, 4, 0, -5 }, /* 0x49 I */ + { 180, 8, 5, 4, 0, -5 }, /* 0x4A J */ + { 185, 8, 5, 4, 0, -5 }, /* 0x4B K */ + { 190, 8, 5, 4, 0, -5 }, /* 0x4C L */ + { 195, 8, 5, 4, 0, -5 }, /* 0x4D M */ + { 200, 8, 5, 4, 0, -5 }, /* 0x4E N */ + { 205, 8, 5, 4, 0, -5 }, /* 0x4F O */ + { 210, 8, 5, 4, 0, -5 }, /* 0x50 P */ + { 215, 8, 5, 4, 0, -5 }, /* 0x51 Q */ + { 220, 8, 5, 4, 0, -5 }, /* 0x52 R */ + { 225, 8, 5, 4, 0, -5 }, /* 0x53 S */ + { 230, 8, 5, 4, 0, -5 }, /* 0x54 T */ + { 235, 8, 5, 4, 0, -5 }, /* 0x55 U */ + { 240, 8, 5, 4, 0, -5 }, /* 0x56 V */ + { 245, 8, 5, 4, 0, -5 }, /* 0x57 W */ + { 250, 8, 5, 4, 0, -5 }, /* 0x58 X */ + { 255, 8, 5, 4, 0, -5 }, /* 0x59 Y */ + { 260, 8, 5, 4, 0, -5 }, /* 0x5A Z */ + { 265, 8, 5, 4, 0, -5 }, /* 0x5B bracketleft */ + { 270, 8, 3, 4, 0, -4 }, /* 0x5C backslash */ + { 273, 8, 5, 4, 0, -5 }, /* 0x5D bracketright */ + { 278, 8, 2, 4, 0, -5 }, /* 0x5E asciicircum */ + { 280, 8, 1, 4, 0, -1 }, /* 0x5F underscore */ + { 281, 8, 2, 3, 0, -5 }, /* 0x60 grave */ + { 283, 8, 4, 4, 0, -4 }, /* 0x61 a */ + { 287, 8, 5, 4, 0, -5 }, /* 0x62 b */ + { 292, 8, 4, 4, 0, -4 }, /* 0x63 c */ + { 296, 8, 5, 4, 0, -5 }, /* 0x64 d */ + { 301, 8, 4, 4, 0, -4 }, /* 0x65 e */ + { 305, 8, 5, 4, 0, -5 }, /* 0x66 f */ + { 310, 8, 5, 4, 0, -4 }, /* 0x67 g */ + { 315, 8, 5, 4, 0, -5 }, /* 0x68 h */ + { 320, 8, 5, 2, 0, -5 }, /* 0x69 i */ + { 325, 8, 6, 4, 0, -5 }, /* 0x6A j */ + { 331, 8, 5, 4, 0, -5 }, /* 0x6B k */ + { 336, 8, 5, 4, 0, -5 }, /* 0x6C l */ + { 341, 8, 4, 4, 0, -4 }, /* 0x6D m */ + { 345, 8, 4, 4, 0, -4 }, /* 0x6E n */ + { 349, 8, 4, 4, 0, -4 }, /* 0x6F o */ + { 353, 8, 5, 4, 0, -4 }, /* 0x70 p */ + { 358, 8, 5, 4, 0, -4 }, /* 0x71 q */ + { 363, 8, 4, 4, 0, -4 }, /* 0x72 r */ + { 367, 8, 4, 4, 0, -4 }, /* 0x73 s */ + { 371, 8, 5, 4, 0, -5 }, /* 0x74 t */ + { 376, 8, 4, 4, 0, -4 }, /* 0x75 u */ + { 380, 8, 4, 4, 0, -4 }, /* 0x76 v */ + { 384, 8, 4, 4, 0, -4 }, /* 0x77 w */ + { 388, 8, 4, 4, 0, -4 }, /* 0x78 x */ + { 392, 8, 5, 4, 0, -4 }, /* 0x79 y */ + { 397, 8, 4, 4, 0, -4 }, /* 0x7A z */ + { 401, 8, 5, 4, 0, -5 }, /* 0x7B braceleft */ + { 406, 8, 5, 2, 0, -5 }, /* 0x7C bar */ + { 411, 8, 5, 4, 0, -5 }, /* 0x7D braceright */ + { 416, 8, 2, 4, 0, -5 }, /* 0x7E asciitilde */ +#if (TOMTHUMB_USE_EXTENDED) + { 418, 8, 5, 2, 0, -5 }, /* 0xA1 exclamdown */ + { 423, 8, 5, 4, 0, -5 }, /* 0xA2 cent */ + { 428, 8, 5, 4, 0, -5 }, /* 0xA3 sterling */ + { 433, 8, 5, 4, 0, -5 }, /* 0xA4 currency */ + { 438, 8, 5, 4, 0, -5 }, /* 0xA5 yen */ + { 443, 8, 5, 2, 0, -5 }, /* 0xA6 brokenbar */ + { 448, 8, 5, 4, 0, -5 }, /* 0xA7 section */ + { 453, 8, 1, 4, 0, -5 }, /* 0xA8 dieresis */ + { 454, 8, 3, 4, 0, -5 }, /* 0xA9 copyright */ + { 457, 8, 5, 4, 0, -5 }, /* 0xAA ordfeminine */ + { 462, 8, 3, 3, 0, -5 }, /* 0xAB guillemotleft */ + { 465, 8, 2, 4, 0, -4 }, /* 0xAC logicalnot */ + { 467, 8, 1, 3, 0, -3 }, /* 0xAD softhyphen */ + { 468, 8, 3, 4, 0, -5 }, /* 0xAE registered */ + { 471, 8, 1, 4, 0, -5 }, /* 0xAF macron */ + { 472, 8, 3, 4, 0, -5 }, /* 0xB0 degree */ + { 475, 8, 5, 4, 0, -5 }, /* 0xB1 plusminus */ + { 480, 8, 3, 4, 0, -5 }, /* 0xB2 twosuperior */ + { 483, 8, 3, 4, 0, -5 }, /* 0xB3 threesuperior */ + { 486, 8, 2, 3, 0, -5 }, /* 0xB4 acute */ + { 488, 8, 5, 4, 0, -5 }, /* 0xB5 mu */ + { 493, 8, 5, 4, 0, -5 }, /* 0xB6 paragraph */ + { 498, 8, 3, 4, 0, -4 }, /* 0xB7 periodcentered */ + { 501, 8, 3, 4, 0, -3 }, /* 0xB8 cedilla */ + { 504, 8, 3, 2, 0, -5 }, /* 0xB9 onesuperior */ + { 507, 8, 5, 4, 0, -5 }, /* 0xBA ordmasculine */ + { 512, 8, 3, 3, 0, -5 }, /* 0xBB guillemotright */ + { 515, 8, 5, 4, 0, -5 }, /* 0xBC onequarter */ + { 520, 8, 5, 4, 0, -5 }, /* 0xBD onehalf */ + { 525, 8, 5, 4, 0, -5 }, /* 0xBE threequarters */ + { 530, 8, 5, 4, 0, -5 }, /* 0xBF questiondown */ + { 535, 8, 5, 4, 0, -5 }, /* 0xC0 Agrave */ + { 540, 8, 5, 4, 0, -5 }, /* 0xC1 Aacute */ + { 545, 8, 5, 4, 0, -5 }, /* 0xC2 Acircumflex */ + { 550, 8, 5, 4, 0, -5 }, /* 0xC3 Atilde */ + { 555, 8, 5, 4, 0, -5 }, /* 0xC4 Adieresis */ + { 560, 8, 5, 4, 0, -5 }, /* 0xC5 Aring */ + { 565, 8, 5, 4, 0, -5 }, /* 0xC6 AE */ + { 570, 8, 6, 4, 0, -5 }, /* 0xC7 Ccedilla */ + { 576, 8, 5, 4, 0, -5 }, /* 0xC8 Egrave */ + { 581, 8, 5, 4, 0, -5 }, /* 0xC9 Eacute */ + { 586, 8, 5, 4, 0, -5 }, /* 0xCA Ecircumflex */ + { 591, 8, 5, 4, 0, -5 }, /* 0xCB Edieresis */ + { 596, 8, 5, 4, 0, -5 }, /* 0xCC Igrave */ + { 601, 8, 5, 4, 0, -5 }, /* 0xCD Iacute */ + { 606, 8, 5, 4, 0, -5 }, /* 0xCE Icircumflex */ + { 611, 8, 5, 4, 0, -5 }, /* 0xCF Idieresis */ + { 616, 8, 5, 4, 0, -5 }, /* 0xD0 Eth */ + { 621, 8, 5, 4, 0, -5 }, /* 0xD1 Ntilde */ + { 626, 8, 5, 4, 0, -5 }, /* 0xD2 Ograve */ + { 631, 8, 5, 4, 0, -5 }, /* 0xD3 Oacute */ + { 636, 8, 5, 4, 0, -5 }, /* 0xD4 Ocircumflex */ + { 641, 8, 5, 4, 0, -5 }, /* 0xD5 Otilde */ + { 646, 8, 5, 4, 0, -5 }, /* 0xD6 Odieresis */ + { 651, 8, 3, 4, 0, -4 }, /* 0xD7 multiply */ + { 654, 8, 5, 4, 0, -5 }, /* 0xD8 Oslash */ + { 659, 8, 5, 4, 0, -5 }, /* 0xD9 Ugrave */ + { 664, 8, 5, 4, 0, -5 }, /* 0xDA Uacute */ + { 669, 8, 5, 4, 0, -5 }, /* 0xDB Ucircumflex */ + { 674, 8, 5, 4, 0, -5 }, /* 0xDC Udieresis */ + { 679, 8, 5, 4, 0, -5 }, /* 0xDD Yacute */ + { 684, 8, 5, 4, 0, -5 }, /* 0xDE Thorn */ + { 689, 8, 6, 4, 0, -5 }, /* 0xDF germandbls */ + { 695, 8, 5, 4, 0, -5 }, /* 0xE0 agrave */ + { 700, 8, 5, 4, 0, -5 }, /* 0xE1 aacute */ + { 705, 8, 5, 4, 0, -5 }, /* 0xE2 acircumflex */ + { 710, 8, 5, 4, 0, -5 }, /* 0xE3 atilde */ + { 715, 8, 5, 4, 0, -5 }, /* 0xE4 adieresis */ + { 720, 8, 5, 4, 0, -5 }, /* 0xE5 aring */ + { 725, 8, 4, 4, 0, -4 }, /* 0xE6 ae */ + { 729, 8, 5, 4, 0, -4 }, /* 0xE7 ccedilla */ + { 734, 8, 5, 4, 0, -5 }, /* 0xE8 egrave */ + { 739, 8, 5, 4, 0, -5 }, /* 0xE9 eacute */ + { 744, 8, 5, 4, 0, -5 }, /* 0xEA ecircumflex */ + { 749, 8, 5, 4, 0, -5 }, /* 0xEB edieresis */ + { 754, 8, 5, 3, 0, -5 }, /* 0xEC igrave */ + { 759, 8, 5, 3, 0, -5 }, /* 0xED iacute */ + { 764, 8, 5, 4, 0, -5 }, /* 0xEE icircumflex */ + { 769, 8, 5, 4, 0, -5 }, /* 0xEF idieresis */ + { 774, 8, 5, 4, 0, -5 }, /* 0xF0 eth */ + { 779, 8, 5, 4, 0, -5 }, /* 0xF1 ntilde */ + { 784, 8, 5, 4, 0, -5 }, /* 0xF2 ograve */ + { 789, 8, 5, 4, 0, -5 }, /* 0xF3 oacute */ + { 794, 8, 5, 4, 0, -5 }, /* 0xF4 ocircumflex */ + { 799, 8, 5, 4, 0, -5 }, /* 0xF5 otilde */ + { 804, 8, 5, 4, 0, -5 }, /* 0xF6 odieresis */ + { 809, 8, 5, 4, 0, -5 }, /* 0xF7 divide */ + { 814, 8, 4, 4, 0, -4 }, /* 0xF8 oslash */ + { 818, 8, 5, 4, 0, -5 }, /* 0xF9 ugrave */ + { 823, 8, 5, 4, 0, -5 }, /* 0xFA uacute */ + { 828, 8, 5, 4, 0, -5 }, /* 0xFB ucircumflex */ + { 833, 8, 5, 4, 0, -5 }, /* 0xFC udieresis */ + { 838, 8, 6, 4, 0, -5 }, /* 0xFD yacute */ + { 844, 8, 5, 4, 0, -4 }, /* 0xFE thorn */ + { 849, 8, 6, 4, 0, -5 }, /* 0xFF ydieresis */ + { 855, 8, 1, 2, 0, -1 }, /* 0x11D gcircumflex */ + { 856, 8, 5, 4, 0, -5 }, /* 0x152 OE */ + { 861, 8, 4, 4, 0, -4 }, /* 0x153 oe */ + { 865, 8, 5, 4, 0, -5 }, /* 0x160 Scaron */ + { 870, 8, 5, 4, 0, -5 }, /* 0x161 scaron */ + { 875, 8, 5, 4, 0, -5 }, /* 0x178 Ydieresis */ + { 880, 8, 5, 4, 0, -5 }, /* 0x17D Zcaron */ + { 885, 8, 5, 4, 0, -5 }, /* 0x17E zcaron */ + { 890, 8, 1, 2, 0, -1 }, /* 0xEA4 uni0EA4 */ + { 891, 8, 1, 2, 0, -1 }, /* 0x13A0 uni13A0 */ + { 892, 8, 1, 2, 0, -3 }, /* 0x2022 bullet */ + { 893, 8, 1, 4, 0, -1 }, /* 0x2026 ellipsis */ + { 894, 8, 5, 4, 0, -5 }, /* 0x20AC Euro */ + { 899, 8, 5, 4, 0, -5 }, /* 0xFFFD uniFFFD */ +#endif /* (TOMTHUMB_USE_EXTENDED) */ +}; + +const GFXfont TomThumb PROGMEM = { + (uint8_t *)TomThumbBitmaps, + (GFXglyph *)TomThumbGlyphs, + 0x20, 0x7E, 6 }; diff --git a/libraries/Adafruit-GFX-Library-master/README.md b/libraries/Adafruit-GFX-Library-master/README.md new file mode 100644 index 0000000..972c966 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/README.md @@ -0,0 +1,21 @@ +# Adafruit GFX Library + +This is the core graphics library for all our displays, providing a common set of graphics primitives (points, lines, circles, etc.). It needs to be paired with a hardware-specific library for each display device we carry (to handle the lower-level functions). + +Adafruit invests time and resources providing this open source code, please support Adafruit and open-source hardware by purchasing products from Adafruit! + +Written by Limor Fried/Ladyada for Adafruit Industries. +BSD license, check license.txt for more information. +All text above must be included in any redistribution. + +Recent Arduino IDE releases include the Library Manager for easy installation. Otherwise, to download, click the DOWNLOAD ZIP button, uncompress and rename the uncompressed folder Adafruit_GFX. Confirm that the Adafruit_GFX folder contains Adafruit_GFX.cpp and Adafruit_GFX.h. Place the Adafruit_GFX library folder your /Libraries/ folder. You may need to create the Libraries subfolder if its your first library. Restart the IDE. + +# Useful Resources + +- Image2Code: This is a handy Java GUI utility to convert a BMP file into the array code necessary to display the image with the drawBitmap function. Check out the code at ehubin's GitHub repository: https://github.com/ehubin/Adafruit-GFX-Library/tree/master/Img2Code + +- drawXBitmap function: You can use the GIMP photo editor to save a .xbm file and use the array saved in the file to draw a bitmap with the drawXBitmap function. See the pull request here for more details: https://github.com/adafruit/Adafruit-GFX-Library/pull/31 + +- 'Fonts' folder contains bitmap fonts for use with recent (1.1 and later) Adafruit_GFX. To use a font in your Arduino sketch, #include the corresponding .h file and pass address of GFXfont struct to setFont(). Pass NULL to revert to 'classic' fixed-space bitmap font. + +- 'fontconvert' folder contains a command-line tool for converting TTF fonts to Adafruit_GFX .h format. diff --git a/libraries/Adafruit-GFX-Library-master/fontconvert/Makefile b/libraries/Adafruit-GFX-Library-master/fontconvert/Makefile new file mode 100644 index 0000000..47f5a0e --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/fontconvert/Makefile @@ -0,0 +1,12 @@ +all: fontconvert + +CC = gcc +CFLAGS = -Wall -I/usr/local/include/freetype2 -I/usr/include/freetype2 -I/usr/include +LIBS = -lfreetype + +fontconvert: fontconvert.c + $(CC) $(CFLAGS) $< $(LIBS) -o $@ + strip $@ + +clean: + rm -f fontconvert diff --git a/libraries/Adafruit-GFX-Library-master/fontconvert/fontconvert.c b/libraries/Adafruit-GFX-Library-master/fontconvert/fontconvert.c new file mode 100644 index 0000000..c6d6498 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/fontconvert/fontconvert.c @@ -0,0 +1,278 @@ +/* +TrueType to Adafruit_GFX font converter. Derived from Peter Jakobs' +Adafruit_ftGFX fork & makefont tool, and Paul Kourany's Adafruit_mfGFX. + +NOT AN ARDUINO SKETCH. This is a command-line tool for preprocessing +fonts to be used with the Adafruit_GFX Arduino library. + +For UNIX-like systems. Outputs to stdout; redirect to header file, e.g.: + ./fontconvert ~/Library/Fonts/FreeSans.ttf 18 > FreeSans18pt7b.h + +REQUIRES FREETYPE LIBRARY. www.freetype.org + +Currently this only extracts the printable 7-bit ASCII chars of a font. +Will eventually extend with some int'l chars a la ftGFX, not there yet. +Keep 7-bit fonts around as an option in that case, more compact. + +See notes at end for glyph nomenclature & other tidbits. +*/ + +#include +#include +#include +#include +#include FT_GLYPH_H +#include "../gfxfont.h" // Adafruit_GFX font structures + +#define DPI 141 // Approximate res. of Adafruit 2.8" TFT + +// Accumulate bits for output, with periodic hexadecimal byte write +void enbit(uint8_t value) { + static uint8_t row = 0, sum = 0, bit = 0x80, firstCall = 1; + if(value) sum |= bit; // Set bit if needed + if(!(bit >>= 1)) { // Advance to next bit, end of byte reached? + if(!firstCall) { // Format output table nicely + if(++row >= 12) { // Last entry on line? + printf(",\n "); // Newline format output + row = 0; // Reset row counter + } else { // Not end of line + printf(", "); // Simple comma delim + } + } + printf("0x%02X", sum); // Write byte value + sum = 0; // Clear for next byte + bit = 0x80; // Reset bit counter + firstCall = 0; // Formatting flag + } +} + +int main(int argc, char *argv[]) { + int i, j, err, size, first=' ', last='~', + bitmapOffset = 0, x, y, byte; + char *fontName, c, *ptr; + FT_Library library; + FT_Face face; + FT_Glyph glyph; + FT_Bitmap *bitmap; + FT_BitmapGlyphRec *g; + GFXglyph *table; + uint8_t bit; + + // Parse command line. Valid syntaxes are: + // fontconvert [filename] [size] + // fontconvert [filename] [size] [last char] + // fontconvert [filename] [size] [first char] [last char] + // Unless overridden, default first and last chars are + // ' ' (space) and '~', respectively + + if(argc < 3) { + fprintf(stderr, "Usage: %s fontfile size [first] [last]\n", + argv[0]); + return 1; + } + + size = atoi(argv[2]); + + if(argc == 4) { + last = atoi(argv[3]); + } else if(argc == 5) { + first = atoi(argv[3]); + last = atoi(argv[4]); + } + + if(last < first) { + i = first; + first = last; + last = i; + } + + ptr = strrchr(argv[1], '/'); // Find last slash in filename + if(ptr) ptr++; // First character of filename (path stripped) + else ptr = argv[1]; // No path; font in local dir. + + // Allocate space for font name and glyph table + if((!(fontName = malloc(strlen(ptr) + 20))) || + (!(table = (GFXglyph *)malloc((last - first + 1) * + sizeof(GFXglyph))))) { + fprintf(stderr, "Malloc error\n"); + return 1; + } + + // Derive font table names from filename. Period (filename + // extension) is truncated and replaced with the font size & bits. + strcpy(fontName, ptr); + ptr = strrchr(fontName, '.'); // Find last period (file ext) + if(!ptr) ptr = &fontName[strlen(fontName)]; // If none, append + // Insert font size and 7/8 bit. fontName was alloc'd w/extra + // space to allow this, we're not sprintfing into Forbidden Zone. + sprintf(ptr, "%dpt%db", size, (last > 127) ? 8 : 7); + // Space and punctuation chars in name replaced w/ underscores. + for(i=0; (c=fontName[i]); i++) { + if(isspace(c) || ispunct(c)) fontName[i] = '_'; + } + + // Init FreeType lib, load font + if((err = FT_Init_FreeType(&library))) { + fprintf(stderr, "FreeType init error: %d", err); + return err; + } + if((err = FT_New_Face(library, argv[1], 0, &face))) { + fprintf(stderr, "Font load error: %d", err); + FT_Done_FreeType(library); + return err; + } + + // << 6 because '26dot6' fixed-point format + FT_Set_Char_Size(face, size << 6, 0, DPI, 0); + + // Currently all symbols from 'first' to 'last' are processed. + // Fonts may contain WAY more glyphs than that, but this code + // will need to handle encoding stuff to deal with extracting + // the right symbols, and that's not done yet. + // fprintf(stderr, "%ld glyphs\n", face->num_glyphs); + + printf("const uint8_t %sBitmaps[] PROGMEM = {\n ", fontName); + + // Process glyphs and output huge bitmap data array + for(i=first, j=0; i<=last; i++, j++) { + // MONO renderer provides clean image with perfect crop + // (no wasted pixels) via bitmap struct. + if((err = FT_Load_Char(face, i, FT_LOAD_TARGET_MONO))) { + fprintf(stderr, "Error %d loading char '%c'\n", + err, i); + continue; + } + + if((err = FT_Render_Glyph(face->glyph, + FT_RENDER_MODE_MONO))) { + fprintf(stderr, "Error %d rendering char '%c'\n", + err, i); + continue; + } + + if((err = FT_Get_Glyph(face->glyph, &glyph))) { + fprintf(stderr, "Error %d getting glyph '%c'\n", + err, i); + continue; + } + + bitmap = &face->glyph->bitmap; + g = (FT_BitmapGlyphRec *)glyph; + + // Minimal font and per-glyph information is stored to + // reduce flash space requirements. Glyph bitmaps are + // fully bit-packed; no per-scanline pad, though end of + // each character may be padded to next byte boundary + // when needed. 16-bit offset means 64K max for bitmaps, + // code currently doesn't check for overflow. (Doesn't + // check that size & offsets are within bounds either for + // that matter...please convert fonts responsibly.) + table[j].bitmapOffset = bitmapOffset; + table[j].width = bitmap->width; + table[j].height = bitmap->rows; + table[j].xAdvance = face->glyph->advance.x >> 6; + table[j].xOffset = g->left; + table[j].yOffset = 1 - g->top; + + for(y=0; y < bitmap->rows; y++) { + for(x=0;x < bitmap->width; x++) { + byte = x / 8; + bit = 0x80 >> (x & 7); + enbit(bitmap->buffer[ + y * bitmap->pitch + byte] & bit); + } + } + + // Pad end of char bitmap to next byte boundary if needed + int n = (bitmap->width * bitmap->rows) & 7; + if(n) { // Pixel count not an even multiple of 8? + n = 8 - n; // # bits to next multiple + while(n--) enbit(0); + } + bitmapOffset += (bitmap->width * bitmap->rows + 7) / 8; + + FT_Done_Glyph(glyph); + } + + printf(" };\n\n"); // End bitmap array + + // Output glyph attributes table (one per character) + printf("const GFXglyph %sGlyphs[] PROGMEM = {\n", fontName); + for(i=first, j=0; i<=last; i++, j++) { + printf(" { %5d, %3d, %3d, %3d, %4d, %4d }", + table[j].bitmapOffset, + table[j].width, + table[j].height, + table[j].xAdvance, + table[j].xOffset, + table[j].yOffset); + if(i < last) { + printf(", // 0x%02X", i); + if((i >= ' ') && (i <= '~')) { + printf(" '%c'", i); + } + putchar('\n'); + } + } + printf(" }; // 0x%02X", last); + if((last >= ' ') && (last <= '~')) printf(" '%c'", last); + printf("\n\n"); + + // Output font structure + printf("const GFXfont %s PROGMEM = {\n", fontName); + printf(" (uint8_t *)%sBitmaps,\n", fontName); + printf(" (GFXglyph *)%sGlyphs,\n", fontName); + printf(" 0x%02X, 0x%02X, %ld };\n\n", + first, last, face->size->metrics.height >> 6); + printf("// Approx. %d bytes\n", + bitmapOffset + (last - first + 1) * 7 + 7); + // Size estimate is based on AVR struct and pointer sizes; + // actual size may vary. + + FT_Done_FreeType(library); + + return 0; +} + +/* ------------------------------------------------------------------------- + +Character metrics are slightly different from classic GFX & ftGFX. +In classic GFX: cursor position is the upper-left pixel of each 5x7 +character; lower extent of most glyphs (except those w/descenders) +is +6 pixels in Y direction. +W/new GFX fonts: cursor position is on baseline, where baseline is +'inclusive' (containing the bottom-most row of pixels in most symbols, +except those with descenders; ftGFX is one pixel lower). + +Cursor Y will be moved automatically when switching between classic +and new fonts. If you switch fonts, any print() calls will continue +along the same baseline. + + ...........#####.. -- yOffset + ..........######.. + ..........######.. + .........#######.. + ........#########. + * = Cursor pos. ........#########. + .......##########. + ......#####..####. + ......#####..####. + *.#.. .....#####...####. + .#.#. ....############## + #...# ...############### + #...# ...############### + ##### ..#####......##### + #...# .#####.......##### +====== #...# ====== #*###.........#### ======= Baseline + || xOffset + +glyph->xOffset and yOffset are pixel offsets, in GFX coordinate space +(+Y is down), from the cursor position to the top-left pixel of the +glyph bitmap. i.e. yOffset is typically negative, xOffset is typically +zero but a few glyphs will have other values (even negative xOffsets +sometimes, totally normal). glyph->xAdvance is the distance to move +the cursor on the X axis after drawing the corresponding symbol. + +There's also some changes with regard to 'background' color and new GFX +fonts (classic fonts unchanged). See Adafruit_GFX.cpp for explanation. +*/ diff --git a/libraries/Adafruit-GFX-Library-master/fontconvert/fontconvert_win.md b/libraries/Adafruit-GFX-Library-master/fontconvert/fontconvert_win.md new file mode 100644 index 0000000..361078b --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/fontconvert/fontconvert_win.md @@ -0,0 +1,88 @@ +### A short guide to use fontconvert.c to create your own fonts using MinGW. + +#### STEP 1: INSTALL MinGW + +Install MinGW (Minimalist GNU for Windows) from [MinGW.org](http://www.mingw.org/). +Please read carefully the instructions found on [Getting started page](http://www.mingw.org/wiki/Getting_Started). +I suggest installing with the "Graphical User Interface Installer". +To complete your initial installation you should further install some "packages". +For our purpose you should only install the "Basic Setup" packages. +To do that: + +1. Open the MinGW Installation Manager +2. From the left panel click "Basic Setup". +3. On the right panel choose "mingw32-base", "mingw-gcc-g++", "mingw-gcc-objc" and "msys-base" +and click "Mark for installation" +4. From the Menu click "Installation" and then "Apply changes". In the pop-up window select "Apply". + + +#### STEP 2: INSTALL Freetype Library + +To read about the freetype project visit [freetype.org](https://www.freetype.org/). +To Download the latest version of freetype go to [download page](http://download.savannah.gnu.org/releases/freetype/) +and choose "freetype-2.7.tar.gz" file (or a newer version if available). +To avoid long cd commands later in the command prompt, I suggest you unzip the file in the C:\ directory. +(I also renamed the folder to "ft27") +Before you build the library it's good to read these articles: +* [Using MSYS with MinGW](http://www.mingw.org/wiki/MSYS) +* [Installation and Use of Supplementary Libraries with MinGW](http://www.mingw.org/wiki/LibraryPathHOWTO) +* [Include Path](http://www.mingw.org/wiki/IncludePathHOWTO) + +Inside the unzipped folder there is another folder named "docs". Open it and read the INSTALL.UNIX (using notepad). +Pay attention to paragraph 3 (Build and Install the Library). So, let's begin the installation. +To give the appropriate commands we will use the MSYS command prompt (not cmd.exe of windows) which is UNIX like. +Follow the path C:\MinGW\msys\1.0 and double click "msys.bat". The command prompt environment appears. +Enter "ft27" directory using the cd commands: +``` +cd /c +cd ft27 +``` + +and then type one by one the commands: +``` +./configure --prefix=/mingw +make +make install +``` +Once you're finished, go inside "C:\MinGW\include" and there should be a new folder named "freetype2". +That, hopefully, means that you have installed the library correctly !! + +#### STEP 3: Build fontconvert.c + +Before proceeding I suggest you make a copy of Adafruit_GFX_library folder in C:\ directory. +Then, inside "fontconvert" folder open the "makefile" with an editor ( I used notepad++). +Change the commands so in the end the program looks like : +``` +all: fontconvert + +CC = gcc +CFLAGS = -Wall -I c:/mingw/include/freetype2 +LIBS = -lfreetype + +fontconvert: fontconvert.c + $(CC) $(CFLAGS) $< $(LIBS) -o $@ + +clean: + rm -f fontconvert +``` +Go back in the command prompt and with a cd command enter the fontconvert directory. +``` +cd /c/adafruit_gfx_library\fontconvert +``` +Give the command: +``` +make +``` +This command will, eventually, create a "fontconvert.exe" file inside fontconvert directory. + +#### STEP 4: Create your own font header files + +Now that you have an executable file, you can use it to create your own fonts to work with Adafruit GFX lib. +So, if we suppose that you already have a .ttf file with your favorite fonts, jump to the command prompt and type: +``` +./fontconvert yourfonts.ttf 9 > yourfonts9pt7b.h +``` +You can read more details at: [learn.adafruit](https://learn.adafruit.com/adafruit-gfx-graphics-library/using-fonts). + +Taraaaaaammm !! you've just created your new font header file. Put it inside the "Fonts" folder, grab a cup of coffee +and start playing with your Arduino (or whatever else ....)+ display module project. diff --git a/libraries/Adafruit-GFX-Library-master/fontconvert/makefonts.sh b/libraries/Adafruit-GFX-Library-master/fontconvert/makefonts.sh new file mode 100644 index 0000000..35f07ea --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/fontconvert/makefonts.sh @@ -0,0 +1,38 @@ +#!/bin/bash + +# Ugly little Bash script, generates a set of .h files for GFX using +# GNU FreeFont sources. There are three fonts: 'Mono' (Courier-like), +# 'Sans' (Helvetica-like) and 'Serif' (Times-like); four styles: regular, +# bold, oblique or italic, and bold+oblique or bold+italic; and four +# sizes: 9, 12, 18 and 24 point. No real error checking or anything, +# this just powers through all the combinations, calling the fontconvert +# utility and redirecting the output to a .h file for each combo. + +# Adafruit_GFX repository does not include the source outline fonts +# (huge zipfile, different license) but they're easily acquired: +# http://savannah.gnu.org/projects/freefont/ + +convert=./fontconvert +inpath=~/Desktop/freefont/ +outpath=../Fonts/ +fonts=(FreeMono FreeSans FreeSerif) +styles=("" Bold Italic BoldItalic Oblique BoldOblique) +sizes=(9 12 18 24) + +for f in ${fonts[*]} +do + for index in ${!styles[*]} + do + st=${styles[$index]} + for si in ${sizes[*]} + do + infile=$inpath$f$st".ttf" + if [ -f $infile ] # Does source combination exist? + then + outfile=$outpath$f$st$si"pt7b.h" +# printf "%s %s %s > %s\n" $convert $infile $si $outfile + $convert $infile $si > $outfile + fi + done + done +done diff --git a/libraries/Adafruit-GFX-Library-master/gfxfont.h b/libraries/Adafruit-GFX-Library-master/gfxfont.h new file mode 100644 index 0000000..07381ed --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/gfxfont.h @@ -0,0 +1,24 @@ +// Font structures for newer Adafruit_GFX (1.1 and later). +// Example fonts are included in 'Fonts' directory. +// To use a font in your Arduino sketch, #include the corresponding .h +// file and pass address of GFXfont struct to setFont(). Pass NULL to +// revert to 'classic' fixed-space bitmap font. + +#ifndef _GFXFONT_H_ +#define _GFXFONT_H_ + +typedef struct { // Data stored PER GLYPH + uint16_t bitmapOffset; // Pointer into GFXfont->bitmap + uint8_t width, height; // Bitmap dimensions in pixels + uint8_t xAdvance; // Distance to advance cursor (x axis) + int8_t xOffset, yOffset; // Dist from cursor pos to UL corner +} GFXglyph; + +typedef struct { // Data stored for FONT AS A WHOLE: + uint8_t *bitmap; // Glyph bitmaps, concatenated + GFXglyph *glyph; // Glyph array + uint8_t first, last; // ASCII extents + uint8_t yAdvance; // Newline distance (y axis) +} GFXfont; + +#endif // _GFXFONT_H_ diff --git a/libraries/Adafruit-GFX-Library-master/glcdfont.c b/libraries/Adafruit-GFX-Library-master/glcdfont.c new file mode 100644 index 0000000..6f88bd2 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/glcdfont.c @@ -0,0 +1,276 @@ +// This is the 'classic' fixed-space bitmap font for Adafruit_GFX since 1.0. +// See gfxfont.h for newer custom bitmap font info. + +#ifndef FONT5X7_H +#define FONT5X7_H + +#ifdef __AVR__ + #include + #include +#elif defined(ESP8266) + #include +#else + #define PROGMEM +#endif + +// Standard ASCII 5x7 font + +static const unsigned char font[] PROGMEM = { + 0x00, 0x00, 0x00, 0x00, 0x00, + 0x3E, 0x5B, 0x4F, 0x5B, 0x3E, + 0x3E, 0x6B, 0x4F, 0x6B, 0x3E, + 0x1C, 0x3E, 0x7C, 0x3E, 0x1C, + 0x18, 0x3C, 0x7E, 0x3C, 0x18, + 0x1C, 0x57, 0x7D, 0x57, 0x1C, + 0x1C, 0x5E, 0x7F, 0x5E, 0x1C, + 0x00, 0x18, 0x3C, 0x18, 0x00, + 0xFF, 0xE7, 0xC3, 0xE7, 0xFF, + 0x00, 0x18, 0x24, 0x18, 0x00, + 0xFF, 0xE7, 0xDB, 0xE7, 0xFF, + 0x30, 0x48, 0x3A, 0x06, 0x0E, + 0x26, 0x29, 0x79, 0x29, 0x26, + 0x40, 0x7F, 0x05, 0x05, 0x07, + 0x40, 0x7F, 0x05, 0x25, 0x3F, + 0x5A, 0x3C, 0xE7, 0x3C, 0x5A, + 0x7F, 0x3E, 0x1C, 0x1C, 0x08, + 0x08, 0x1C, 0x1C, 0x3E, 0x7F, + 0x14, 0x22, 0x7F, 0x22, 0x14, + 0x5F, 0x5F, 0x00, 0x5F, 0x5F, + 0x06, 0x09, 0x7F, 0x01, 0x7F, + 0x00, 0x66, 0x89, 0x95, 0x6A, + 0x60, 0x60, 0x60, 0x60, 0x60, + 0x94, 0xA2, 0xFF, 0xA2, 0x94, + 0x08, 0x04, 0x7E, 0x04, 0x08, + 0x10, 0x20, 0x7E, 0x20, 0x10, + 0x08, 0x08, 0x2A, 0x1C, 0x08, + 0x08, 0x1C, 0x2A, 0x08, 0x08, + 0x1E, 0x10, 0x10, 0x10, 0x10, + 0x0C, 0x1E, 0x0C, 0x1E, 0x0C, + 0x30, 0x38, 0x3E, 0x38, 0x30, + 0x06, 0x0E, 0x3E, 0x0E, 0x06, + 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x5F, 0x00, 0x00, + 0x00, 0x07, 0x00, 0x07, 0x00, + 0x14, 0x7F, 0x14, 0x7F, 0x14, + 0x24, 0x2A, 0x7F, 0x2A, 0x12, + 0x23, 0x13, 0x08, 0x64, 0x62, + 0x36, 0x49, 0x56, 0x20, 0x50, + 0x00, 0x08, 0x07, 0x03, 0x00, + 0x00, 0x1C, 0x22, 0x41, 0x00, + 0x00, 0x41, 0x22, 0x1C, 0x00, + 0x2A, 0x1C, 0x7F, 0x1C, 0x2A, + 0x08, 0x08, 0x3E, 0x08, 0x08, + 0x00, 0x80, 0x70, 0x30, 0x00, + 0x08, 0x08, 0x08, 0x08, 0x08, + 0x00, 0x00, 0x60, 0x60, 0x00, + 0x20, 0x10, 0x08, 0x04, 0x02, + 0x3E, 0x51, 0x49, 0x45, 0x3E, + 0x00, 0x42, 0x7F, 0x40, 0x00, + 0x72, 0x49, 0x49, 0x49, 0x46, + 0x21, 0x41, 0x49, 0x4D, 0x33, + 0x18, 0x14, 0x12, 0x7F, 0x10, + 0x27, 0x45, 0x45, 0x45, 0x39, + 0x3C, 0x4A, 0x49, 0x49, 0x31, + 0x41, 0x21, 0x11, 0x09, 0x07, + 0x36, 0x49, 0x49, 0x49, 0x36, + 0x46, 0x49, 0x49, 0x29, 0x1E, + 0x00, 0x00, 0x14, 0x00, 0x00, + 0x00, 0x40, 0x34, 0x00, 0x00, + 0x00, 0x08, 0x14, 0x22, 0x41, + 0x14, 0x14, 0x14, 0x14, 0x14, + 0x00, 0x41, 0x22, 0x14, 0x08, + 0x02, 0x01, 0x59, 0x09, 0x06, + 0x3E, 0x41, 0x5D, 0x59, 0x4E, + 0x7C, 0x12, 0x11, 0x12, 0x7C, + 0x7F, 0x49, 0x49, 0x49, 0x36, + 0x3E, 0x41, 0x41, 0x41, 0x22, + 0x7F, 0x41, 0x41, 0x41, 0x3E, + 0x7F, 0x49, 0x49, 0x49, 0x41, + 0x7F, 0x09, 0x09, 0x09, 0x01, + 0x3E, 0x41, 0x41, 0x51, 0x73, + 0x7F, 0x08, 0x08, 0x08, 0x7F, + 0x00, 0x41, 0x7F, 0x41, 0x00, + 0x20, 0x40, 0x41, 0x3F, 0x01, + 0x7F, 0x08, 0x14, 0x22, 0x41, + 0x7F, 0x40, 0x40, 0x40, 0x40, + 0x7F, 0x02, 0x1C, 0x02, 0x7F, + 0x7F, 0x04, 0x08, 0x10, 0x7F, + 0x3E, 0x41, 0x41, 0x41, 0x3E, + 0x7F, 0x09, 0x09, 0x09, 0x06, + 0x3E, 0x41, 0x51, 0x21, 0x5E, + 0x7F, 0x09, 0x19, 0x29, 0x46, + 0x26, 0x49, 0x49, 0x49, 0x32, + 0x03, 0x01, 0x7F, 0x01, 0x03, + 0x3F, 0x40, 0x40, 0x40, 0x3F, + 0x1F, 0x20, 0x40, 0x20, 0x1F, + 0x3F, 0x40, 0x38, 0x40, 0x3F, + 0x63, 0x14, 0x08, 0x14, 0x63, + 0x03, 0x04, 0x78, 0x04, 0x03, + 0x61, 0x59, 0x49, 0x4D, 0x43, + 0x00, 0x7F, 0x41, 0x41, 0x41, + 0x02, 0x04, 0x08, 0x10, 0x20, + 0x00, 0x41, 0x41, 0x41, 0x7F, + 0x04, 0x02, 0x01, 0x02, 0x04, + 0x40, 0x40, 0x40, 0x40, 0x40, + 0x00, 0x03, 0x07, 0x08, 0x00, + 0x20, 0x54, 0x54, 0x78, 0x40, + 0x7F, 0x28, 0x44, 0x44, 0x38, + 0x38, 0x44, 0x44, 0x44, 0x28, + 0x38, 0x44, 0x44, 0x28, 0x7F, + 0x38, 0x54, 0x54, 0x54, 0x18, + 0x00, 0x08, 0x7E, 0x09, 0x02, + 0x18, 0xA4, 0xA4, 0x9C, 0x78, + 0x7F, 0x08, 0x04, 0x04, 0x78, + 0x00, 0x44, 0x7D, 0x40, 0x00, + 0x20, 0x40, 0x40, 0x3D, 0x00, + 0x7F, 0x10, 0x28, 0x44, 0x00, + 0x00, 0x41, 0x7F, 0x40, 0x00, + 0x7C, 0x04, 0x78, 0x04, 0x78, + 0x7C, 0x08, 0x04, 0x04, 0x78, + 0x38, 0x44, 0x44, 0x44, 0x38, + 0xFC, 0x18, 0x24, 0x24, 0x18, + 0x18, 0x24, 0x24, 0x18, 0xFC, + 0x7C, 0x08, 0x04, 0x04, 0x08, + 0x48, 0x54, 0x54, 0x54, 0x24, + 0x04, 0x04, 0x3F, 0x44, 0x24, + 0x3C, 0x40, 0x40, 0x20, 0x7C, + 0x1C, 0x20, 0x40, 0x20, 0x1C, + 0x3C, 0x40, 0x30, 0x40, 0x3C, + 0x44, 0x28, 0x10, 0x28, 0x44, + 0x4C, 0x90, 0x90, 0x90, 0x7C, + 0x44, 0x64, 0x54, 0x4C, 0x44, + 0x00, 0x08, 0x36, 0x41, 0x00, + 0x00, 0x00, 0x77, 0x00, 0x00, + 0x00, 0x41, 0x36, 0x08, 0x00, + 0x02, 0x01, 0x02, 0x04, 0x02, + 0x3C, 0x26, 0x23, 0x26, 0x3C, + 0x1E, 0xA1, 0xA1, 0x61, 0x12, + 0x3A, 0x40, 0x40, 0x20, 0x7A, + 0x38, 0x54, 0x54, 0x55, 0x59, + 0x21, 0x55, 0x55, 0x79, 0x41, + 0x22, 0x54, 0x54, 0x78, 0x42, // a-umlaut + 0x21, 0x55, 0x54, 0x78, 0x40, + 0x20, 0x54, 0x55, 0x79, 0x40, + 0x0C, 0x1E, 0x52, 0x72, 0x12, + 0x39, 0x55, 0x55, 0x55, 0x59, + 0x39, 0x54, 0x54, 0x54, 0x59, + 0x39, 0x55, 0x54, 0x54, 0x58, + 0x00, 0x00, 0x45, 0x7C, 0x41, + 0x00, 0x02, 0x45, 0x7D, 0x42, + 0x00, 0x01, 0x45, 0x7C, 0x40, + 0x7D, 0x12, 0x11, 0x12, 0x7D, // A-umlaut + 0xF0, 0x28, 0x25, 0x28, 0xF0, + 0x7C, 0x54, 0x55, 0x45, 0x00, + 0x20, 0x54, 0x54, 0x7C, 0x54, + 0x7C, 0x0A, 0x09, 0x7F, 0x49, + 0x32, 0x49, 0x49, 0x49, 0x32, + 0x3A, 0x44, 0x44, 0x44, 0x3A, // o-umlaut + 0x32, 0x4A, 0x48, 0x48, 0x30, + 0x3A, 0x41, 0x41, 0x21, 0x7A, + 0x3A, 0x42, 0x40, 0x20, 0x78, + 0x00, 0x9D, 0xA0, 0xA0, 0x7D, + 0x3D, 0x42, 0x42, 0x42, 0x3D, // O-umlaut + 0x3D, 0x40, 0x40, 0x40, 0x3D, + 0x3C, 0x24, 0xFF, 0x24, 0x24, + 0x48, 0x7E, 0x49, 0x43, 0x66, + 0x2B, 0x2F, 0xFC, 0x2F, 0x2B, + 0xFF, 0x09, 0x29, 0xF6, 0x20, + 0xC0, 0x88, 0x7E, 0x09, 0x03, + 0x20, 0x54, 0x54, 0x79, 0x41, + 0x00, 0x00, 0x44, 0x7D, 0x41, + 0x30, 0x48, 0x48, 0x4A, 0x32, + 0x38, 0x40, 0x40, 0x22, 0x7A, + 0x00, 0x7A, 0x0A, 0x0A, 0x72, + 0x7D, 0x0D, 0x19, 0x31, 0x7D, + 0x26, 0x29, 0x29, 0x2F, 0x28, + 0x26, 0x29, 0x29, 0x29, 0x26, + 0x30, 0x48, 0x4D, 0x40, 0x20, + 0x38, 0x08, 0x08, 0x08, 0x08, + 0x08, 0x08, 0x08, 0x08, 0x38, + 0x2F, 0x10, 0xC8, 0xAC, 0xBA, + 0x2F, 0x10, 0x28, 0x34, 0xFA, + 0x00, 0x00, 0x7B, 0x00, 0x00, + 0x08, 0x14, 0x2A, 0x14, 0x22, + 0x22, 0x14, 0x2A, 0x14, 0x08, + 0x55, 0x00, 0x55, 0x00, 0x55, // #176 (25% block) missing in old code + 0xAA, 0x55, 0xAA, 0x55, 0xAA, // 50% block + 0xFF, 0x55, 0xFF, 0x55, 0xFF, // 75% block + 0x00, 0x00, 0x00, 0xFF, 0x00, + 0x10, 0x10, 0x10, 0xFF, 0x00, + 0x14, 0x14, 0x14, 0xFF, 0x00, + 0x10, 0x10, 0xFF, 0x00, 0xFF, + 0x10, 0x10, 0xF0, 0x10, 0xF0, + 0x14, 0x14, 0x14, 0xFC, 0x00, + 0x14, 0x14, 0xF7, 0x00, 0xFF, + 0x00, 0x00, 0xFF, 0x00, 0xFF, + 0x14, 0x14, 0xF4, 0x04, 0xFC, + 0x14, 0x14, 0x17, 0x10, 0x1F, + 0x10, 0x10, 0x1F, 0x10, 0x1F, + 0x14, 0x14, 0x14, 0x1F, 0x00, + 0x10, 0x10, 0x10, 0xF0, 0x00, + 0x00, 0x00, 0x00, 0x1F, 0x10, + 0x10, 0x10, 0x10, 0x1F, 0x10, + 0x10, 0x10, 0x10, 0xF0, 0x10, + 0x00, 0x00, 0x00, 0xFF, 0x10, + 0x10, 0x10, 0x10, 0x10, 0x10, + 0x10, 0x10, 0x10, 0xFF, 0x10, + 0x00, 0x00, 0x00, 0xFF, 0x14, + 0x00, 0x00, 0xFF, 0x00, 0xFF, + 0x00, 0x00, 0x1F, 0x10, 0x17, + 0x00, 0x00, 0xFC, 0x04, 0xF4, + 0x14, 0x14, 0x17, 0x10, 0x17, + 0x14, 0x14, 0xF4, 0x04, 0xF4, + 0x00, 0x00, 0xFF, 0x00, 0xF7, + 0x14, 0x14, 0x14, 0x14, 0x14, + 0x14, 0x14, 0xF7, 0x00, 0xF7, + 0x14, 0x14, 0x14, 0x17, 0x14, + 0x10, 0x10, 0x1F, 0x10, 0x1F, + 0x14, 0x14, 0x14, 0xF4, 0x14, + 0x10, 0x10, 0xF0, 0x10, 0xF0, + 0x00, 0x00, 0x1F, 0x10, 0x1F, + 0x00, 0x00, 0x00, 0x1F, 0x14, + 0x00, 0x00, 0x00, 0xFC, 0x14, + 0x00, 0x00, 0xF0, 0x10, 0xF0, + 0x10, 0x10, 0xFF, 0x10, 0xFF, + 0x14, 0x14, 0x14, 0xFF, 0x14, + 0x10, 0x10, 0x10, 0x1F, 0x00, + 0x00, 0x00, 0x00, 0xF0, 0x10, + 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, + 0xF0, 0xF0, 0xF0, 0xF0, 0xF0, + 0xFF, 0xFF, 0xFF, 0x00, 0x00, + 0x00, 0x00, 0x00, 0xFF, 0xFF, + 0x0F, 0x0F, 0x0F, 0x0F, 0x0F, + 0x38, 0x44, 0x44, 0x38, 0x44, + 0xFC, 0x4A, 0x4A, 0x4A, 0x34, // sharp-s or beta + 0x7E, 0x02, 0x02, 0x06, 0x06, + 0x02, 0x7E, 0x02, 0x7E, 0x02, + 0x63, 0x55, 0x49, 0x41, 0x63, + 0x38, 0x44, 0x44, 0x3C, 0x04, + 0x40, 0x7E, 0x20, 0x1E, 0x20, + 0x06, 0x02, 0x7E, 0x02, 0x02, + 0x99, 0xA5, 0xE7, 0xA5, 0x99, + 0x1C, 0x2A, 0x49, 0x2A, 0x1C, + 0x4C, 0x72, 0x01, 0x72, 0x4C, + 0x30, 0x4A, 0x4D, 0x4D, 0x30, + 0x30, 0x48, 0x78, 0x48, 0x30, + 0xBC, 0x62, 0x5A, 0x46, 0x3D, + 0x3E, 0x49, 0x49, 0x49, 0x00, + 0x7E, 0x01, 0x01, 0x01, 0x7E, + 0x2A, 0x2A, 0x2A, 0x2A, 0x2A, + 0x44, 0x44, 0x5F, 0x44, 0x44, + 0x40, 0x51, 0x4A, 0x44, 0x40, + 0x40, 0x44, 0x4A, 0x51, 0x40, + 0x00, 0x00, 0xFF, 0x01, 0x03, + 0xE0, 0x80, 0xFF, 0x00, 0x00, + 0x08, 0x08, 0x6B, 0x6B, 0x08, + 0x36, 0x12, 0x36, 0x24, 0x36, + 0x06, 0x0F, 0x09, 0x0F, 0x06, + 0x00, 0x00, 0x18, 0x18, 0x00, + 0x00, 0x00, 0x10, 0x10, 0x00, + 0x30, 0x40, 0xFF, 0x01, 0x01, + 0x00, 0x1F, 0x01, 0x01, 0x1E, + 0x00, 0x19, 0x1D, 0x17, 0x12, + 0x00, 0x3C, 0x3C, 0x3C, 0x3C, + 0x00, 0x00, 0x00, 0x00, 0x00 // #255 NBSP +}; +#endif // FONT5X7_H diff --git a/libraries/Adafruit-GFX-Library-master/library.properties b/libraries/Adafruit-GFX-Library-master/library.properties new file mode 100644 index 0000000..8a83286 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/library.properties @@ -0,0 +1,9 @@ +name=Adafruit GFX Library +version=1.1.5 +author=Adafruit +maintainer=Adafruit +sentence=Adafruit GFX graphics core library, this is the 'core' class that all our other graphics libraries derive from. +paragraph=Install this library in addition to the display library for your hardware. +category=Display +url=https://github.com/adafruit/Adafruit-GFX-Library +architectures=* diff --git a/libraries/Adafruit-GFX-Library-master/license.txt b/libraries/Adafruit-GFX-Library-master/license.txt new file mode 100644 index 0000000..7492e93 --- /dev/null +++ b/libraries/Adafruit-GFX-Library-master/license.txt @@ -0,0 +1,24 @@ +Software License Agreement (BSD License) + +Copyright (c) 2012 Adafruit Industries. All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +- Redistributions of source code must retain the above copyright notice, + this list of conditions and the following disclaimer. +- Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. diff --git a/libraries/BMA150/BMA150.cpp b/libraries/BMA150/BMA150.cpp new file mode 100644 index 0000000..99c2b77 --- /dev/null +++ b/libraries/BMA150/BMA150.cpp @@ -0,0 +1,550 @@ +// I2Cdev library collection - BMA150 I2C device class header file +// Based on BMA150 datasheet, 29/05/2008 +// 01/18/2012 by Brian McCain +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2012-01-18 - 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 "BMA150.h" + +/** Default constructor, uses default I2C address. + * @see BMA150_DEFAULT_ADDRESS + */ +BMA150::BMA150() { + devAddr = BMA150_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see BMA150_DEFAULT_ADDRESS + * @see BMA150_ADDRESS_00 + */ +BMA150::BMA150(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. This sets the full scale range of + * the sensor, as well as the bandwidth + */ +void BMA150::initialize() { + setRange(BMA150_RANGE_2G); + setBandwidth(BMA150_BW_25HZ); +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool BMA150::testConnection() { + return getDeviceID() == 0b010; +} + +// CHIP_ID register +/** Get Device ID. + * This register is used to verify the identity of the device (0b010). + * @return Device ID (should be 2 dec) + * @see BMA150_RA_CHIP_ID + */ +uint8_t BMA150::getDeviceID() { + I2Cdev::readByte(devAddr, BMA150_RA_CHIP_ID, buffer); + return buffer[0]; +} + + +// VERSION register +/** Get Chip Revision number + * @return Chip Revision + * @see BMA150_RA_VERSION + */ + uint8_t BMA150::getChipRevision() { + I2Cdev::readByte(devAddr, BMA150_RA_VERSION, buffer); + return buffer[0]; +} + +// AXIS registers +/** Get 3-axis accelerometer readings. + * @param x 16-bit signed integer container for X-axis acceleration + * @param y 16-bit signed integer container for Y-axis acceleration + * @param z 16-bit signed integer container for Z-axis acceleration + * @see BMA150_RA_Y_AXIS_LSB + */ + +void BMA150::getAcceleration(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, BMA150_RA_X_AXIS_LSB, 6, buffer); + *x = ((((int16_t)buffer[1]) << 8) | buffer[0]) >> 6; + *y = ((((int16_t)buffer[3]) << 8) | buffer[2]) >> 6; + *z = ((((int16_t)buffer[5]) << 8) | buffer[4]) >> 6; +} + +/** Get X-axis accelerometer reading. + * @return X-axis acceleration measurement in 16-bit 2's complement format + * @see BMA150_RA_X_AXIS_LSB + */ +int16_t BMA150::getAccelerationX() { + I2Cdev::readBytes(devAddr, BMA150_RA_X_AXIS_LSB, 2, buffer); + return ((((int16_t)buffer[1]) << 8) | buffer[0]) >> 6; +} + +/** Get Y-axis accelerometer reading. + * @return Y-axis acceleration measurement in 16-bit 2's complement format + * @see BMA150_RA_Y_AXIS_LSB + */ +int16_t BMA150::getAccelerationY() { + I2Cdev::readBytes(devAddr, BMA150_RA_Y_AXIS_LSB, 2, buffer); + return ((((int16_t)buffer[1]) << 8) | buffer[0]) >> 6; +} + +/** Get Z-axis accelerometer reading. + * @return Z-axis acceleration measurement in 16-bit 2's complement format + * @see BMA150_RA_Z_AXIS_LSB + */ +int16_t BMA150::getAccelerationZ() { + I2Cdev::readBytes(devAddr, BMA150_RA_Z_AXIS_LSB, 2, buffer); + return ((((int16_t)buffer[1]) << 8) | buffer[0]) >> 6; +} + +/** Check for new X axis acceleration data. + * @return New X-Axis Data Status + * @see BMA150_RA_X_AXIS_LSB + */ +bool BMA150::newDataX() { + I2Cdev::readBit(devAddr, BMA150_RA_X_AXIS_LSB, BMA150_X_NEW_DATA_BIT, buffer); + return buffer[0]; +} + +/** Check for new Y axis acceleration data. + * @return New Y-Axis Data Status + * @see BMA150_RA_Y_AXIS_LSB + */ +bool BMA150::newDataY() { + I2Cdev::readBit(devAddr, BMA150_RA_Y_AXIS_LSB, BMA150_Y_NEW_DATA_BIT, buffer); + return buffer[0]; +} + +/** Check for new Z axis acceleration data. + * @return New Z-Axis Data Status + * @see BMA150_RA_Z_AXIS_LSB + */ +bool BMA150::newDataZ() { + I2Cdev::readBit(devAddr, BMA150_RA_Z_AXIS_LSB, BMA150_Z_NEW_DATA_BIT, buffer); + return buffer[0]; +} + +// TEMP register +/** Check for current temperature + * @return Current Temperature in 0.5C increments from -30C at 00h + * @see BMA150_RA_TEMP_RD + */ +int8_t BMA150::getTemperature() { + I2Cdev::readByte(devAddr, BMA150_RA_TEMP_RD, buffer); + return buffer[0]; +} + +// SMB150 registers +bool BMA150::getStatusHG() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_STATUS, BMA150_STATUS_HG_BIT, buffer); + return buffer[0]; +} +void BMA150::setStatusHG(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_STATUS, BMA150_STATUS_HG_BIT, enabled); +} + +bool BMA150::getStatusLG() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_STATUS, BMA150_STATUS_LG_BIT, buffer); + return buffer[0]; +} +void BMA150::setStatusLG(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_STATUS, BMA150_STATUS_LG_BIT, enabled); +} + +bool BMA150::getHGLatched() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_STATUS, BMA150_HG_LATCHED_BIT, buffer); + return buffer[0]; +} +void BMA150::setHGLatched(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_STATUS, BMA150_HG_LATCHED_BIT, enabled); +} + +bool BMA150::getLGLatched() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_STATUS, BMA150_LG_LATCHED_BIT, buffer); + return buffer[0]; +} +void BMA150::setLGLatched(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_STATUS, BMA150_LG_LATCHED_BIT, enabled); +} + +bool BMA150::getAlertPhase() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_STATUS, BMA150_ALERT_PHASE_BIT, buffer); + return buffer[0]; +} +void BMA150::setAlertPhase(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_STATUS, BMA150_ALERT_PHASE_BIT, enabled); +} + +bool BMA150::getSTResult() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_STATUS, BMA150_ST_RESULT_BIT, buffer); + return buffer[0]; +} +void BMA150::setSTResult(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_STATUS, BMA150_ST_RESULT_BIT, enabled); +} + + + + + + +bool BMA150::getSleep() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_SLEEP_BIT, buffer); + return buffer[0]; +} +void BMA150::setSleep(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_SLEEP_BIT, enabled); +} + +bool BMA150::getSoftReset() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_SOFT_RESET_BIT, buffer); + return buffer[0]; +} +void BMA150::setSoftReset(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_SOFT_RESET_BIT, enabled); +} + +bool BMA150::getSelfTest0() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_ST0_BIT, buffer); + return buffer[0]; +} +void BMA150::setSelfTest0(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_ST0_BIT, enabled); +} + +bool BMA150::getSelfTest1() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_ST1_BIT, buffer); + return buffer[0]; +} +void BMA150::setSelfTest1(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_ST1_BIT, enabled); +} + +bool BMA150::getEEW() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_EEW_BIT, buffer); + return buffer[0]; +} +void BMA150::setEEW(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_EEW_BIT, enabled); +} + +bool BMA150::getUpdateImage() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_UPDATE_IMAGE_BIT, buffer); + return buffer[0]; +} +void BMA150::setUpdateImage(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_UPDATE_IMAGE_BIT, enabled); +} + +bool BMA150::getResetINT() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_RESET_INT_BIT, buffer); + return buffer[0]; +} +void BMA150::setResetINT(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CTRL, BMA150_RESET_INT_BIT, enabled); +} + + + + +bool BMA150::getEnableLG() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CONF1, BMA150_ENABLE_LG_BIT, buffer); + return buffer[0]; +} +void BMA150::setEnableLG(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CONF1, BMA150_ENABLE_LG_BIT, enabled); +} + +bool BMA150::getEnableHG() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CONF1, BMA150_ENABLE_HG_BIT, buffer); + return buffer[0]; +} +void BMA150::setEnableHG(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CONF1, BMA150_ENABLE_HG_BIT, enabled); +} + +int8_t BMA150::getCounterLG() { + I2Cdev::readBits(devAddr, BMA150_RA_SMB150_CONF1, BMA150_COUNTER_LG_BIT, BMA150_COUNTER_LG_LENGTH, buffer); + return buffer[0]; +} + +void BMA150::setCounterLG(int8_t counter_lg) { + I2Cdev::writeBits(devAddr, BMA150_RA_SMB150_CONF1, BMA150_COUNTER_LG_BIT, BMA150_COUNTER_LG_LENGTH, counter_lg); +} + +int8_t BMA150::getCounterHG() { + I2Cdev::readBits(devAddr, BMA150_RA_SMB150_CONF1, BMA150_COUNTER_HG_BIT, BMA150_COUNTER_HG_LENGTH, buffer); + return buffer[0]; +} + +void BMA150::setCounterHG(int8_t counter_hg) { + I2Cdev::writeBits(devAddr, BMA150_RA_SMB150_CONF1, BMA150_COUNTER_HG_BIT, BMA150_COUNTER_HG_LENGTH, counter_hg); +} + +bool BMA150::getAnyMotion() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CONF1, BMA150_ANY_MOTION_BIT, buffer); + return buffer[0]; +} +void BMA150::setAnyMotion(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CONF1, BMA150_ANY_MOTION_BIT, enabled); +} + +bool BMA150::getAlert() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CONF1, BMA150_ALERT_BIT, buffer); + return buffer[0]; +} +void BMA150::setAlert(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CONF1, BMA150_ALERT_BIT, enabled); +} + + + + + + +bool BMA150::getWakeUp() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CONF2, BMA150_WAKE_UP_BIT, buffer); + return buffer[0]; +} +void BMA150::setWakeUp(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CONF2, BMA150_WAKE_UP_BIT, enabled); +} + +int8_t BMA150::getWakeUpPause() { + I2Cdev::readBits(devAddr, BMA150_RA_SMB150_CONF1, BMA150_WAKE_UP_PAUSE_BIT, BMA150_WAKE_UP_PAUSE_LENGTH, buffer); + return buffer[0]; +} + +void BMA150::setWakeUpPause(int8_t wake_up_pause) { + I2Cdev::writeBits(devAddr, BMA150_RA_SMB150_CONF1, BMA150_WAKE_UP_PAUSE_BIT, BMA150_WAKE_UP_PAUSE_LENGTH, wake_up_pause); +} + +bool BMA150::getShadowDis() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CONF2, BMA150_SHADOW_DIS_BIT, buffer); + return buffer[0]; +} +void BMA150::setShadowDis(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CONF2, BMA150_SHADOW_DIS_BIT, enabled); +} + +bool BMA150::getLatchInt() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CONF2, BMA150_LATCH_INT_BIT, buffer); + return buffer[0]; +} +void BMA150::setLatchInt(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CONF2, BMA150_LATCH_INT_BIT, enabled); +} + +bool BMA150::getNewDataInt() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CONF2, BMA150_NEW_DATA_INT_BIT, buffer); + return buffer[0]; +} +void BMA150::setNewDataInt(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CONF2, BMA150_NEW_DATA_INT_BIT, enabled); +} + +bool BMA150::getEnableAdvInt() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CONF2, BMA150_ENABLE_ADV_INT_BIT, buffer); + return buffer[0]; +} +void BMA150::setEnableAdvInt(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CONF2, BMA150_ENABLE_ADV_INT_BIT, enabled); +} + +bool BMA150::getSPI4() { + I2Cdev::readBit(devAddr, BMA150_RA_SMB150_CONF2, BMA150_SPI4_BIT, buffer); + return buffer[0]; +} +void BMA150::setSPI4(bool enabled) { + I2Cdev::writeBit(devAddr, BMA150_RA_SMB150_CONF2, BMA150_SPI4_BIT, enabled); +} + + +// LG / HG registers +uint8_t BMA150::getLGThreshold() { + I2Cdev::readByte(devAddr, BMA150_RA_LG_THRESHOLD, buffer); + return buffer[0]; +} + +void BMA150::setLGThreshold(uint8_t lgthres) { + I2Cdev::writeByte(devAddr, BMA150_RA_LG_THRESHOLD, lgthres); +} + + +uint8_t BMA150::getLGDuration() { + I2Cdev::readByte(devAddr, BMA150_RA_LG_DURATION, buffer); + return buffer[0]; +} + +void BMA150::setLGDuration(uint8_t lgdur) { + I2Cdev::writeByte(devAddr, BMA150_RA_LG_DURATION, lgdur); +} + + +uint8_t BMA150::getHGThreshold() { + I2Cdev::readByte(devAddr, BMA150_RA_HG_THRESHOLD, buffer); + return buffer[0]; +} + +void BMA150::setHGThreshold(uint8_t hgthres) { + I2Cdev::writeByte(devAddr, BMA150_RA_HG_THRESHOLD, hgthres); +} + + +uint8_t BMA150::getHGDuration() { + I2Cdev::readByte(devAddr, BMA150_RA_HG_DURATION, buffer); + return buffer[0]; +} + +void BMA150::setHGDuration(uint8_t hgdur) { + I2Cdev::writeByte(devAddr, BMA150_RA_HG_DURATION, hgdur); +} + + +// MOTION_THRS register +uint8_t BMA150::getMotionThreshold() { + I2Cdev::readByte(devAddr, BMA150_RA_MOTION_THRS, buffer); + return buffer[0]; +} + +void BMA150::setMotionThreshold(uint8_t mot_thres) { + I2Cdev::writeByte(devAddr, BMA150_RA_MOTION_THRS, mot_thres); +} + +// HYSTERESIS register +uint8_t BMA150::getLGHysteresis() { + I2Cdev::readBits(devAddr, BMA150_RA_HYSTERESIS, BMA150_LG_HYST_BIT, BMA150_LG_HYST_LENGTH, buffer); + return buffer[0]; +} + +void BMA150::setLGHysteresis(uint8_t lg_hyst) { + I2Cdev::writeBits(devAddr, BMA150_RA_HYSTERESIS, BMA150_LG_HYST_BIT, BMA150_LG_HYST_LENGTH,lg_hyst); +} + +uint8_t BMA150::getHGHysteresis() { + I2Cdev::readBits(devAddr, BMA150_RA_HYSTERESIS, BMA150_HG_HYST_BIT, BMA150_HG_HYST_LENGTH, buffer); + return buffer[0]; +} + +void BMA150::setHGHysteresis(uint8_t hg_hyst) { + I2Cdev::writeBits(devAddr, BMA150_RA_HYSTERESIS, BMA150_HG_HYST_BIT, BMA150_HG_HYST_LENGTH,hg_hyst); +} + +uint8_t BMA150::getMotionDuration() { + I2Cdev::readBits(devAddr, BMA150_RA_HYSTERESIS, BMA150_ANY_MOTION_DUR_BIT, BMA150_ANY_MOTION_DUR_LENGTH, buffer); + return buffer[0]; +} + +void BMA150::setMotionDuration(uint8_t mot_dur) { + I2Cdev::writeBits(devAddr, BMA150_RA_HYSTERESIS, BMA150_ANY_MOTION_DUR_BIT, BMA150_ANY_MOTION_DUR_LENGTH, mot_dur); +} + + +// CUSTOMER registers +uint8_t BMA150::getCustom1() { + I2Cdev::readByte(devAddr, BMA150_RA_CUSTOMER1, buffer); + return buffer[0]; +} + +void BMA150::setCustom1(uint8_t custom1) { + I2Cdev::writeByte(devAddr, BMA150_RA_CUSTOMER1, custom1); +} + +uint8_t BMA150::getCustom2() { + I2Cdev::readByte(devAddr, BMA150_RA_CUSTOMER2, buffer); + return buffer[0]; +} + +void BMA150::setCustom2(uint8_t custom2) { + I2Cdev::writeByte(devAddr, BMA150_RA_CUSTOMER2, custom2); +} + +// RANGE / BANDWIDTH registers + +/** Get Sensor Full Range + * @return Current Sensor Full Scale Range + * 0 = +/- 2G + * 1 = +/- 4G + * 2 = +/- 8G + * @see BMA150_RA_RANGE_BWIDTH + * @see BMA150_RANGE_BIT + * @see BMA150_RANGE_LENGTH + */ +uint8_t BMA150::getRange() { + I2Cdev::readBits(devAddr, BMA150_RA_RANGE_BWIDTH, BMA150_RANGE_BIT, BMA150_RANGE_LENGTH, buffer); + return buffer[0]; +} + +/** Set Sensor Full Range + * @param range New full-scale range value + * @see getRange() + * @see BMA150_RA_RANGE_BWIDTH + * @see BMA150_RANGE_BIT + * @see BMA150_RANGE_LENGTH + */ +void BMA150::setRange(uint8_t range) { + I2Cdev::writeBits(devAddr, BMA150_RA_RANGE_BWIDTH, BMA150_RANGE_BIT, BMA150_RANGE_LENGTH, range); +} + + +/** Get digital filter bandwidth. + * The bandwidth parameter is used to setup the digital filtering of ADC output data to obtain + * the desired bandwidth. + * @return Current Sensor Bandwidth + * 0 = 25Hz + * 1 = 50Hz + * 2 = 100Hz + * 3 = 190Hz + * 4 = 375Hz + * 5 = 750Hz + * 6 = 1500Hz + * @see BMA150_RA_RANGE_BWIDTH + * @see BMA150_RANGE_BIT + * @see BMA150_RANGE_LENGTH + */ +uint8_t BMA150::getBandwidth() { + I2Cdev::readBits(devAddr, BMA150_RA_RANGE_BWIDTH, BMA150_RANGE_BIT, BMA150_RANGE_LENGTH, buffer); + return buffer[0]; +} + +/** Set Sensor Full Range + * @param bandwidth New bandwidth value + * @see getBandwidth() + * @see BMA150_RA_RANGE_BWIDTH + * @see BMA150_RANGE_BIT + * @see BMA150_RANGE_LENGTH + */ +void BMA150::setBandwidth(uint8_t bandwidth) { + I2Cdev::writeBits(devAddr, BMA150_RA_RANGE_BWIDTH, BMA150_BANDWIDTH_BIT, BMA150_BANDWIDTH_LENGTH, bandwidth); +} \ No newline at end of file diff --git a/libraries/BMA150/BMA150.h b/libraries/BMA150/BMA150.h new file mode 100644 index 0000000..56ecd5f --- /dev/null +++ b/libraries/BMA150/BMA150.h @@ -0,0 +1,280 @@ +// I2Cdev library collection - BMA150 I2C device class header file +// Based on BMA150 datasheet, 29/05/2008 +// 01/18/2012 by Brian McCain +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2012-01-18 - 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 _BMA150_H_ +#define _BMA150_H_ + +#include "I2Cdev.h" + +#define BMA150_ADDRESS_00 0xA1 // Default Address +#define BMA150_ADDRESS_01 0x38 // Used on the Atmel ATAVRSBIN1 +#define BMA150_DEFAULT_ADDRESS BMA150_ADDRESS_01 + +#define BMA150_RA_CHIP_ID 0x00 +#define BMA150_RA_VERSION 0x01 +#define BMA150_RA_X_AXIS_LSB 0x02 +#define BMA150_RA_X_AXIS_MSB 0x03 +#define BMA150_RA_Y_AXIS_LSB 0x04 +#define BMA150_RA_Y_AXIS_MSB 0x05 +#define BMA150_RA_Z_AXIS_LSB 0x06 +#define BMA150_RA_Z_AXIS_MSB 0x07 +#define BMA150_RA_TEMP_RD 0x08 +#define BMA150_RA_SMB150_STATUS 0x09 +#define BMA150_RA_SMB150_CTRL 0x0a +#define BMA150_RA_SMB150_CONF1 0x0b +#define BMA150_RA_LG_THRESHOLD 0x0c +#define BMA150_RA_LG_DURATION 0x0d +#define BMA150_RA_HG_THRESHOLD 0x0e +#define BMA150_RA_HG_DURATION 0x0f +#define BMA150_RA_MOTION_THRS 0x10 +#define BMA150_RA_HYSTERESIS 0x11 +#define BMA150_RA_CUSTOMER1 0x12 +#define BMA150_RA_CUSTOMER2 0x13 +#define BMA150_RA_RANGE_BWIDTH 0x14 +#define BMA150_RA_SMB150_CONF2 0x15 +#define BMA150_RA_OFFS_GAIN_X 0x16 +#define BMA150_RA_OFFS_GAIN_Y 0x17 +#define BMA150_RA_OFFS_GAIN_Z 0x18 +#define BMA150_RA_OFFS_GAIN_T 0x19 +#define BMA150_RA_OFFSET_X 0x1a +#define BMA150_RA_OFFSET_Y 0x1b +#define BMA150_RA_OFFSET_Z 0x1c +#define BMA150_RA_OFFSET_T 0x1d + +#define BMA150_CHIP_ID_BIT 2 +#define BMA150_CHIP_ID_LENGTH 3 + +#define BMA150_X_AXIS_LSB_BIT 7 +#define BMA150_X_AXIS_LSB_LENGTH 2 +#define BMA150_X_NEW_DATA_BIT 0 + +#define BMA150_Y_AXIS_LSB_BIT 7 +#define BMA150_Y_AXIS_LSB_LENGTH 2 +#define BMA150_Y_NEW_DATA_BIT 0 + +#define BMA150_Z_AXIS_LSB_BIT 7 +#define BMA150_Z_AXIS_LSB_LENGTH 2 +#define BMA150_Z_NEW_DATA_BIT 0 + +#define BMA150_STATUS_HG_BIT 0 +#define BMA150_STATUS_LG_BIT 1 +#define BMA150_HG_LATCHED_BIT 2 +#define BMA150_LG_LATCHED_BIT 3 +#define BMA150_ALERT_PHASE_BIT 4 +#define BMA150_ST_RESULT_BIT 7 + +#define BMA150_SLEEP_BIT 0 +#define BMA150_SOFT_RESET_BIT 1 +#define BMA150_ST0_BIT 2 +#define BMA150_ST1_BIT 3 +#define BMA150_EEW_BIT 4 +#define BMA150_UPDATE_IMAGE_BIT 5 +#define BMA150_RESET_INT_BIT 6 + +#define BMA150_ENABLE_LG_BIT 0 +#define BMA150_ENABLE_HG_BIT 1 +#define BMA150_COUNTER_LG_BIT 3 +#define BMA150_COUNTER_LG_LENGTH 2 +#define BMA150_COUNTER_HG_BIT 5 +#define BMA150_COUNTER_HG_LENGTH 2 +#define BMA150_ANY_MOTION_BIT 6 +#define BMA150_ALERT_BIT 7 + +#define BMA150_LG_HYST_BIT 2 +#define BMA150_LG_HYST_LENGTH 3 +#define BMA150_HG_HYST_BIT 5 +#define BMA150_HG_HYST_LENGTH 3 +#define BMA150_ANY_MOTION_DUR_BIT 7 +#define BMA150_ANY_MOTION_DUR_LENGTH 2 + +#define BMA150_BANDWIDTH_BIT 2 +#define BMA150_BANDWIDTH_LENGTH 3 +#define BMA150_RANGE_BIT 4 +#define BMA150_RANGE_LENGTH 2 + +#define BMA150_WAKE_UP_BIT 0 +#define BMA150_WAKE_UP_PAUSE_BIT 2 +#define BMA150_WAKE_UP_PAUSE_LENGTH 2 +#define BMA150_SHADOW_DIS_BIT 3 +#define BMA150_LATCH_INT_BIT 4 +#define BMA150_NEW_DATA_INT_BIT 5 +#define BMA150_ENABLE_ADV_INT_BIT 6 +#define BMA150_SPI4_BIT 7 + +/* range and bandwidth */ +#define BMA150_RANGE_2G 0 +#define BMA150_RANGE_4G 1 +#define BMA150_RANGE_8G 2 + +#define BMA150_BW_25HZ 0 +#define BMA150_BW_50HZ 1 +#define BMA150_BW_100HZ 2 +#define BMA150_BW_190HZ 3 +#define BMA150_BW_375HZ 4 +#define BMA150_BW_750HZ 5 +#define BMA150_BW_1500HZ 6 + +/* mode settings */ +#define BMA150_MODE_NORMAL 0 +#define BMA150_MODE_SLEEP 1 + +class BMA150 { + public: + BMA150(); + BMA150(uint8_t address); + + void initialize(); + bool testConnection(); + + // CHIP_ID register + uint8_t getDeviceID(); + + // VERSION register + uint8_t getChipRevision(); + + // AXIS registers + void getAcceleration(int16_t* x, int16_t* y, int16_t* z); + int16_t getAccelerationX(); + int16_t getAccelerationY(); + int16_t getAccelerationZ(); + bool newDataX(); + bool newDataY(); + bool newDataZ(); + + // TEMP register + int8_t getTemperature(); + + // SMB150 registers + bool getStatusHG(); + bool getStatusLG(); + bool getHGLatched(); + bool getLGLatched(); + bool getAlertPhase(); + bool getSTResult(); + void setStatusHG(bool status_hg); + void setStatusLG(bool status_lg); + void setHGLatched(bool hg_latched); + void setLGLatched(bool lg_latched); + void setAlertPhase(bool alert_phase); + void setSTResult(bool st_result); + + bool getSleep(); + bool getSoftReset(); + bool getSelfTest0(); + bool getSelfTest1(); + bool getEEW(); + bool getUpdateImage(); + bool getResetINT(); + void setSleep(bool sleep); + void setSoftReset(bool soft_reset); + void setSelfTest0(bool st0); + void setSelfTest1(bool st1); + void setEEW(bool eew); + void setUpdateImage(bool update_image); + void setResetINT(bool reset_int); + + bool getEnableLG(); + bool getEnableHG(); + int8_t getCounterLG(); + int8_t getCounterHG(); + bool getAnyMotion(); + bool getAlert(); + void setEnableLG(bool enable_lg); + void setEnableHG(bool enable_hg); + void setCounterLG(int8_t counter_lg); + void setCounterHG(int8_t counter_hg); + void setAnyMotion(bool any_motion); + void setAlert(bool alert); + + bool getWakeUp(); + int8_t getWakeUpPause(); + bool getShadowDis(); + bool getLatchInt(); + bool getNewDataInt(); + bool getEnableAdvInt(); + bool getSPI4(); + void setWakeUp(bool wake_up); + void setWakeUpPause(int8_t wake_up_pause); + void setShadowDis(bool shadow_dis); + void setLatchInt(bool latch_int); + void setNewDataInt(bool new_data_int); + void setEnableAdvInt(bool enable_adv_int); + void setSPI4(bool spi4); + + // LG / HG registers + uint8_t getLGThreshold(); + void setLGThreshold(uint8_t lgthres); + + uint8_t getLGDuration(); + void setLGDuration(uint8_t lgdur); + + uint8_t getHGThreshold(); + void setHGThreshold(uint8_t hgthres); + + uint8_t getHGDuration(); + void setHGDuration(uint8_t hgdur); + + // MOTION_THRS register + uint8_t getMotionThreshold(); + void setMotionThreshold(uint8_t mot_thres); + + // HYSTERESIS register + uint8_t getLGHysteresis(); + void setLGHysteresis(uint8_t lg_hys); + uint8_t getHGHysteresis(); + void setHGHysteresis(uint8_t hg_hys); + uint8_t getMotionDuration(); + void setMotionDuration(uint8_t mot_dur); + + // CUSTOMER registers + uint8_t getCustom1(); + void setCustom1(uint8_t custom1); + uint8_t getCustom2(); + void setCustom2(uint8_t custom2); + + // RANGE / BANDWIDTH registers + uint8_t getRange(); + void setRange(uint8_t range); + uint8_t getBandwidth(); + void setBandwidth(uint8_t bandwidth); + + // OFFS_GAIN registers + + // OFFSET registers + + private: + uint8_t devAddr; + uint8_t buffer[6]; + uint8_t mode; +}; + +#endif /* _BMA150_H_ */ \ No newline at end of file diff --git a/libraries/BMA150/examples/BMA150_raw/BMA150_raw.ino b/libraries/BMA150/examples/BMA150_raw/BMA150_raw.ino new file mode 100644 index 0000000..23fb931 --- /dev/null +++ b/libraries/BMA150/examples/BMA150_raw/BMA150_raw.ino @@ -0,0 +1,84 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for BMA150 class +// 18/01/2012 by Brian McCain +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2012-01-18 - 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 BMA150 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 "BMA150.h" + +// class default I2C address is 0x38 + +BMA150 accel; + +int16_t ax, ay, az; + +#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..."); + accel.initialize(); + + // verify connection + Serial.println("Testing device connections..."); + Serial.println(accel.testConnection() ? "BMA150 connection successful" : "BMA150 connection failed"); + + // configure Arduino LED for + pinMode(LED_PIN, OUTPUT); +} + +void loop() { + // read raw gyro 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); +} diff --git a/libraries/BMA150/library.json b/libraries/BMA150/library.json new file mode 100644 index 0000000..bd28c41 --- /dev/null +++ b/libraries/BMA150/library.json @@ -0,0 +1,18 @@ +{ + "name": "I2Cdevlib-BMA150", + "keywords": "accelerometer, sensor, i2cdevlib, i2c", + "description": "The BMA150 is a triaxial, low-g acceleration sensor IC with digital output for consumer market applications", + "include": "Arduino/BMA150", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "dependencies": + { + "name": "I2Cdevlib-Core", + "frameworks": "arduino" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/BMP085/BMP085.cpp b/libraries/BMP085/BMP085.cpp new file mode 100644 index 0000000..2119ae1 --- /dev/null +++ b/libraries/BMP085/BMP085.cpp @@ -0,0 +1,272 @@ +// I2Cdev library collection - BMP085 I2C device class +// Based on register information stored in the I2Cdevlib internal database +// 2012-06-28 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2012-06-28 - initial release, dynamically built + +/* ============================================ +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. +=============================================== +*/ + +#include "BMP085.h" + +/** + * Default constructor, uses default I2C device address. + * @see BMP085_DEFAULT_ADDRESS + */ +BMP085::BMP085() { + devAddr = BMP085_DEFAULT_ADDRESS; +} + +/** + * Specific address constructor. + * @param address Specific device address + * @see BMP085_DEFAULT_ADDRESS + */ +BMP085::BMP085(uint8_t address) { + devAddr = address; +} + +/** + * Prepare device for normal usage. + */ +void BMP085::initialize() { + // load sensor's calibration constants + loadCalibration(); +} + +/** + * Verify the device is connected and available. + */ +bool BMP085::testConnection() { + // test for a response, though this is very basic + return I2Cdev::readByte(devAddr, BMP085_RA_AC1_H, buffer) == 1; +} + +/* calibration register methods */ + +void BMP085::loadCalibration() { + uint8_t buf2[22]; + I2Cdev::readBytes(devAddr, BMP085_RA_AC1_H, 22, buf2); + ac1 = ((int16_t)buf2[0] << 8) + buf2[1]; + ac2 = ((int16_t)buf2[2] << 8) + buf2[3]; + ac3 = ((int16_t)buf2[4] << 8) + buf2[5]; + ac4 = ((uint16_t)buf2[6] << 8) + buf2[7]; + ac5 = ((uint16_t)buf2[8] << 8) + buf2[9]; + ac6 = ((uint16_t)buf2[10] << 8) + buf2[11]; + b1 = ((int16_t)buf2[12] << 8) + buf2[13]; + b2 = ((int16_t)buf2[14] << 8) + buf2[15]; + mb = ((int16_t)buf2[16] << 8) + buf2[17]; + mc = ((int16_t)buf2[18] << 8) + buf2[19]; + md = ((int16_t)buf2[20] << 8) + buf2[21]; + calibrationLoaded = true; +} + +#ifdef BMP085_INCLUDE_INDIVIDUAL_CALIBRATION_ACCESS + int16_t BMP085::getAC1() { + if (calibrationLoaded) return ac1; + I2Cdev::readBytes(devAddr, BMP085_RA_AC1_H, 2, buffer); + return ((int16_t)buffer[1] << 8) + buffer[0]; + } + + int16_t BMP085::getAC2() { + if (calibrationLoaded) return ac2; + I2Cdev::readBytes(devAddr, BMP085_RA_AC2_H, 2, buffer); + return ((int16_t)buffer[1] << 8) + buffer[0]; + } + + int16_t BMP085::getAC3() { + if (calibrationLoaded) return ac3; + I2Cdev::readBytes(devAddr, BMP085_RA_AC3_H, 2, buffer); + return ((int16_t)buffer[1] << 8) + buffer[0]; + } + + uint16_t BMP085::getAC4() { + if (calibrationLoaded) return ac4; + I2Cdev::readBytes(devAddr, BMP085_RA_AC4_H, 2, buffer); + return ((uint16_t)buffer[1] << 8) + buffer[0]; + } + + uint16_t BMP085::getAC5() { + if (calibrationLoaded) return ac5; + I2Cdev::readBytes(devAddr, BMP085_RA_AC5_H, 2, buffer); + return ((uint16_t)buffer[1] << 8) + buffer[0]; + } + + uint16_t BMP085::getAC6() { + if (calibrationLoaded) return ac6; + I2Cdev::readBytes(devAddr, BMP085_RA_AC6_H, 2, buffer); + return ((uint16_t)buffer[1] << 8) + buffer[0]; + } + + int16_t BMP085::getB1() { + if (calibrationLoaded) return b1; + I2Cdev::readBytes(devAddr, BMP085_RA_B1_H, 2, buffer); + return ((int16_t)buffer[1] << 8) + buffer[0]; + } + + int16_t BMP085::getB2() { + if (calibrationLoaded) return b2; + I2Cdev::readBytes(devAddr, BMP085_RA_B2_H, 2, buffer); + return ((int16_t)buffer[1] << 8) + buffer[0]; + } + + int16_t BMP085::getMB() { + if (calibrationLoaded) return mb; + I2Cdev::readBytes(devAddr, BMP085_RA_MB_H, 2, buffer); + return ((int16_t)buffer[1] << 8) + buffer[0]; + } + + int16_t BMP085::getMC() { + if (calibrationLoaded) return mc; + I2Cdev::readBytes(devAddr, BMP085_RA_MC_H, 2, buffer); + return ((int16_t)buffer[1] << 8) + buffer[0]; + } + + int16_t BMP085::getMD() { + if (calibrationLoaded) return md; + I2Cdev::readBytes(devAddr, BMP085_RA_MD_H, 2, buffer); + return ((int16_t)buffer[1] << 8) + buffer[0]; + } +#endif + +/* control register methods */ + +uint8_t BMP085::getControl() { + I2Cdev::readByte(devAddr, BMP085_RA_CONTROL, buffer); + return buffer[0]; +} +void BMP085::setControl(uint8_t value) { + I2Cdev::writeByte(devAddr, BMP085_RA_CONTROL, value); + measureMode = value; +} + +/* measurement register methods */ + +uint16_t BMP085::getMeasurement2() { + I2Cdev::readBytes(devAddr, BMP085_RA_MSB, 2, buffer); + return ((uint16_t)buffer[0] << 8) + buffer[1]; +} +uint32_t BMP085::getMeasurement3() { + I2Cdev::readBytes(devAddr, BMP085_RA_MSB, 3, buffer); + return ((uint32_t)buffer[0] << 16) + ((uint16_t)buffer[1] << 8) + buffer[2]; +} +uint8_t BMP085::getMeasureDelayMilliseconds(uint8_t mode) { + if (mode == 0) mode = measureMode; + if (measureMode == 0x2E) return 5; + else if (measureMode == 0x34) return 5; + else if (measureMode == 0x74) return 8; + else if (measureMode == 0xB4) return 14; + else if (measureMode == 0xF4) return 26; + return 0; // invalid mode +} +uint16_t BMP085::getMeasureDelayMicroseconds(uint8_t mode) { + if (mode == 0) mode = measureMode; + if (measureMode == 0x2E) return 4500; + else if (measureMode == 0x34) return 4500; + else if (measureMode == 0x74) return 7500; + else if (measureMode == 0xB4) return 13500; + else if (measureMode == 0xF4) return 25500; + return 0; // invalid mode +} + +uint16_t BMP085::getRawTemperature() { + if (measureMode == 0x2E) return getMeasurement2(); + return 0; // wrong measurement mode for temperature request +} + +float BMP085::getTemperatureC() { + /* + Datasheet formula: + UT = raw temperature + X1 = (UT - AC6) * AC5 / 2^15 + X2 = MC * 2^11 / (X1 + MD) + B5 = X1 + X2 + T = (B5 + 8) / 2^4 + */ + int32_t ut = getRawTemperature(); + int32_t x1 = ((ut - (int32_t)ac6) * (int32_t)ac5) >> 15; + int32_t x2 = ((int32_t)mc << 11) / (x1 + md); + b5 = x1 + x2; + return (float)((b5 + 8) >> 4) / 10.0f; +} + +float BMP085::getTemperatureF() { + return getTemperatureC() * 9.0f / 5.0f + 32; +} + +uint32_t BMP085::getRawPressure() { + if (measureMode & 0x34) return getMeasurement3() >> (8 - ((measureMode & 0xC0) >> 6)); + return 0; // wrong measurement mode for pressure request +} + +float BMP085::getPressure() { + /* + Datasheet forumla + UP = raw pressure + B6 = B5 - 4000 + X1 = (B2 * (B6 * B6 / 2^12)) / 2^11 + X2 = AC2 * B6 / 2^11 + X3 = X1 + X2 + B3 = ((AC1 * 4 + X3) << oss + 2) / 4 + X1 = AC3 * B6 / 2^13 + X2 = (B1 * (B6 * B6 / 2^12)) / 2^16 + X3 = ((X1 + X2) + 2) / 2^2 + B4 = AC4 * (unsigned long)(X3 + 32768) / 2^15 + B7 = ((unsigned long)UP - B3) * (50000 >> oss) + if (B7 < 0x80000000) { p = (B7 * 2) / B4 } + else { p = (B7 / B4) * 2 } + X1 = (p / 2^8) * (p / 2^8) + X1 = (X1 * 3038) / 2^16 + X2 = (-7357 * p) / 2^16 + p = p + (X1 + X2 + 3791) / 2^4 + */ + uint32_t up = getRawPressure(); + uint8_t oss = (measureMode & 0xC0) >> 6; + int32_t p; + int32_t b6 = b5 - 4000; + int32_t x1 = ((int32_t)b2 * ((b6 * b6) >> 12)) >> 11; + int32_t x2 = ((int32_t)ac2 * b6) >> 11; + int32_t x3 = x1 + x2; + int32_t b3 = ((((int32_t)ac1 * 4 + x3) << oss) + 2) >> 2; + x1 = ((int32_t)ac3 * b6) >> 13; + x2 = ((int32_t)b1 * ((b6 * b6) >> 12)) >> 16; + x3 = ((x1 + x2) + 2) >> 2; + uint32_t b4 = ((uint32_t)ac4 * (uint32_t)(x3 + 32768)) >> 15; + uint32_t b7 = ((uint32_t)up - b3) * (uint32_t)(50000UL >> oss); + if (b7 < 0x80000000) { + p = (b7 << 1) / b4; + } else { + p = (b7 / b4) << 1; + } + x1 = (p >> 8) * (p >> 8); + x1 = (x1 * 3038) >> 16; + x2 = (-7357 * p) >> 16; + return p + ((x1 + x2 + (int32_t)3791) >> 4); +} + +float BMP085::getAltitude(float pressure, float seaLevelPressure) { + return 44330 * (1.0 - pow(pressure / seaLevelPressure, 0.1903)); +} \ No newline at end of file diff --git a/libraries/BMP085/BMP085.h b/libraries/BMP085/BMP085.h new file mode 100644 index 0000000..58f6224 --- /dev/null +++ b/libraries/BMP085/BMP085.h @@ -0,0 +1,128 @@ +// I2Cdev library collection - BMP085 I2C device class +// Based on register information stored in the I2Cdevlib internal database +// 2012-06-28 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2012-06-28 - initial release, dynamically built + +/* ============================================ +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. +=============================================== +*/ + +#ifndef _BMP085_H_ +#define _BMP085_H_ + +#include "I2Cdev.h" +#include + +#define BMP085_ADDRESS 0x77 +#define BMP085_DEFAULT_ADDRESS BMP085_ADDRESS + +#define BMP085_RA_AC1_H 0xAA /* AC1_H */ +#define BMP085_RA_AC1_L 0xAB /* AC1_L */ +#define BMP085_RA_AC2_H 0xAC /* AC2_H */ +#define BMP085_RA_AC2_L 0xAD /* AC2_L */ +#define BMP085_RA_AC3_H 0xAE /* AC3_H */ +#define BMP085_RA_AC3_L 0xAF /* AC3_L */ +#define BMP085_RA_AC4_H 0xB0 /* AC4_H */ +#define BMP085_RA_AC4_L 0xB1 /* AC4_L */ +#define BMP085_RA_AC5_H 0xB2 /* AC5_H */ +#define BMP085_RA_AC5_L 0xB3 /* AC5_L */ +#define BMP085_RA_AC6_H 0xB4 /* AC6_H */ +#define BMP085_RA_AC6_L 0xB5 /* AC6_L */ +#define BMP085_RA_B1_H 0xB6 /* B1_H */ +#define BMP085_RA_B1_L 0xB7 /* B1_L */ +#define BMP085_RA_B2_H 0xB8 /* B2_H */ +#define BMP085_RA_B2_L 0xB9 /* B2_L */ +#define BMP085_RA_MB_H 0xBA /* MB_H */ +#define BMP085_RA_MB_L 0xBB /* MB_L */ +#define BMP085_RA_MC_H 0xBC /* MC_H */ +#define BMP085_RA_MC_L 0xBD /* MC_L */ +#define BMP085_RA_MD_H 0xBE /* MD_H */ +#define BMP085_RA_MD_L 0xBF /* MD_L */ +#define BMP085_RA_CONTROL 0xF4 /* CONTROL */ +#define BMP085_RA_MSB 0xF6 /* MSB */ +#define BMP085_RA_LSB 0xF7 /* LSB */ +#define BMP085_RA_XLSB 0xF8 /* XLSB */ + +#define BMP085_MODE_TEMPERATURE 0x2E +#define BMP085_MODE_PRESSURE_0 0x34 +#define BMP085_MODE_PRESSURE_1 0x74 +#define BMP085_MODE_PRESSURE_2 0xB4 +#define BMP085_MODE_PRESSURE_3 0xF4 + +class BMP085 { + public: + BMP085(); + BMP085(uint8_t address); + + void initialize(); + bool testConnection(); + +#ifdef BMP085_INCLUDE_INDIVIDUAL_CALIBRATION_ACCESS + /* calibration register methods */ + int16_t getAC1(); + int16_t getAC2(); + int16_t getAC3(); + uint16_t getAC4(); + uint16_t getAC5(); + uint16_t getAC6(); + int16_t getB1(); + int16_t getB2(); + int16_t getMB(); + int16_t getMC(); + int16_t getMD(); +#endif + + /* CONTROL register methods */ + uint8_t getControl(); + void setControl(uint8_t value); + + /* MEASURE register methods */ + uint16_t getMeasurement2(); // 16-bit data + uint32_t getMeasurement3(); // 24-bit data + uint8_t getMeasureDelayMilliseconds(uint8_t mode=0); + uint16_t getMeasureDelayMicroseconds(uint8_t mode=0); + + // convenience methods + void loadCalibration(); + uint16_t getRawTemperature(); + float getTemperatureC(); + float getTemperatureF(); + uint32_t getRawPressure(); + float getPressure(); + float getAltitude(float pressure, float seaLevelPressure=101325); + + private: + uint8_t devAddr; + uint8_t buffer[3]; + + bool calibrationLoaded; + int16_t ac1, ac2, ac3, b1, b2, mb, mc, md; + uint16_t ac4, ac5, ac6; + int32_t b5; + uint8_t measureMode; +}; + +#endif /* _BMP085_H_ */ diff --git a/libraries/BMP085/examples/BMP085_basic/BMP085_basic.ino b/libraries/BMP085/examples/BMP085_basic/BMP085_basic.ino new file mode 100644 index 0000000..0e9633e --- /dev/null +++ b/libraries/BMP085/examples/BMP085_basic/BMP085_basic.ino @@ -0,0 +1,112 @@ +// I2Cdev library collection - BMP085 basic Arduino example sketch +// Based on register information stored in the I2Cdevlib internal database +// 2012-06-28 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2012-06-28 - initial release, dynamically built + +/* ============================================ +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 and BMP085 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 "BMP085.h" + +// class default I2C address is 0x77 +// specific I2C addresses may be passed as a parameter here +// (though the BMP085 supports only one address) +BMP085 barometer; + +float temperature; +float pressure; +float altitude; +int32_t lastMicros; + +#define LED_PIN 13 // (Arduino is 13, Teensy is 11, 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..."); + barometer.initialize(); + + // verify connection + Serial.println("Testing device connections..."); + Serial.println(barometer.testConnection() ? "BMP085 connection successful" : "BMP085 connection failed"); + + // configure LED pin for activity indication + pinMode(LED_PIN, OUTPUT); +} + +void loop() { + // request temperature + barometer.setControl(BMP085_MODE_TEMPERATURE); + + // wait appropriate time for conversion (4.5ms delay) + lastMicros = micros(); + while (micros() - lastMicros < barometer.getMeasureDelayMicroseconds()); + + // read calibrated temperature value in degrees Celsius + temperature = barometer.getTemperatureC(); + + // request pressure (3x oversampling mode, high detail, 23.5ms delay) + barometer.setControl(BMP085_MODE_PRESSURE_3); + while (micros() - lastMicros < barometer.getMeasureDelayMicroseconds()); + + // read calibrated pressure value in Pascals (Pa) + pressure = barometer.getPressure(); + + // calculate absolute altitude in meters based on known pressure + // (may pass a second "sea level pressure" parameter here, + // otherwise uses the standard value of 101325 Pa) + altitude = barometer.getAltitude(pressure); + + // display measured values if appropriate + Serial.print("T/P/A\t"); + Serial.print(temperature); Serial.print("\t"); + Serial.print(pressure); Serial.print("\t"); + Serial.print(altitude); + Serial.println(""); + + // blink LED to indicate activity + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); + + // delay 100 msec to allow visually parsing blink and any serial output + delay(100); +} \ No newline at end of file diff --git a/libraries/BMP085/library.json b/libraries/BMP085/library.json new file mode 100644 index 0000000..a29ef25 --- /dev/null +++ b/libraries/BMP085/library.json @@ -0,0 +1,18 @@ +{ + "name": "I2Cdevlib-BMP085", + "keywords": "altimeter, altitude, barometer, pressure, temperature, sensor, i2cdevlib, i2c", + "description": "The BMP085 is barometric pressure, temperature and altitude sensor", + "include": "Arduino/BMP085", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "dependencies": + { + "name": "I2Cdevlib-Core", + "frameworks": "arduino" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/CalLib/CalLib.cpp b/libraries/CalLib/CalLib.cpp new file mode 100644 index 0000000..4bd76d2 --- /dev/null +++ b/libraries/CalLib/CalLib.cpp @@ -0,0 +1,93 @@ +//////////////////////////////////////////////////////////////////////////// +// +// This file is part of MPU9150Lib +// +// Copyright (c) 2013 Pansenti, LLC +// +// 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 "CalLib.h" +#ifdef __SAM3X8E__ + +// Due version + +#include "DueFlash.h" + +DueFlash flash; + +void calLibErase(byte device) +{ + uint32_t data = 0; + + flash.write(CALLIB_START + sizeof(CALLIB_DATA) * device, &data, 1); // just destroy the valid byte +} + +void calLibWrite(byte device, CALLIB_DATA *calData) +{ + calData->valid = CALLIB_DATA_VALID; + + flash.write(CALLIB_START + sizeof(CALLIB_DATA) * device, (uint32_t *)calData, sizeof(CALLIB_DATA) / 4); +} + +boolean calLibRead(byte device, CALLIB_DATA *calData) +{ + memcpy(calData, CALLIB_START + sizeof(CALLIB_DATA) * device, sizeof(CALLIB_DATA)); + return calData->valid == CALLIB_DATA_VALID; +} + +#else + +// AVR version + +#include + +void calLibErase(byte device) +{ + EEPROM.write(sizeof(CALLIB_DATA) * device, 0); // just destroy the valid byte +} + +void calLibWrite(byte device, CALLIB_DATA *calData) +{ + byte *ptr = (byte *)calData; + byte length = sizeof(CALLIB_DATA); + int eeprom = sizeof(CALLIB_DATA) * device; + + calData->valid = CALLIB_DATA_VALID; + + for (byte i = 0; i < length; i++) + EEPROM.write(eeprom + i, *ptr++); +} + +boolean calLibRead(byte device, CALLIB_DATA *calData) +{ + byte *ptr = (byte *)calData; + byte length = sizeof(CALLIB_DATA); + int eeprom = sizeof(CALLIB_DATA) * device; + + calData->magValid = false; + calData->accelValid = false; + + if ((EEPROM.read(eeprom) != CALLIB_DATA_VALID_LOW) || + (EEPROM.read(eeprom + 1) != CALLIB_DATA_VALID_HIGH)) + return false; // invalid data + + for (byte i = 0; i < length; i++) + *ptr++ = EEPROM.read(eeprom + i); + return true; +} +#endif diff --git a/libraries/CalLib/CalLib.h b/libraries/CalLib/CalLib.h new file mode 100644 index 0000000..ce46eeb --- /dev/null +++ b/libraries/CalLib/CalLib.h @@ -0,0 +1,69 @@ +//////////////////////////////////////////////////////////////////////////// +// +// This file is part of MPU9150Lib +// +// Copyright (c) 2013 Pansenti, LLC +// +// 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 _CALLIB_H_ +#define _CALLIB_H_ + +#include + +#define CALLIB_DATA_VALID 0x15fc +#define CALLIB_DATA_VALID_LOW 0xfc // pattern to detect valid config - low byte +#define CALLIB_DATA_VALID_HIGH 0x15 // pattern to detect valid config - high byte + +#ifdef __SAM3X8E__ +#define CALLIB_START ((uint32_t *)(IFLASH1_ADDR + IFLASH1_SIZE - IFLASH1_PAGE_SIZE)) +#endif + +typedef struct +{ + short valid; // should contain the valid pattern if a good config + short magValid; // true if mag data valid + short magMinX; // mag min x value + short magMaxX; // mag max x value + short magMinY; // mag min y value + short magMaxY; // mag max y value + short magMinZ; // mag min z value + short magMaxZ; // mag max z value + short accelValid; // true if accel data valid + short accelMinX; // mag min x value + short accelMaxX; // mag max x value + short accelMinY; // mag min y value + short accelMaxY; // mag max y value + short accelMinZ; // mag min z value + short accelMaxZ; // mag max z value + short unused; // must be multiple of 32 bits for Due +} CALLIB_DATA; + +// calLibErase() erases any current data in the EEPROM + +void calLibErase(byte device); + +// calLibWrite() writes new data to the EEPROM + +void calLibWrite(byte device, CALLIB_DATA * calData); + +// calLibRead() reads existing data and returns true if valid else false in not. + +boolean calLibRead(byte device, CALLIB_DATA * calData); + +#endif // _CALLIB_H_ diff --git a/libraries/DS1307/DS1307.cpp b/libraries/DS1307/DS1307.cpp new file mode 100644 index 0000000..1d01761 --- /dev/null +++ b/libraries/DS1307/DS1307.cpp @@ -0,0 +1,468 @@ +// I2Cdev library collection - DS1307 I2C device class +// Based on Maxim DS1307 datasheet, 2008 +// 11/13/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// I2C Device Library hosted at http://www.i2cdevlib.com +// +// Changelog: +// 2011-11-13 - initial release +// 2012-03-29 - alain.spineux@gmail.com: bug in getHours24() +// am/pm is bit 0x20 instead of 0x80 +// + +/* ============================================ +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 "DS1307.h" + +/** Default constructor, uses default I2C address. + * @see DS1307_DEFAULT_ADDRESS + */ +DS1307::DS1307() { + devAddr = DS1307_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see DS1307_DEFAULT_ADDRESS + * @see DS1307_ADDRESS + */ +DS1307::DS1307(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * This method reads the current 12/24-hour mode setting into the locally stored + * variable so that it isn't accidentally changed by the setHour*() methods. + */ +void DS1307::initialize() { + getMode(); // automatically sets internal "mode12" member variable + getClockRunning(); // automatically sets internal "clockHalt" member variable +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool DS1307::testConnection() { + if (I2Cdev::readByte(devAddr, DS1307_RA_SECONDS, buffer) == 1) { + return true; + } + return false; +} + +// SECONDS register +bool DS1307::getClockRunning() { + I2Cdev::readBit(devAddr, DS1307_RA_SECONDS, DS1307_SECONDS_CH_BIT, buffer); + clockHalt = buffer[0]; + return !buffer[0]; +} +void DS1307::setClockRunning(bool running) { + I2Cdev::writeBit(devAddr, DS1307_RA_SECONDS, DS1307_SECONDS_CH_BIT, !running); +} +uint8_t DS1307::getSeconds() { + // Byte: [7 = CH] [6:4 = 10SEC] [3:0 = 1SEC] + I2Cdev::readByte(devAddr, DS1307_RA_SECONDS, buffer); + clockHalt = buffer[0] & 0x80; + return (buffer[0] & 0x0F) + ((buffer[0] & 0x70) >> 4) * 10; +} +void DS1307::setSeconds(uint8_t seconds) { + if (seconds > 59) return; + uint8_t value = (clockHalt ? 0x80 : 0x00) + ((seconds / 10) << 4) + (seconds % 10); + I2Cdev::writeByte(devAddr, DS1307_RA_SECONDS, value); +} + +// MINUTES register +uint8_t DS1307::getMinutes() { + // Byte: [7 = 0] [6:4 = 10MIN] [3:0 = 1MIN] + I2Cdev::readByte(devAddr, DS1307_RA_MINUTES, buffer); + return (buffer[0] & 0x0F) + ((buffer[0] & 0x70) >> 4) * 10; +} +void DS1307::setMinutes(uint8_t minutes) { + if (minutes > 59) return; + uint8_t value = ((minutes / 10) << 4) + (minutes % 10); + I2Cdev::writeByte(devAddr, DS1307_RA_MINUTES, value); +} + +// HOURS register +uint8_t DS1307::getMode() { + I2Cdev::readBit(devAddr, DS1307_RA_HOURS, DS1307_HOURS_MODE_BIT, buffer); + mode12 = buffer[0]; + return buffer[0]; +} +void DS1307::setMode(uint8_t mode) { + I2Cdev::writeBit(devAddr, DS1307_RA_HOURS, DS1307_HOURS_MODE_BIT, mode); +} +uint8_t DS1307::getAMPM() { + I2Cdev::readBit(devAddr, DS1307_RA_HOURS, DS1307_HOURS_AMPM_BIT, buffer); + return buffer[0]; +} +void DS1307::setAMPM(uint8_t ampm) { + I2Cdev::writeBit(devAddr, DS1307_RA_HOURS, DS1307_HOURS_AMPM_BIT, ampm); +} +uint8_t DS1307::getHours12() { + I2Cdev::readByte(devAddr, DS1307_RA_HOURS, buffer); + mode12 = buffer[0] & 0x40; + if (mode12) { + // bit 6 is high, 12-hour mode + // Byte: [5 = AM/PM] [4 = 10HR] [3:0 = 1HR] + return (buffer[0] & 0x0F) + ((buffer[0] & 0x10) >> 4) * 10; + } else { + // bit 6 is low, 24-hour mode (default) + // Byte: [5:4 = 10HR] [3:0 = 1HR] + uint8_t hours = (buffer[0] & 0x0F) + ((buffer[0] & 0x30) >> 4) * 10; + + // convert 24-hour to 12-hour format, since that's what's requested + if (hours > 12) hours -= 12; + else if (hours == 0) hours = 12; + return hours; + } +} +void DS1307::setHours12(uint8_t hours, uint8_t ampm) { + if (hours > 12 || hours < 1) return; + if (mode12) { + // bit 6 is high, 12-hour mode + // Byte: [5 = AM/PM] [4 = 10HR] [3:0 = 1HR] + if (ampm > 0) ampm = 0x20; + uint8_t value = 0x40 + ampm + ((hours / 10) << 4) + (hours % 10); + I2Cdev::writeByte(devAddr, DS1307_RA_HOURS, value); + } else { + // bit 6 is low, 24-hour mode (default) + // Byte: [5:4 = 10HR] [3:0 = 1HR] + if (ampm > 0) hours += 12; + if (hours == 0) hours = 12; // 12 AM + else if (hours == 24) hours = 12; // 12 PM, after +12 adjustment + uint8_t value = ((hours / 10) << 4) + (hours % 10); + I2Cdev::writeByte(devAddr, DS1307_RA_HOURS, value); + } +} +uint8_t DS1307::getHours24() { + I2Cdev::readByte(devAddr, DS1307_RA_HOURS, buffer); + mode12 = buffer[0] & 0x40; + if (mode12) { + // bit 6 is high, 12-hour mode + // Byte: [5 = AM/PM] [4 = 10HR] [3:0 = 1HR] + uint8_t hours = (buffer[0] & 0x0F) + ((buffer[0] & 0x10) >> 4) * 10; + + // convert 12-hour to 24-hour format, since that's what's requested + if (buffer[0] & 0x20) { + // currently PM + if (hours < 12) hours += 12; + } else { + // currently AM + if (hours == 12) hours = 0; + } + return hours; + } else { + // bit 6 is low, 24-hour mode (default) + // Byte: [5:4 = 10HR] [3:0 = 1HR] + return (buffer[0] & 0x0F) + ((buffer[0] & 0x30) >> 4) * 10; + } +} +void DS1307::setHours24(uint8_t hours) { + if (hours > 23) return; + if (mode12) { + // bit 6 is high, 12-hour mode + // Byte: [5 = AM/PM] [4 = 10HR] [3:0 = 1HR] + uint8_t ampm = 0; + if (hours > 11) ampm = 0x20; + if (hours > 12) hours -= 12; + else if (hours == 0) hours = 12; + uint8_t value = 0x40 + ampm + ((hours / 10) << 4) + (hours % 10); + I2Cdev::writeByte(devAddr, DS1307_RA_HOURS, value); + } else { + // bit 6 is low, 24-hour mode (default) + // Byte: [5:4 = 10HR] [3:0 = 1HR] + uint8_t value = ((hours / 10) << 4) + (hours % 10); + I2Cdev::writeByte(devAddr, DS1307_RA_HOURS, value); + } +} + +// DAY register +uint8_t DS1307::getDayOfWeek() { + I2Cdev::readBits(devAddr, DS1307_RA_DAY, DS1307_DAY_BIT, DS1307_DAY_LENGTH, buffer); + return buffer[0]; +} +void DS1307::setDayOfWeek(uint8_t dow) { + if (dow < 1 || dow > 7) return; + I2Cdev::writeBits(devAddr, DS1307_RA_DAY, DS1307_DAY_BIT, DS1307_DAY_LENGTH, dow); +} + +// DATE register +uint8_t DS1307::getDay() { + // Byte: [7:6 = 0] [5:4 = 10DAY] [3:0 = 1DAY] + I2Cdev::readByte(devAddr, DS1307_RA_DATE, buffer); + return (buffer[0] & 0x0F) + ((buffer[0] & 0x30) >> 4) * 10; +} +void DS1307::setDay(uint8_t day) { + uint8_t value = ((day / 10) << 4) + (day % 10); + I2Cdev::writeByte(devAddr, DS1307_RA_DATE, value); +} + +// MONTH register +uint8_t DS1307::getMonth() { + // Byte: [7:5 = 0] [4 = 10MONTH] [3:0 = 1MONTH] + I2Cdev::readByte(devAddr, DS1307_RA_MONTH, buffer); + return (buffer[0] & 0x0F) + ((buffer[0] & 0x10) >> 4) * 10; +} +void DS1307::setMonth(uint8_t month) { + if (month < 1 || month > 12) return; + uint8_t value = ((month / 10) << 4) + (month % 10); + I2Cdev::writeByte(devAddr, DS1307_RA_MONTH, value); +} + +// YEAR register +uint16_t DS1307::getYear() { + I2Cdev::readByte(devAddr, DS1307_RA_YEAR, buffer); + return 2000 + (buffer[0] & 0x0F) + ((buffer[0] & 0xF0) >> 4) * 10; +} +void DS1307::setYear(uint16_t year) { + if (year < 2000) return; + year -= 2000; + uint8_t value = ((year / 10) << 4) + (year % 10); + I2Cdev::writeByte(devAddr, DS1307_RA_YEAR, value); +} + +// CONTROL register +bool DS1307::getFixedOutputLevel() { + I2Cdev::readBit(devAddr, DS1307_RA_CONTROL, DS1307_CONTROL_OUT_BIT, buffer); + return buffer[0]; +} +void DS1307::setFixedOutputLevel(bool level) { + I2Cdev::writeBit(devAddr, DS1307_RA_CONTROL, DS1307_CONTROL_OUT_BIT, level); +} +bool DS1307::getSquareWaveEnabled() { + I2Cdev::readBit(devAddr, DS1307_RA_CONTROL, DS1307_CONTROL_SQWE_BIT, buffer); + return buffer[0]; +} +void DS1307::setSquareWaveEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, DS1307_RA_CONTROL, DS1307_CONTROL_SQWE_BIT, enabled); +} +uint8_t DS1307::getSquareWaveRate() { + I2Cdev::readBits(devAddr, DS1307_RA_CONTROL, DS1307_CONTROL_RS_BIT, DS1307_CONTROL_RS_LENGTH, buffer); + return buffer[0]; +} +void DS1307::setSquareWaveRate(uint8_t rate) { + I2Cdev::writeBits(devAddr, DS1307_RA_CONTROL, DS1307_CONTROL_RS_BIT, DS1307_CONTROL_RS_LENGTH, rate); +} + +// RAM registers +uint8_t DS1307::getMemoryByte(uint8_t offset) { + if (offset > 55) return 0; + I2Cdev::readByte(devAddr, DS1307_RA_RAM + offset, buffer); + return buffer[0]; +} +void DS1307::setMemoryByte(uint8_t offset, uint8_t value) { + if (offset > 55) return; + I2Cdev::writeByte(devAddr, DS1307_RA_RAM + offset, value); +} + +// convenience methods + +void DS1307::getDate(uint16_t *year, uint8_t *month, uint8_t *day) { + *year = getYear(); + *month = getMonth(); + *day = getDay(); +} +void DS1307::setDate(uint16_t year, uint8_t month, uint8_t day) { + setYear(year); + setMonth(month); + setDay(day); +} + +void DS1307::getTime12(uint8_t *hours, uint8_t *minutes, uint8_t *seconds, uint8_t *ampm) { + *hours = getHours12(); + *minutes = getMinutes(); + *seconds = getSeconds(); + *ampm = getAMPM(); +} +void DS1307::setTime12(uint8_t hours, uint8_t minutes, uint8_t seconds, uint8_t ampm) { + // write seconds first to reset divider chain and give + // us 1 second to write remaining time info + setSeconds(seconds); + setMinutes(minutes); + setHours12(hours, ampm); +} + +void DS1307::getTime24(uint8_t *hours, uint8_t *minutes, uint8_t *seconds) { + *hours = getHours24(); + *minutes = getMinutes(); + *seconds = getSeconds(); +} +void DS1307::setTime24(uint8_t hours, uint8_t minutes, uint8_t seconds) { + // write seconds first to reset divider chain and give + // us 1 second to write remaining time info + setSeconds(seconds); + setMinutes(minutes); + setHours24(hours); +} + +void DS1307::getDateTime12(uint16_t *year, uint8_t *month, uint8_t *day, uint8_t *hours, uint8_t *minutes, uint8_t *seconds, uint8_t *ampm) { + getTime12(hours, minutes, seconds, ampm); + getDate(year, month, day); +} +void DS1307::setDateTime12(uint16_t year, uint8_t month, uint8_t day, uint8_t hours, uint8_t minutes, uint8_t seconds, uint8_t ampm) { + setTime12(hours, minutes, seconds, ampm); + setDate(year, month, day); +} + +void DS1307::getDateTime24(uint16_t *year, uint8_t *month, uint8_t *day, uint8_t *hours, uint8_t *minutes, uint8_t *seconds) { + getTime24(hours, minutes, seconds); + getDate(year, month, day); +} +void DS1307::setDateTime24(uint16_t year, uint8_t month, uint8_t day, uint8_t hours, uint8_t minutes, uint8_t seconds) { + setTime24(hours, minutes, seconds); + setDate(year, month, day); +} + +#ifdef DS1307_INCLUDE_DATETIME_METHODS + DateTime DS1307::getDateTime() { + DateTime dt = DateTime(getYear(), getMonth(), getDay(), getHours24(), getMinutes(), getSeconds()); + return dt; + } + void DS1307::setDateTime(DateTime dt) { + setSeconds(dt.second()); + setMinutes(dt.minute()); + setHours24(dt.hour()); + setDay(dt.day()); + setMonth(dt.month()); + setYear(dt.year()); + } +#endif + +#ifdef DS1307_INCLUDE_DATETIME_CLASS + // DateTime class courtesy of public domain JeeLabs code + #include + #define SECONDS_PER_DAY 86400L + #define SECONDS_FROM_1970_TO_2000 946684800 + + //////////////////////////////////////////////////////////////////////////////// + // utility code, some of this could be exposed in the DateTime API if needed + + static uint8_t daysInMonth [] PROGMEM = { 31,28,31,30,31,30,31,31,30,31,30,31 }; + + // number of days since 2000/01/01, valid for 2001..2099 + static uint16_t date2days(uint16_t y, uint8_t m, uint8_t d) { + if (y >= 2000) + y -= 2000; + uint16_t days = d; + for (uint8_t i = 1; i < m; ++i) + days += pgm_read_byte(daysInMonth + i - 1); + if (m > 2 && y % 4 == 0) + ++days; + return days + 365 * y + (y + 3) / 4 - 1; + } + + static long time2long(uint16_t days, uint8_t h, uint8_t m, uint8_t s) { + return ((days * 24L + h) * 60 + m) * 60 + s; + } + + //////////////////////////////////////////////////////////////////////////////// + // DateTime implementation - ignores time zones and DST changes + // NOTE: also ignores leap seconds, see http://en.wikipedia.org/wiki/Leap_second + + DateTime::DateTime (uint32_t t) { + t -= SECONDS_FROM_1970_TO_2000; // bring to 2000 timestamp from 1970 + + ss = t % 60; + t /= 60; + mm = t % 60; + t /= 60; + hh = t % 24; + uint16_t days = t / 24; + uint8_t leap; + for (yOff = 0; ; ++yOff) { + leap = yOff % 4 == 0; + if (days < 365 + leap) + break; + days -= 365 + leap; + } + for (m = 1; ; ++m) { + uint8_t daysPerMonth = pgm_read_byte(daysInMonth + m - 1); + if (leap && m == 2) + ++daysPerMonth; + if (days < daysPerMonth) + break; + days -= daysPerMonth; + } + d = days + 1; + } + + DateTime::DateTime (uint16_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec) { + if (year >= 2000) + year -= 2000; + yOff = year; + m = month; + d = day; + hh = hour; + mm = min; + ss = sec; + } + + static uint8_t conv2d(const char* p) { + uint8_t v = 0; + if ('0' <= *p && *p <= '9') + v = *p - '0'; + return 10 * v + *++p - '0'; + } + + // A convenient constructor for using "the compiler's time": + // DateTime now (__DATE__, __TIME__); + // NOTE: using PSTR would further reduce the RAM footprint + DateTime::DateTime (const char* date, const char* time) { + // sample input: date = "Dec 26 2009", time = "12:34:56" + yOff = conv2d(date + 9); + // Jan Feb Mar Apr May Jun Jul Aug Sep Oct Nov Dec + switch (date[0]) { + case 'J': m = (date[1] == 'a' ? 1 : (date[2] == 'n' ? 6 : 7)); break; + case 'F': m = 2; break; + case 'A': m = date[2] == 'r' ? 4 : 8; break; + case 'M': m = date[2] == 'r' ? 3 : 5; break; + case 'S': m = 9; break; + case 'O': m = 10; break; + case 'N': m = 11; break; + case 'D': m = 12; break; + } + d = conv2d(date + 4); + hh = conv2d(time); + mm = conv2d(time + 3); + ss = conv2d(time + 6); + } + + uint8_t DateTime::dayOfWeek() const { + uint16_t day = secondstime() / SECONDS_PER_DAY; + return (day + 6) % 7; // Jan 1, 2000 is a Saturday, i.e. returns 6 + } + + uint32_t DateTime::unixtime(void) const { + return secondstime() + SECONDS_FROM_1970_TO_2000; + } + + long DateTime::secondstime(void) const { + uint32_t t; + uint16_t days = date2days(yOff, m, d); + t = time2long(days, hh, mm, ss); + return t; + } +#endif diff --git a/libraries/DS1307/DS1307.h b/libraries/DS1307/DS1307.h new file mode 100644 index 0000000..9fb51be --- /dev/null +++ b/libraries/DS1307/DS1307.h @@ -0,0 +1,214 @@ +// I2Cdev library collection - DS1307 I2C device class header file +// Based on Maxim DS1307 datasheet, 2008 +// 11/13/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// I2C Device Library hosted at http://www.i2cdevlib.com +// +// Changelog: +// 2011-11-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. +=============================================== +*/ + +#ifndef _DS1307_H_ +#define _DS1307_H_ + +#include "I2Cdev.h" + +// comment this out if you already have a JeeLabs' DateTime class in your code +// or if you don't need DateTime functionality +#define DS1307_INCLUDE_DATETIME_CLASS + +// comment this out if you don't need DateTime functionality +#define DS1307_INCLUDE_DATETIME_METHODS + +#define DS1307_ADDRESS 0x68 // this device only has one address +#define DS1307_DEFAULT_ADDRESS 0x68 + +#define DS1307_RA_SECONDS 0x00 +#define DS1307_RA_MINUTES 0x01 +#define DS1307_RA_HOURS 0x02 +#define DS1307_RA_DAY 0x03 +#define DS1307_RA_DATE 0x04 +#define DS1307_RA_MONTH 0x05 +#define DS1307_RA_YEAR 0x06 +#define DS1307_RA_CONTROL 0x07 +#define DS1307_RA_RAM 0x08 + +#define DS1307_SECONDS_CH_BIT 7 +#define DS1307_SECONDS_10_BIT 6 +#define DS1307_SECONDS_10_LENGTH 3 +#define DS1307_SECONDS_1_BIT 3 +#define DS1307_SECONDS_1_LENGTH 4 + +#define DS1307_MINUTES_10_BIT 6 +#define DS1307_MINUTES_10_LENGTH 3 +#define DS1307_MINUTES_1_BIT 3 +#define DS1307_MINUTES_1_LENGTH 4 + +#define DS1307_HOURS_MODE_BIT 6 // 0 = 24-hour mode, 1 = 12-hour mode +#define DS1307_HOURS_AMPM_BIT 5 // 2nd HOURS_10 bit if in 24-hour mode +#define DS1307_HOURS_10_BIT 4 +#define DS1307_HOURS_1_BIT 3 +#define DS1307_HOURS_1_LENGTH 4 + +#define DS1307_DAY_BIT 2 +#define DS1307_DAY_LENGTH 3 + +#define DS1307_DATE_10_BIT 5 +#define DS1307_DATE_10_LENGTH 2 +#define DS1307_DATE_1_BIT 3 +#define DS1307_DATE_1_LENGTH 4 + +#define DS1307_MONTH_10_BIT 4 +#define DS1307_MONTH_1_BIT 3 +#define DS1307_MONTH_1_LENGTH 4 + +#define DS1307_YEAR_10H_BIT 7 +#define DS1307_YEAR_10H_LENGTH 4 +#define DS1307_YEAR_1H_BIT 3 +#define DS1307_YEAR_1H_LENGTH 4 + +#define DS1307_CONTROL_OUT_BIT 7 +#define DS1307_CONTROL_SQWE_BIT 4 +#define DS1307_CONTROL_RS_BIT 1 +#define DS1307_CONTROL_RS_LENGTH 2 + +#define DS1307_SQW_RATE_1 0x0 +#define DS1307_SQW_RATE_4096 0x1 +#define DS1307_SQW_RATE_8192 0x2 +#define DS1307_SQW_RATE_32768 0x3 + +#ifdef DS1307_INCLUDE_DATETIME_CLASS + // DateTime class courtesy of public domain JeeLabs code + // simple general-purpose date/time class (no TZ / DST / leap second handling!) + class DateTime { + public: + DateTime (uint32_t t=0); + DateTime (uint16_t year, uint8_t month, uint8_t day, uint8_t hour=0, uint8_t min=0, uint8_t sec=0); + DateTime (const char* date, const char* time); + uint16_t year() const { return 2000 + yOff; } + uint8_t month() const { return m; } + uint8_t day() const { return d; } + uint8_t hour() const { return hh; } + uint8_t minute() const { return mm; } + uint8_t second() const { return ss; } + uint8_t dayOfWeek() const; + + // 32-bit times as seconds since 1/1/2000 + long secondstime() const; + // 32-bit times as seconds since 1/1/1970 + uint32_t unixtime(void) const; + + protected: + uint8_t yOff, m, d, hh, mm, ss; + }; +#endif + +class DS1307 { + public: + DS1307(); + DS1307(uint8_t address); + + void initialize(); + bool testConnection(); + + // SECONDS register + bool getClockRunning(); + void setClockRunning(bool running); + uint8_t getSeconds(); // 0-59 + void setSeconds(uint8_t seconds); + + // MINUTES register + uint8_t getMinutes(); // 0-59 + void setMinutes(uint8_t minutes); + + // HOURS register + uint8_t getMode(); // 0-1 + void setMode(uint8_t mode); + uint8_t getAMPM(); // 0-1 + void setAMPM(uint8_t ampm); + uint8_t getHours12(); // 1-12 + void setHours12(uint8_t hours, uint8_t ampm); + uint8_t getHours24(); // 0-23 + void setHours24(uint8_t hours); + + // DAY register + uint8_t getDayOfWeek(); // 1-7 + void setDayOfWeek(uint8_t dow); + + // DATE register + uint8_t getDay(); // 1-31 + void setDay(uint8_t day); + + // MONTH register + uint8_t getMonth(); // 1-12 + void setMonth(uint8_t month); + + // YEAR register + uint16_t getYear(); // 1970, 2000, 2011, etc + void setYear(uint16_t year); + + // CONTROL register + bool getFixedOutputLevel(); + void setFixedOutputLevel(bool level); + bool getSquareWaveEnabled(); + void setSquareWaveEnabled(bool enabled); + uint8_t getSquareWaveRate(); + void setSquareWaveRate(uint8_t rate); + + // RAM registers + uint8_t getMemoryByte(uint8_t offset); + void setMemoryByte(uint8_t offset, uint8_t value); + + // convenience methods + + void getDate(uint16_t *year, uint8_t *month, uint8_t *day); + void setDate(uint16_t year, uint8_t month, uint8_t day); + + void getTime12(uint8_t *hours, uint8_t *minutes, uint8_t *seconds, uint8_t *ampm); + void setTime12(uint8_t hours, uint8_t minutes, uint8_t seconds, uint8_t ampm); + + void getTime24(uint8_t *hours, uint8_t *minutes, uint8_t *seconds); + void setTime24(uint8_t hours, uint8_t minutes, uint8_t seconds); + + void getDateTime12(uint16_t *year, uint8_t *month, uint8_t *day, uint8_t *hours, uint8_t *minutes, uint8_t *seconds, uint8_t *ampm); + void setDateTime12(uint16_t year, uint8_t month, uint8_t day, uint8_t hours, uint8_t minutes, uint8_t seconds, uint8_t ampm); + + void getDateTime24(uint16_t *year, uint8_t *month, uint8_t *day, uint8_t *hours, uint8_t *minutes, uint8_t *seconds); + void setDateTime24(uint16_t year, uint8_t month, uint8_t day, uint8_t hours, uint8_t minutes, uint8_t seconds); + + #ifdef DS1307_INCLUDE_DATETIME_METHODS + DateTime getDateTime(); + void setDateTime(DateTime dt); + #endif + + private: + uint8_t devAddr; + uint8_t buffer[1]; + bool mode12; + bool clockHalt; +}; + +#endif /* _DS1307_H_ */ diff --git a/libraries/DS1307/examples/DS1307_tick/DS1307_tick.ino b/libraries/DS1307/examples/DS1307_tick/DS1307_tick.ino new file mode 100644 index 0000000..038e920 --- /dev/null +++ b/libraries/DS1307/examples/DS1307_tick/DS1307_tick.ino @@ -0,0 +1,101 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for DS1307 class +// 11/12/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// I2C Device Library hosted at http://www.i2cdevlib.com +// +// Changelog: +// 2011-11-12 - 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 DS1307 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 "DS1307.h" + +// class default I2C address is 0x68 +// specific I2C addresses may be passed as a parameter here +// but this device only supports one I2C address (0x68) +DS1307 rtc; + +uint16_t year; +uint8_t month, day, dow, hours, minutes, seconds; + +#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..."); + rtc.initialize(); + + // verify connection + Serial.println("Testing device connections..."); + Serial.println(rtc.testConnection() ? "DS1307 connection successful" : "DS1307 connection failed"); + + // configure LED pin for output + pinMode(LED_PIN, OUTPUT); + + // set sample time + rtc.setDateTime24(2011, 11, 12, 13, 45, 0); +} + +void loop() { + // read all clock info from device + rtc.getDateTime24(&year, &month, &day, &hours, &minutes, &seconds); + + // display YYYY-MM-DD hh:mm:ss time + Serial.print("rtc:\t"); + Serial.print(year); Serial.print("-"); + if (month < 10) Serial.print("0"); + Serial.print(month); Serial.print("-"); + if (day < 10) Serial.print("0"); + Serial.print(day); Serial.print(" "); + if (hours < 10) Serial.print("0"); + Serial.print(hours); Serial.print(":"); + if (minutes < 10) Serial.print("0"); + Serial.print(minutes); Serial.print(":"); + if (seconds < 10) Serial.print("0"); + Serial.println(seconds); + + // blink LED to indicate activity + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); + + // wait one second so the next reading will be different + delay(1000); +} diff --git a/libraries/DS1307/library.json b/libraries/DS1307/library.json new file mode 100644 index 0000000..8dba547 --- /dev/null +++ b/libraries/DS1307/library.json @@ -0,0 +1,18 @@ +{ + "name": "I2Cdevlib-DS1307", + "keywords": "rtc, time, clock, i2cdevlib, i2c", + "description": "The DS1307 serial real-time clock (RTC) is a low-power, full binary-coded decimal (BCD) clock/calendar plus 56 bytes of NV SRAM", + "include": "Arduino/DS1307", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "dependencies": + { + "name": "I2Cdevlib-Core", + "frameworks": "arduino" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/DueFlash/DueFlash.cpp b/libraries/DueFlash/DueFlash.cpp new file mode 100644 index 0000000..7726878 --- /dev/null +++ b/libraries/DueFlash/DueFlash.cpp @@ -0,0 +1,83 @@ +//////////////////////////////////////////////////////////////////////////// +// +// This file is part of DueFlash +// +// Copyright (c) 2013 Pansenti, LLC +// +// 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 "DueFlash.h" + +DueFlash::DueFlash() +{ + uint32_t retCode; + + /* Initialize flash: 6 wait states for flash writing. */ + + retCode = flash_init(FLASH_ACCESS_MODE_128, 6); + if (retCode != FLASH_RC_OK) { + _FLASH_DEBUG("Flash init failed\n"); + } +} + +boolean DueFlash::write(uint32_t *flashStart, uint32_t *data, uint32_t dataLength) +{ + uint32_t retCode; + uint32_t byteLength = dataLength * sizeof(uint32_t); + + if ((uint32_t)flashStart < IFLASH1_ADDR) { + _FLASH_DEBUG("Flash write address too low\n"); + return false; + } + + if ((uint32_t)flashStart >= (IFLASH1_ADDR + IFLASH1_SIZE)) { + _FLASH_DEBUG("Flash write address too high\n"); + return false; + } + + if (((uint32_t)flashStart & 3) != 0) { + _FLASH_DEBUG("Flash start address must be on four byte boundary\n"); + return false; + } + + // Unlock page + + retCode = flash_unlock((uint32_t)flashStart, (uint32_t)flashStart + byteLength - 1, 0, 0); + if (retCode != FLASH_RC_OK) { + _FLASH_DEBUG("Failed to unlock flash for write\n"); + return false; + } + + // write data + + retCode = flash_write((uint32_t)flashStart, data, byteLength, 1); + + if (retCode != FLASH_RC_OK) { + _FLASH_DEBUG("Flash write failed\n"); + return false; + } + + // Lock page + + retCode = flash_lock((uint32_t)flashStart, (uint32_t)flashStart + byteLength - 1, 0, 0); + if (retCode != FLASH_RC_OK) { + _FLASH_DEBUG("Failed to lock flash page\n"); + return false; + } + return true; +} diff --git a/libraries/DueFlash/DueFlash.h b/libraries/DueFlash/DueFlash.h new file mode 100644 index 0000000..9e7e13a --- /dev/null +++ b/libraries/DueFlash/DueFlash.h @@ -0,0 +1,68 @@ +//////////////////////////////////////////////////////////////////////////// +// +// This file is part of DueFlash +// +// Copyright (c) 2013 Pansenti, LLC +// +// 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 DUEFLASH_H +#define DUEFLASH_H + +#include +#include "flash_efc.h" + +// DueFlash supports saving of non-volatile data for Arduino Due sketches. +// +// All writes are in flash block 1 and are always multiples of 32 bits. They +// can start on any 32 bit boundary withing flash block 1. +// +// Note: uploading new software will erase all flash so data written to flash +// using this library will not survive a new software upload. +// + +// FLASH_DEBUG can be enabled to get debugging information displayed. + +#define FLASH_DEBUG + +#ifdef FLASH_DEBUG +#define _FLASH_DEBUG(x) Serial.print(x); +#else +#define _FLASH_DEBUG(x) +#endif + +// DueFlash is the main class for flash functions + +class DueFlash +{ +public: + + // Constructor does basic initialization + + DueFlash(); + + // write() writes the specified amount of data into flash. + // flashStart is the address in memory where the write should start + // data is a pointer to the data to be written (multiple of 32 bits) + // dataLength is length of data in units of 32 bits + + boolean write(uint32_t *flashStart, uint32_t *data, uint32_t dataLength); +}; + +#endif // DUEFLASH_H diff --git a/libraries/DueFlash/efc.cpp b/libraries/DueFlash/efc.cpp new file mode 100644 index 0000000..74f0c8a --- /dev/null +++ b/libraries/DueFlash/efc.cpp @@ -0,0 +1,340 @@ +/** + * \file + * + * \brief Enhanced Embedded Flash Controller (EEFC) driver for SAM. + * + * Copyright (c) 2011-2012 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * 4. This software may only be redistributed and used in connection with an + * Atmel microcontroller product. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#include "efc.h" + +/// @cond 0 +/**INDENT-OFF**/ +#ifdef __cplusplus +extern "C" { +#endif +/**INDENT-ON**/ +/// @endcond + +/** + * \defgroup sam_drivers_efc_group Enhanced Embedded Flash Controller (EEFC) + * + * The Enhanced Embedded Flash Controller ensures the interface of the Flash + * block with the 32-bit internal bus. + * + * @{ + */ + +/* Address definition for read operation */ +# define READ_BUFF_ADDR0 IFLASH0_ADDR +# define READ_BUFF_ADDR1 IFLASH1_ADDR + +/* Flash Writing Protection Key */ +#define FWP_KEY 0x5Au + +#if (SAM4S || SAM4E) +#define EEFC_FCR_FCMD(value) \ + ((EEFC_FCR_FCMD_Msk & ((value) << EEFC_FCR_FCMD_Pos))) +#define EEFC_ERROR_FLAGS (EEFC_FSR_FLOCKE | EEFC_FSR_FCMDE | EEFC_FSR_FLERR) +#else +#define EEFC_ERROR_FLAGS (EEFC_FSR_FLOCKE | EEFC_FSR_FCMDE) +#endif + + + +/* + * Local function declaration. + * Because they are RAM functions, they need 'extern' declaration. + */ +extern void efc_write_fmr(Efc *p_efc, uint32_t ul_fmr); +extern uint32_t efc_perform_fcr(Efc *p_efc, uint32_t ul_fcr); + +/** + * \brief Initialize the EFC controller. + * + * \param ul_access_mode 0 for 128-bit, EEFC_FMR_FAM for 64-bit. + * \param ul_fws The number of wait states in cycle (no shift). + * + * \return 0 if successful. + */ +uint32_t efc_init(Efc *p_efc, uint32_t ul_access_mode, uint32_t ul_fws) +{ + efc_write_fmr(p_efc, ul_access_mode | EEFC_FMR_FWS(ul_fws)); + return EFC_RC_OK; +} + +/** + * \brief Enable the flash ready interrupt. + * + * \param p_efc Pointer to an EFC instance. + */ +void efc_enable_frdy_interrupt(Efc *p_efc) +{ + uint32_t ul_fmr = p_efc->EEFC_FMR; + + efc_write_fmr(p_efc, ul_fmr | EEFC_FMR_FRDY); +} + +/** + * \brief Disable the flash ready interrupt. + * + * \param p_efc Pointer to an EFC instance. + */ +void efc_disable_frdy_interrupt(Efc *p_efc) +{ + uint32_t ul_fmr = p_efc->EEFC_FMR; + + efc_write_fmr(p_efc, ul_fmr & (~EEFC_FMR_FRDY)); +} + +/** + * \brief Set flash access mode. + * + * \param p_efc Pointer to an EFC instance. + * \param ul_mode 0 for 128-bit, EEFC_FMR_FAM for 64-bit. + */ +void efc_set_flash_access_mode(Efc *p_efc, uint32_t ul_mode) +{ + uint32_t ul_fmr = p_efc->EEFC_FMR & (~EEFC_FMR_FAM); + + efc_write_fmr(p_efc, ul_fmr | ul_mode); +} + +/** + * \brief Get flash access mode. + * + * \param p_efc Pointer to an EFC instance. + * + * \return 0 for 128-bit or EEFC_FMR_FAM for 64-bit. + */ +uint32_t efc_get_flash_access_mode(Efc *p_efc) +{ + return (p_efc->EEFC_FMR & EEFC_FMR_FAM); +} + +/** + * \brief Set flash wait state. + * + * \param p_efc Pointer to an EFC instance. + * \param ul_fws The number of wait states in cycle (no shift). + */ +void efc_set_wait_state(Efc *p_efc, uint32_t ul_fws) +{ + uint32_t ul_fmr = p_efc->EEFC_FMR & (~EEFC_FMR_FWS_Msk); + + efc_write_fmr(p_efc, ul_fmr | EEFC_FMR_FWS(ul_fws)); +} + +/** + * \brief Get flash wait state. + * + * \param p_efc Pointer to an EFC instance. + * + * \return The number of wait states in cycle (no shift). + */ +uint32_t efc_get_wait_state(Efc *p_efc) +{ + return ((p_efc->EEFC_FMR & EEFC_FMR_FWS_Msk) >> EEFC_FMR_FWS_Pos); +} + +/** + * \brief Perform the given command and wait until its completion (or an error). + * + * \note Unique ID commands are not supported, use efc_read_unique_id. + * + * \param p_efc Pointer to an EFC instance. + * \param ul_command Command to perform. + * \param ul_argument Optional command argument. + * + * \note This function will automatically choose to use IAP function. + * + * \return 0 if successful, otherwise returns an error code. + */ +uint32_t efc_perform_command(Efc *p_efc, uint32_t ul_command, + uint32_t ul_argument) +{ + /* Unique ID commands are not supported. */ + if (ul_command == EFC_FCMD_STUI || ul_command == EFC_FCMD_SPUI) { + return EFC_RC_NOT_SUPPORT; + } + + /* Use IAP function with 2 parameters in ROM. */ + static uint32_t(*iap_perform_command) (uint32_t, uint32_t); + uint32_t ul_efc_nb = (p_efc == EFC0) ? 0 : 1; + + iap_perform_command = + (uint32_t(*)(uint32_t, uint32_t)) + *((uint32_t *) CHIP_FLASH_IAP_ADDRESS); + iap_perform_command(ul_efc_nb, + EEFC_FCR_FKEY(FWP_KEY) | EEFC_FCR_FARG(ul_argument) | + EEFC_FCR_FCMD(ul_command)); + return (p_efc->EEFC_FSR & EEFC_ERROR_FLAGS); +} + +/** + * \brief Get the current status of the EEFC. + * + * \note This function clears the value of some status bits (FLOCKE, FCMDE). + * + * \param p_efc Pointer to an EFC instance. + * + * \return The current status. + */ +uint32_t efc_get_status(Efc *p_efc) +{ + return p_efc->EEFC_FSR; +} + +/** + * \brief Get the result of the last executed command. + * + * \param p_efc Pointer to an EFC instance. + * + * \return The result of the last executed command. + */ +uint32_t efc_get_result(Efc *p_efc) +{ + return p_efc->EEFC_FRR; +} + +/** + * \brief Perform read sequence. Supported sequences are read Unique ID and + * read User Signature + * + * \param p_efc Pointer to an EFC instance. + * \param ul_cmd_st Start command to perform. + * \param ul_cmd_sp Stop command to perform. + * \param p_ul_buf Pointer to an data buffer. + * \param ul_size Buffer size. + * + * \return 0 if successful, otherwise returns an error code. + */ +RAMFUNC +uint32_t efc_perform_read_sequence(Efc *p_efc, + uint32_t ul_cmd_st, uint32_t ul_cmd_sp, + uint32_t *p_ul_buf, uint32_t ul_size) +{ + volatile uint32_t ul_status; + uint32_t ul_cnt; + + uint32_t *p_ul_data = + (uint32_t *) ((p_efc == EFC0) ? + READ_BUFF_ADDR0 : READ_BUFF_ADDR1); + + if (p_ul_buf == NULL) { + return EFC_RC_INVALID; + } + + p_efc->EEFC_FMR |= (0x1u << 16); + + /* Send the Start Read command */ + + p_efc->EEFC_FCR = EEFC_FCR_FKEY(FWP_KEY) | EEFC_FCR_FARG(0) + | EEFC_FCR_FCMD(ul_cmd_st); + /* Wait for the FRDY bit in the Flash Programming Status Register + * (EEFC_FSR) falls. + */ + do { + ul_status = p_efc->EEFC_FSR; + } while ((ul_status & EEFC_FSR_FRDY) == EEFC_FSR_FRDY); + + /* The data is located in the first address of the Flash + * memory mapping. + */ + for (ul_cnt = 0; ul_cnt < ul_size; ul_cnt++) { + p_ul_buf[ul_cnt] = p_ul_data[ul_cnt]; + } + + /* To stop the read mode */ + p_efc->EEFC_FCR = + EEFC_FCR_FKEY(FWP_KEY) | EEFC_FCR_FARG(0) | + EEFC_FCR_FCMD(ul_cmd_sp); + /* Wait for the FRDY bit in the Flash Programming Status Register (EEFC_FSR) + * rises. + */ + do { + ul_status = p_efc->EEFC_FSR; + } while ((ul_status & EEFC_FSR_FRDY) != EEFC_FSR_FRDY); + + p_efc->EEFC_FMR &= ~(0x1u << 16); + + return EFC_RC_OK; +} + +/** + * \brief Set mode register. + * + * \param p_efc Pointer to an EFC instance. + * \param ul_fmr Value of mode register + */ +RAMFUNC +void efc_write_fmr(Efc *p_efc, uint32_t ul_fmr) +{ + p_efc->EEFC_FMR = ul_fmr; +} + +/** + * \brief Perform command. + * + * \param p_efc Pointer to an EFC instance. + * \param ul_fcr Flash command. + * + * \return The current status. + */ +RAMFUNC +uint32_t efc_perform_fcr(Efc *p_efc, uint32_t ul_fcr) +{ + volatile uint32_t ul_status; + + p_efc->EEFC_FCR = ul_fcr; + do { + ul_status = p_efc->EEFC_FSR; + } while ((ul_status & EEFC_FSR_FRDY) != EEFC_FSR_FRDY); + + return (ul_status & EEFC_ERROR_FLAGS); +} + +//@} + +/// @cond 0 +/**INDENT-OFF**/ +#ifdef __cplusplus +} +#endif +/**INDENT-ON**/ +/// @endcond diff --git a/libraries/DueFlash/efc.h b/libraries/DueFlash/efc.h new file mode 100644 index 0000000..4481b98 --- /dev/null +++ b/libraries/DueFlash/efc.h @@ -0,0 +1,139 @@ +/** + * \file + * + * \brief Embedded Flash Controller (EFC) driver for SAM. + * + * Copyright (c) 2011-2012 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * 4. This software may only be redistributed and used in connection with an + * Atmel microcontroller product. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef EFC_H_INCLUDED +#define EFC_H_INCLUDED + +#include +#include + +#define SAM3XA +#define RAMFUNC __attribute__ ((section(".ramfunc"))) + +/// @cond 0 +/**INDENT-OFF**/ +#ifdef __cplusplus +extern "C" { +#endif +/**INDENT-ON**/ +/// @endcond + +/*! \name EFC return codes */ +//! @{ +typedef enum efc_rc { + EFC_RC_OK = 0, //!< Operation OK + EFC_RC_YES = 0, //!< Yes + EFC_RC_NO = 1, //!< No + EFC_RC_ERROR = 1, //!< General error + EFC_RC_INVALID, //!< Invalid argument input + EFC_RC_NOT_SUPPORT = 0xFFFFFFFF //!< Operation is not supported +} efc_rc_t; +//! @} + +/*! \name EFC command */ +//! @{ +#define EFC_FCMD_GETD 0x00 //!< Get Flash Descriptor +#define EFC_FCMD_WP 0x01 //!< Write page +#define EFC_FCMD_WPL 0x02 //!< Write page and lock +#define EFC_FCMD_EWP 0x03 //!< Erase page and write page +#define EFC_FCMD_EWPL 0x04 //!< Erase page and write page then lock +#define EFC_FCMD_EA 0x05 //!< Erase all +#if (SAM3SD8) +#define EFC_FCMD_EPL 0x06 //!< Erase plane +#endif +#if (SAM4S || SAM4E) +#define EFC_FCMD_EPA 0x07 //!< Erase pages +#endif +#define EFC_FCMD_SLB 0x08 //!< Set Lock Bit +#define EFC_FCMD_CLB 0x09 //!< Clear Lock Bit +#define EFC_FCMD_GLB 0x0A //!< Get Lock Bit +#define EFC_FCMD_SGPB 0x0B //!< Set GPNVM Bit +#define EFC_FCMD_CGPB 0x0C //!< Clear GPNVM Bit +#define EFC_FCMD_GGPB 0x0D //!< Get GPNVM Bit +#define EFC_FCMD_STUI 0x0E //!< Start unique ID +#define EFC_FCMD_SPUI 0x0F //!< Stop unique ID +#if (!SAM3U && !SAM3SD8 && !SAM3S8) +#define EFC_FCMD_GCALB 0x10 //!< Get CALIB Bit +#endif +#if (SAM4S || SAM4E) +#define EFC_FCMD_ES 0x11 //!< Erase sector +#define EFC_FCMD_WUS 0x12 //!< Write user signature +#define EFC_FCMD_EUS 0x13 //!< Erase user signature +#define EFC_FCMD_STUS 0x14 //!< Start read user signature +#define EFC_FCMD_SPUS 0x15 //!< Stop read user signature +#endif +//! @} + +/*! The IAP function entry address */ +#define CHIP_FLASH_IAP_ADDRESS (IROM_ADDR + 8) + +/*! \name EFC access mode */ +//! @{ +#define EFC_ACCESS_MODE_128 0 +#define EFC_ACCESS_MODE_64 EEFC_FMR_FAM +//! @} + +uint32_t efc_init(Efc *p_efc, uint32_t ul_access_mode, uint32_t ul_fws); +void efc_enable_frdy_interrupt(Efc *p_efc); +void efc_disable_frdy_interrupt(Efc *p_efc); +void efc_set_flash_access_mode(Efc *p_efc, uint32_t ul_mode); +uint32_t efc_get_flash_access_mode(Efc *p_efc); +void efc_set_wait_state(Efc *p_efc, uint32_t ul_fws); +uint32_t efc_get_wait_state(Efc *p_efc); +uint32_t efc_perform_command(Efc *p_efc, uint32_t ul_command, + uint32_t ul_argument); +uint32_t efc_get_status(Efc *p_efc); +uint32_t efc_get_result(Efc *p_efc); +uint32_t efc_perform_read_sequence(Efc *p_efc, + uint32_t ul_cmd_st, uint32_t ul_cmd_sp, + uint32_t *p_ul_buf, uint32_t ul_size); + +/// @cond 0 +/**INDENT-OFF**/ +#ifdef __cplusplus +} +#endif +/**INDENT-ON**/ +/// @endcond + +#endif /* EFC_H_INCLUDED */ diff --git a/libraries/DueFlash/flash_efc.cpp b/libraries/DueFlash/flash_efc.cpp new file mode 100644 index 0000000..c7b3aa8 --- /dev/null +++ b/libraries/DueFlash/flash_efc.cpp @@ -0,0 +1,916 @@ +/** + * \file + * + * \brief Embedded Flash service for SAM. + * + * Copyright (c) 2011-2013 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * 4. This software may only be redistributed and used in connection with an + * Atmel microcontroller product. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#include +#include +#include "flash_efc.h" + +/// @cond 0 +/**INDENT-OFF**/ +#ifdef __cplusplus +extern "C" { +#endif +/**INDENT-ON**/ +/// @endcond + +/** + * \defgroup sam_services_flash_efc_group Embedded Flash Service + * + * The Embedded Flash service provides functions for internal flash operations. + * + * @{ + */ + +#if SAM4E +/* User signature size */ +# define FLASH_USER_SIG_SIZE (512) +#endif + +#if SAM4S +/* Internal Flash Controller 0. */ +# define EFC EFC0 +/* User signature size */ +# define FLASH_USER_SIG_SIZE (512) +/* Internal Flash 0 base address. */ +# define IFLASH_ADDR IFLASH0_ADDR +/* Internal flash page size. */ +# define IFLASH_PAGE_SIZE IFLASH0_PAGE_SIZE +/* Internal flash lock region size. */ +# define IFLASH_LOCK_REGION_SIZE IFLASH0_LOCK_REGION_SIZE +#endif + +/* Internal Flash Controller 0. */ +# define EFC EFC0 +/* The max GPNVM number. */ +# define GPNVM_NUM_MAX 3 +/* Internal Flash 0 base address. */ +# define IFLASH_ADDR IFLASH0_ADDR +/* Internal flash page size. */ +# define IFLASH_PAGE_SIZE IFLASH0_PAGE_SIZE +/* Internal flash lock region size. */ +# define IFLASH_LOCK_REGION_SIZE IFLASH0_LOCK_REGION_SIZE + +/* Flash page buffer for alignment */ +static uint32_t gs_ul_page_buffer[IFLASH_PAGE_SIZE / sizeof(uint32_t)]; + +/** + * \brief Translate the given flash address to page and offset values. + * \note pus_page and pus_offset must not be null in order to store the + * corresponding values. + * + * \param pp_efc Pointer to an EFC pointer. + * \param ul_addr Address to translate. + * \param pus_page The first page accessed. + * \param pus_offset Byte offset in the first page. + */ +static void translate_address(Efc **pp_efc, uint32_t ul_addr, + uint16_t *pus_page, uint16_t *pus_offset) +{ + Efc *p_efc; + uint16_t us_page; + uint16_t us_offset; + + if (ul_addr >= IFLASH1_ADDR) { + p_efc = EFC1; + us_page = (ul_addr - IFLASH1_ADDR) / IFLASH1_PAGE_SIZE; + us_offset = (ul_addr - IFLASH1_ADDR) % IFLASH1_PAGE_SIZE; + } else { + p_efc = EFC0; + us_page = (ul_addr - IFLASH0_ADDR) / IFLASH0_PAGE_SIZE; + us_offset = (ul_addr - IFLASH0_ADDR) % IFLASH0_PAGE_SIZE; + } + + /* Store values */ + if (pp_efc) { + *pp_efc = p_efc; + } + + if (pus_page) { + *pus_page = us_page; + } + + if (pus_offset) { + *pus_offset = us_offset; + } +} + +/** + * \brief Compute the address of a flash by the given page and offset. + * + * \param p_efc Pointer to an EFC instance. + * \param us_page Page number. + * \param us_offset Byte offset inside page. + * \param pul_addr Computed address (optional). + */ +static void compute_address(Efc *p_efc, uint16_t us_page, uint16_t us_offset, + uint32_t *pul_addr) +{ + uint32_t ul_addr; + +/* Dual bank flash */ +#ifdef EFC1 + /* Compute address */ + ul_addr = (p_efc == EFC0) ? + IFLASH0_ADDR + us_page * IFLASH_PAGE_SIZE + us_offset : + IFLASH1_ADDR + us_page * IFLASH_PAGE_SIZE + us_offset; + +/* One bank flash */ +#else + /* avoid Cppcheck Warning */ + UNUSED(p_efc); + /* Compute address */ + ul_addr = IFLASH_ADDR + us_page * IFLASH_PAGE_SIZE + us_offset; +#endif + + /* Store result */ + if (pul_addr != NULL) { + *pul_addr = ul_addr; + } +} + +/** + * \brief Compute the lock range associated with the given address range. + * + * \param ul_start Start address of lock range. + * \param ul_end End address of lock range. + * \param pul_actual_start Actual start address of lock range. + * \param pul_actual_end Actual end address of lock range. + */ +static void compute_lock_range(uint32_t ul_start, uint32_t ul_end, + uint32_t *pul_actual_start, uint32_t *pul_actual_end) +{ + uint32_t ul_actual_start, ul_actual_end; + + ul_actual_start = ul_start - (ul_start % IFLASH_LOCK_REGION_SIZE); + ul_actual_end = ul_end - (ul_end % IFLASH_LOCK_REGION_SIZE) + + IFLASH_LOCK_REGION_SIZE - 1; + + if (pul_actual_start) { + *pul_actual_start = ul_actual_start; + } + + if (pul_actual_end) { + *pul_actual_end = ul_actual_end; + } +} + +/** + * \brief Initialize the flash service. + * + * \param ul_mode FLASH_ACCESS_MODE_128 or FLASH_ACCESS_MODE_64. + * \param ul_fws The number of wait states in cycle (no shift). + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_init(uint32_t ul_mode, uint32_t ul_fws) +{ + efc_init(EFC, ul_mode, ul_fws); + +#ifdef EFC1 + efc_init(EFC1, ul_mode, ul_fws); +#endif + + return FLASH_RC_OK; +} + +/** + * \brief Set flash wait state. + * + * \param ul_address Flash bank start address. + * \param ul_fws The number of wait states in cycle (no shift). + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_set_wait_state(uint32_t ul_address, uint32_t ul_fws) +{ + Efc *p_efc; + + translate_address(&p_efc, ul_address, NULL, NULL); + efc_set_wait_state(p_efc, ul_fws); + + return FLASH_RC_OK; +} + +/** + * \brief Set flash wait state. + * + * \param ul_address Flash bank start address. + * \param ul_fws The number of wait states in cycle (no shift). + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_set_wait_state_adaptively(uint32_t ul_address) +{ + Efc *p_efc; + uint32_t clock = SystemCoreClock; + + translate_address(&p_efc, ul_address, NULL, NULL); + + /* Set FWS for embedded Flash access according to operating frequency */ + if (clock < CHIP_FREQ_FWS_0) { + efc_set_wait_state(p_efc, 0); + } else if (clock < CHIP_FREQ_FWS_1) { + efc_set_wait_state(p_efc, 1); + } else if (clock < CHIP_FREQ_FWS_2) { + efc_set_wait_state(p_efc, 2); + } else if (clock < CHIP_FREQ_FWS_3) { + efc_set_wait_state(p_efc, 3); + } else { + efc_set_wait_state(p_efc, 4); + } + return FLASH_RC_OK; +} + +/** + * \brief Get flash wait state. + * + * \param ul_address Flash bank start address. + * + * \return The number of wait states in cycle (no shift). + */ +uint32_t flash_get_wait_state(uint32_t ul_address) +{ + Efc *p_efc; + + translate_address(&p_efc, ul_address, NULL, NULL); + return efc_get_wait_state(p_efc); +} + +/** + * \brief Get flash descriptor. + * + * \param ul_address Flash bank start address. + * \param pul_flash_descriptor Pointer to a data buffer to store flash descriptor. + * \param ul_size Data buffer size in DWORD. + * + * \return The actual descriptor length. + */ +uint32_t flash_get_descriptor(uint32_t ul_address, + uint32_t *pul_flash_descriptor, uint32_t ul_size) +{ + Efc *p_efc; + uint32_t ul_tmp; + uint32_t ul_cnt; + + translate_address(&p_efc, ul_address, NULL, NULL); + + /* Command fails */ + if (FLASH_RC_OK != efc_perform_command(p_efc, EFC_FCMD_GETD, 0)) { + return 0; + } else { + /* Read until no result */ + for (ul_cnt = 0;; ul_cnt++) { + ul_tmp = efc_get_result(p_efc); + if ((ul_size > ul_cnt) && (ul_tmp != 0)) { + *pul_flash_descriptor++ = ul_tmp; + } else { + break; + } + } + } + + return ul_cnt; +} + +/** + * \brief Get flash total page count for the specified bank. + * + * \note The flash descriptor must be fetched from flash_get_descriptor + * function first. + * + * \param pul_flash_descriptor Pointer to a flash descriptor. + * + * \return The flash total page count. + */ +uint32_t flash_get_page_count(const uint32_t *pul_flash_descriptor) +{ + return (pul_flash_descriptor[1] / pul_flash_descriptor[2]); +} + +/** + * \brief Get flash page count per region (plane) for the specified bank. + * + * \note The flash descriptor must be fetched from flash_get_descriptor + * function first. + * + * \param pul_flash_descriptor Pointer to a flash descriptor. + * + * \return The flash page count per region (plane). + */ +uint32_t flash_get_page_count_per_region(const uint32_t *pul_flash_descriptor) +{ + return (pul_flash_descriptor[4] / pul_flash_descriptor[2]); +} + +/** + * \brief Get flash region (plane) count for the specified bank. + * + * \note The flash descriptor must be fetched from flash_get_descriptor + * function first. + * + * \param pul_flash_descriptor Pointer to a flash descriptor. + * + * \return The flash region (plane) count. + */ +uint32_t flash_get_region_count(const uint32_t *pul_flash_descriptor) +{ + return (pul_flash_descriptor[3]); +} + +/** + * \brief Erase the entire flash. + * + * \note Only the flash bank including ul_address will be erased. If there are + * two flash banks, we need to call this function twice with each bank start + * address. + * + * \param ul_address Flash bank start address. + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_erase_all(uint32_t ul_address) +{ + Efc *p_efc; + + translate_address(&p_efc, ul_address, NULL, NULL); + + if (EFC_RC_OK != efc_perform_command(p_efc, EFC_FCMD_EA, 0)) { + return FLASH_RC_ERROR; + } + + return FLASH_RC_OK; +} + +#if SAM3SD8 +/** + * \brief Erase the flash by plane. + * + * \param ul_address Flash plane start address. + * + * \note Erase plane command needs a page number parameter which belongs to + * the plane to be erased. + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_erase_plane(uint32_t ul_address) +{ + Efc *p_efc; + uint16_t us_page; + + translate_address(&p_efc, ul_address, &us_page, NULL); + + if (EFC_RC_OK != efc_perform_command(p_efc, EFC_FCMD_EPL, us_page)) { + return FLASH_RC_ERROR; + } + + return FLASH_RC_OK; +} +#endif + +#if (SAM4S || SAM4E) +/** + * \brief Erase the specified pages of flash. + * + * \param ul_address Flash bank start address. + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_erase_page(uint32_t ul_address, uint8_t uc_page_num) +{ + Efc *p_efc; + uint16_t us_page; + + if (uc_page_num >= IFLASH_ERASE_PAGES_INVALID) { + return FLASH_RC_INVALID; + } + + if (ul_address & (IFLASH_PAGE_SIZE - 1)) { + return FLASH_RC_INVALID; + } + + translate_address(&p_efc, ul_address, &us_page, NULL); + + if (EFC_RC_OK != efc_perform_command(p_efc, EFC_FCMD_EPA, + (us_page | uc_page_num))) { + return FLASH_RC_ERROR; + } + + return FLASH_RC_OK; +} + +/** + * \brief Erase the flash sector. + * + * \note Erase sector command needs a page number parameter which belongs to + * the sector to be erased. + * + * \param ul_address Flash sector start address. + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_erase_sector(uint32_t ul_address) +{ + Efc *p_efc; + uint16_t us_page; + + translate_address(&p_efc, ul_address, &us_page, NULL); + + if (EFC_RC_OK != efc_perform_command(p_efc, EFC_FCMD_ES, us_page)) { + return FLASH_RC_ERROR; + } + + return FLASH_RC_OK; +} +#endif + +/** + * \brief Write a data buffer on flash. + * + * \note This function works in polling mode, and thus only returns when the + * data has been effectively written. + * \note For dual bank flash, this function doesn't support cross write from + * bank 0 to bank 1. In this case, flash_write must be called twice (ie for + * each bank). + * + * \param ul_address Write address. + * \param p_buffer Data buffer. + * \param ul_size Size of data buffer in bytes. + * \param ul_erase_flag Flag to set if erase first. + * + * \return 0 if successful, otherwise returns an error code. + */ +uint32_t flash_write(uint32_t ul_address, const void *p_buffer, + uint32_t ul_size, uint32_t ul_erase_flag) +{ + Efc *p_efc; + uint32_t ul_fws_temp; + uint16_t us_page; + uint16_t us_offset; + uint32_t writeSize; + uint32_t ul_page_addr; + uint16_t us_padding; + uint32_t ul_error; + uint32_t ul_idx; + uint32_t *p_aligned_dest; + uint8_t *puc_page_buffer = (uint8_t *) gs_ul_page_buffer; + + translate_address(&p_efc, ul_address, &us_page, &us_offset); + + /* According to the errata, set the wait state value to 6. */ + ul_fws_temp = efc_get_wait_state(p_efc); + efc_set_wait_state(p_efc, 6); + + /* Write all pages */ + while (ul_size > 0) { + /* Copy data in temporary buffer to avoid alignment problems. */ + writeSize = Min((uint32_t) IFLASH_PAGE_SIZE - us_offset, + ul_size); + compute_address(p_efc, us_page, 0, &ul_page_addr); + us_padding = IFLASH_PAGE_SIZE - us_offset - writeSize; + + /* Pre-buffer data */ + memcpy(puc_page_buffer, (void *)ul_page_addr, us_offset); + + /* Buffer data */ + memcpy(puc_page_buffer + us_offset, p_buffer, writeSize); + + /* Post-buffer data */ + memcpy(puc_page_buffer + us_offset + writeSize, + (void *)(ul_page_addr + us_offset + writeSize), + us_padding); + + /* Write page. + * Writing 8-bit and 16-bit data is not allowed and may lead to + * unpredictable data corruption. + */ + p_aligned_dest = (uint32_t *) ul_page_addr; + for (ul_idx = 0; ul_idx < (IFLASH_PAGE_SIZE / sizeof(uint32_t)); + ++ul_idx) { + *p_aligned_dest++ = gs_ul_page_buffer[ul_idx]; + } + + if (ul_erase_flag) { + ul_error = efc_perform_command(p_efc, EFC_FCMD_EWP, + us_page); + } else { + ul_error = efc_perform_command(p_efc, EFC_FCMD_WP, + us_page); + } + + if (ul_error) { + return ul_error; + } + + /* Progression */ + p_buffer = (void *)((uint32_t) p_buffer + writeSize); + ul_size -= writeSize; + us_page++; + us_offset = 0; + } + + /* According to the errata, restore the wait state value. */ + efc_set_wait_state(p_efc, ul_fws_temp); + + return FLASH_RC_OK; +} + + +/** + * \brief Lock all the regions in the given address range. The actual lock + * range is reported through two output parameters. + * + * \param ul_start Start address of lock range. + * \param ul_end End address of lock range. + * \param pul_actual_start Start address of the actual lock range (optional). + * \param pul_actual_end End address of the actual lock range (optional). + * + * \return 0 if successful, otherwise returns an error code. + */ +uint32_t flash_lock(uint32_t ul_start, uint32_t ul_end, + uint32_t *pul_actual_start, uint32_t *pul_actual_end) +{ + Efc *p_efc; + uint32_t ul_actual_start, ul_actual_end; + uint16_t us_start_page, us_end_page; + uint32_t ul_error; + uint16_t us_num_pages_in_region = + IFLASH_LOCK_REGION_SIZE / IFLASH_PAGE_SIZE; + + /* Compute actual lock range and store it */ + compute_lock_range(ul_start, ul_end, &ul_actual_start, &ul_actual_end); + + if (pul_actual_start != NULL) { + *pul_actual_start = ul_actual_start; + } + + if (pul_actual_end != NULL) { + *pul_actual_end = ul_actual_end; + } + + /* Compute page numbers */ + translate_address(&p_efc, ul_actual_start, &us_start_page, 0); + translate_address(0, ul_actual_end, &us_end_page, 0); + + /* Lock all pages */ + while (us_start_page < us_end_page) { + ul_error = efc_perform_command(p_efc, EFC_FCMD_SLB, us_start_page); + + if (ul_error) { + return ul_error; + } + us_start_page += us_num_pages_in_region; + } + + return FLASH_RC_OK; +} + +/** + * \brief Unlock all the regions in the given address range. The actual unlock + * range is reported through two output parameters. + * + * \param ul_start Start address of unlock range. + * \param ul_end End address of unlock range. + * \param pul_actual_start Start address of the actual unlock range (optional). + * \param pul_actual_end End address of the actual unlock range (optional). + * + * \return 0 if successful, otherwise returns an error code. + */ +uint32_t flash_unlock(uint32_t ul_start, uint32_t ul_end, + uint32_t *pul_actual_start, uint32_t *pul_actual_end) +{ + Efc *p_efc; + uint32_t ul_actual_start, ul_actual_end; + uint16_t us_start_page, us_end_page; + uint32_t ul_error; + uint16_t us_num_pages_in_region = + IFLASH_LOCK_REGION_SIZE / IFLASH_PAGE_SIZE; + + /* Compute actual unlock range and store it */ + compute_lock_range(ul_start, ul_end, &ul_actual_start, &ul_actual_end); + if (pul_actual_start != NULL) { + *pul_actual_start = ul_actual_start; + } + if (pul_actual_end != NULL) { + *pul_actual_end = ul_actual_end; + } + + /* Compute page numbers */ + translate_address(&p_efc, ul_actual_start, &us_start_page, 0); + translate_address(0, ul_actual_end, &us_end_page, 0); + + /* Unlock all pages */ + while (us_start_page < us_end_page) { + ul_error = efc_perform_command(p_efc, EFC_FCMD_CLB, + us_start_page); + if (ul_error) { + return ul_error; + } + us_start_page += us_num_pages_in_region; + } + + return FLASH_RC_OK; +} + +/** + * \brief Get the number of locked regions inside the given address range. + * + * \param ul_start Start address of range + * \param ul_end End address of range. + * + * \return The number of locked regions inside the given address range. + */ +uint32_t flash_is_locked(uint32_t ul_start, uint32_t ul_end) +{ + Efc *p_efc; + uint16_t us_start_page, us_end_page; + uint8_t uc_start_region, uc_end_region; + uint16_t us_num_pages_in_region; + uint32_t ul_status; + uint32_t ul_error; + uint32_t ul_num_locked_regions = 0; + uint32_t ul_count = 0; + uint32_t ul_bit = 0; + + /* Compute page numbers */ + translate_address(&p_efc, ul_start, &us_start_page, 0); + translate_address(0, ul_end, &us_end_page, 0); + + /* Compute region numbers */ + us_num_pages_in_region = IFLASH_LOCK_REGION_SIZE / IFLASH_PAGE_SIZE; + uc_start_region = us_start_page / us_num_pages_in_region; + uc_end_region = us_end_page / us_num_pages_in_region; + + /* Retrieve lock status */ + ul_error = efc_perform_command(p_efc, EFC_FCMD_GLB, 0); + + /* Skip unrequested regions (if necessary) */ + ul_status = efc_get_result(p_efc); + while (!(ul_count <= uc_start_region && + uc_start_region < (ul_count + 32))) { + ul_status = efc_get_result(p_efc); + ul_count += 32; + } + + /* Check status of each involved region */ + ul_bit = uc_start_region - ul_count; + + /* Number of region to check (must be > 0) */ + ul_count = uc_end_region - uc_start_region + 1; + + while (ul_count > 0) { + if (ul_status & (1 << (ul_bit))) { + ul_num_locked_regions++; + } + + ul_count -= 1; + ul_bit += 1; + if (ul_bit == 32) { + ul_status = efc_get_result(p_efc); + ul_bit = 0; + } + } + + return ul_num_locked_regions; +} + +/** + * \brief Set the given GPNVM bit. + * + * \param ul_gpnvm GPNVM bit index. + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_set_gpnvm(uint32_t ul_gpnvm) +{ + if (ul_gpnvm >= GPNVM_NUM_MAX) { + return FLASH_RC_INVALID; + } + + if (FLASH_RC_YES == flash_is_gpnvm_set(ul_gpnvm)) { + return FLASH_RC_OK; + } + + if (EFC_RC_OK == efc_perform_command(EFC, EFC_FCMD_SGPB, ul_gpnvm)) { + return FLASH_RC_OK; + } + + return FLASH_RC_ERROR; +} + +/** + * \brief Clear the given GPNVM bit. + * + * \param ul_gpnvm GPNVM bit index. + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_clear_gpnvm(uint32_t ul_gpnvm) +{ + if (ul_gpnvm >= GPNVM_NUM_MAX) { + return FLASH_RC_INVALID; + } + + if (FLASH_RC_NO == flash_is_gpnvm_set(ul_gpnvm)) { + return FLASH_RC_OK; + } + + if (EFC_RC_OK == efc_perform_command(EFC, EFC_FCMD_CGPB, ul_gpnvm)) { + return FLASH_RC_OK; + } + + return FLASH_RC_ERROR; +} + +/** + * \brief Check if the given GPNVM bit is set or not. + * + * \param ul_gpnvm GPNVM bit index. + * + * \retval 1 If the given GPNVM bit is currently set. + * \retval 0 If the given GPNVM bit is currently cleared. + */ +uint32_t flash_is_gpnvm_set(uint32_t ul_gpnvm) +{ + uint32_t ul_gpnvm_bits; + + if (ul_gpnvm >= GPNVM_NUM_MAX) { + return FLASH_RC_INVALID; + } + + if (EFC_RC_OK != efc_perform_command(EFC, EFC_FCMD_GGPB, 0)) { + return FLASH_RC_ERROR; + } + + ul_gpnvm_bits = efc_get_result(EFC); + if (ul_gpnvm_bits & (1 << ul_gpnvm)) { + return FLASH_RC_YES; + } + + return FLASH_RC_NO; +} + +/** + * \brief Set security bit. + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_enable_security_bit(void) +{ + return flash_set_gpnvm(0); +} + +/** + * \brief Check if the security bit is set or not. + * + * \retval 1 If the security bit is currently set. + * \retval 0 If the security bit is currently cleared. + */ +uint32_t flash_is_security_bit_enabled(void) +{ + return flash_is_gpnvm_set(0); +} + +/** + * \brief Read the flash unique ID. + * + * \param pul_data Pointer to a data buffer to store 128-bit unique ID. + * \param ul_size Data buffer size in DWORD. + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_read_unique_id(uint32_t *pul_data, uint32_t ul_size) +{ + uint32_t uid_buf[4]; + uint32_t ul_idx; + + if (FLASH_RC_OK != efc_perform_read_sequence(EFC, EFC_FCMD_STUI, + EFC_FCMD_SPUI, uid_buf, 4)) { + return FLASH_RC_ERROR; + } + + if (ul_size > 4) { + /* Only 4 dword to store unique ID */ + ul_size = 4; + } + + for (ul_idx = 0; ul_idx < ul_size; ul_idx++) { + pul_data[ul_idx] = uid_buf[ul_idx]; + } + + return FLASH_RC_OK; +} + +#if (SAM4S || SAM4E) +/** + * \brief Read the flash user signature. + * + * \param p_data Pointer to a data buffer to store 512 bytes of user signature. + * \param ul_size Data buffer size. + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_read_user_signature(uint32_t *p_data, uint32_t ul_size) +{ + if (ul_size > FLASH_USER_SIG_SIZE) { + /* Only 512 byte to store unique ID */ + ul_size = FLASH_USER_SIG_SIZE; + } + + /* Send the read user signature commands */ + if (FLASH_RC_OK != efc_perform_read_sequence(EFC, EFC_FCMD_STUS, + EFC_FCMD_SPUS, p_data, ul_size)) { + return FLASH_RC_ERROR; + } + + return FLASH_RC_OK; +} + +/** + * \brief Write the flash user signature. + * + * \param ul_address Write address. + * \param p_data Pointer to a data buffer to store 512 bytes of user signature. + * \param ul_size Data buffer size. + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_write_user_signature(uint32_t ul_address, const void *p_buffer, + uint32_t ul_size) +{ + /* The user signature should be no longer than 512 bytes */ + if (ul_size > FLASH_USER_SIG_SIZE) { + return FLASH_RC_INVALID; + } + + /* Write the full page */ + flash_write(ul_address, p_buffer, ul_size, 0); + + /* Send the write signature command */ + if (FLASH_RC_OK != efc_perform_command(EFC, EFC_FCMD_WUS, 0)) { + return FLASH_RC_ERROR; + } + + return FLASH_RC_OK; +} + +/** + * \brief Erase the flash user signature. + * + * \return 0 if successful; otherwise returns an error code. + */ +uint32_t flash_erase_user_signature(void) +{ + /* Perform the erase user signature command */ + return efc_perform_command(EFC, EFC_FCMD_EUS, 0); +} +#endif + +//@} + +/// @cond 0 +/**INDENT-OFF**/ +#ifdef __cplusplus +} +#endif +/**INDENT-ON**/ +/// @endcond diff --git a/libraries/DueFlash/flash_efc.h b/libraries/DueFlash/flash_efc.h new file mode 100644 index 0000000..bd52033 --- /dev/null +++ b/libraries/DueFlash/flash_efc.h @@ -0,0 +1,151 @@ +/** + * \file + * + * \brief Embedded Flash service for SAM. + * + * Copyright (c) 2011-2013 Atmel Corporation. All rights reserved. + * + * \asf_license_start + * + * \page License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * 3. The name of Atmel may not be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * 4. This software may only be redistributed and used in connection with an + * Atmel microcontroller product. + * + * THIS SOFTWARE IS PROVIDED BY ATMEL "AS IS" AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NON-INFRINGEMENT ARE + * EXPRESSLY AND SPECIFICALLY DISCLAIMED. IN NO EVENT SHALL ATMEL BE LIABLE FOR + * ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS + * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) + * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, + * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * \asf_license_stop + * + */ + +#ifndef FLASH_H_INCLUDED +#define FLASH_H_INCLUDED + +#include +#include "efc.h" + +/* Internal Flash 0 base address. */ +#define IFLASH_ADDR IFLASH0_ADDR + /* Internal flash page size. */ +#define IFLASH_PAGE_SIZE IFLASH0_PAGE_SIZE + +/* Last page start address. */ +#define IFLASH_LAST_PAGE_ADDRESS (IFLASH1_ADDR + IFLASH1_SIZE - IFLASH1_PAGE_SIZE) + +/// @cond 0 +/**INDENT-OFF**/ +#ifdef __cplusplus + extern "C" { +#endif +/**INDENT-ON**/ +/// @endcond + +/*! \name Flash driver return codes */ +//! @{ +typedef enum flash_rc { + FLASH_RC_OK = 0, //!< Operation OK + FLASH_RC_YES = 0, //!< Yes + FLASH_RC_NO = 1, //!< No + FLASH_RC_ERROR = 0x10, //!< General error + FLASH_RC_INVALID, //!< Invalid argument input + FLASH_RC_NOT_SUPPORT = 0xFFFFFFFF //!< Operation is not supported +} flash_rc_t; +//! @} + +/*! \name Flash erase page num in FARG[1:0] + \note The erase page commands should be cautiouly used as EPA4/EPA32 will not + take effect according to errata and EPA8/EPA16 must module 8/16 page addresses.*/ +//! @{ +typedef enum flash_farg_page_num { + /* 4 of pages to be erased with EPA command*/ + IFLASH_ERASE_PAGES_4=0, + /* 8 of pages to be erased with EPA command*/ + IFLASH_ERASE_PAGES_8, + /* 16 of pages to be erased with EPA command*/ + IFLASH_ERASE_PAGES_16, + /* 32 of pages to be erased with EPA command*/ + IFLASH_ERASE_PAGES_32, + /* Parameter is not support */ + IFLASH_ERASE_PAGES_INVALID, +}flash_farg_page_num_t; +//! @} + +/*! \name Flash access mode */ +//! @{ +#define FLASH_ACCESS_MODE_128 EFC_ACCESS_MODE_128 +#define FLASH_ACCESS_MODE_64 EFC_ACCESS_MODE_64 +//! @} + +uint32_t flash_init(uint32_t ul_mode, uint32_t ul_fws); +uint32_t flash_set_wait_state(uint32_t ul_address, uint32_t ul_fws); +uint32_t flash_set_wait_state_adaptively(uint32_t ul_address); +uint32_t flash_get_wait_state(uint32_t ul_address); +uint32_t flash_get_descriptor(uint32_t ul_address, + uint32_t *pul_flash_descriptor, uint32_t ul_size); +uint32_t flash_get_page_count(const uint32_t *pul_flash_descriptor); +uint32_t flash_get_page_count_per_region(const uint32_t *pul_flash_descriptor); +uint32_t flash_get_region_count(const uint32_t *pul_flash_descriptor); +uint32_t flash_erase_all(uint32_t ul_address); + +#if SAM3SD8 +uint32_t flash_erase_plane(uint32_t ul_address); +#endif + +#if (SAM4S || SAM4E) +uint32_t flash_erase_page(uint32_t ul_address, uint8_t uc_page_num); +uint32_t flash_erase_sector(uint32_t ul_address); +#endif + +uint32_t flash_write(uint32_t ul_address, const void *p_buffer, + uint32_t ul_size, uint32_t ul_erase_flag); +uint32_t flash_lock(uint32_t ul_start, uint32_t ul_end, + uint32_t *pul_actual_start, uint32_t *pul_actual_end); +uint32_t flash_unlock(uint32_t ul_start, uint32_t ul_end, + uint32_t *pul_actual_start, uint32_t *pul_actual_end); +uint32_t flash_is_locked(uint32_t ul_start, uint32_t ul_end); +uint32_t flash_set_gpnvm(uint32_t ul_gpnvm); +uint32_t flash_clear_gpnvm(uint32_t ul_gpnvm); +uint32_t flash_is_gpnvm_set(uint32_t ul_gpnvm); +uint32_t flash_enable_security_bit(void); +uint32_t flash_is_security_bit_enabled(void); +uint32_t flash_read_unique_id(uint32_t *pul_data, uint32_t ul_size); + +#if (SAM4S || SAM4E) +uint32_t flash_read_user_signature(uint32_t *p_data, uint32_t ul_size); +uint32_t flash_write_user_signature(uint32_t ul_address, const void *p_buffer, + uint32_t ul_size); +uint32_t flash_erase_user_signature(void); +#endif + +/// @cond 0 +/**INDENT-OFF**/ +#ifdef __cplusplus +} +#endif +/**INDENT-ON**/ +/// @endcond + +#endif /* FLASH_H_INCLUDED */ diff --git a/libraries/EEPROM/EEPROM.cpp b/libraries/EEPROM/EEPROM.cpp new file mode 100644 index 0000000..dfa1deb --- /dev/null +++ b/libraries/EEPROM/EEPROM.cpp @@ -0,0 +1,50 @@ +/* + EEPROM.cpp - EEPROM library + Copyright (c) 2006 David A. Mellis. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +/****************************************************************************** + * Includes + ******************************************************************************/ + +#include +#include "Arduino.h" +#include "EEPROM.h" + +/****************************************************************************** + * Definitions + ******************************************************************************/ + +/****************************************************************************** + * Constructors + ******************************************************************************/ + +/****************************************************************************** + * User API + ******************************************************************************/ + +uint8_t EEPROMClass::read(int address) +{ + return eeprom_read_byte((unsigned char *) address); +} + +void EEPROMClass::write(int address, uint8_t value) +{ + eeprom_write_byte((unsigned char *) address, value); +} + +EEPROMClass EEPROM; diff --git a/libraries/EEPROM/EEPROM.h b/libraries/EEPROM/EEPROM.h new file mode 100644 index 0000000..aa2b577 --- /dev/null +++ b/libraries/EEPROM/EEPROM.h @@ -0,0 +1,35 @@ +/* + EEPROM.h - EEPROM library + Copyright (c) 2006 David A. Mellis. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#ifndef EEPROM_h +#define EEPROM_h + +#include + +class EEPROMClass +{ + public: + uint8_t read(int); + void write(int, uint8_t); +}; + +extern EEPROMClass EEPROM; + +#endif + diff --git a/libraries/EEPROM/examples/eeprom_clear/eeprom_clear.ino b/libraries/EEPROM/examples/eeprom_clear/eeprom_clear.ino new file mode 100644 index 0000000..d1e29bd --- /dev/null +++ b/libraries/EEPROM/examples/eeprom_clear/eeprom_clear.ino @@ -0,0 +1,23 @@ +/* + * EEPROM Clear + * + * Sets all of the bytes of the EEPROM to 0. + * This example code is in the public domain. + + */ + +#include + +void setup() +{ + // write a 0 to all 512 bytes of the EEPROM + for (int i = 0; i < 512; i++) + EEPROM.write(i, 0); + + // turn the LED on when we're done + digitalWrite(13, HIGH); +} + +void loop() +{ +} diff --git a/libraries/EEPROM/examples/eeprom_read/eeprom_read.ino b/libraries/EEPROM/examples/eeprom_read/eeprom_read.ino new file mode 100644 index 0000000..0709b2d --- /dev/null +++ b/libraries/EEPROM/examples/eeprom_read/eeprom_read.ino @@ -0,0 +1,43 @@ +/* + * EEPROM Read + * + * Reads the value of each byte of the EEPROM and prints it + * to the computer. + * This example code is in the public domain. + */ + +#include + +// start reading from the first byte (address 0) of the EEPROM +int address = 0; +byte value; + +void setup() +{ + // initialize serial and wait for port to open: + Serial.begin(9600); + while (!Serial) { + ; // wait for serial port to connect. Needed for Leonardo only + } +} + +void loop() +{ + // read a byte from the current address of the EEPROM + value = EEPROM.read(address); + + Serial.print(address); + Serial.print("\t"); + Serial.print(value, DEC); + Serial.println(); + + // advance to the next address of the EEPROM + address = address + 1; + + // there are only 512 bytes of EEPROM, from 0 to 511, so if we're + // on address 512, wrap around to address 0 + if (address == 512) + address = 0; + + delay(500); +} diff --git a/libraries/EEPROM/examples/eeprom_write/eeprom_write.ino b/libraries/EEPROM/examples/eeprom_write/eeprom_write.ino new file mode 100644 index 0000000..ae7c57e --- /dev/null +++ b/libraries/EEPROM/examples/eeprom_write/eeprom_write.ino @@ -0,0 +1,38 @@ +/* + * EEPROM Write + * + * Stores values read from analog input 0 into the EEPROM. + * These values will stay in the EEPROM when the board is + * turned off and may be retrieved later by another sketch. + */ + +#include + +// the current address in the EEPROM (i.e. which byte +// we're going to write to next) +int addr = 0; + +void setup() +{ +} + +void loop() +{ + // need to divide by 4 because analog inputs range from + // 0 to 1023 and each byte of the EEPROM can only hold a + // value from 0 to 255. + int val = analogRead(0) / 4; + + // write the value to the appropriate byte of the EEPROM. + // these values will remain there when the board is + // turned off. + EEPROM.write(addr, val); + + // advance to the next address. there are 512 bytes in + // the EEPROM, so go back to 0 when we hit 512. + addr = addr + 1; + if (addr == 512) + addr = 0; + + delay(100); +} diff --git a/libraries/EEPROM/keywords.txt b/libraries/EEPROM/keywords.txt new file mode 100644 index 0000000..d3218fe --- /dev/null +++ b/libraries/EEPROM/keywords.txt @@ -0,0 +1,18 @@ +####################################### +# Syntax Coloring Map For Ultrasound +####################################### + +####################################### +# Datatypes (KEYWORD1) +####################################### + +EEPROM KEYWORD1 + +####################################### +# Methods and Functions (KEYWORD2) +####################################### + +####################################### +# Constants (LITERAL1) +####################################### + diff --git a/libraries/FingerPrint/Adafruit_Fingerprint.cpp b/libraries/FingerPrint/Adafruit_Fingerprint.cpp new file mode 100644 index 0000000..45b232d --- /dev/null +++ b/libraries/FingerPrint/Adafruit_Fingerprint.cpp @@ -0,0 +1,283 @@ +/*************************************************** + This is a library for our optical Fingerprint sensor + + Designed specifically to work with the Adafruit BMP085 Breakout + ----> http://www.adafruit.com/products/751 + + These displays use TTL Serial to communicate, 2 pins are required to + interface + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + Written by Limor Fried/Ladyada for Adafruit Industries. + BSD license, all text above must be included in any redistribution + ****************************************************/ + +#include "Adafruit_Fingerprint.h" +#include +#if (ARDUINO >= 100) + #include +#else + #include +#endif + +#include + +//static SoftwareSerial mySerial = SoftwareSerial(2, 3); + +Adafruit_Fingerprint::Adafruit_Fingerprint(SoftwareSerial *ss) { + + thePassword = 0x0; + theAddress = 0xFFFFFFFF; + + mySerial = ss; +} + + +void Adafruit_Fingerprint::begin(uint16_t baudrate) { + mySerial->begin(baudrate); +} + +boolean Adafruit_Fingerprint::verifyPassword(void) +{ + uint8_t packet[] = {FINGERPRINT_VERIFYPASSWORD, + (thePassword >> 24), (thePassword >> 16), + (thePassword >> 8), thePassword}; + writePacket(theAddress, FINGERPRINT_COMMANDPACKET, 7, packet); + int len = getReply(packet); + + if(0xff == len) + { + //cout << "time out" << endl; + return false; + } + //cout << "len = " << len << endl; + //cout << "packer[0] = " << packet[0] << '\t' << "packet[1] = " << packet[1] << endl; + if ((len == 1) && (packet[0] == FINGERPRINT_ACKPACKET) && (packet[1] == FINGERPRINT_OK)) + return true; + + return false; +} + +uint8_t Adafruit_Fingerprint::getImage(void) { + uint8_t packet[] = {FINGERPRINT_GETIMAGE}; + writePacket(theAddress, FINGERPRINT_COMMANDPACKET, 3, packet); + uint8_t len = getReply(packet); + + if ((len != 1) && (packet[0] != FINGERPRINT_ACKPACKET)) + return -1; + return packet[1]; +} + +uint8_t Adafruit_Fingerprint::image2Tz(uint8_t slot) { + uint8_t packet[] = {FINGERPRINT_IMAGE2TZ, slot}; + writePacket(theAddress, FINGERPRINT_COMMANDPACKET, sizeof(packet)+2, packet); + uint8_t len = getReply(packet); + + if ((len != 1) && (packet[0] != FINGERPRINT_ACKPACKET)) + return -1; + return packet[1]; +} + + +void Adafruit_Fingerprint::setKey(unsigned long key_t) +{ + thePassword = key_t; +} +void Adafruit_Fingerprint::setAddr(unsigned long addr_t) +{ + theAddress = addr_t; +} +uint8_t Adafruit_Fingerprint::createModel(void) { + uint8_t packet[] = {FINGERPRINT_REGMODEL}; + writePacket(theAddress, FINGERPRINT_COMMANDPACKET, sizeof(packet)+2, packet); + uint8_t len = getReply(packet); + + if ((len != 1) && (packet[0] != FINGERPRINT_ACKPACKET)) + return -1; + return packet[1]; +} + + +uint8_t Adafruit_Fingerprint::storeModel(uint16_t id) { + uint8_t packet[] = {FINGERPRINT_STORE, 0x01, id >> 8, id & 0xFF}; + writePacket(theAddress, FINGERPRINT_COMMANDPACKET, sizeof(packet)+2, packet); + uint8_t len = getReply(packet); + + if ((len != 1) && (packet[0] != FINGERPRINT_ACKPACKET)) + return -1; + return packet[1]; +} + +uint8_t Adafruit_Fingerprint::emptyDatabase(void) { + uint8_t packet[] = {FINGERPRINT_EMPTY}; + writePacket(theAddress, FINGERPRINT_COMMANDPACKET, sizeof(packet)+2, packet); + uint8_t len = getReply(packet); + + if ((len != 1) && (packet[0] != FINGERPRINT_ACKPACKET)) + return -1; + return packet[1]; +} + +uint8_t Adafruit_Fingerprint::fingerFastSearch(void) { + fingerID = 0xFFFF; + confidence = 0xFFFF; + // high speed search of slot #1 starting at page 0x0000 and page #0x00A3 + uint8_t packet[] = {FINGERPRINT_HISPEEDSEARCH, 0x01, 0x00, 0x00, 0x00, 0xA3}; + writePacket(theAddress, FINGERPRINT_COMMANDPACKET, sizeof(packet)+2, packet); + uint8_t len = getReply(packet); + + if ((len != 1) && (packet[0] != FINGERPRINT_ACKPACKET)) + return -1; + + fingerID = packet[2]; + fingerID <<= 8; + fingerID |= packet[3]; + + confidence = packet[4]; + confidence <<= 8; + confidence |= packet[5]; + + return packet[1]; +} + +uint8_t Adafruit_Fingerprint::getTemplateCount(void) { + templateCount = 0xFFFF; + // get number of templates in memory + uint8_t packet[] = {FINGERPRINT_TEMPLATECOUNT}; + writePacket(theAddress, FINGERPRINT_COMMANDPACKET, sizeof(packet)+2, packet); + uint8_t len = getReply(packet); + + if ((len != 1) && (packet[0] != FINGERPRINT_ACKPACKET)) + return -1; + + templateCount = packet[2]; + templateCount <<= 8; + templateCount |= packet[3]; + + return packet[1]; +} + +void Adafruit_Fingerprint::writePacket(uint32_t addr, uint8_t packettype, uint16_t len, uint8_t *packet) { +#ifdef FINGERPRINT_DEBUG + Serial.print("---> 0x"); + Serial.print((uint8_t)(FINGERPRINT_STARTCODE >> 8), HEX); + Serial.print(" 0x"); + Serial.print((uint8_t)FINGERPRINT_STARTCODE, HEX); + Serial.print(" 0x"); + Serial.print((uint8_t)(addr >> 24), HEX); + Serial.print(" 0x"); + Serial.print((uint8_t)(addr >> 16), HEX); + Serial.print(" 0x"); + Serial.print((uint8_t)(addr >> 8), HEX); + Serial.print(" 0x"); + Serial.print((uint8_t)(addr), HEX); + Serial.print(" 0x"); + Serial.print((uint8_t)packettype, HEX); + Serial.print(" 0x"); + Serial.print((uint8_t)(len >> 8), HEX); + Serial.print(" 0x"); + Serial.print((uint8_t)(len), HEX); +#endif + + + mySerial->write((uint8_t)(FINGERPRINT_STARTCODE >> 8)); + mySerial->write((uint8_t)FINGERPRINT_STARTCODE); + mySerial->write((uint8_t)(addr >> 24)); + mySerial->write((uint8_t)(addr >> 16)); + mySerial->write((uint8_t)(addr >> 8)); + mySerial->write((uint8_t)(addr)); + mySerial->write((uint8_t)packettype); + mySerial->write((uint8_t)(len >> 8)); + mySerial->write((uint8_t)(len)); + + uint16_t sum = (len>>8) + (len&0xFF) + packettype; + for (uint8_t i=0; i< len-2; i++) { + + mySerial->write((uint8_t)(packet[i])); +#ifdef FINGERPRINT_DEBUG + Serial.print(" 0x"); Serial.print(packet[i], HEX); +#endif + sum += packet[i]; + } +#ifdef FINGERPRINT_DEBUG + //Serial.print("Checksum = 0x"); Serial.println(sum); + Serial.print(" 0x"); Serial.print((uint8_t)(sum>>8), HEX); + Serial.print(" 0x"); Serial.println((uint8_t)(sum), HEX); +#endif +#if ARDUINO >= 100 + mySerial->write((uint8_t)(sum>>8)); + mySerial->write((uint8_t)sum); + + // cout << "sum = " << sum << endl; +#else + mySerial->print((uint8_t)(sum>>8), BYTE); + mySerial->print((uint8_t)sum, BYTE); +#endif +} + + +uint8_t Adafruit_Fingerprint::getReply(uint8_t packet[], uint16_t timeout) +{ + uint8_t reply[20], idx; + uint16_t timer=0; + + idx = 0; +#ifdef FINGERPRINT_DEBUG + Serial.print("<--- "); +#endif + while (true) + { + while (!mySerial->available()) + { + delay(1); + timer++; + if (timer >= timeout) return FINGERPRINT_TIMEOUT; + } + // something to read! + + reply[idx] = mySerial->read(); + +#ifdef FINGERPRINT_DEBUG + Serial.print(" 0x"); Serial.print(reply[idx], HEX); +#endif + if ((idx == 0) && (reply[0] != (FINGERPRINT_STARTCODE >> 8))) // wait head + { + continue; + } + + idx++; + + // check packet! + if (idx >= 9) + { + if ( (reply[0] != (FINGERPRINT_STARTCODE >> 8)) || (reply[1] != (FINGERPRINT_STARTCODE & 0xFF)) ) // head err + { + return FINGERPRINT_BADPACKET; + } + + uint8_t packettype = reply[6]; + + uint16_t len = reply[7]; + + len <<= 8; + len |= reply[8]; + + len -= 2; // packge len without checksum + + if (idx <= (len+10)) continue; + + packet[0] = packettype; + for (uint8_t i=0; i http://www.adafruit.com/products/751 + + These displays use TTL Serial to communicate, 2 pins are required to + interface + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + Written by Limor Fried/Ladyada for Adafruit Industries. + BSD license, all text above must be included in any redistribution + ****************************************************/ + +#if (ARDUINO >= 100) + #include "Arduino.h" + #include +#else + #include "WProgram.h" + #include +#endif + + +#define FINGERPRINT_OK 0x00 +#define FINGERPRINT_PACKETRECIEVEERR 0x01 +#define FINGERPRINT_NOFINGER 0x02 +#define FINGERPRINT_IMAGEFAIL 0x03 +#define FINGERPRINT_IMAGEMESS 0x06 +#define FINGERPRINT_FEATUREFAIL 0x07 +#define FINGERPRINT_NOMATCH 0x08 +#define FINGERPRINT_NOTFOUND 0x09 +#define FINGERPRINT_ENROLLMISMATCH 0x0A +#define FINGERPRINT_BADLOCATION 0x0B +#define FINGERPRINT_DBRANGEFAIL 0x0C +#define FINGERPRINT_UPLOADFEATUREFAIL 0x0D +#define FINGERPRINT_PACKETRESPONSEFAIL 0x0E +#define FINGERPRINT_UPLOADFAIL 0x0F +#define FINGERPRINT_DELETEFAIL 0x10 +#define FINGERPRINT_DBCLEARFAIL 0x11 +#define FINGERPRINT_PASSFAIL 0x13 +#define FINGERPRINT_INVALIDIMAGE 0x15 +#define FINGERPRINT_FLASHERR 0x18 +#define FINGERPRINT_INVALIDREG 0x1A +#define FINGERPRINT_ADDRCODE 0x20 +#define FINGERPRINT_PASSVERIFY 0x21 + +#define FINGERPRINT_STARTCODE 0xEF01 + +#define FINGERPRINT_COMMANDPACKET 0x1 +#define FINGERPRINT_DATAPACKET 0x2 +#define FINGERPRINT_ACKPACKET 0x7 +#define FINGERPRINT_ENDDATAPACKET 0x8 + +#define FINGERPRINT_TIMEOUT 0xFF +#define FINGERPRINT_BADPACKET 0xFE + +#define FINGERPRINT_GETIMAGE 0x01 +#define FINGERPRINT_IMAGE2TZ 0x02 +#define FINGERPRINT_REGMODEL 0x05 +#define FINGERPRINT_STORE 0x06 +#define FINGERPRINT_EMPTY 0x0D +#define FINGERPRINT_VERIFYPASSWORD 0x13 +#define FINGERPRINT_HISPEEDSEARCH 0x1B +#define FINGERPRINT_TEMPLATECOUNT 0x1D + +//#define FINGERPRINT_DEBUG + +#define DEFAULTTIMEOUT 5000 // milliseconds + + +class Adafruit_Fingerprint { + +public: +#if ARDUINO >= 100 + Adafruit_Fingerprint(SoftwareSerial *); +#else + Adafruit_Fingerprint(NewSoftSerial *); +#endif + void begin(uint16_t baud); + + boolean verifyPassword(void); + uint8_t getImage(void); + uint8_t image2Tz(uint8_t slot = 1); + uint8_t createModel(void); + uint8_t emptyDatabase(void); + uint8_t storeModel(uint16_t id); + uint8_t fingerFastSearch(void); + uint8_t getTemplateCount(void); + void writePacket(uint32_t addr, uint8_t packettype, uint16_t len, uint8_t *packet); + uint8_t getReply(uint8_t packet[], uint16_t timeout=DEFAULTTIMEOUT); + + uint16_t fingerID, confidence, templateCount; + + void setKey(unsigned long key_t); + void setAddr(unsigned long addr_t); + +private: + uint32_t thePassword; + uint32_t theAddress; +#if ARDUINO >= 100 + SoftwareSerial *mySerial; +#else + NewSoftSerial *mySerial; +#endif +}; diff --git a/libraries/FingerPrint/examples/blank/blank.ino b/libraries/FingerPrint/examples/blank/blank.ino new file mode 100644 index 0000000..f06909c --- /dev/null +++ b/libraries/FingerPrint/examples/blank/blank.ino @@ -0,0 +1,11 @@ +// this sketch will allow you to bypass the Atmega chip +// and connect the fingerprint sensor directly to the USB/Serial +// chip converter. + +// Red connects to +5V +// Black connects to Ground +// White goes to Digital 0 +// Green goes to Digital 1 + +void setup() {} +void loop() {} diff --git a/libraries/FingerPrint/examples/enroll/enroll.ino b/libraries/FingerPrint/examples/enroll/enroll.ino new file mode 100644 index 0000000..f043479 --- /dev/null +++ b/libraries/FingerPrint/examples/enroll/enroll.ino @@ -0,0 +1,206 @@ +/*************************************************** + This is an example sketch for our optical Fingerprint sensor + + Designed specifically to work with the Adafruit BMP085 Breakout + ----> http://www.adafruit.com/products/751 + + These displays use TTL Serial to communicate, 2 pins are required to + interface + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + Written by Limor Fried/Ladyada for Adafruit Industries. + BSD license, all text above must be included in any redistribution + ****************************************************/ + +#include +#include +#if ARDUINO >= 100 + #include +#else + #include +#endif + +uint8_t getFingerprintEnroll(uint8_t id); + + +// pin #2 is IN from sensor (GREEN wire) +// pin #3 is OUT from arduino (WHITE wire) +#if ARDUINO >= 100 +SoftwareSerial mySerial(A5, A4);// tx, rx +#else +NewSoftSerial mySerial(2, 3); +#endif + +Adafruit_Fingerprint finger = Adafruit_Fingerprint(&mySerial); + +void setup() +{ + Serial.begin(38400); + Serial.println("fingertest"); + + // set the data rate for the sensor serial port + finger.begin(19200); + + if (finger.verifyPassword()) { + Serial.println("Found fingerprint sensor!"); + } else { + Serial.println("Did not find fingerprint sensor :("); + while (1); + } +} + +void loop() // run over and over again +{ + Serial.println("Type in the ID # you want to save this finger as..."); + uint8_t id = 0; + while (true) { + while (! Serial.available()); + char c = Serial.read(); + if (! isdigit(c)) break; + id *= 10; + id += c - '0'; + } + Serial.print("Enrolling ID #"); + Serial.println(id); + + while (! getFingerprintEnroll(id) ); +} + +uint8_t getFingerprintEnroll(uint8_t id) +{ + uint8_t p = -1; + Serial.println("Waiting for valid finger to enroll"); + while (p != FINGERPRINT_OK) { + p = finger.getImage(); + switch (p) { + case FINGERPRINT_OK: + Serial.println("Image taken"); + break; + case FINGERPRINT_NOFINGER: + //Serial.println("."); + break; + case FINGERPRINT_PACKETRECIEVEERR: + Serial.println("Communication error"); + break; + case FINGERPRINT_IMAGEFAIL: + Serial.println("Imaging error"); + break; + default: + Serial.println("Unknown error"); + break; + } + } + + // OK success! + + p = finger.image2Tz(1); + switch (p) { + case FINGERPRINT_OK: + Serial.println("Image converted"); + break; + case FINGERPRINT_IMAGEMESS: + Serial.println("Image too messy"); + return p; + case FINGERPRINT_PACKETRECIEVEERR: + Serial.println("Communication error"); + return p; + case FINGERPRINT_FEATUREFAIL: + Serial.println("Could not find fingerprint features"); + return p; + case FINGERPRINT_INVALIDIMAGE: + Serial.println("Could not find fingerprint features"); + return p; + default: + Serial.println("Unknown error"); + return p; + } + + Serial.println("Remove finger"); + delay(2000); + p = 0; + while (p != FINGERPRINT_NOFINGER) { + p = finger.getImage(); + } + + p = -1; + Serial.println("Place same finger again"); + while (p != FINGERPRINT_OK) { + p = finger.getImage(); + switch (p) { + case FINGERPRINT_OK: + Serial.println("Image taken"); + break; + case FINGERPRINT_NOFINGER: + //Serial.print("."); + break; + case FINGERPRINT_PACKETRECIEVEERR: + Serial.println("Communication error"); + break; + case FINGERPRINT_IMAGEFAIL: + Serial.println("Imaging error"); + break; + default: + Serial.println("Unknown error"); + break; + } + } + + // OK success! + + p = finger.image2Tz(2); + switch (p) { + case FINGERPRINT_OK: + Serial.println("Image converted"); + break; + case FINGERPRINT_IMAGEMESS: + Serial.println("Image too messy"); + return p; + case FINGERPRINT_PACKETRECIEVEERR: + Serial.println("Communication error"); + return p; + case FINGERPRINT_FEATUREFAIL: + Serial.println("Could not find fingerprint features"); + return p; + case FINGERPRINT_INVALIDIMAGE: + Serial.println("Could not find fingerprint features"); + return p; + default: + Serial.println("Unknown error"); + return p; + } + + + // OK converted! + p = finger.createModel(); + if (p == FINGERPRINT_OK) { + Serial.println("Prints matched!"); + } else if (p == FINGERPRINT_PACKETRECIEVEERR) { + Serial.println("Communication error"); + return p; + } else if (p == FINGERPRINT_ENROLLMISMATCH) { + Serial.println("Fingerprints did not match"); + return p; + } else { + Serial.println("Unknown error"); + return p; + } + + p = finger.storeModel(id); + if (p == FINGERPRINT_OK) { + Serial.println("Stored!"); + } else if (p == FINGERPRINT_PACKETRECIEVEERR) { + Serial.println("Communication error"); + return p; + } else if (p == FINGERPRINT_BADLOCATION) { + Serial.println("Could not store in that location"); + return p; + } else if (p == FINGERPRINT_FLASHERR) { + Serial.println("Error writing to flash"); + return p; + } else { + Serial.println("Unknown error"); + return p; + } +} diff --git a/libraries/FingerPrint/examples/fingerprint/fingerprint.ino b/libraries/FingerPrint/examples/fingerprint/fingerprint.ino new file mode 100644 index 0000000..e2ecc05 --- /dev/null +++ b/libraries/FingerPrint/examples/fingerprint/fingerprint.ino @@ -0,0 +1,180 @@ +/*************************************************** + This is an example sketch for our optical Fingerprint sensor + + Designed specifically to work with the Adafruit BMP085 Breakout + ----> http://www.adafruit.com/products/751 + + These displays use TTL Serial to communicate, 2 pins are required to + interface + Adafruit invests time and resources providing this open source code, + please support Adafruit and open-source hardware by purchasing + products from Adafruit! + + Written by Limor Fried/Ladyada for Adafruit Industries. + BSD license, all text above must be included in any redistribution + ****************************************************/ + + +#include +#if ARDUINO >= 100 + #include +#else + #include +#endif + +#include + +int getFingerprintIDez(); + +// pin #2 is IN from sensor (GREEN wire) +// pin #3 is OUT from arduino (WHITE wire) +#if ARDUINO >= 100 +SoftwareSerial mySerial(A5, A4);// tx, rx +#else +NewSoftSerial mySerial(2, 3); +#endif + +Adafruit_Fingerprint finger = Adafruit_Fingerprint(&mySerial); + +#include + +Servo myservo; // create servo object to control a servo + +void doorOpen() +{ + myservo.attach(9); + for(int i=20; i<100; i++) + { + myservo.write(i); + delay(5); + } + myservo.detach(); +} + +void doorClose() +{ + myservo.attach(9); + for(int i=99; i>=20; i--) + { + myservo.write(i); + delay(5); + } + myservo.detach(); +} + + +void setup() +{ + Serial.begin(38400); + Serial.println("fingertest"); + + pinMode(A2, OUTPUT); + + digitalWrite(A2, HIGH); + delay(1000); + digitalWrite(A2, LOW); + + // set the data rate for the sensor serial port + finger.begin(19200); + + if (finger.verifyPassword()) { + Serial.println("Found fingerprint sensor!"); + } else { + Serial.println("Did not find fingerprint sensor :("); + while (1); + } + Serial.println("Waiting for valid finger..."); +} + +void loop() // run over and over again +{ + if(getFingerprintIDez()>=0) + { + doorOpen(); + delay(2000); + doorClose(); + } + + //delay(1000); +} + +uint8_t getFingerprintID() { + uint8_t p = finger.getImage(); + switch (p) { + case FINGERPRINT_OK: + Serial.println("Image taken"); + break; + case FINGERPRINT_NOFINGER: + Serial.println("No finger detected"); + return p; + case FINGERPRINT_PACKETRECIEVEERR: + Serial.println("Communication error"); + return p; + case FINGERPRINT_IMAGEFAIL: + Serial.println("Imaging error"); + return p; + default: + Serial.println("Unknown error"); + return p; + } + + // OK success! + + p = finger.image2Tz(); + switch (p) { + case FINGERPRINT_OK: + Serial.println("Image converted"); + break; + case FINGERPRINT_IMAGEMESS: + Serial.println("Image too messy"); + return p; + case FINGERPRINT_PACKETRECIEVEERR: + Serial.println("Communication error"); + return p; + case FINGERPRINT_FEATUREFAIL: + Serial.println("Could not find fingerprint features"); + return p; + case FINGERPRINT_INVALIDIMAGE: + Serial.println("Could not find fingerprint features"); + return p; + default: + Serial.println("Unknown error"); + return p; + } + + // OK converted! + p = finger.fingerFastSearch(); + if (p == FINGERPRINT_OK) { + Serial.println("Found a print match!"); + } else if (p == FINGERPRINT_PACKETRECIEVEERR) { + Serial.println("Communication error"); + return p; + } else if (p == FINGERPRINT_NOTFOUND) { + Serial.println("Did not find a match"); + return p; + } else { + Serial.println("Unknown error"); + return p; + } + + // found a match! + Serial.print("Found ID #"); Serial.print(finger.fingerID); + Serial.print(" with confidence of "); Serial.println(finger.confidence); +} + +// returns -1 if failed, otherwise returns ID # +int getFingerprintIDez() { + uint8_t p = finger.getImage(); + if (p != FINGERPRINT_OK) return -1; + + p = finger.image2Tz(); + if (p != FINGERPRINT_OK) return -1; + + p = finger.fingerFastSearch(); + if (p != FINGERPRINT_OK) return -1; + + // found a match! + Serial.print("Found ID #"); Serial.print(finger.fingerID); + Serial.print(" with confidence of "); Serial.println(finger.confidence); + return finger.fingerID; +} \ No newline at end of file diff --git a/libraries/FingerPrint/license.txt b/libraries/FingerPrint/license.txt new file mode 100644 index 0000000..f6a0f22 --- /dev/null +++ b/libraries/FingerPrint/license.txt @@ -0,0 +1,26 @@ +Software License Agreement (BSD License) + +Copyright (c) 2012, Adafruit Industries +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: +1. Redistributions of source code must retain the above copyright +notice, this list of conditions and the following disclaimer. +2. Redistributions in binary form must reproduce the above copyright +notice, this list of conditions and the following disclaimer in the +documentation and/or other materials provided with the distribution. +3. Neither the name of the copyright holders nor the +names of its contributors may be used to endorse or promote products +derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS ''AS IS'' AND ANY +EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY +DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/libraries/HMC5843/HMC5843.cpp b/libraries/HMC5843/HMC5843.cpp new file mode 100644 index 0000000..a31ea5a --- /dev/null +++ b/libraries/HMC5843/HMC5843.cpp @@ -0,0 +1,353 @@ +// I2Cdev library collection - HMC5843 I2C device class +// Based on Honeywell HMC5843 datasheet, 6/2010 (Form #900367) +// 8/22/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2011-08-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 "HMC5843.h" + +/** Default constructor, uses default I2C address. + * @see HMC5843_DEFAULT_ADDRESS + */ +HMC5843::HMC5843() { + devAddr = HMC5843_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see HMC5843_DEFAULT_ADDRESS + * @see HMC5843_ADDRESS + */ +HMC5843::HMC5843(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * This will prepare the magnetometer with default settings, ready for single- + * use mode (very low power requirements). Default settings include 8-sample + * averaging, 15 Hz data output rate, normal measurement bias, a,d 1090 gain (in + * terms of LSB/Gauss). Be sure to adjust any settings you need specifically + * after initialization, especially the gain settings if you happen to be seeing + * a lot of -4096 values (see the datasheet for mor information). + */ +void HMC5843::initialize() { + // write CONFIG_A register + I2Cdev::writeByte(devAddr, HMC5843_RA_CONFIG_A, + (HMC5843_RATE_10 << (HMC5843_CRA_RATE_BIT - HMC5843_CRA_RATE_LENGTH + 1)) | + (HMC5843_BIAS_NORMAL << (HMC5843_CRA_BIAS_BIT - HMC5843_CRA_BIAS_LENGTH + 1))); + + // write CONFIG_B register + setGain(HMC5843_GAIN_1300); + + // write MODE register + setMode(HMC5843_MODE_SINGLE); +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool HMC5843::testConnection() { + if (I2Cdev::readBytes(devAddr, HMC5843_RA_ID_A, 3, buffer) == 3) { + return (buffer[0] == 'H' && buffer[1] == '4' && buffer[2] == '3'); + } + return false; +} + +// CONFIG_A register + +/** Get data output rate value. + * The Table below shows all selectable output rates in continuous measurement + * mode. All three channels shall be measured within a given output rate. + * + * Value | Typical Data Output Rate (Hz) + * ------+------------------------------ + * 0 | 0.5 + * 1 | 1 + * 2 | 2 + * 3 | 5 + * 4 | 10 (Default) + * 5 | 20 + * 6 | 50 + * 7 | Not used + * + * @return Current rate of data output to registers + * @see HMC5843_RATE_10 + * @see HMC5843_RA_CONFIG_A + * @see HMC5843_CRA_RATE_BIT + * @see HMC5843_CRA_RATE_LENGTH + */ +uint8_t HMC5843::getDataRate() { + I2Cdev::readBits(devAddr, HMC5843_RA_CONFIG_A, HMC5843_CRA_RATE_BIT, HMC5843_CRA_RATE_LENGTH, buffer); + return buffer[0]; +} +/** Set data output rate value. + * @param rate Rate of data output to registers + * @see getDataRate() + * @see HMC5843_RATE_10 + * @see HMC5843_RA_CONFIG_A + * @see HMC5843_CRA_RATE_BIT + * @see HMC5843_CRA_RATE_LENGTH + */ +void HMC5843::setDataRate(uint8_t rate) { + I2Cdev::writeBits(devAddr, HMC5843_RA_CONFIG_A, HMC5843_CRA_RATE_BIT, HMC5843_CRA_RATE_LENGTH, rate); +} +/** Get measurement bias value. + * @return Current bias value (0-2 for normal/positive/negative respectively) + * @see HMC5843_BIAS_NORMAL + * @see HMC5843_RA_CONFIG_A + * @see HMC5843_CRA_BIAS_BIT + * @see HMC5843_CRA_BIAS_LENGTH + */ +uint8_t HMC5843::getMeasurementBias() { + I2Cdev::readBits(devAddr, HMC5843_RA_CONFIG_A, HMC5843_CRA_BIAS_BIT, HMC5843_CRA_BIAS_LENGTH, buffer); + return buffer[0]; +} +/** Set measurement bias value. + * @param bias New bias value (0-2 for normal/positive/negative respectively) + * @see HMC5843_BIAS_NORMAL + * @see HMC5843_RA_CONFIG_A + * @see HMC5843_CRA_BIAS_BIT + * @see HMC5843_CRA_BIAS_LENGTH + */ +void HMC5843::setMeasurementBias(uint8_t bias) { + I2Cdev::writeBits(devAddr, HMC5843_RA_CONFIG_A, HMC5843_CRA_BIAS_BIT, HMC5843_CRA_BIAS_LENGTH, bias); +} + +// CONFIG_B register + +/** Get magnetic field gain value. + * The table below shows nominal gain settings. Use the Gain column to convert + * counts to Gauss. Choose a lower gain value (higher GN#) when total field + * strength causes overflow in one of the data output registers (saturation). + * The data output range for all settings is 0xF800-0x07FF (-2048 - 2047). + * + * Value | Field Range | Gain (LSB/Gauss) + * ------+-------------+----------------- + * 0 | +/- 0.7 Ga | 1620 + * 1 | +/- 1.0 Ga | 1300 (Default) + * 2 | +/- 1.5 Ga | 970 + * 3 | +/- 2.0 Ga | 780 + * 4 | +/- 3.2 Ga | 530 + * 5 | +/- 3.8 Ga | 460 + * 6 | +/- 4.5 Ga | 390 + * 7 | +/- 6.5 Ga | 280 (Not recommended) + * + * @return Current magnetic field gain value + * @see HMC5843_GAIN_1300 + * @see HMC5843_RA_CONFIG_B + * @see HMC5843_CRB_GAIN_BIT + * @see HMC5843_CRB_GAIN_LENGTH + */ +uint8_t HMC5843::getGain() { + I2Cdev::readBits(devAddr, HMC5843_RA_CONFIG_B, HMC5843_CRB_GAIN_BIT, HMC5843_CRB_GAIN_LENGTH, buffer); + return buffer[0]; +} +/** Set magnetic field gain value. + * @param gain New magnetic field gain value + * @see getGain() + * @see HMC5843_RA_CONFIG_B + * @see HMC5843_CRB_GAIN_BIT + * @see HMC5843_CRB_GAIN_LENGTH + */ +void HMC5843::setGain(uint8_t gain) { + // use this method to guarantee that bits 4-0 are set to zero, which is a + // requirement specified in the datasheet; it's actually more efficient than + // using the I2Cdev.writeBits method + I2Cdev::writeByte(devAddr, HMC5843_RA_CONFIG_B, gain << (HMC5843_CRB_GAIN_BIT - HMC5843_CRB_GAIN_LENGTH + 1)); +} + +// MODE register + +/** Get measurement mode. + * In continuous-measurement mode, the device continuously performs measurements + * and places the result in the data register. RDY goes high when new data is + * placed in all three registers. After a power-on or a write to the mode or + * configuration register, the first measurement set is available from all three + * data output registers after a period of 2/fDO and subsequent measurements are + * available at a frequency of fDO, where fDO is the frequency of data output. + * + * When single-measurement mode (default) is selected, device performs a single + * measurement, sets RDY high and returned to idle mode. Mode register returns + * to idle mode bit values. The measurement remains in the data output register + * and RDY remains high until the data output register is read or another + * measurement is performed. + * + * @return Current measurement mode + * @see HMC5843_MODE_CONTINUOUS + * @see HMC5843_MODE_SINGLE + * @see HMC5843_MODE_IDLE + * @see HMC5843_MODE_SLEEP + * @see HMC5843_RA_MODE + * @see HMC5843_MODEREG_BIT + * @see HMC5843_MODEREG_LENGTH + */ +uint8_t HMC5843::getMode() { + I2Cdev::readBits(devAddr, HMC5843_RA_MODE, HMC5843_MODEREG_BIT, HMC5843_MODEREG_LENGTH, buffer); + return buffer[0]; +} +/** Set measurement mode. + * @param newMode New measurement mode + * @see getMode() + * @see HMC5843_MODE_CONTINUOUS + * @see HMC5843_MODE_SINGLE + * @see HMC5843_MODE_IDLE + * @see HMC5843_MODE_SLEEP + * @see HMC5843_RA_MODE + * @see HMC5843_MODEREG_BIT + * @see HMC5843_MODEREG_LENGTH + */ +void HMC5843::setMode(uint8_t newMode) { + // use this method to guarantee that bits 7-2 are set to zero, which is a + // requirement specified in the datasheet; it's actually more efficient than + // using the I2Cdev.writeBits method + I2Cdev::writeByte(devAddr, HMC5843_RA_MODE, newMode << (HMC5843_MODEREG_BIT - HMC5843_MODEREG_LENGTH + 1)); + mode = newMode; // track to tell if we have to clear bit 7 after a read +} + +// DATA* registers + +/** Get 3-axis heading measurements. + * In the event the ADC reading overflows or underflows for the given channel, + * or if there is a math overflow during the bias measurement, this data + * register will contain the value -4096. This register value will clear when + * after the next valid measurement is made. Note that this method automatically + * clears the appropriate bit in the MODE register if Single mode is active. + * @param x 16-bit signed integer container for X-axis heading + * @param y 16-bit signed integer container for Y-axis heading + * @param z 16-bit signed integer container for Z-axis heading + * @see HMC5843_RA_DATAX_H + */ +void HMC5843::getHeading(int16_t *x, int16_t *y, int16_t *z) { + I2Cdev::readBytes(devAddr, HMC5843_RA_DATAX_H, 6, buffer); + if (mode == HMC5843_MODE_SINGLE) I2Cdev::writeByte(devAddr, HMC5843_RA_MODE, HMC5843_MODE_SINGLE << (HMC5843_MODEREG_BIT - HMC5843_MODEREG_LENGTH + 1)); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis heading measurement. + * @return 16-bit signed integer with X-axis heading + * @see HMC5843_RA_DATAX_H + */ +int16_t HMC5843::getHeadingX() { + // each axis read requires that ALL axis registers be read, even if only + // one is used; this was not done ineffiently in the code by accident + I2Cdev::readBytes(devAddr, HMC5843_RA_DATAX_H, 6, buffer); + if (mode == HMC5843_MODE_SINGLE) I2Cdev::writeByte(devAddr, HMC5843_RA_MODE, HMC5843_MODE_SINGLE << (HMC5843_MODEREG_BIT - HMC5843_MODEREG_LENGTH + 1)); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis heading measurement. + * @return 16-bit signed integer with Y-axis heading + * @see HMC5843_RA_DATAY_H + */ +int16_t HMC5843::getHeadingY() { + // each axis read requires that ALL axis registers be read, even if only + // one is used; this was not done ineffiently in the code by accident + I2Cdev::readBytes(devAddr, HMC5843_RA_DATAX_H, 6, buffer); + if (mode == HMC5843_MODE_SINGLE) I2Cdev::writeByte(devAddr, HMC5843_RA_MODE, HMC5843_MODE_SINGLE << (HMC5843_MODEREG_BIT - HMC5843_MODEREG_LENGTH + 1)); + return (((int16_t)buffer[2]) << 8) | buffer[3]; +} +/** Get Z-axis heading measurement. + * @return 16-bit signed integer with Z-axis heading + * @see HMC5843_RA_DATAZ_H + */ +int16_t HMC5843::getHeadingZ() { + // each axis read requires that ALL axis registers be read, even if only + // one is used; this was not done ineffiently in the code by accident + I2Cdev::readBytes(devAddr, HMC5843_RA_DATAX_H, 6, buffer); + if (mode == HMC5843_MODE_SINGLE) I2Cdev::writeByte(devAddr, HMC5843_RA_MODE, HMC5843_MODE_SINGLE << (HMC5843_MODEREG_BIT - HMC5843_MODEREG_LENGTH + 1)); + return (((int16_t)buffer[4]) << 8) | buffer[5]; +} + +// STATUS register + +/** Get regulator enabled status. + * This bit is set when the internal voltage regulator is enabled. This bit is + * cleared when the internal regulator is disabled. + * @return Regulator enabled status + * @see HMC5843_RA_STATUS + * @see HMC5843_STATUS_REN_BIT + */ +bool HMC5843::getRegulatorEnabledStatus() { + I2Cdev::readBit(devAddr, HMC5843_RA_STATUS, HMC5843_STATUS_REN_BIT, buffer); + return buffer[0]; +} +/** Get data output register lock status. + * This bit is set when this some but not all for of the six data output + * registers have been read. When this bit is set, the six data output registers + * are locked and any new data will not be placed in these register until one of + * three conditions are met: one, all six bytes have been read or the mode + * changed, two, the mode is changed, or three, the measurement configuration is + * changed. + * @return Data output register lock status + * @see HMC5843_RA_STATUS + * @see HMC5843_STATUS_LOCK_BIT + */ +bool HMC5843::getLockStatus() { + I2Cdev::readBit(devAddr, HMC5843_RA_STATUS, HMC5843_STATUS_LOCK_BIT, buffer); + return buffer[0]; +} +/** Get data ready status. + * This bit is set when data is written to all six data registers, and cleared + * when the device initiates a write to the data output registers and after one + * or more of the data output registers are written to. When RDY bit is clear it + * shall remain cleared for 250 us. DRDY pin can be used as an alternative to + * the status register for monitoring the device for measurement data. + * @return Data ready status + * @see HMC5843_RA_STATUS + * @see HMC5843_STATUS_READY_BIT + */ +bool HMC5843::getReadyStatus() { + I2Cdev::readBit(devAddr, HMC5843_RA_STATUS, HMC5843_STATUS_READY_BIT, buffer); + return buffer[0]; +} + +// ID_* registers + +/** Get identification byte A + * @return ID_A byte (should be 01001000, ASCII value 'H') + */ +uint8_t HMC5843::getIDA() { + I2Cdev::readByte(devAddr, HMC5843_RA_ID_A, buffer); + return buffer[0]; +} +/** Get identification byte B + * @return ID_A byte (should be 00110100, ASCII value '4') + */ +uint8_t HMC5843::getIDB() { + I2Cdev::readByte(devAddr, HMC5843_RA_ID_B, buffer); + return buffer[0]; +} +/** Get identification byte C + * @return ID_A byte (should be 00110011, ASCII value '3') + */ +uint8_t HMC5843::getIDC() { + I2Cdev::readByte(devAddr, HMC5843_RA_ID_C, buffer); + return buffer[0]; +} diff --git a/libraries/HMC5843/HMC5843.h b/libraries/HMC5843/HMC5843.h new file mode 100644 index 0000000..2076f4c --- /dev/null +++ b/libraries/HMC5843/HMC5843.h @@ -0,0 +1,186 @@ +// I2Cdev library collection - HMC5843 I2C device class header file +// Based on Honeywell HMC5843 datasheet, 6/2010 (Form #900367) +// 8/22/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2011-08-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. +=============================================== +*/ + +#ifndef _HMC5843_H_ +#define _HMC5843_H_ + +#include "I2Cdev.h" + +#define HMC5843_ADDRESS 0x1E // this device only has one address +#define HMC5843_DEFAULT_ADDRESS 0x1E + +#define HMC5843_RA_CONFIG_A 0x00 +#define HMC5843_RA_CONFIG_B 0x01 +#define HMC5843_RA_MODE 0x02 +#define HMC5843_RA_DATAX_H 0x03 +#define HMC5843_RA_DATAX_L 0x04 +#define HMC5843_RA_DATAY_H 0x05 +#define HMC5843_RA_DATAY_L 0x06 +#define HMC5843_RA_DATAZ_H 0x07 +#define HMC5843_RA_DATAZ_L 0x08 +#define HMC5843_RA_STATUS 0x09 +#define HMC5843_RA_ID_A 0x0A +#define HMC5843_RA_ID_B 0x0B +#define HMC5843_RA_ID_C 0x0C + +#define HMC5843_CRA_RATE_BIT 4 +#define HMC5843_CRA_RATE_LENGTH 3 +#define HMC5843_CRA_BIAS_BIT 1 +#define HMC5843_CRA_BIAS_LENGTH 2 + +#define HMC5843_RATE_0P5 0x00 +#define HMC5843_RATE_1 0x01 +#define HMC5843_RATE_2 0x02 +#define HMC5843_RATE_5 0x03 +#define HMC5843_RATE_10 0x04 // default +#define HMC5843_RATE_20 0x05 +#define HMC5843_RATE_50 0x06 + +#define HMC5843_BIAS_NORMAL 0x00 // default +#define HMC5843_BIAS_POSITIVE 0x01 +#define HMC5843_BIAS_NEGATIVE 0x02 + +#define HMC5843_CRB_GAIN_BIT 7 +#define HMC5843_CRB_GAIN_LENGTH 3 + +#define HMC5843_GAIN_1620 0x00 +#define HMC5843_GAIN_1300 0x01 // default +#define HMC5843_GAIN_970 0x02 +#define HMC5843_GAIN_780 0x03 +#define HMC5843_GAIN_530 0x04 +#define HMC5843_GAIN_460 0x05 +#define HMC5843_GAIN_390 0x06 +#define HMC5843_GAIN_280 0x07 // not recommended + +#define HMC5843_MODEREG_BIT 1 +#define HMC5843_MODEREG_LENGTH 2 + +/** + * During continuous-measurement mode, the device continuously makes + * measurements and places measured data in data output registers. Settings in + * the configuration register affect the data output rate (bits DO[n]), the + * measurement configuration (bits MS[n]), and the gain (bits GN[n]) when in + * continuous-measurement mode. To conserve current between measurements, the + * device is placed in a state similar to idle mode, but the mode is not changed + * to idle mode. That is, MD[n] bits are unchanged. Data can be re-read from the + * data output registers if necessary; however, if the master does not ensure + * that the data register is accessed before the completion of the next + * measurement, the new measurement may be lost. All registers maintain values + * while in continuous-measurement mode. The I2C bus is enabled for use by other + * devices on the network in while continuous-measurement mode. + */ +#define HMC5843_MODE_CONTINUOUS 0x00 +/** + * This is the default single supply power-up mode. In dual supply configuration + * this is the default mode when AVDD goes high. During single-measurement mode, + * the device makes a single measurement and places the measured data in data + * output registers. Settings in the configuration register affect the + * measurement configuration (bits MS[n]), and the gain (bits GN[n]) when in + * single-measurement mode. After the measurement is complete and output data + * registers are updated, the device is placed sleep mode, and the mode register + * is changed to sleep mode by setting MD[n] bits. All registers maintain values + * while in single-measurement mode. The I2C bus is enabled for use by other + * devices on the network while in single-measurement mode. + */ +#define HMC5843_MODE_SINGLE 0x01 +/** + * During this mode the device is accessible through the I2C bus, but major + * sources of power consumption are disabled, such as, but not limited to, the + * ADC, the amplifier, the SVDD pin, and the sensor bias current. All registers + * maintain values while in idle mode. The I2C bus is enabled for use by other + * devices on the network while in idle mode. + */ +#define HMC5843_MODE_IDLE 0x02 +/** + * This is the default dual supply power-up mode when only DVDD goes high and + * AVDD remains low. During sleep mode the device functionality is limited to + * listening to the I2C bus. The internal clock is not running and register + * values are not maintained while in sleep mode. The only functionality that + * exists during this mode is the device is able to recognize and execute any + * instructions specific to this device but does not change from sleep mode due + * to other traffic on the I2C bus. The I2C bus is enabled for use by other + * devices on the network while in sleep mode. This mode has two practical + * differences from idle mode. First this state will create less noise on system + * since the clock is disabled, and secondly this state is a lower current + * consuming state since the clock is disabled. + */ +#define HMC5843_MODE_SLEEP 0x03 + +#define HMC5843_STATUS_REN_BIT 2 +#define HMC5843_STATUS_LOCK_BIT 1 +#define HMC5843_STATUS_READY_BIT 0 + +class HMC5843 { + public: + HMC5843(); + HMC5843(uint8_t address); + + void initialize(); + bool testConnection(); + + // CONFIG_A register + uint8_t getDataRate(); + void setDataRate(uint8_t rate); + uint8_t getMeasurementBias(); + void setMeasurementBias(uint8_t bias); + + // CONFIG_B register + uint8_t getGain(); + void setGain(uint8_t gain); + + // MODE register + uint8_t getMode(); + void setMode(uint8_t mode); + + // DATA* registers + void getHeading(int16_t *x, int16_t *y, int16_t *z); + int16_t getHeadingX(); + int16_t getHeadingY(); + int16_t getHeadingZ(); + + // STATUS register + bool getRegulatorEnabledStatus(); + bool getLockStatus(); + bool getReadyStatus(); + + // ID_* registers + uint8_t getIDA(); + uint8_t getIDB(); + uint8_t getIDC(); + + private: + uint8_t devAddr; + uint8_t buffer[6]; + uint8_t mode; +}; + +#endif /* _HMC5843_H_ */ diff --git a/libraries/HMC5843/examples/HMC5843_raw/HMC5843_raw.ino b/libraries/HMC5843/examples/HMC5843_raw/HMC5843_raw.ino new file mode 100644 index 0000000..7c45f10 --- /dev/null +++ b/libraries/HMC5843/examples/HMC5843_raw/HMC5843_raw.ino @@ -0,0 +1,85 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for HMC5843 class +// 10/7/2011 by Jeff Rowberg +// 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 HMC5843 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 "HMC5843.h" + +// class default I2C address is 0x1E +// specific I2C addresses may be passed as a parameter here +// this device only supports one I2C address (0x1E) +HMC5843 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() ? "HMC5843 connection successful" : "HMC5843 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); +} diff --git a/libraries/HMC5843/library.json b/libraries/HMC5843/library.json new file mode 100644 index 0000000..51f6926 --- /dev/null +++ b/libraries/HMC5843/library.json @@ -0,0 +1,18 @@ +{ + "name": "I2Cdevlib-HMC5843", + "keywords": "magnetometer, compass, sensor, i2cdevlib, i2c", + "description": "The HMC5843 is 3-Axis digital compass/magnetometer", + "include": "Arduino/HMC5843", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "dependencies": + { + "name": "I2Cdevlib-Core", + "frameworks": "arduino" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/HMC5883L/HMC5883L.cpp b/libraries/HMC5883L/HMC5883L.cpp new file mode 100644 index 0000000..29d8fb5 --- /dev/null +++ b/libraries/HMC5883L/HMC5883L.cpp @@ -0,0 +1,365 @@ +// I2Cdev library collection - HMC5883L I2C device class +// Based on Honeywell HMC5883L datasheet, 10/2010 (Form #900405 Rev B) +// 6/12/2012 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2012-06-12 - fixed swapped Y/Z axes +// 2011-08-22 - small Doxygen comment fixes +// 2011-07-31 - 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. +=============================================== +*/ + +#include "HMC5883L.h" + +/** Default constructor, uses default I2C address. + * @see HMC5883L_DEFAULT_ADDRESS + */ +HMC5883L::HMC5883L() { + devAddr = HMC5883L_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see HMC5883L_DEFAULT_ADDRESS + * @see HMC5883L_ADDRESS + */ +HMC5883L::HMC5883L(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * This will prepare the magnetometer with default settings, ready for single- + * use mode (very low power requirements). Default settings include 8-sample + * averaging, 15 Hz data output rate, normal measurement bias, a,d 1090 gain (in + * terms of LSB/Gauss). Be sure to adjust any settings you need specifically + * after initialization, especially the gain settings if you happen to be seeing + * a lot of -4096 values (see the datasheet for mor information). + */ +void HMC5883L::initialize() { + // write CONFIG_A register + I2Cdev::writeByte(devAddr, HMC5883L_RA_CONFIG_A, + (HMC5883L_AVERAGING_8 << (HMC5883L_CRA_AVERAGE_BIT - HMC5883L_CRA_AVERAGE_LENGTH + 1)) | + (HMC5883L_RATE_15 << (HMC5883L_CRA_RATE_BIT - HMC5883L_CRA_RATE_LENGTH + 1)) | + (HMC5883L_BIAS_NORMAL << (HMC5883L_CRA_BIAS_BIT - HMC5883L_CRA_BIAS_LENGTH + 1))); + + // write CONFIG_B register + setGain(HMC5883L_GAIN_1090); + + // write MODE register + setMode(HMC5883L_MODE_SINGLE); +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool HMC5883L::testConnection() { + if (I2Cdev::readBytes(devAddr, HMC5883L_RA_ID_A, 3, buffer) == 3) { + return (buffer[0] == 'H' && buffer[1] == '4' && buffer[2] == '3'); + } + return false; +} + +// CONFIG_A register + +/** Get number of samples averaged per measurement. + * @return Current samples averaged per measurement (0-3 for 1/2/4/8 respectively) + * @see HMC5883L_AVERAGING_8 + * @see HMC5883L_RA_CONFIG_A + * @see HMC5883L_CRA_AVERAGE_BIT + * @see HMC5883L_CRA_AVERAGE_LENGTH + */ +uint8_t HMC5883L::getSampleAveraging() { + I2Cdev::readBits(devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_AVERAGE_BIT, HMC5883L_CRA_AVERAGE_LENGTH, buffer); + return buffer[0]; +} +/** Set number of samples averaged per measurement. + * @param averaging New samples averaged per measurement setting(0-3 for 1/2/4/8 respectively) + * @see HMC5883L_RA_CONFIG_A + * @see HMC5883L_CRA_AVERAGE_BIT + * @see HMC5883L_CRA_AVERAGE_LENGTH + */ +void HMC5883L::setSampleAveraging(uint8_t averaging) { + I2Cdev::writeBits(devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_AVERAGE_BIT, HMC5883L_CRA_AVERAGE_LENGTH, averaging); +} +/** Get data output rate value. + * The Table below shows all selectable output rates in continuous measurement + * mode. All three channels shall be measured within a given output rate. Other + * output rates with maximum rate of 160 Hz can be achieved by monitoring DRDY + * interrupt pin in single measurement mode. + * + * Value | Typical Data Output Rate (Hz) + * ------+------------------------------ + * 0 | 0.75 + * 1 | 1.5 + * 2 | 3 + * 3 | 7.5 + * 4 | 15 (Default) + * 5 | 30 + * 6 | 75 + * 7 | Not used + * + * @return Current rate of data output to registers + * @see HMC5883L_RATE_15 + * @see HMC5883L_RA_CONFIG_A + * @see HMC5883L_CRA_RATE_BIT + * @see HMC5883L_CRA_RATE_LENGTH + */ +uint8_t HMC5883L::getDataRate() { + I2Cdev::readBits(devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_RATE_BIT, HMC5883L_CRA_RATE_LENGTH, buffer); + return buffer[0]; +} +/** Set data output rate value. + * @param rate Rate of data output to registers + * @see getDataRate() + * @see HMC5883L_RATE_15 + * @see HMC5883L_RA_CONFIG_A + * @see HMC5883L_CRA_RATE_BIT + * @see HMC5883L_CRA_RATE_LENGTH + */ +void HMC5883L::setDataRate(uint8_t rate) { + I2Cdev::writeBits(devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_RATE_BIT, HMC5883L_CRA_RATE_LENGTH, rate); +} +/** Get measurement bias value. + * @return Current bias value (0-2 for normal/positive/negative respectively) + * @see HMC5883L_BIAS_NORMAL + * @see HMC5883L_RA_CONFIG_A + * @see HMC5883L_CRA_BIAS_BIT + * @see HMC5883L_CRA_BIAS_LENGTH + */ +uint8_t HMC5883L::getMeasurementBias() { + I2Cdev::readBits(devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_BIAS_BIT, HMC5883L_CRA_BIAS_LENGTH, buffer); + return buffer[0]; +} +/** Set measurement bias value. + * @param bias New bias value (0-2 for normal/positive/negative respectively) + * @see HMC5883L_BIAS_NORMAL + * @see HMC5883L_RA_CONFIG_A + * @see HMC5883L_CRA_BIAS_BIT + * @see HMC5883L_CRA_BIAS_LENGTH + */ +void HMC5883L::setMeasurementBias(uint8_t bias) { + I2Cdev::writeBits(devAddr, HMC5883L_RA_CONFIG_A, HMC5883L_CRA_BIAS_BIT, HMC5883L_CRA_BIAS_LENGTH, bias); +} + +// CONFIG_B register + +/** Get magnetic field gain value. + * The table below shows nominal gain settings. Use the "Gain" column to convert + * counts to Gauss. Choose a lower gain value (higher GN#) when total field + * strength causes overflow in one of the data output registers (saturation). + * The data output range for all settings is 0xF800-0x07FF (-2048 - 2047). + * + * Value | Field Range | Gain (LSB/Gauss) + * ------+-------------+----------------- + * 0 | +/- 0.88 Ga | 1370 + * 1 | +/- 1.3 Ga | 1090 (Default) + * 2 | +/- 1.9 Ga | 820 + * 3 | +/- 2.5 Ga | 660 + * 4 | +/- 4.0 Ga | 440 + * 5 | +/- 4.7 Ga | 390 + * 6 | +/- 5.6 Ga | 330 + * 7 | +/- 8.1 Ga | 230 + * + * @return Current magnetic field gain value + * @see HMC5883L_GAIN_1090 + * @see HMC5883L_RA_CONFIG_B + * @see HMC5883L_CRB_GAIN_BIT + * @see HMC5883L_CRB_GAIN_LENGTH + */ +uint8_t HMC5883L::getGain() { + I2Cdev::readBits(devAddr, HMC5883L_RA_CONFIG_B, HMC5883L_CRB_GAIN_BIT, HMC5883L_CRB_GAIN_LENGTH, buffer); + return buffer[0]; +} +/** Set magnetic field gain value. + * @param gain New magnetic field gain value + * @see getGain() + * @see HMC5883L_RA_CONFIG_B + * @see HMC5883L_CRB_GAIN_BIT + * @see HMC5883L_CRB_GAIN_LENGTH + */ +void HMC5883L::setGain(uint8_t gain) { + // use this method to guarantee that bits 4-0 are set to zero, which is a + // requirement specified in the datasheet; it's actually more efficient than + // using the I2Cdev.writeBits method + I2Cdev::writeByte(devAddr, HMC5883L_RA_CONFIG_B, gain << (HMC5883L_CRB_GAIN_BIT - HMC5883L_CRB_GAIN_LENGTH + 1)); +} + +// MODE register + +/** Get measurement mode. + * In continuous-measurement mode, the device continuously performs measurements + * and places the result in the data register. RDY goes high when new data is + * placed in all three registers. After a power-on or a write to the mode or + * configuration register, the first measurement set is available from all three + * data output registers after a period of 2/fDO and subsequent measurements are + * available at a frequency of fDO, where fDO is the frequency of data output. + * + * When single-measurement mode (default) is selected, device performs a single + * measurement, sets RDY high and returned to idle mode. Mode register returns + * to idle mode bit values. The measurement remains in the data output register + * and RDY remains high until the data output register is read or another + * measurement is performed. + * + * @return Current measurement mode + * @see HMC5883L_MODE_CONTINUOUS + * @see HMC5883L_MODE_SINGLE + * @see HMC5883L_MODE_IDLE + * @see HMC5883L_RA_MODE + * @see HMC5883L_MODEREG_BIT + * @see HMC5883L_MODEREG_LENGTH + */ +uint8_t HMC5883L::getMode() { + I2Cdev::readBits(devAddr, HMC5883L_RA_MODE, HMC5883L_MODEREG_BIT, HMC5883L_MODEREG_LENGTH, buffer); + return buffer[0]; +} +/** Set measurement mode. + * @param newMode New measurement mode + * @see getMode() + * @see HMC5883L_MODE_CONTINUOUS + * @see HMC5883L_MODE_SINGLE + * @see HMC5883L_MODE_IDLE + * @see HMC5883L_RA_MODE + * @see HMC5883L_MODEREG_BIT + * @see HMC5883L_MODEREG_LENGTH + */ +void HMC5883L::setMode(uint8_t newMode) { + // use this method to guarantee that bits 7-2 are set to zero, which is a + // requirement specified in the datasheet; it's actually more efficient than + // using the I2Cdev.writeBits method + I2Cdev::writeByte(devAddr, HMC5883L_RA_MODE, newMode << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1)); + mode = newMode; // track to tell if we have to clear bit 7 after a read +} + +// DATA* registers + +/** Get 3-axis heading measurements. + * In the event the ADC reading overflows or underflows for the given channel, + * or if there is a math overflow during the bias measurement, this data + * register will contain the value -4096. This register value will clear when + * after the next valid measurement is made. Note that this method automatically + * clears the appropriate bit in the MODE register if Single mode is active. + * @param x 16-bit signed integer container for X-axis heading + * @param y 16-bit signed integer container for Y-axis heading + * @param z 16-bit signed integer container for Z-axis heading + * @see HMC5883L_RA_DATAX_H + */ +void HMC5883L::getHeading(int16_t *x, int16_t *y, int16_t *z) { + I2Cdev::readBytes(devAddr, HMC5883L_RA_DATAX_H, 6, buffer); + if (mode == HMC5883L_MODE_SINGLE) I2Cdev::writeByte(devAddr, HMC5883L_RA_MODE, HMC5883L_MODE_SINGLE << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1)); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[4]) << 8) | buffer[5]; + *z = (((int16_t)buffer[2]) << 8) | buffer[3]; +} +/** Get X-axis heading measurement. + * @return 16-bit signed integer with X-axis heading + * @see HMC5883L_RA_DATAX_H + */ +int16_t HMC5883L::getHeadingX() { + // each axis read requires that ALL axis registers be read, even if only + // one is used; this was not done ineffiently in the code by accident + I2Cdev::readBytes(devAddr, HMC5883L_RA_DATAX_H, 6, buffer); + if (mode == HMC5883L_MODE_SINGLE) I2Cdev::writeByte(devAddr, HMC5883L_RA_MODE, HMC5883L_MODE_SINGLE << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1)); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis heading measurement. + * @return 16-bit signed integer with Y-axis heading + * @see HMC5883L_RA_DATAY_H + */ +int16_t HMC5883L::getHeadingY() { + // each axis read requires that ALL axis registers be read, even if only + // one is used; this was not done ineffiently in the code by accident + I2Cdev::readBytes(devAddr, HMC5883L_RA_DATAX_H, 6, buffer); + if (mode == HMC5883L_MODE_SINGLE) I2Cdev::writeByte(devAddr, HMC5883L_RA_MODE, HMC5883L_MODE_SINGLE << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1)); + return (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get Z-axis heading measurement. + * @return 16-bit signed integer with Z-axis heading + * @see HMC5883L_RA_DATAZ_H + */ +int16_t HMC5883L::getHeadingZ() { + // each axis read requires that ALL axis registers be read, even if only + // one is used; this was not done ineffiently in the code by accident + I2Cdev::readBytes(devAddr, HMC5883L_RA_DATAX_H, 6, buffer); + if (mode == HMC5883L_MODE_SINGLE) I2Cdev::writeByte(devAddr, HMC5883L_RA_MODE, HMC5883L_MODE_SINGLE << (HMC5883L_MODEREG_BIT - HMC5883L_MODEREG_LENGTH + 1)); + return (((int16_t)buffer[2]) << 8) | buffer[3]; +} + +// STATUS register + +/** Get data output register lock status. + * This bit is set when this some but not all for of the six data output + * registers have been read. When this bit is set, the six data output registers + * are locked and any new data will not be placed in these register until one of + * three conditions are met: one, all six bytes have been read or the mode + * changed, two, the mode is changed, or three, the measurement configuration is + * changed. + * @return Data output register lock status + * @see HMC5883L_RA_STATUS + * @see HMC5883L_STATUS_LOCK_BIT + */ +bool HMC5883L::getLockStatus() { + I2Cdev::readBit(devAddr, HMC5883L_RA_STATUS, HMC5883L_STATUS_LOCK_BIT, buffer); + return buffer[0]; +} +/** Get data ready status. + * This bit is set when data is written to all six data registers, and cleared + * when the device initiates a write to the data output registers and after one + * or more of the data output registers are written to. When RDY bit is clear it + * shall remain cleared for 250 us. DRDY pin can be used as an alternative to + * the status register for monitoring the device for measurement data. + * @return Data ready status + * @see HMC5883L_RA_STATUS + * @see HMC5883L_STATUS_READY_BIT + */ +bool HMC5883L::getReadyStatus() { + I2Cdev::readBit(devAddr, HMC5883L_RA_STATUS, HMC5883L_STATUS_READY_BIT, buffer); + return buffer[0]; +} + +// ID_* registers + +/** Get identification byte A + * @return ID_A byte (should be 01001000, ASCII value 'H') + */ +uint8_t HMC5883L::getIDA() { + I2Cdev::readByte(devAddr, HMC5883L_RA_ID_A, buffer); + return buffer[0]; +} +/** Get identification byte B + * @return ID_A byte (should be 00110100, ASCII value '4') + */ +uint8_t HMC5883L::getIDB() { + I2Cdev::readByte(devAddr, HMC5883L_RA_ID_B, buffer); + return buffer[0]; +} +/** Get identification byte C + * @return ID_A byte (should be 00110011, ASCII value '3') + */ +uint8_t HMC5883L::getIDC() { + I2Cdev::readByte(devAddr, HMC5883L_RA_ID_C, buffer); + return buffer[0]; +} diff --git a/libraries/HMC5883L/HMC5883L.h b/libraries/HMC5883L/HMC5883L.h new file mode 100644 index 0000000..dcb1974 --- /dev/null +++ b/libraries/HMC5883L/HMC5883L.h @@ -0,0 +1,148 @@ +// I2Cdev library collection - HMC5883L I2C device class header file +// Based on Honeywell HMC5883L datasheet, 10/2010 (Form #900405 Rev B) +// 6/12/2012 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2012-06-12 - fixed swapped Y/Z axes +// 2011-08-22 - small Doxygen comment fixes +// 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 _HMC5883L_H_ +#define _HMC5883L_H_ + +#include "I2Cdev.h" + +#define HMC5883L_ADDRESS 0x1E // this device only has one address +#define HMC5883L_DEFAULT_ADDRESS 0x1E + +#define HMC5883L_RA_CONFIG_A 0x00 +#define HMC5883L_RA_CONFIG_B 0x01 +#define HMC5883L_RA_MODE 0x02 +#define HMC5883L_RA_DATAX_H 0x03 +#define HMC5883L_RA_DATAX_L 0x04 +#define HMC5883L_RA_DATAZ_H 0x05 +#define HMC5883L_RA_DATAZ_L 0x06 +#define HMC5883L_RA_DATAY_H 0x07 +#define HMC5883L_RA_DATAY_L 0x08 +#define HMC5883L_RA_STATUS 0x09 +#define HMC5883L_RA_ID_A 0x0A +#define HMC5883L_RA_ID_B 0x0B +#define HMC5883L_RA_ID_C 0x0C + +#define HMC5883L_CRA_AVERAGE_BIT 6 +#define HMC5883L_CRA_AVERAGE_LENGTH 2 +#define HMC5883L_CRA_RATE_BIT 4 +#define HMC5883L_CRA_RATE_LENGTH 3 +#define HMC5883L_CRA_BIAS_BIT 1 +#define HMC5883L_CRA_BIAS_LENGTH 2 + +#define HMC5883L_AVERAGING_1 0x00 +#define HMC5883L_AVERAGING_2 0x01 +#define HMC5883L_AVERAGING_4 0x02 +#define HMC5883L_AVERAGING_8 0x03 + +#define HMC5883L_RATE_0P75 0x00 +#define HMC5883L_RATE_1P5 0x01 +#define HMC5883L_RATE_3 0x02 +#define HMC5883L_RATE_7P5 0x03 +#define HMC5883L_RATE_15 0x04 +#define HMC5883L_RATE_30 0x05 +#define HMC5883L_RATE_75 0x06 + +#define HMC5883L_BIAS_NORMAL 0x00 +#define HMC5883L_BIAS_POSITIVE 0x01 +#define HMC5883L_BIAS_NEGATIVE 0x02 + +#define HMC5883L_CRB_GAIN_BIT 7 +#define HMC5883L_CRB_GAIN_LENGTH 3 + +#define HMC5883L_GAIN_1370 0x00 +#define HMC5883L_GAIN_1090 0x01 +#define HMC5883L_GAIN_820 0x02 +#define HMC5883L_GAIN_660 0x03 +#define HMC5883L_GAIN_440 0x04 +#define HMC5883L_GAIN_390 0x05 +#define HMC5883L_GAIN_330 0x06 +#define HMC5883L_GAIN_220 0x07 + +#define HMC5883L_MODEREG_BIT 1 +#define HMC5883L_MODEREG_LENGTH 2 + +#define HMC5883L_MODE_CONTINUOUS 0x00 +#define HMC5883L_MODE_SINGLE 0x01 +#define HMC5883L_MODE_IDLE 0x02 + +#define HMC5883L_STATUS_LOCK_BIT 1 +#define HMC5883L_STATUS_READY_BIT 0 + +class HMC5883L { + public: + HMC5883L(); + HMC5883L(uint8_t address); + + void initialize(); + bool testConnection(); + + // CONFIG_A register + uint8_t getSampleAveraging(); + void setSampleAveraging(uint8_t averaging); + uint8_t getDataRate(); + void setDataRate(uint8_t rate); + uint8_t getMeasurementBias(); + void setMeasurementBias(uint8_t bias); + + // CONFIG_B register + uint8_t getGain(); + void setGain(uint8_t gain); + + // MODE register + uint8_t getMode(); + void setMode(uint8_t mode); + + // DATA* registers + void getHeading(int16_t *x, int16_t *y, int16_t *z); + int16_t getHeadingX(); + int16_t getHeadingY(); + int16_t getHeadingZ(); + + // STATUS register + bool getLockStatus(); + bool getReadyStatus(); + + // ID_* registers + uint8_t getIDA(); + uint8_t getIDB(); + uint8_t getIDC(); + + private: + uint8_t devAddr; + uint8_t buffer[6]; + uint8_t mode; +}; + +#endif /* _HMC5883L_H_ */ diff --git a/libraries/HMC5883L/examples/HMC5883L_raw/HMC5883L_raw.ino b/libraries/HMC5883L/examples/HMC5883L_raw/HMC5883L_raw.ino new file mode 100644 index 0000000..0d34606 --- /dev/null +++ b/libraries/HMC5883L/examples/HMC5883L_raw/HMC5883L_raw.ino @@ -0,0 +1,93 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for HMC5883L class +// 10/7/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2013-05-04 - Added Heading Calculation in degrees +// 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 HMC5883L 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 "HMC5883L.h" + +// class default I2C address is 0x1E +// specific I2C addresses may be passed as a parameter here +// this device only supports one I2C address (0x1E) +HMC5883L 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() ? "HMC5883L connection successful" : "HMC5883L 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.print(mz); Serial.print("\t"); + +// To calculate heading in degrees. 0 degree indicates North + float heading = atan2(my, mx); + if(heading < 0) + heading += 2 * M_PI; + Serial.print("heading:\t"); + Serial.println(heading * 180/M_PI); + + // blink LED to indicate activity + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); +} diff --git a/libraries/HMC5883L/library.json b/libraries/HMC5883L/library.json new file mode 100644 index 0000000..14614e9 --- /dev/null +++ b/libraries/HMC5883L/library.json @@ -0,0 +1,18 @@ +{ + "name": "I2Cdevlib-HMC5883L", + "keywords": "magnetometer, compass, sensor, i2cdevlib, i2c", + "description": "The HMC5883L is 3-Axis digital compass/magnetometer", + "include": "Arduino/HMC5883L", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "dependencies": + { + "name": "I2Cdevlib-Core", + "frameworks": "arduino" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/HTU21D/HTU21D.cpp b/libraries/HTU21D/HTU21D.cpp new file mode 100644 index 0000000..838c7fd --- /dev/null +++ b/libraries/HTU21D/HTU21D.cpp @@ -0,0 +1,97 @@ +// I2Cdev library collection - HTU21D I2C device class header file +// Based on MEAS HTU21D HPC199_2 HTU321(F) datasheet, October 2013 +// 2016-03-24 by https://github.com/eadf +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2016-03-24 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2016 Eadf, 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 "HTU21D.h" + + +/** Default constructor, uses default I2C address. + * @see HTU21D_DEFAULT_ADDRESS + */ +HTU21D::HTU21D() { + devAddr = HTU21D_DEFAULT_ADDRESS; +} + +/** Power on and prepare for general usage. + * This operation calls reset() on the HTU21D device and it takes at least 15milliseconds. + */ +void HTU21D::initialize() { + reset(); +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * This operation calls reset() on the HTU21D device and it takes at least 15milliseconds. + * @return True if connection is valid, false otherwise + */ +bool HTU21D::testConnection() { + reset(); + buffer[0] = 0; + I2Cdev::readByte(devAddr, HTU21D_READ_USER_REGISTER, buffer); + return buffer[0] == 0x2; +} + +/** Reads and returns the temperature, ignores the CRC field. + * @return The measured temperature, or NaN if the operation failed. + */ +float HTU21D::getTemperature() { + // Ignore the CRC byte + uint16_t t = 0; + if (1!=I2Cdev::readWord(devAddr, HTU21D_RA_TEMPERATURE, &t)){ + return NAN; + } + // clear the status bits (bit0 & bit1) and calculate the temperature + // as per the formula in the datasheet + return ((float)(t&0xFFFC))*175.72/65536.0-46.85; +} + +/** Reads and returns the humidity, ignores the CRC field + * @return The measured humidity, or NaN if the operation failed. + */ +float HTU21D::getHumidity() { + // Ignore the CRC byte + uint16_t t = 0; + if (1!=I2Cdev::readWord(devAddr, HTU21D_RA_HUMIDITY, &t)){ + return NAN; + } + // clear the status bits (bit0 & bit1) and calculate the humidity + // as per the formula in the datasheet + return ((float)(t&0xFFFC))*125.0/65536.0-6.0; +} + +/** Does a soft reset of the HTU21D + * This operation takes at least 15milliseconds. + */ +void HTU21D::reset() { + I2Cdev::writeByte(devAddr, HTU21D_RESET, 0); + delay(15); +} + diff --git a/libraries/HTU21D/HTU21D.h b/libraries/HTU21D/HTU21D.h new file mode 100644 index 0000000..a5e277e --- /dev/null +++ b/libraries/HTU21D/HTU21D.h @@ -0,0 +1,63 @@ +// I2Cdev library collection - HTU21D I2C device class header file +// Based on MEAS HTU21D HPC199_2 HTU321(F) datasheet, October 2013 +// 2016-03-24 by https://github.com/eadf +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2016-03-24 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2016 Eadf, 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 _HTU21D_H_ +#define _HTU21D_H_ + +#include "I2Cdev.h" + +#define HTU21D_DEFAULT_ADDRESS 0x40 + +#define HTU21D_RA_TEMPERATURE 0xE3 +#define HTU21D_RA_HUMIDITY 0xE5 +#define HTU21D_RESET 0xFE +#define HTU21D_WRITE_USER_REGISTER 0xE6 +#define HTU21D_READ_USER_REGISTER 0xE7 + +class HTU21D { + public: + HTU21D(); + + void initialize(); + bool testConnection(); + + float getTemperature(); + float getHumidity(); + + void reset(); + + private: + uint8_t devAddr; + uint8_t buffer[2]; +}; + +#endif /* _HTU21D_H_ */ diff --git a/libraries/HTU21D/examples/HTU21D_simple/HTU21D_simple.ino b/libraries/HTU21D/examples/HTU21D_simple/HTU21D_simple.ino new file mode 100644 index 0000000..0b198fb --- /dev/null +++ b/libraries/HTU21D/examples/HTU21D_simple/HTU21D_simple.ino @@ -0,0 +1,51 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for HTU21D class +// Example of reading temperature and humidity from the HTU21D sensor +// 2016-03-24 by Eadf (https://github.com/eadf) +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2016-03-24 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2016 Eadf, 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 "HTU21D.h" + +HTU21D htu21d; + +void setup() { + //I2Cdev::begin(); // join I2C bus + Wire.begin(); + Serial.begin(38400); + htu21d.initialize(); + Serial.println("Testing device connections..."); + Serial.println(htu21d.testConnection() ? "HTU21D connection successful" : "HTU21D connection failed"); +} + +void loop() { + Serial.print("Temperature: "); Serial.print(htu21d.getTemperature()); + Serial.print("\t\tHumidity: "); Serial.println(htu21d.getHumidity()); + delay(400); +} + diff --git a/libraries/HTU21D/library.json b/libraries/HTU21D/library.json new file mode 100644 index 0000000..6afea2a --- /dev/null +++ b/libraries/HTU21D/library.json @@ -0,0 +1,18 @@ +{ + "name": "I2Cdevlib-HTU21D”, + "keywords": “temperature, humidity, i2cdevlib, i2c", + "description": "HTU21D is 12-Bit humidity and 14-bit temperature sensor", + "include": "Arduino/HTU21D", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "dependencies": + { + "name": "I2Cdevlib-Core", + "frameworks": "arduino" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/I2Cdev/I2Cdev.cpp b/libraries/I2Cdev/I2Cdev.cpp new file mode 100644 index 0000000..b23ab12 --- /dev/null +++ b/libraries/I2Cdev/I2Cdev.cpp @@ -0,0 +1,519 @@ +// I2Cdev library collection - Main I2C device class +// Abstracts bit and byte I2C R/W functions into a convenient class +// 6/9/2012 by Jeff Rowberg +// +// Changelog: +// 2012-06-09 - fix major issue with reading > 32 bytes at a time with Arduino Wire +// - add compiler warnings when using outdated or IDE or limited I2Cdev implementation +// 2011-11-01 - fix write*Bits mask calculation (thanks sasquatch @ Arduino forums) +// 2011-10-03 - added automatic Arduino version detection for ease of use +// 2011-10-02 - added Gene Knight's NBWire TwoWire class implementation with small modifications +// 2011-08-31 - added support for Arduino 1.0 Wire library (methods are different from 0.x) +// 2011-08-03 - added optional timeout parameter to read* methods to easily change from default +// 2011-08-02 - added support for 16-bit registers +// - fixed incorrect Doxygen comments on some methods +// - added timeout value for read operations (thanks mem @ Arduino forums) +// 2011-07-30 - changed read/write function structures to return success or byte counts +// - made all methods static for multi-device memory savings +// 2011-07-28 - 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. +=============================================== +*/ + +#include "I2Cdev.h" +//#define I2CDEV_SERIAL_DEBUG +/** Default constructor. + */ +I2Cdev::I2Cdev() { +} + +/** Read a single bit from an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to read from + * @param bitNum Bit position to read (0-7) + * @param data Container for single bit value + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Status of read operation (true = success) + */ +int8_t I2Cdev::readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout) { + uint8_t b; + uint8_t count = readByte(devAddr, regAddr, &b, timeout); + *data = b & (1 << bitNum); + return count; +} + +/** Read a single bit from a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to read from + * @param bitNum Bit position to read (0-15) + * @param data Container for single bit value + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Status of read operation (true = success) + */ +/* +int8_t I2Cdev::readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout) { + uint16_t b; + uint8_t count = readWord(devAddr, regAddr, &b, timeout); + *data = b & (1 << bitNum); + return count; +} +*/ + +/** Read multiple bits from an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to read from + * @param bitStart First bit position to read (0-7) + * @param length Number of bits to read (not more than 8) + * @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05) + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Status of read operation (true = success) + */ +int8_t I2Cdev::readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout) { + // 01101001 read byte + // 76543210 bit numbers + // xxx args: bitStart=4, length=3 + // 010 masked + // -> 010 shifted + uint8_t count, b; + if ((count = readByte(devAddr, regAddr, &b, timeout)) != 0) { + uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1); + b &= mask; + b >>= (bitStart - length + 1); + *data = b; + } + return count; +} + +/** Read multiple bits from a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to read from + * @param bitStart First bit position to read (0-15) + * @param length Number of bits to read (not more than 16) + * @param data Container for right-aligned value (i.e. '101' read from any bitStart position will equal 0x05) + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Status of read operation (1 = success, 0 = failure, -1 = timeout) + */ + /* +int8_t I2Cdev::readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout) +{ + // 1101011001101001 read byte + // fedcba9876543210 bit numbers + // xxx args: bitStart=12, length=3 + // 010 masked + // -> 010 shifted + uint16_t w; + + uint8_t count = readWord(devAddr, regAddr, &w, timeout); + + if (count != 0) { + uint16_t mask = ((1 << length) - 1) << (bitStart - length + 1); + w &= mask; + w >>= (bitStart - length + 1); + *data = w; + } + + return count; +} +*/ +/** Read single byte from an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to read from + * @param data Container for byte value read from device + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Status of read operation (true = success) + */ +int8_t I2Cdev::readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout) +{ + return readBytes(devAddr, regAddr, 1, data, timeout); +} + +/** Read single word from a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to read from + * @param data Container for word value read from device + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Status of read operation (true = success) + */ +/* +int8_t I2Cdev::readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout) +{ + return readWords(devAddr, regAddr, 1, data, timeout); +} +*/ +/** Read multiple bytes from an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register regAddr to read from + * @param length Number of bytes to read + * @param data Buffer to store read data in + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Number of bytes read (-1 indicates failure) + */ +int8_t I2Cdev::readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout) +{ +#ifdef I2CDEV_SERIAL_DEBUG + Serial.print("I2C (0x"); + Serial.print(devAddr, HEX); + Serial.print(") reading "); + Serial.print(length, DEC); + Serial.print(" bytes from 0x"); + Serial.print(regAddr, HEX); + Serial.print("..."); +#endif + + int8_t count = 0; + uint32_t t1 = millis(); + + // Arduino v1.0.1+, Wire library + // Adds official support for repeated start condition, yay! + + // I2C/TWI subsystem uses internal buffer that breaks with large data requests + // so if user requests more than BUFFER_LENGTH bytes, we have to do it in + // smaller chunks instead of all at once + for (uint8_t k = 0; k < length; k += min(length, BUFFER_LENGTH)) { + Wire.beginTransmission(devAddr); + Wire.write(regAddr); + Wire.endTransmission(); + Wire.beginTransmission(devAddr); + Wire.requestFrom(devAddr, (uint8_t)min(length - k, BUFFER_LENGTH)); + + while (Wire.available() && (timeout == 0 || millis() - t1 < timeout)) { + data[count++] = Wire.read(); + +#ifdef I2CDEV_SERIAL_DEBUG + Serial.print(data[count], HEX); + if (count < length) { + Serial.print(" "); + } +#endif + } + + Wire.endTransmission(); + } + + // check for timeout + if (timeout > 0 && millis() - t1 >= timeout && count < length) { + count = -1; // timeout + } + + #ifdef I2CDEV_SERIAL_DEBUG + Serial.print(". Done ("); + Serial.print(count, DEC); + Serial.println(" read)."); + #endif + + return count; +} + +/** Read multiple words from a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register regAddr to read from + * @param length Number of words to read + * @param data Buffer to store read data in + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Number of words read (0 indicates failure) + */ +/* +int8_t I2Cdev::readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout) +{ +#ifdef I2CDEV_SERIAL_DEBUG + Serial.print("I2C (0x"); + Serial.print(devAddr, HEX); + Serial.print(") reading "); + Serial.print(length, DEC); + Serial.print(" words from 0x"); + Serial.print(regAddr, HEX); + Serial.print("..."); +#endif + + int8_t count = 0; + uint32_t t1 = millis(); + + // Arduino v1.0.1+, Wire library + // Adds official support for repeated start condition, yay! + + // I2C/TWI subsystem uses internal buffer that breaks with large data requests + // so if user requests more than BUFFER_LENGTH bytes, we have to do it in + // smaller chunks instead of all at once + for (uint8_t k = 0; k < length * 2; k += min(length * 2, BUFFER_LENGTH)) { + Wire.beginTransmission(devAddr); + Wire.write(regAddr); + Wire.endTransmission(); + Wire.beginTransmission(devAddr); + Wire.requestFrom(devAddr, (uint8_t)(length * 2)); // length=words, this wants bytes + + bool msb = true; // starts with MSB, then LSB + + while (Wire.available() && count < length && (timeout == 0 || millis() - t1 < timeout)) { + if (msb) { + // first byte is bits 15-8 (MSb=15) + data[count] = Wire.read() << 8; + } + else { + // second byte is bits 7-0 (LSb=0) + data[count++] |= Wire.read(); + +#ifdef I2CDEV_SERIAL_DEBUG + Serial.print(data[count], HEX); + if (count < length) { + Serial.print(" "); + } +#endif + } + + msb = !msb; + } + + Wire.endTransmission(); + } + + if (timeout > 0 && millis() - t1 >= timeout && count < length) { + count = -1; // timeout + } + +#ifdef I2CDEV_SERIAL_DEBUG + Serial.print(". Done ("); + Serial.print(count, DEC); + Serial.println(" read)."); +#endif + + return count; +} +*/ + +/** write a single bit in an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to write to + * @param bitNum Bit position to write (0-7) + * @param value New bit value to write + * @return Status of operation (true = success) + */ +bool I2Cdev::writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data) { + uint8_t b; + readByte(devAddr, regAddr, &b); + b = (data != 0) ? (b | (1 << bitNum)) : (b & ~(1 << bitNum)); + return writeByte(devAddr, regAddr, b); +} + +/** write a single bit in a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to write to + * @param bitNum Bit position to write (0-15) + * @param value New bit value to write + * @return Status of operation (true = success) + */ +/* +bool I2Cdev::writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data) { + uint16_t w; + readWord(devAddr, regAddr, &w); + w = (data != 0) ? (w | (1 << bitNum)) : (w & ~(1 << bitNum)); + return writeWord(devAddr, regAddr, w); +} +*/ + +/** Write multiple bits in an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to write to + * @param bitStart First bit position to write (0-7) + * @param length Number of bits to write (not more than 8) + * @param data Right-aligned value to write + * @return Status of operation (true = success) + */ +bool I2Cdev::writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data) +{ + // 010 value to write + // 76543210 bit numbers + // xxx args: bitStart=4, length=3 + // 00011100 mask byte + // 10101111 original value (sample) + // 10100011 original & ~mask + // 10101011 masked | value + uint8_t b; + + if (readByte(devAddr, regAddr, &b) != 0) { + uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1); + data <<= (bitStart - length + 1); // shift data into correct position + data &= mask; // zero all non-important bits in data + b &= ~(mask); // zero all important bits in existing byte + b |= data; // combine data with existing byte + + return writeByte(devAddr, regAddr, b); + } + + return false; +} + +/** Write multiple bits in a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register regAddr to write to + * @param bitStart First bit position to write (0-15) + * @param length Number of bits to write (not more than 16) + * @param data Right-aligned value to write + * @return Status of operation (true = success) + */ +/* +bool I2Cdev::writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data) +{ + // 010 value to write + // fedcba9876543210 bit numbers + // xxx args: bitStart=12, length=3 + // 0001110000000000 mask byte + // 1010111110010110 original value (sample) + // 1010001110010110 original & ~mask + // 1010101110010110 masked | value + uint16_t w; + + if (readWord(devAddr, regAddr, &w) != 0) { + uint8_t mask = ((1 << length) - 1) << (bitStart - length + 1); + data <<= (bitStart - length + 1); // shift data into correct position + data &= mask; // zero all non-important bits in data + w &= ~(mask); // zero all important bits in existing word + w |= data; // combine data with existing word + + return writeWord(devAddr, regAddr, w); + } + + return false; +} +*/ +/** Write single byte to an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register address to write to + * @param data New byte value to write + * @return Status of operation (true = success) + */ +bool I2Cdev::writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data) +{ + return writeBytes(devAddr, regAddr, 1, &data); +} + +/** Write single word to a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr Register address to write to + * @param data New word value to write + * @return Status of operation (true = success) + */ +bool I2Cdev::writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data) +{ + return writeWords(devAddr, regAddr, 1, &data); +} + +/** Write multiple bytes to an 8-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register address to write to + * @param length Number of bytes to write + * @param data Buffer to copy new data from + * @return Status of operation (true = success) + */ +bool I2Cdev::writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t* data) +{ +#ifdef I2CDEV_SERIAL_DEBUG + Serial.print("I2C (0x"); + Serial.print(devAddr, HEX); + Serial.print(") writing "); + Serial.print(length, DEC); + Serial.print(" bytes to 0x"); + Serial.print(regAddr, HEX); + Serial.print("..."); +#endif + + uint8_t status = 0; + + Wire.beginTransmission(devAddr); + Wire.write((uint8_t) regAddr); // send address + + for (uint8_t i = 0; i < length; i++) { + Wire.write((uint8_t) data[i]); + +#ifdef I2CDEV_SERIAL_DEBUG + Serial.print(data[i], HEX); + if (i + 1 < length) Serial.print(" "); +#endif + } + + status = Wire.endTransmission(); + +#ifdef I2CDEV_SERIAL_DEBUG + Serial.println(". Done."); +#endif + +#ifdef __SAM3X8E__ + return status > 0; +#else + return status == 0; +#endif +} + +/** Write multiple words to a 16-bit device register. + * @param devAddr I2C slave device address + * @param regAddr First register address to write to + * @param length Number of words to write + * @param data Buffer to copy new data from + * @return Status of operation (true = success) + */ +bool I2Cdev::writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t* data) +{ +#ifdef I2CDEV_SERIAL_DEBUG + Serial.print("I2C (0x"); + Serial.print(devAddr, HEX); + Serial.print(") writing "); + Serial.print(length, DEC); + Serial.print(" words to 0x"); + Serial.print(regAddr, HEX); + Serial.print("..."); +#endif + + uint8_t status = 0; + + Wire.beginTransmission(devAddr); + Wire.write(regAddr); // send address + + for (uint8_t i = 0; i < length * 2; i++) { + Wire.write((uint8_t)(data[i++] >> 8)); // send MSB + Wire.write((uint8_t)data[i]); // send LSB + +#ifdef I2CDEV_SERIAL_DEBUG + Serial.print(data[i], HEX); + if (i + 1 < length) Serial.print(" "); +#endif + } + + status = Wire.endTransmission(); + +#ifdef I2CDEV_SERIAL_DEBUG + Serial.println(". Done."); +#endif + +#ifdef __SAM3X8E__ + return status > 0; +#else + return status == 0; +#endif +} + +/** Default timeout value for read operations. + * Set this to 0 to disable timeout detection. + */ +uint16_t I2Cdev::readTimeout = I2CDEV_DEFAULT_READ_TIMEOUT; + + diff --git a/libraries/I2Cdev/I2Cdev.h b/libraries/I2Cdev/I2Cdev.h new file mode 100644 index 0000000..b1e65d2 --- /dev/null +++ b/libraries/I2Cdev/I2Cdev.h @@ -0,0 +1,97 @@ +// I2Cdev library collection - Main I2C device class header file +// Abstracts bit and byte I2C R/W functions into a convenient class +// 6/9/2012 by Jeff Rowberg +// +// Changelog: +// 2012-06-09 - fix major issue with reading > 32 bytes at a time with Arduino Wire +// - add compiler warnings when using outdated or IDE or limited I2Cdev implementation +// 2011-11-01 - fix write*Bits mask calculation (thanks sasquatch @ Arduino forums) +// 2011-10-03 - added automatic Arduino version detection for ease of use +// 2011-10-02 - added Gene Knight's NBWire TwoWire class implementation with small modifications +// 2011-08-31 - added support for Arduino 1.0 Wire library (methods are different from 0.x) +// 2011-08-03 - added optional timeout parameter to read* methods to easily change from default +// 2011-08-02 - added support for 16-bit registers +// - fixed incorrect Doxygen comments on some methods +// - added timeout value for read operations (thanks mem @ Arduino forums) +// 2011-07-30 - changed read/write function structures to return success or byte counts +// - made all methods static for multi-device memory savings +// 2011-07-28 - 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. +=============================================== +*/ + +#ifndef _I2CDEV_H_ +#define _I2CDEV_H_ + +// ----------------------------------------------------------------------------- +// I2C interface implementation setting +// ----------------------------------------------------------------------------- +#define I2CDEV_IMPLEMENTATION I2CDEV_ARDUINO_WIRE + +// comment this out if you are using a non-optimal IDE/implementation setting +// but want the compiler to shut up about it +#define I2CDEV_IMPLEMENTATION_WARNINGS + +// ----------------------------------------------------------------------------- +// I2C interface implementation options +// ----------------------------------------------------------------------------- +#define I2CDEV_ARDUINO_WIRE 1 // Wire object from Arduino + +// ----------------------------------------------------------------------------- +// Arduino-style "Serial.print" debug constant (uncomment to enable) +// ----------------------------------------------------------------------------- +//#define I2CDEV_SERIAL_DEBUG + +#include "Arduino.h" +#include + +// 1000ms default read timeout (modify with "I2Cdev::readTimeout = [ms];") +#define I2CDEV_DEFAULT_READ_TIMEOUT 1000 + +class I2Cdev { + public: + I2Cdev(); + + static int8_t readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); + //static int8_t readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); + //static int8_t readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); + //static int8_t readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); + //static int8_t readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout); + + static bool writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data); + //static bool writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data); + static bool writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data); + //static bool writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data); + static bool writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data); + static bool writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data); + static bool writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data); + static bool writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data); + + static uint16_t readTimeout; +}; + +#endif /* _I2CDEV_H_ */ diff --git a/libraries/I2Cdev/keywords.txt b/libraries/I2Cdev/keywords.txt new file mode 100644 index 0000000..4132a06 --- /dev/null +++ b/libraries/I2Cdev/keywords.txt @@ -0,0 +1,38 @@ +####################################### +# Syntax Coloring Map For I2Cdev +####################################### + +####################################### +# Datatypes (KEYWORD1) +####################################### +I2Cdev KEYWORD1 + +####################################### +# Methods and Functions (KEYWORD2) +####################################### + +readBit KEYWORD2 +readBitW KEYWORD2 +readBits KEYWORD2 +readBitsW KEYWORD2 +readByte KEYWORD2 +readBytes KEYWORD2 +readWord KEYWORD2 +readWords KEYWORD2 +writeBit KEYWORD2 +writeBitW KEYWORD2 +writeBits KEYWORD2 +writeBitsW KEYWORD2 +writeByte KEYWORD2 +writeBytes KEYWORD2 +writeWord KEYWORD2 +writeWords KEYWORD2 + +####################################### +# Instances (KEYWORD2) +####################################### + +####################################### +# Constants (LITERAL1) +####################################### + diff --git a/libraries/I2Cdev/library.json b/libraries/I2Cdev/library.json new file mode 100644 index 0000000..d456096 --- /dev/null +++ b/libraries/I2Cdev/library.json @@ -0,0 +1,13 @@ +{ + "name": "I2Cdevlib-Core", + "keywords": "i2cdevlib, i2c", + "description": "The I2C Device Library (I2Cdevlib) is a collection of uniform and well-documented classes to provide simple and intuitive interfaces to I2C devices.", + "include": "Arduino/I2Cdev", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/IAQ2000/IAQ2000.cpp b/libraries/IAQ2000/IAQ2000.cpp new file mode 100644 index 0000000..3430eb7 --- /dev/null +++ b/libraries/IAQ2000/IAQ2000.cpp @@ -0,0 +1,141 @@ +// I2Cdev library collection - iAQ-2000 I2C device class +// Based on AppliedSensor iAQ-2000 Interface Description, Version PA1, 2009 +// 2012-04-01 by Peteris Skorovs +// +// 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 +// 2012-11-08 - added TVoc and Status + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2012 Peteris Skorovs, 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 "IAQ2000.h" + +/** Default constructor, uses default I2C address. + * @see IAQ2000_DEFAULT_ADDRESS + */ +IAQ2000::IAQ2000() { + devAddr = IAQ2000_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see IAQ2000_DEFAULT_ADDRESS + * @see IAQ2000_ADDRESS + */ +IAQ2000::IAQ2000(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + */ +void IAQ2000::initialize() { + // Nothing is required, but + // the method should exist anyway. +} + +/** Very primitive method o verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool IAQ2000::testConnection() { + if (getIaqpred() >= 450) { + return true; + } + else { + return false; + } +} + +/** Read iAQ-2000 indoor air quality sensor. + * @return Predicted CO2 concentration based on human induced volatile organic compounds (VOC) detection (in ppm VOC + CO2 equivalents) + */ +uint16_t IAQ2000::getIaqpred() { + // read bytes from the DATA0 AND DATA1 registers and bit-shifting them into a 16-bit value + readAllBytes(devAddr, 2, buffer); + return ((buffer[0] << 8) | buffer[1]); +} + +uint8_t IAQ2000::getIaqstatus() { + // read bytes from the DATA2 register + readAllBytes(devAddr, 3, buffer); + return (buffer[2]); +} + +uint16_t IAQ2000::getIaqtvoc() { + // read bytes from the DATA7 AND DATA8 registers and bit-shifting them into a 16-bit value + readAllBytes(devAddr, 9, buffer); + return ((buffer[7] << 8) | buffer[8]); +} + + + +/** Read bytes from a slave device. + * This is a "stripped-down" version of the standard Jeff Rowberg's I2Cdev::readBytes method + * intended to provide compatibility with iAQ-2000, + * which apparently does not support setting of an address pointer to indicate from which position is to start read from. + * @param devAddr Address of the slave device to read bytes from + * @param length Number of bytes to read + * @param data Buffer to store read data in + * @param timeout Optional read timeout in milliseconds (0 to disable, leave off to use default class value in I2Cdev::readTimeout) + * @return Number of bytes read (0 indicates failure) + */ +int8_t IAQ2000::readAllBytes(uint8_t devAddr, uint8_t length, uint8_t *data, uint16_t timeout) { +#ifdef I2CDEV_SERIAL_DEBUG + Serial.print("I2C (0x"); + Serial.print(devAddr, HEX); + Serial.print(") reading "); + Serial.print(length, DEC); + Serial.print(" bytes..."); +#endif + + int8_t count = 0; + + Wire.requestFrom(devAddr, length); + + uint32_t t1 = millis(); + for (; Wire.available() && (timeout == 0 || millis() - t1 < timeout); count++) { +#if ((I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO < 100) || I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_NBWIRE) + data[count] = Wire.receive(); +#elif (I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE && ARDUINO >= 100) + data[count] = Wire.read(); +#endif +#ifdef I2CDEV_SERIAL_DEBUG + Serial.print(data[count], HEX); + if (count + 1 < length) Serial.print(" "); +#endif + } + if (timeout > 0 && millis() - t1 >= timeout && count < length) count = -1; // timeout + +#ifdef I2CDEV_SERIAL_DEBUG + Serial.print(". Done ("); + Serial.print(count, DEC); + Serial.println(" read)."); +#endif + + return count; +} diff --git a/libraries/IAQ2000/IAQ2000.h b/libraries/IAQ2000/IAQ2000.h new file mode 100644 index 0000000..05a8a0b --- /dev/null +++ b/libraries/IAQ2000/IAQ2000.h @@ -0,0 +1,64 @@ +// I2Cdev library collection - iAQ-2000 I2C device class header file +// Based on AppliedSensor iAQ-2000 Interface Description, Version PA1, 2009 +// 2012-04-01 by Peteris Skorovs +// +// 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 +// 2015-11-08 - added TVoc and Status + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2012 Peteris Skorovs, 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 _IAQ2000_H_ +#define _IAQ2000_H_ + +#include "I2Cdev.h" + +#define IAQ2000_ADDRESS 0x5A +#define IAQ2000_DEFAULT_ADDRESS IAQ2000_ADDRESS + +#define IAQ2000_RA_DATA1 0x00 +#define IAQ2000_RA_DATA2 0x01 + +class IAQ2000 { + public: + IAQ2000(); + IAQ2000(uint8_t address); + void initialize(); + bool testConnection(); + uint16_t getIaqtvoc(); + uint16_t getIaqpred(); + uint8_t getIaqstatus(); + + private: + uint8_t devAddr; + uint8_t buffer[8]; + + int8_t readAllBytes(uint8_t devAddr, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); +}; + +#endif /* _IAQ200_H_ */ diff --git a/libraries/IAQ2000/examples/IAQ2000/IAQ2000.ino b/libraries/IAQ2000/examples/IAQ2000/IAQ2000.ino new file mode 100644 index 0000000..96dcf4f --- /dev/null +++ b/libraries/IAQ2000/examples/IAQ2000/IAQ2000.ino @@ -0,0 +1,162 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for IAQ2000 class +// 2012-04-01 by Peteris Skorovs +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// I2C Device Library hosted at http://www.i2cdevlib.com +// +// Changelog: +// 2012-04-01 - initial release +// 2015-11-08 - added TVoc and Status + +/* ============================================ + IAQ2000 device library code is placed under the MIT license + Copyright (c) 2012 Peteris Skorovs, 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 IAQ2000 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 "IAQ2000.h" + + +// class default I2C address is 0x5A +// specific I2C addresses may be passed as a parameter here +// but this device only supports one I2C address (0x5A) +IAQ2000 iaq; + +uint16_t airQuality; +uint8_t iAQstatus; +uint16_t airTvoc; + +unsigned long startTime; +uint16_t oldairQuality = 0; +uint8_t oldiAQstatus = 0; +uint16_t oldairTvoc = 0; +uint8_t result = 0; + + +#define LED_PIN 13 +bool blinkState = false; + + +void setup() { + // configure LED pin for output + pinMode(LED_PIN, OUTPUT); + // 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); + delay(1000); + Serial.println("Initializing Serial..."); + delay(1000); + + while (!Serial) { + ; // wait for serial port to connect + } + + startTime = millis(); + + // initialize device + // Serial.println("Initializing I2C devices..."); + + + iaq.initialize(); + if (!iaq.testConnection()) { + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); + delay(500); + } +} + +void loop() { + + // display predicted CO2 concentration based on human induced volatile organic compounds (VOC) detection (in ppm VOC + CO2 equivalents) + // during the first 6 hours of continuous operation (burn-in) the module will display 450ppm + // the successful burn-in is saved to the EEPROM, the run-in time after restart is 15min + Serial.print("CO2 = "); + Serial.print(airQuality); + Serial.print(" "); + Serial.print("[ppm] 450-2000"); + + // blink LED to indicate activity + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); + + // wait five seconds + delay(5000); + + // read seansor + iAQstatus = iaq.getIaqstatus(); + + // display predicted CO2 concentration based on human induced volatile organic compounds (VOC) detection (in ppm VOC + CO2 equivalents) + // during the first 6 hours of continuous operation (burn-in) the module will display 450ppm + // the successful burn-in is saved to the EEPROM, the run-in time after restart is 15min + Serial.print(" -- Status = "); + if (iAQstatus == 0) + { + Serial.print("OK"); + } + if (iAQstatus == 1) + { + Serial.print("BUSY"); + } + if (iAQstatus == 16) + { + Serial.print("WARUMUP"); + } + if (iAQstatus == 128) + { + Serial.print("ERROR"); + } + + // blink LED to indicate activity + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); + + // wait five seconds + delay(5000); + + // read seansor + airTvoc = iaq.getIaqtvoc(); + + // display predicted CO2 concentration based on human induced volatile organic compounds (VOC) detection (in ppm VOC + CO2 equivalents) + // during the first 6 hours of continuous operation (burn-in) the module will display 450ppm + // the successful burn-in is saved to the EEPROM, the run-in time after restart is 15min + Serial.print(" -- TVoc = "); + Serial.print(airTvoc); + Serial.print(" "); + Serial.println("[ppb] 125-600"); + + // blink LED to indicate activity + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); + + // wait five seconds + delay(5000); + +} diff --git a/libraries/IAQ2000/keywords.txt b/libraries/IAQ2000/keywords.txt new file mode 100644 index 0000000..775b857 --- /dev/null +++ b/libraries/IAQ2000/keywords.txt @@ -0,0 +1,25 @@ +####################################### +# Syntax Coloring Map For IAQ2000 +####################################### + +####################################### +# Datatypes (KEYWORD1) +####################################### +IAQ2000 KEYWORD1 + +####################################### +# Methods and Functions (KEYWORD2) +####################################### + +initialize KEYWORD2 +testConnection KEYWORD2 +getIaq KEYWORD2 + +####################################### +# Instances (KEYWORD2) +####################################### + +####################################### +# Constants (LITERAL1) +####################################### + diff --git a/libraries/IAQ2000/library.json b/libraries/IAQ2000/library.json new file mode 100644 index 0000000..5eb1595 --- /dev/null +++ b/libraries/IAQ2000/library.json @@ -0,0 +1,18 @@ +{ + "name": "I2Cdevlib-IAQ2000", + "keywords": "co2, carbon, dioxide, sensor, i2cdevlib, i2c", + "description": "The iAQ-2000 Indoor Air Quality Module is a sensitive, low-cost solution for detecting poor air quality", + "include": "Arduino/IAQ2000", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "dependencies": + { + "name": "I2Cdevlib-Core", + "frameworks": "arduino" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/ITG3200/ITG3200.cpp b/libraries/ITG3200/ITG3200.cpp new file mode 100644 index 0000000..d34854d --- /dev/null +++ b/libraries/ITG3200/ITG3200.cpp @@ -0,0 +1,521 @@ +// I2Cdev library collection - ITG3200 I2C device class +// Based on InvenSense ITG-3200 datasheet rev. 1.4, 3/30/2010 (PS-ITG-3200A-00-01.4) +// 7/31/2011 by Jeff Rowberg +// 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. +=============================================== +*/ + +#include "ITG3200.h" + +/** Default constructor, uses default I2C address. + * @see ITG3200_DEFAULT_ADDRESS + */ +ITG3200::ITG3200() { + devAddr = ITG3200_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see ITG3200_DEFAULT_ADDRESS + * @see ITG3200_ADDRESS_AD0_LOW + * @see ITG3200_ADDRESS_AD0_HIGH + */ +ITG3200::ITG3200(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * This will activate the gyroscope, so be sure to adjust the power settings + * after you call this method if you want it to enter standby mode, or another + * less demanding mode of operation. This also sets the gyroscope to use the + * X-axis gyro for a clock source. Note that it doesn't have any delays in the + * routine, which means you might want to add ~50ms to be safe if you happen + * to need to read gyro data immediately after initialization. The data will + * flow in either case, but the first reports may have higher error offsets. + */ +void ITG3200::initialize() { + setFullScaleRange(ITG3200_FULLSCALE_2000); + setClockSource(ITG3200_CLOCK_PLL_XGYRO); +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool ITG3200::testConnection() { + return getDeviceID() == 0b110100; +} + +// WHO_AM_I register + +/** Get Device ID. + * This register is used to verify the identity of the device (0b110100). + * @return Device ID (should be 0x34, 52 dec, 64 oct) + * @see ITG3200_RA_WHO_AM_I + * @see ITG3200_RA_DEVID_BIT + * @see ITG3200_RA_DEVID_LENGTH + */ +uint8_t ITG3200::getDeviceID() { + I2Cdev::readBits(devAddr, ITG3200_RA_WHO_AM_I, ITG3200_DEVID_BIT, ITG3200_DEVID_LENGTH, buffer); + return buffer[0]; +} +/** Set Device ID. + * Write a new ID into the WHO_AM_I register (no idea why this should ever be + * necessary though). + * @param id New device ID to set. + * @see getDeviceID() + * @see ITG3200_RA_WHO_AM_I + * @see ITG3200_RA_DEVID_BIT + * @see ITG3200_RA_DEVID_LENGTH + */ +void ITG3200::setDeviceID(uint8_t id) { + I2Cdev::writeBits(devAddr, ITG3200_RA_WHO_AM_I, ITG3200_DEVID_BIT, ITG3200_DEVID_LENGTH, id); +} + +// SMPLRT_DIV register + +/** Get sample rate. + * This register determines the sample rate of the ITG-3200 gyros. The gyros' + * outputs are sampled internally at either 1kHz or 8kHz, determined by the + * DLPF_CFG setting (see register 22). This sampling is then filtered digitally + * and delivered into the sensor registers after the number of cycles determined + * by this register. The sample rate is given by the following formula: + * + * F_sample = F_internal / (divider+1), where F_internal is either 1kHz or 8kHz + * + * As an example, if the internal sampling is at 1kHz, then setting this + * register to 7 would give the following: + * + * F_sample = 1kHz / (7 + 1) = 125Hz, or 8ms per sample + * + * @return Current sample rate + * @see setDLPFBandwidth() + * @see ITG3200_RA_SMPLRT_DIV + */ +uint8_t ITG3200::getRate() { + I2Cdev::readByte(devAddr, ITG3200_RA_SMPLRT_DIV, buffer); + return buffer[0]; +} +/** Set sample rate. + * @param rate New sample rate + * @see getRate() + * @see setDLPFBandwidth() + * @see ITG3200_RA_SMPLRT_DIV + */ +void ITG3200::setRate(uint8_t rate) { + I2Cdev::writeByte(devAddr, ITG3200_RA_SMPLRT_DIV, rate); +} + +// DLPF_FS register + +/** Set full-scale range. + * The FS_SEL parameter allows setting the full-scale range of the gyro sensors, + * as described in the table below. The power-on-reset value of FS_SEL is 00h. + * Set to 03h for proper operation. + * + * 0 = Reserved + * 1 = Reserved + * 2 = Reserved + * 3 = +/- 2000 degrees/sec + * + * @return Current full-scale range setting + * @see ITG3200_FULLSCALE_2000 + * @see ITG3200_RA_DLPF_FS + * @see ITG3200_DF_FS_SEL_BIT + * @see ITG3200_DF_FS_SEL_LENGTH + */ +uint8_t ITG3200::getFullScaleRange() { + I2Cdev::readBits(devAddr, ITG3200_RA_DLPF_FS, ITG3200_DF_FS_SEL_BIT, ITG3200_DF_FS_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set full-scale range setting. + * @param range New full-scale range value + * @see getFullScaleRange() + * @see ITG3200_FULLSCALE_2000 + * @see ITG3200_RA_DLPF_FS + * @see ITG3200_DF_FS_SEL_BIT + * @see ITG3200_DF_FS_SEL_LENGTH + */ +void ITG3200::setFullScaleRange(uint8_t range) { + I2Cdev::writeBits(devAddr, ITG3200_RA_DLPF_FS, ITG3200_DF_FS_SEL_BIT, ITG3200_DF_FS_SEL_LENGTH, range); +} +/** Get digital low-pass filter bandwidth. + * The DLPF_CFG parameter sets the digital low pass filter configuration. It + * also determines the internal sampling rate used by the device as shown in + * the table below. + * + * DLPF_CFG | Low-Pass Filter Bandwidth | Internal Sample Rate + * ---------+---------------------------+--------------------- + * 0 | 256Hz | 8kHz + * 1 | 188Hz | 1kHz + * 2 | 98Hz | 1kHz + * 3 | 42Hz | 1kHz + * 4 | 20Hz | 1kHz + * 5 | 10Hz | 1kHz + * 6 | 5Hz | 1kHz + * 7 | Reserved | Reserved + * + * @return DLFP bandwidth setting + * @see ITG3200_RA_DLPF_FS + * @see ITG3200_DF_DLPF_CFG_BIT + * @see ITG3200_DF_DLPF_CFG_LENGTH + */ +uint8_t ITG3200::getDLPFBandwidth() { + I2Cdev::readBits(devAddr, ITG3200_RA_DLPF_FS, ITG3200_DF_DLPF_CFG_BIT, ITG3200_DF_DLPF_CFG_LENGTH, buffer); + return buffer[0]; +} +/** Set digital low-pass filter bandwidth. + * @param bandwidth New DLFP bandwidth setting + * @see getDLPFBandwidth() + * @see ITG3200_DLPF_BW_256 + * @see ITG3200_RA_DLPF_FS + * @see ITG3200_DF_DLPF_CFG_BIT + * @see ITG3200_DF_DLPF_CFG_LENGTH + */ +void ITG3200::setDLPFBandwidth(uint8_t bandwidth) { + I2Cdev::writeBits(devAddr, ITG3200_RA_DLPF_FS, ITG3200_DF_DLPF_CFG_BIT, ITG3200_DF_DLPF_CFG_LENGTH, bandwidth); +} + +// INT_CFG register + +/** Get interrupt logic level mode. + * Will be set 0 for active-high, 1 for active-low. + * @return Current interrupt mode (0=active-high, 1=active-low) + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_ACTL_BIT + */ +bool ITG3200::getInterruptMode() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_ACTL_BIT, buffer); + return buffer[0]; +} +/** Set interrupt logic level mode. + * @param mode New interrupt mode (0=active-high, 1=active-low) + * @see getInterruptMode() + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_ACTL_BIT + */ +void ITG3200::setInterruptMode(bool mode) { + I2Cdev::writeBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_ACTL_BIT, mode); +} +/** Get interrupt drive mode. + * Will be set 0 for push-pull, 1 for open-drain. + * @return Current interrupt drive mode (0=push-pull, 1=open-drain) + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_OPEN_BIT + */ +bool ITG3200::getInterruptDrive() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_OPEN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt drive mode. + * @param drive New interrupt drive mode (0=push-pull, 1=open-drain) + * @see getInterruptDrive() + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_OPEN_BIT + */ +void ITG3200::setInterruptDrive(bool drive) { + I2Cdev::writeBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_OPEN_BIT, drive); +} +/** Get interrupt latch mode. + * Will be set 0 for 50us-pulse, 1 for latch-until-int-cleared. + * @return Current latch mode (0=50us-pulse, 1=latch-until-int-cleared) + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_LATCH_INT_EN_BIT + */ +bool ITG3200::getInterruptLatch() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_LATCH_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch mode. + * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared) + * @see getInterruptLatch() + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_LATCH_INT_EN_BIT + */ +void ITG3200::setInterruptLatch(bool latch) { + I2Cdev::writeBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_LATCH_INT_EN_BIT, latch); +} +/** Get interrupt latch clear mode. + * Will be set 0 for status-read-only, 1 for any-register-read. + * @return Current latch clear mode (0=status-read-only, 1=any-register-read) + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_INT_ANYRD_2CLEAR_BIT + */ +bool ITG3200::getInterruptLatchClear() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_INT_ANYRD_2CLEAR_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch clear mode. + * @param clear New latch clear mode (0=status-read-only, 1=any-register-read) + * @see getInterruptLatchClear() + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_INT_ANYRD_2CLEAR_BIT + */ +void ITG3200::setInterruptLatchClear(bool clear) { + I2Cdev::writeBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_INT_ANYRD_2CLEAR_BIT, clear); +} +/** Get "device ready" interrupt enabled setting. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled setting + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_ITG_RDY_EN_BIT + */ +bool ITG3200::getIntDeviceReadyEnabled() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_ITG_RDY_EN_BIT, buffer); + return buffer[0]; +} +/** Set "device ready" interrupt enabled setting. + * @param enabled New interrupt enabled setting + * @see getIntDeviceReadyEnabled() + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_ITG_RDY_EN_BIT + */ +void ITG3200::setIntDeviceReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_ITG_RDY_EN_BIT, enabled); +} +/** Get "data ready" interrupt enabled setting. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled setting + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_RAW_RDY_EN_BIT + */ +bool ITG3200::getIntDataReadyEnabled() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_RAW_RDY_EN_BIT, buffer); + return buffer[0]; +} +/** Set "data ready" interrupt enabled setting. + * @param enabled New interrupt enabled setting + * @see getIntDataReadyEnabled() + * @see ITG3200_RA_INT_CFG + * @see ITG3200_INTCFG_RAW_RDY_EN_BIT + */ +void ITG3200::setIntDataReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ITG3200_RA_INT_CFG, ITG3200_INTCFG_RAW_RDY_EN_BIT, enabled); +} + +// INT_STATUS register + +/** Get Device Ready interrupt status. + * The ITG_RDY interrupt indicates that the PLL is ready and gyroscopic data can + * be read. + * @return Device Ready interrupt status + * @see ITG3200_RA_INT_STATUS + * @see ITG3200_INTSTAT_RAW_DATA_READY_BIT + */ +bool ITG3200::getIntDeviceReadyStatus() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_STATUS, ITG3200_INTSTAT_ITG_RDY_BIT, buffer); + return buffer[0]; +} +/** Get Data Ready interrupt status. + * In normal use, the RAW_DATA_RDY interrupt is used to determine when new + * sensor data is available in and of the sensor registers (27 to 32). + * @return Data Ready interrupt status + * @see ITG3200_RA_INT_STATUS + * @see ITG3200_INTSTAT_RAW_DATA_READY_BIT + */ +bool ITG3200::getIntDataReadyStatus() { + I2Cdev::readBit(devAddr, ITG3200_RA_INT_STATUS, ITG3200_INTSTAT_RAW_DATA_READY_BIT, buffer); + return buffer[0]; +} + +// TEMP_OUT_* registers + +/** Get current internal temperature. + * @return Temperature reading in 16-bit 2's complement format + * @see ITG3200_RA_TEMP_OUT_H + */ +int16_t ITG3200::getTemperature() { + I2Cdev::readBytes(devAddr, ITG3200_RA_TEMP_OUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// GYRO_*OUT_* registers + +/** Get 3-axis gyroscope readings. + * @param x 16-bit signed integer container for X-axis rotation + * @param y 16-bit signed integer container for Y-axis rotation + * @param z 16-bit signed integer container for Z-axis rotation + * @see ITG3200_RA_GYRO_XOUT_H + */ +void ITG3200::getRotation(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, ITG3200_RA_GYRO_XOUT_H, 6, buffer); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis gyroscope reading. + * @return X-axis rotation measurement in 16-bit 2's complement format + * @see ITG3200_RA_GYRO_XOUT_H + */ +int16_t ITG3200::getRotationX() { + I2Cdev::readBytes(devAddr, ITG3200_RA_GYRO_XOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis gyroscope reading. + * @return Y-axis rotation measurement in 16-bit 2's complement format + * @see ITG3200_RA_GYRO_YOUT_H + */ +int16_t ITG3200::getRotationY() { + I2Cdev::readBytes(devAddr, ITG3200_RA_GYRO_YOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Z-axis gyroscope reading. + * @return Z-axis rotation measurement in 16-bit 2's complement format + * @see ITG3200_RA_GYRO_ZOUT_H + */ +int16_t ITG3200::getRotationZ() { + I2Cdev::readBytes(devAddr, ITG3200_RA_GYRO_ZOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// PWR_MGM register + +/** Trigger a full device reset. + * A small delay of ~50ms may be desirable after triggering a reset. + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_H_RESET_BIT + */ +void ITG3200::reset() { + I2Cdev::writeBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_H_RESET_BIT, true); +} +/** Get sleep mode status. + * Setting the SLEEP bit in the register puts the device into very low power + * sleep mode. In this mode, only the serial interface and internal registers + * remain active, allowing for a very low standby current. Clearing this bit + * puts the device back into normal mode. To save power, the individual standby + * selections for each of the gyros should be used if any gyro axis is not used + * by the application. + * @return Current sleep mode enabled status + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_SLEEP_BIT + */ +bool ITG3200::getSleepEnabled() { + I2Cdev::readBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_SLEEP_BIT, buffer); + return buffer[0]; +} +/** Set sleep mode status. + * @param enabled New sleep mode enabled status + * @see getSleepEnabled() + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_SLEEP_BIT + */ +void ITG3200::setSleepEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_SLEEP_BIT, enabled); +} +/** Get X-axis standby enabled status. + * If enabled, the X-axis will not gather or report data (or use power). + * @return Current X-axis standby enabled status + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_STBY_XG_BIT + */ +bool ITG3200::getStandbyXEnabled() { + I2Cdev::readBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_STBY_XG_BIT, buffer); + return buffer[0]; +} +/** Set X-axis standby enabled status. + * @param New X-axis standby enabled status + * @see getStandbyXEnabled() + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_STBY_XG_BIT + */ +void ITG3200::setStandbyXEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_STBY_XG_BIT, enabled); +} +/** Get Y-axis standby enabled status. + * If enabled, the Y-axis will not gather or report data (or use power). + * @return Current Y-axis standby enabled status + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_STBY_YG_BIT + */ +bool ITG3200::getStandbyYEnabled() { + I2Cdev::readBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_STBY_YG_BIT, buffer); + return buffer[0]; +} +/** Set Y-axis standby enabled status. + * @param New Y-axis standby enabled status + * @see getStandbyYEnabled() + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_STBY_YG_BIT + */ +void ITG3200::setStandbyYEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_STBY_YG_BIT, enabled); +} +/** Get Z-axis standby enabled status. + * If enabled, the Z-axis will not gather or report data (or use power). + * @return Current Z-axis standby enabled status + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_STBY_ZG_BIT + */ +bool ITG3200::getStandbyZEnabled() { + I2Cdev::readBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_STBY_ZG_BIT, buffer); + return buffer[0]; +} +/** Set Z-axis standby enabled status. + * @param New Z-axis standby enabled status + * @see getStandbyZEnabled() + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_STBY_ZG_BIT + */ +void ITG3200::setStandbyZEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_STBY_ZG_BIT, enabled); +} +/** Get clock source setting. + * @return Current clock source setting + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_CLK_SEL_BIT + * @see ITG3200_PWR_CLK_SEL_LENGTH + */ +uint8_t ITG3200::getClockSource() { + I2Cdev::readBits(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_CLK_SEL_BIT, ITG3200_PWR_CLK_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set clock source setting. + * On power up, the ITG-3200 defaults to the internal oscillator. It is highly recommended that the device is configured to use one of the gyros (or an external clock) as the clock reference, due to the improved stability. + * + * The CLK_SEL setting determines the device clock source as follows: + * + * CLK_SEL | Clock Source + * --------+-------------------------------------- + * 0 | Internal oscillator + * 1 | PLL with X Gyro reference + * 2 | PLL with Y Gyro reference + * 3 | PLL with Z Gyro reference + * 4 | PLL with external 32.768kHz reference + * 5 | PLL with external 19.2MHz reference + * 6 | Reserved + * 7 | Reserved + * + * @param source New clock source setting + * @see getClockSource() + * @see ITG3200_RA_PWR_MGM + * @see ITG3200_PWR_CLK_SEL_BIT + * @see ITG3200_PWR_CLK_SEL_LENGTH + */ +void ITG3200::setClockSource(uint8_t source) { + I2Cdev::writeBits(devAddr, ITG3200_RA_PWR_MGM, ITG3200_PWR_CLK_SEL_BIT, ITG3200_PWR_CLK_SEL_LENGTH, source); +} diff --git a/libraries/ITG3200/ITG3200.h b/libraries/ITG3200/ITG3200.h new file mode 100644 index 0000000..6a40039 --- /dev/null +++ b/libraries/ITG3200/ITG3200.h @@ -0,0 +1,179 @@ +// I2Cdev library collection - ITG3200 I2C device class header file +// Based on InvenSense ITG-3200 datasheet rev. 1.4, 3/30/2010 (PS-ITG-3200A-00-01.4) +// 7/31/2011 by Jeff Rowberg +// 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 _ITG3200_H_ +#define _ITG3200_H_ + +#include "I2Cdev.h" + +#define ITG3200_ADDRESS_AD0_LOW 0x68 // address pin low (GND), default for SparkFun IMU Digital Combo board +#define ITG3200_ADDRESS_AD0_HIGH 0x69 // address pin high (VCC), default for SparkFun ITG-3200 Breakout board +#define ITG3200_DEFAULT_ADDRESS ITG3200_ADDRESS_AD0_LOW + +#define ITG3200_RA_WHO_AM_I 0x00 +#define ITG3200_RA_SMPLRT_DIV 0x15 +#define ITG3200_RA_DLPF_FS 0x16 +#define ITG3200_RA_INT_CFG 0x17 +#define ITG3200_RA_INT_STATUS 0x1A +#define ITG3200_RA_TEMP_OUT_H 0x1B +#define ITG3200_RA_TEMP_OUT_L 0x1C +#define ITG3200_RA_GYRO_XOUT_H 0x1D +#define ITG3200_RA_GYRO_XOUT_L 0x1E +#define ITG3200_RA_GYRO_YOUT_H 0x1F +#define ITG3200_RA_GYRO_YOUT_L 0x20 +#define ITG3200_RA_GYRO_ZOUT_H 0x21 +#define ITG3200_RA_GYRO_ZOUT_L 0x22 +#define ITG3200_RA_PWR_MGM 0x3E + +#define ITG3200_DEVID_BIT 6 +#define ITG3200_DEVID_LENGTH 6 + +#define ITG3200_DF_FS_SEL_BIT 4 +#define ITG3200_DF_FS_SEL_LENGTH 2 +#define ITG3200_DF_DLPF_CFG_BIT 2 +#define ITG3200_DF_DLPF_CFG_LENGTH 3 + +#define ITG3200_FULLSCALE_2000 0x03 + +#define ITG3200_DLPF_BW_256 0x00 +#define ITG3200_DLPF_BW_188 0x01 +#define ITG3200_DLPF_BW_98 0x02 +#define ITG3200_DLPF_BW_42 0x03 +#define ITG3200_DLPF_BW_20 0x04 +#define ITG3200_DLPF_BW_10 0x05 +#define ITG3200_DLPF_BW_5 0x06 + +#define ITG3200_INTCFG_ACTL_BIT 7 +#define ITG3200_INTCFG_OPEN_BIT 6 +#define ITG3200_INTCFG_LATCH_INT_EN_BIT 5 +#define ITG3200_INTCFG_INT_ANYRD_2CLEAR_BIT 4 +#define ITG3200_INTCFG_ITG_RDY_EN_BIT 2 +#define ITG3200_INTCFG_RAW_RDY_EN_BIT 0 + +#define ITG3200_INTMODE_ACTIVEHIGH 0x00 +#define ITG3200_INTMODE_ACTIVELOW 0x01 + +#define ITG3200_INTDRV_PUSHPULL 0x00 +#define ITG3200_INTDRV_OPENDRAIN 0x01 + +#define ITG3200_INTLATCH_50USPULSE 0x00 +#define ITG3200_INTLATCH_WAITCLEAR 0x01 + +#define ITG3200_INTCLEAR_STATUSREAD 0x00 +#define ITG3200_INTCLEAR_ANYREAD 0x01 + +#define ITG3200_INTSTAT_ITG_RDY_BIT 2 +#define ITG3200_INTSTAT_RAW_DATA_READY_BIT 0 + +#define ITG3200_PWR_H_RESET_BIT 7 +#define ITG3200_PWR_SLEEP_BIT 6 +#define ITG3200_PWR_STBY_XG_BIT 5 +#define ITG3200_PWR_STBY_YG_BIT 4 +#define ITG3200_PWR_STBY_ZG_BIT 3 +#define ITG3200_PWR_CLK_SEL_BIT 2 +#define ITG3200_PWR_CLK_SEL_LENGTH 3 + +#define ITG3200_CLOCK_INTERNAL 0x00 +#define ITG3200_CLOCK_PLL_XGYRO 0x01 +#define ITG3200_CLOCK_PLL_YGYRO 0x02 +#define ITG3200_CLOCK_PLL_ZGYRO 0x03 +#define ITG3200_CLOCK_PLL_EXT32K 0x04 +#define ITG3200_CLOCK_PLL_EXT19M 0x05 + +class ITG3200 { + public: + ITG3200(); + ITG3200(uint8_t address); + + void initialize(); + bool testConnection(); + + // WHO_AM_I register + uint8_t getDeviceID(); + void setDeviceID(uint8_t id); + + // SMPLRT_DIV register + uint8_t getRate(); + void setRate(uint8_t rate); + + // DLPF_FS register + uint8_t getFullScaleRange(); + void setFullScaleRange(uint8_t range); + uint8_t getDLPFBandwidth(); + void setDLPFBandwidth(uint8_t bandwidth); + + // INT_CFG register + bool getInterruptMode(); + void setInterruptMode(bool mode); + bool getInterruptDrive(); + void setInterruptDrive(bool drive); + bool getInterruptLatch(); + void setInterruptLatch(bool latch); + bool getInterruptLatchClear(); + void setInterruptLatchClear(bool clear); + bool getIntDeviceReadyEnabled(); + void setIntDeviceReadyEnabled(bool enabled); + bool getIntDataReadyEnabled(); + void setIntDataReadyEnabled(bool enabled); + + // INT_STATUS register + bool getIntDeviceReadyStatus(); + bool getIntDataReadyStatus(); + + // TEMP_OUT_* registers + int16_t getTemperature(); + + // GYRO_*OUT_* registers + void getRotation(int16_t* x, int16_t* y, int16_t* z); + int16_t getRotationX(); + int16_t getRotationY(); + int16_t getRotationZ(); + + // PWR_MGM register + void reset(); + bool getSleepEnabled(); + void setSleepEnabled(bool enabled); + bool getStandbyXEnabled(); + void setStandbyXEnabled(bool enabled); + bool getStandbyYEnabled(); + void setStandbyYEnabled(bool enabled); + bool getStandbyZEnabled(); + void setStandbyZEnabled(bool enabled); + uint8_t getClockSource(); + void setClockSource(uint8_t source); + + private: + uint8_t devAddr; + uint8_t buffer[6]; +}; + +#endif /* _ITG3200_H_ */ diff --git a/libraries/ITG3200/examples/ITG3200_raw/ITG3200_raw.ino b/libraries/ITG3200/examples/ITG3200_raw/ITG3200_raw.ino new file mode 100644 index 0000000..f4bd729 --- /dev/null +++ b/libraries/ITG3200/examples/ITG3200_raw/ITG3200_raw.ino @@ -0,0 +1,86 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for ITG3200 class +// 10/7/2011 by Jeff Rowberg +// 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 ITG3200 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 "ITG3200.h" + +// class default I2C address is 0x68 +// specific I2C addresses may be passed as a parameter here +// AD0 low = 0x68 (default for SparkFun 6DOF board) +// AD0 high = 0x69 (default for SparkFun ITG-3200 standalone board) +ITG3200 gyro; + +int16_t gx, gy, gz; + +#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..."); + gyro.initialize(); + + // verify connection + Serial.println("Testing device connections..."); + Serial.println(gyro.testConnection() ? "ITG3200 connection successful" : "ITG3200 connection failed"); + + // configure Arduino LED for + pinMode(LED_PIN, OUTPUT); +} + +void loop() { + // read raw gyro measurements from device + gyro.getRotation(&gx, &gy, &gz); + + // display tab-separated gyro x/y/z values + Serial.print("gyro:\t"); + Serial.print(gx); Serial.print("\t"); + Serial.print(gy); Serial.print("\t"); + Serial.println(gz); + + // blink LED to indicate activity + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); +} diff --git a/libraries/ITG3200/library.json b/libraries/ITG3200/library.json new file mode 100644 index 0000000..398dfcd --- /dev/null +++ b/libraries/ITG3200/library.json @@ -0,0 +1,18 @@ +{ + "name": "I2Cdevlib-ITG3200", + "keywords": "gyroscope, sensor, i2cdevlib, i2c", + "description": "The ITG-3200 is groundbreaking 3-axis, digital output MEMS gyroscope", + "include": "Arduino/ITG3200", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "dependencies": + { + "name": "I2Cdevlib-Core", + "frameworks": "arduino" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/L3G4200D/L3G4200D.cpp b/libraries/L3G4200D/L3G4200D.cpp new file mode 100644 index 0000000..04e10c5 --- /dev/null +++ b/libraries/L3G4200D/L3G4200D.cpp @@ -0,0 +1,1508 @@ +// I2Cdev library collection - L3G4200D I2C device class +// Based on STMicroelectronics L3G4200D datasheet rev. 3, 12/2010 +// 7/31/2013 by Jonathan Arnett +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2013-07-31 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Jonathan Arnett, 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 "L3G4200D.h" + +/** Default constructor, uses default I2C address. + * @see L3G4200D_DEFAULT_ADDRESS + */ +L3G4200D::L3G4200D() { + devAddr = L3G4200D_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see L3G4200D_DEFAULT_ADDRESS + * @see L3G4200D_ADDRESS + */ +L3G4200D::L3G4200D(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * All values are defaults except for the power on bit in CTRL_REG_1 + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_RA_CTRL_REG2 + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_RA_CTRL_REG4 + * @see L3G4200D_RA_CTRL_REG5 + */ +void L3G4200D::initialize() { + I2Cdev::writeByte(devAddr, L3G4200D_RA_CTRL_REG1, 0b00001111); + I2Cdev::writeByte(devAddr, L3G4200D_RA_CTRL_REG2, 0b00000000); + I2Cdev::writeByte(devAddr, L3G4200D_RA_CTRL_REG3, 0b00000000); + I2Cdev::writeByte(devAddr, L3G4200D_RA_CTRL_REG4, 0b00000000); + I2Cdev::writeByte(devAddr, L3G4200D_RA_CTRL_REG5, 0b00000000); +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool L3G4200D::testConnection() { + return getDeviceID() == 0b11010011; +} + +// WHO_AM_I register, read-only + +/** Get the Device ID. + * The WHO_AM_I register holds the device's id + * @return Device ID (should be 0b11010011, 109, 0x69) + * @see L3G4200D_RA_WHO_AM_I + */ +uint8_t L3G4200D::getDeviceID() { + I2Cdev::readByte(devAddr, L3G4200D_RA_WHO_AM_I, buffer); + return buffer[0]; +} + +// CTRL_REG1 register, r/w + +/** Set the output data rate + * @param rate The new data output rate (can be 100, 200, 400, or 800) + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_ODR_BIT + * @see L3G4200D_ODR_LENGTH + * @see L3G4200D_RATE_100 + * @see L3G4200D_RATE_200 + * @see L3G4200D_RATE_400 + * @see L3G4200D_RATE_800 + */ +void L3G4200D::setOutputDataRate(uint16_t rate) { + uint8_t writeVal; + + if (rate == 100) { + writeVal = L3G4200D_RATE_100; + } else if (rate == 200) { + writeVal = L3G4200D_RATE_200; + } else if (rate == 400) { + writeVal = L3G4200D_RATE_400; + } else { + writeVal = L3G4200D_RATE_800; + } + + I2Cdev::writeBits(devAddr, L3G4200D_RA_CTRL_REG1, L3G4200D_ODR_BIT, + L3G4200D_ODR_LENGTH, writeVal); +} + +/** Get the current output data rate + * @return Current data output rate + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_ODR_BIT + * @see L3G4200D_ODR_LENGTH + * @see L3G4200D_RATE_100 + * @see L3G4200D_RATE_200 + * @see L3G4200D_RATE_400 + * @see L3G4200D_RATE_800 + */ +uint16_t L3G4200D::getOutputDataRate() { + I2Cdev::readBits(devAddr, L3G4200D_RA_CTRL_REG1, L3G4200D_ODR_BIT, + L3G4200D_ODR_LENGTH, buffer); + uint8_t rate = buffer[0]; + + if (rate == L3G4200D_RATE_100) { + return 100; + } else if (rate == L3G4200D_RATE_200) { + return 200; + } else if (rate == L3G4200D_RATE_400) { + return 400; + } + return 800; +} + +/** Set the bandwidth cut-off mode + * @param mode The new bandwidth cut-off mode + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_BW_BIT + * @see L3G4200D_BW_LENGTH + * @see L3G4200D_BW_LOW + * @see L3G4200D_BW_MED_LOW + * @see L3G4200D_BW_MED_HIGH + * @see L3G4200D_BW_HIGH + */ +void L3G4200D::setBandwidthCutOffMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, L3G4200D_RA_CTRL_REG1, L3G4200D_BW_BIT, + L3G4200D_BW_LENGTH, mode); +} + +/** Get the current bandwidth cut-off mode + * @return Current bandwidth cut off mode + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_BW_BIT + * @see L3G4200D_BW_LENGTH + * @see L3G4200D_BW_LOW + * @see L3G4200D_BW_MED_LOW + * @see L3G4200D_BW_MED_HIGH + * @see L3G4200D_BW_HIGH + */ +uint8_t L3G4200D::getBandwidthCutOffMode() { + I2Cdev::readBits(devAddr, L3G4200D_RA_CTRL_REG1, L3G4200D_BW_BIT, + L3G4200D_BW_LENGTH, buffer); + return buffer[0]; +} + +/** Gets the current bandwidth cutoff based on ODR and BW + * @return Float value of the bandwidth cut off + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_ODR_BIT + * @see L3G4200D_ODR_LENGTH + * @see L3G4200D_RATE_100 + * @see L3G4200D_RATE_200 + * @see L3G4200D_RATE_400 + * @see L3G4200D_RATE_800 + * @see L3G4200D_BW_BIT + * @see L3G4200D_BW_LENGTH + * @see L3G4200D_BW_LOW + * @see L3G4200D_BW_MED_LOW + * @see L3G4200D_BW_MED_HIGH + * @see L3G4200D_BW_HIGH + */ +float L3G4200D::getBandwidthCutOff() { + uint16_t dataRate = getOutputDataRate(); + uint8_t bandwidthMode = getBandwidthCutOffMode(); + + if (dataRate == 100) { + if (bandwidthMode == L3G4200D_BW_LOW) { + return 12.5; + } else { + return 25.0; + } + } else if (dataRate == 200) { + if (bandwidthMode == L3G4200D_BW_LOW) { + return 12.5; + } else if (bandwidthMode == L3G4200D_BW_MED_LOW) { + return 25.0; + } else if (bandwidthMode == L3G4200D_BW_MED_HIGH) { + return 50.0; + } else { + return 70.0; + } + } else if (dataRate == 400) { + if (bandwidthMode == L3G4200D_BW_LOW) { + return 20.0; + } else if (bandwidthMode == L3G4200D_BW_MED_LOW) { + return 25.0; + } else if (bandwidthMode == L3G4200D_BW_MED_HIGH) { + return 50.0; + } else { + return 110.0; + } + } else { + if (bandwidthMode == L3G4200D_BW_LOW) { + return 30.0; + } else if (bandwidthMode == L3G4200D_BW_MED_LOW) { + return 35.0; + } else if (bandwidthMode == L3G4200D_BW_MED_HIGH) { + return 50.0; + } else { + return 110.0; + } + } +} + +/** Set power on or off + * @param enabled The new power setting (true for on, false for off) + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_PD_BIT + */ +void L3G4200D::setPowerOn(bool on) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG1, L3G4200D_PD_BIT, on); +} + +/** Get the current power state + * @return Powered on state (true for on, false for off) + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_PD_BIT + */ +bool L3G4200D::getPowerOn() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG1, L3G4200D_PD_BIT, buffer); + return buffer[0]; +} + +/** Enables or disables the ability to get Z data + * @param enabled The new enabled state of the Z axis + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_ZEN_BIT + */ +void L3G4200D::setZEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG1, L3G4200D_ZEN_BIT, enabled); +} + +/** Get whether Z axis data is enabled + * @return True if the Z axis is enabled, false otherwise + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_ZEN_BIT + */ +bool L3G4200D::getZEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG1, L3G4200D_ZEN_BIT, buffer); + return buffer[0]; +} + +/** Enables or disables the ability to get Y data + * @param enabled The new enabled state of the Y axis + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_YEN_BIT + */ +void L3G4200D::setYEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG1, L3G4200D_YEN_BIT, enabled); +} + +/** Get whether Y axis data is enabled + * @return True if the Y axis is enabled, false otherwise + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_YEN_BIT + */ +bool L3G4200D::getYEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG1, L3G4200D_YEN_BIT, buffer); + return buffer[0]; +} + +/** Enables or disables the ability to get X data + * @param enabled The new enabled state of the X axis + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_XEN_BIT + */ +void L3G4200D::setXEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG1, L3G4200D_XEN_BIT, enabled); +} + +/** Get whether X axis data is enabled + * @return True if the X axis is enabled, false otherwise + * @see L3G4200D_RA_CTRL_REG1 + * @see L3G4200D_XEN_BIT + */ +bool L3G4200D::getXEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG1, L3G4200D_XEN_BIT, buffer); + return buffer[0]; +} + +// CTRL_REG2 register, r/w + +/** Set the high pass mode + * @param mode The new high pass mode + * @see L3G4200D_RA_CTRL_REG2 + * @see L3G4200D_HPM_BIT + * @see L3G4200D_HPM_LENGTH + * @see L3G4200D_HPM_HRF + * @see L3G4200D_HPM_REFERENCE + * @see L3G4200D_HPM_NORMAL + * @see L3G4200D_HPM_AUTORESET + */ +void L3G4200D::setHighPassMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, L3G4200D_RA_CTRL_REG2, L3G4200D_HPM_BIT, + L3G4200D_HPM_LENGTH, mode); +} + +/** Get the high pass mode + * @return High pass mode + * @see L3G4200D_RA_CTRL_REG2 + * @see L3G4200D_HPM_BIT + * @see L3G4200D_HPM_LENGTH + * @see L3G4200D_HPM_HRF + * @see L3G4200D_HPM_REFERENCE + * @see L3G4200D_HPM_NORMAL + * @see L3G4200D_HPM_AUTORESET + */ +uint8_t L3G4200D::getHighPassMode() { + I2Cdev::readBits(devAddr, L3G4200D_RA_CTRL_REG2, L3G4200D_HPM_BIT, + L3G4200D_HPM_LENGTH, buffer); + return buffer[0]; +} + +/** Set the high pass filter cut off frequency level (1 - 10) + * @param level The new level for the hpcf, using one of the defined levels + * @see L3G4200D_RA_CTRL_REG2 + * @see L3G4200D_HPCF_BIT + * @see L3G4200D_HPCF_LENGTH + * @see L3G4200D_HPCF1 + * @see L3G4200D_HPCF2 + * @see L3G4200D_HPCF3 + * @see L3G4200D_HPCF4 + * @see L3G4200D_HPCF5 + * @see L3G4200D_HPCF6 + * @see L3G4200D_HPCF7 + * @see L3G4200D_HPCF8 + * @see L3G4200D_HPCF9 + * @see L3G4200D_HPCF10 + */ +void L3G4200D::setHighPassFilterCutOffFrequencyLevel(uint8_t level) { + I2Cdev::writeBits(devAddr, L3G4200D_RA_CTRL_REG2, L3G4200D_HPCF_BIT, + L3G4200D_HPCF_LENGTH, level); +} + +/** Get the high pass filter cut off frequency level (1 - 10) + * @return High pass filter cut off frequency level + * @see L3G4200D_RA_CTRL_REG2 + * @see L3G4200D_HPCF_BIT + * @see L3G4200D_HPCF_LENGTH + * @see L3G4200D_HPCF1 + * @see L3G4200D_HPCF2 + * @see L3G4200D_HPCF3 + * @see L3G4200D_HPCF4 + * @see L3G4200D_HPCF5 + * @see L3G4200D_HPCF6 + * @see L3G4200D_HPCF7 + * @see L3G4200D_HPCF8 + * @see L3G4200D_HPCF9 + * @see L3G4200D_HPCF10 + */ +uint8_t L3G4200D::getHighPassFilterCutOffFrequencyLevel() { + I2Cdev::readBits(devAddr, L3G4200D_RA_CTRL_REG2, L3G4200D_HPCF_BIT, + L3G4200D_HPCF_LENGTH, buffer); + return buffer[0]; +} + +// CTRL_REG3 register, r/w + +/** Set the INT1 interrupt enabled state + * @param enabled New enabled state for the INT1 interrupt + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_I1_INT1_BIT + */ +void L3G4200D::setINT1InterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_I1_INT1_BIT, + enabled); +} + +/** Get the INT1 interrupt enabled state + * @return True if the INT1 interrupt is enabled, false otherwise + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_I1_INT1_BIT + */ +bool L3G4200D::getINT1InterruptEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_I1_INT1_BIT, + buffer); + return buffer[0]; +} + +/** Set the INT1 boot status enabled state + * @param enabled New enabled state for the INT1 boot status + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_I1_BOOT_BIT + */ +void L3G4200D::setINT1BootStatusEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_I1_BOOT_BIT, + enabled); +} + +/** Get the INT1 boot status enabled state + * @return INT1 boot status status + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_I1_BOOT_BIT + */ +bool L3G4200D::getINT1BootStatusEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_I1_BOOT_BIT, + buffer); + return buffer[0]; +} + +/** Interrupts the active INT1 configuration + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_H_LACTIVE_BIT + */ +void L3G4200D::interruptActiveINT1Config() { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_H_LACTIVE_BIT, 1); +} + +/** Set output mode to push-pull or open-drain + * @param mode New output mode + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_PP_OD_BIT + * @see L3G4200D_PUSH_PULL + * @see L3G4200D_OPEN_DRAIN + */ +void L3G4200D::setOutputMode(bool mode) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_PP_OD_BIT, + mode); +} + +/** Get whether mode is push-pull or open drain + * @return Output mode (TRUE for push-pull, FALSE for open-drain) + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_PP_OD_BIT + * @see L3G4200D_PUSH_PULL + * @see L3G4200D_OPEN_DRAIN + */ +bool L3G4200D::getOutputMode() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_PP_OD_BIT, + buffer); + return buffer[0]; +} + +/** Set data ready interrupt enabled state on INT2 pin + * @param enabled New INT2 data ready interrupt enabled state + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_I2_DRDY_BIT + */ +void L3G4200D::setINT2DataReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_I2_DRDY_BIT, + enabled); +} + +/** Get whether the data ready interrupt is enabled on the INT2 pin + * @return True if the INT2 data ready interrupt is enabled, false otherwise + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_I2_DRDY_BIT + */ +bool L3G4200D::getINT2DataReadyEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_I2_DRDY_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the INT2 FIFO watermark interrupt is enabled + * The sensor contains a 32-slot FIFO buffer for storing data so that it may be + * read later. If enabled, the sensor will generate an interrupt on the + * INT2/DRDY pin when the watermark has been reached. The watermark can be + * configured through the setFIFOWatermark function. + * @param enabled New enabled state of the INT2 FIFO watermark + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_I2_WTM_BIT + */ +void L3G4200D::setINT2FIFOWatermarkInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_I2_WTM_BIT, + enabled); +} + +/** Get the INT2 FIFO watermark interrupt enabled state + * @return true if the FIFO watermark is enabled, false otherwise + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_I2_WTM_BIT + */ +bool L3G4200D::getINT2FIFOWatermarkInterruptEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_I2_WTM_BIT, + buffer); + return buffer[0]; +} + +/** Set whether an interrupt is triggered on INT2 when the FIFO is overrun + * @param enabled New FIFO overrun interrupt enabled state + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_I2_ORUN_BIT + */ +void L3G4200D::setINT2FIFOOverrunInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_I2_ORUN_BIT, + enabled); +} + +/** Get whether an interrupt is triggered on INT2 when the FIFO is overrun + * @return True if the INT2 FIFO overrun interrupt is enabled, false otherwise + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_I2_ORUN_BIT + */ +bool L3G4200D::getINT2FIFOOverrunInterruptEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_I2_ORUN_BIT, + buffer); + return buffer[0]; +} + +/** Set whether an interrupt is triggered on INT2 when the FIFO buffer is empty + * @param enabled New INT2 FIFO empty interrupt state + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_I2_EMPTY_BIT + */ +void L3G4200D::setINT2FIFOEmptyInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_I2_EMPTY_BIT, + enabled); +} + +/** Get whether the INT2 FIFO empty interrupt is enabled + * @returns Trur if the INT2 FIFO empty interrupt is enabled, false otherwise + * @see L3G4200D_RA_CTRL_REG3 + * @see L3G4200D_I2_EMPTY_BIT + */ +bool L3G4200D::getINT2FIFOEmptyInterruptEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG3, L3G4200D_I2_EMPTY_BIT, + buffer); + return buffer[0]; +} + +// CTRL_REG4 register, r/w + +/** Set the Block Data Update (BDU) enabled state + * @param enabled New BDU enabled state + * @see L3G4200D_RA_CTRL_REG4 + * @see L3G4200D_BDU_BIT + */ +void L3G4200D::setBlockDataUpdateEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG4, L3G4200D_BDU_BIT, enabled); +} + +/** Get the BDU enabled state + * @return True if Block Data Update is enabled, false otherwise + * @see L3G4200D_RA_CTRL_REG4 + * @see L3G4200D_BDU_BIT + */ +bool L3G4200D::getBlockDataUpdateEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG4, L3G4200D_BDU_BIT, buffer); + return buffer[0]; +} + +/** Set the data endian modes + * In Big Endian mode, the Most Significat Byte (MSB) is on the lower address, + * and the Least Significant Byte (LSB) is on the higher address. Little Endian + * mode reverses this order. Little Endian is the default mode. + * @param endianness New endian mode + * @see L3G4200D_RA_CTRL_REG4 + * @see L3G4200D_BLE_BIT + * @see L3G4200D_BIG_ENDIAN + * @see L3G4200D_LITTLE_ENDIAN + */ +void L3G4200D::setEndianMode(bool endianness) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG4, L3G4200D_BLE_BIT, + endianness); +} + +/** Get the data endian mode + * @return Current endian mode + * @see L3G4200D_RA_CTRL_REG4 + * @see L3G4200D_BLE_BIT + * @see L3G4200D_BIG_ENDIAN + * @see L3G4200D_LITTLE_ENDIAN + */ +bool L3G4200D::getEndianMode() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG4, L3G4200D_BLE_BIT, + buffer); + return buffer[0]; +} + +/** Set the full scale of the data output (in dps) + * @param scale The new scale of the data output (250, 500, 2000) + * @see L3G4200D_RA_CTRL_REG4 + * @see L3G4200D_FS_BIT + * @see L3G4200D_FS_LENGTH + * @see L3G4200D_FS_250 + * @see L3G4200D_FS_500 + * @see L3G4200D_FS_2000 + */ +void L3G4200D::setFullScale(uint16_t scale) { + uint8_t writeBits; + + if (scale == 250) { + writeBits = L3G4200D_FS_250; + } else if (scale == 500) { + writeBits = L3G4200D_FS_500; + } else { + writeBits = L3G4200D_FS_2000; + } + + I2Cdev::writeBits(devAddr, L3G4200D_RA_CTRL_REG4, L3G4200D_FS_BIT, + L3G4200D_FS_LENGTH, writeBits); +} + +/** Get the current full scale of the output data (in dps) + * @return Current scale of the output data + * @see L3G4200D_RA_CTRL_REG4 + * @see L3G4200D_FS_BIT + * @see L3G4200D_FS_LENGTH + * @see L3G4200D_FS_250 + * @see L3G4200D_FS_500 + * @see L3G4200D_FS_2000 + */ +uint16_t L3G4200D::getFullScale() { + I2Cdev::readBits(devAddr, L3G4200D_RA_CTRL_REG4, + L3G4200D_FS_BIT, L3G4200D_FS_LENGTH, buffer); + uint8_t readBits = buffer[0]; + + if (readBits == L3G4200D_FS_250) { + return 250; + } else if (readBits == L3G4200D_FS_500) { + return 500; + } else { + return 2000; + } +} + +/** Set the self test mode + * @param mode New self test mode (Normal, 0, 1) + * @see L3G4200D_RA_CTRL_REG4 + * @see L3G4200D_ST_BIT + * @see L3G4200D_ST_LENGTH + * @see L3G4200D_SELF_TEST_NORMAL + * @see L3G4200D_SELF_TEST_0 + * @see L3G4200D_SELF_TEST_1 + */ +void L3G4200D::setSelfTestMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, L3G4200D_RA_CTRL_REG4, L3G4200D_ST_BIT, + L3G4200D_ST_LENGTH, mode); +} + +/** Get the current self test mode + * @return Current self test mode + * @see L3G4200D_RA_CTRL_REG4 + * @see L3G4200D_ST_BIT + * @see L3G4200D_ST_LENGTH + * @see L3G4200D_SELF_TEST_NORMAL + * @see L3G4200D_SELF_TEST_0 + * @see L3G4200D_SELF_TEST_1 + */ +uint8_t L3G4200D::getSelfTestMode() { + I2Cdev::readBits(devAddr, L3G4200D_RA_CTRL_REG4, L3G4200D_ST_BIT, + L3G4200D_ST_LENGTH, buffer); + return buffer[0]; +} + +/** Set the SPI mode + * @param mode New SPI mode + * @see L3G4200D_RA_CTRL_REG4 + * @see L3G4200D_SIM_BIT + * @see L3G4200D_SPI_4_WIRE + * @see L3G4200D_SPI_3_WIRE + */ +void L3G4200D::setSPIMode(bool mode) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG4, L3G4200D_SIM_BIT, mode); +} + +/** Get the SPI mode + * @return Current SPI mode + * @see L3G4200D_RA_CTRL_REG4 + * @see L3G4200D_SIM_BIT + * @see L3G4200D_SPI_4_WIRE + * @see L3G4200D_SPI_3_WIRE + */ +bool L3G4200D::getSPIMode() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG4, L3G4200D_SIM_BIT, + buffer); + return buffer[0]; +} + +// CTRL_REG5 register, r/w + +/** Reboots the FIFO memory content + * @see L3G4200D_RA_CTRL_REG5 + * @see L3G4200D_BOOT_BIT + */ +void L3G4200D::rebootMemoryContent() { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG5, L3G4200D_BOOT_BIT, true); +} + +/** Set whether the FIFO buffer is enabled + * @param enabled New enabled state of the FIFO buffer + * @see L3G4200D_RA_CTRL_REG5 + * @see L3G4200D_FIFO_EN_BIT + */ +void L3G4200D::setFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG5, L3G4200D_FIFO_EN_BIT, + enabled); +} + +/** Get whether the FIFO buffer is enabled + * @return True if the FIFO buffer is enabled, false otherwise + * @see L3G4200D_RA_CTRL_REG5 + * @see L3G4200D_FIFO_EN_BIT + */ +bool L3G4200D::getFIFOEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG5, L3G4200D_FIFO_EN_BIT, + buffer); + return buffer[0]; +} + +/** Set the high pass filter enabled state + * @param enabled New high pass filter enabled state + * @see L3G4200D_RA_CTRL_REG5 + * @see L3G4200D_HPEN_BIT + */ +void L3G4200D::setHighPassFilterEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_CTRL_REG5, L3G4200D_HPEN_BIT, + enabled); +} + +/** Get whether the high pass filter is enabled + * @return True if the high pass filter is enabled, false otherwise + * @see L3G4200D_RA_CTRL_REG5 + * @see L3G4200D_HPEN_BIT + */ +bool L3G4200D::getHighPassFilterEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_CTRL_REG5, L3G4200D_HPEN_BIT, + buffer); + return buffer[0]; +} + +/** Sets the filter mode to one of the four provided. + * This function also uses the setHighPassFilterEnabled function in order to set + * the mode. That function does not haved to be called in addition to this one. + * In addition to setting the filter for the data in the FIFO buffer + * (controlled by the bits written to OUT_SEL), this function also sets the + * filter used for interrupt generation (the bits written to INT1_SEL) to be the + * same as the filter used for the FIFO buffer. + * @param filter New method to be used when filtering data + * @see L3G4200D_RA_CTRL_REG5 + * @see L3G4200D_INT1_SEL_BIT + * @see L3G4200D_INT1_SEL_LENGTH + * @see L3G4200D_OUT_SEL_BIT + * @see L3G4200D_OUT_SEL_LENGTH + * @see L3G4200D_NON_HIGH_PASS + * @see L3G4200D_HIGH_PASS + * @see L3G4200D_LOW_PASS + * @see L3G4200D_LOW_HIGH_PASS + */ +void L3G4200D::setDataFilter(uint8_t filter) { + if (filter == L3G4200D_HIGH_PASS || filter == L3G4200D_LOW_HIGH_PASS) { + setHighPassFilterEnabled(true); + } else { + setHighPassFilterEnabled(false); + } + + I2Cdev::writeBits(devAddr, L3G4200D_RA_CTRL_REG5, L3G4200D_OUT_SEL_BIT, + L3G4200D_OUT_SEL_LENGTH, filter); + I2Cdev::writeBits(devAddr, L3G4200D_RA_CTRL_REG5, L3G4200D_INT1_SEL_BIT, + L3G4200D_INT1_SEL_LENGTH, filter); +} + +/** Gets the data filter currently in use + * @return Defined value that represents the filter in use + * @see L3G4200D_RA_CTRL_REG5 + * @see L3G4200D_OUT_SEL_BIT + * @see L3G4200D_OUT_SEL_LENGTH + * @see L3G4200D_NON_HIGH_PASS + * @see L3G4200D_HIGH_PASS + * @see L3G4200D_LOW_PASS + * @see L3G4200D_LOW_HIGH_PASS + */ +uint8_t L3G4200D::getDataFilter() { + I2Cdev::readBits(devAddr, L3G4200D_RA_CTRL_REG5, L3G4200D_OUT_SEL_BIT, + L3G4200D_OUT_SEL_LENGTH, buffer); + uint8_t outBits = buffer[0]; + + if (outBits == L3G4200D_NON_HIGH_PASS || outBits == L3G4200D_HIGH_PASS) { + return outBits; + } + + if (getHighPassFilterEnabled()) { + return L3G4200D_LOW_HIGH_PASS; + } else { + return L3G4200D_LOW_PASS; + } +} + +// REFERENCE/DATACAPTURE register, r/w + +/** Set the reference value for interrupt generation + * @param reference New reference value for interrupt generation + * @see L3G4200D_RA_REFERENCE + */ +void L3G4200D::setInterruptReference(uint8_t reference) { + I2Cdev::writeByte(devAddr, L3G4200D_RA_REFERENCE, reference); +} + +/** Get the 8-bit reference value for interrupt generation + * @return 8-bit reference value for interrupt generation + * @see L3G4200D_RA_REFERENCE + */ +uint8_t L3G4200D::getInterruptReference() { + I2Cdev::readByte(devAddr, L3G4200D_RA_REFERENCE, buffer); + return buffer[0]; +} + +// OUT_TEMP register, read-only + +/** Gets the current temperature reading from the sensor + * @return Current temperature + * @see L3G4200D_RA_OUT_TEMP + */ +uint8_t L3G4200D::getTemperature() { + I2Cdev::readByte(devAddr, L3G4200D_RA_OUT_TEMP, buffer); + return buffer[0]; +} + +// STATUS register, read-only + +/** Get whether new data overwrote the last set of data before it was read + * @return True if the last set of data was overwritten before being read, false + * otherwise + * @see L3G4200D_RA_STATUS + * @see L3G4200D_ZYXOR_BIT + */ +bool L3G4200D::getXYZOverrun() { + I2Cdev::readBit(devAddr, L3G4200D_RA_STATUS, L3G4200D_ZYXOR_BIT, + buffer); + return buffer[0]; +} + +/** Get whether new Z data overwrote the last set of data before it was read + * @return True if the last set of Z data was overwritten before being read, + * false otherwise + * @see L3G4200D_RA_STATUS + * @see L3G4200D_ZOR_BIT + */ +bool L3G4200D::getZOverrun() { + I2Cdev::readBit(devAddr, L3G4200D_RA_STATUS, L3G4200D_ZOR_BIT, + buffer); + return buffer[0]; +} + +/** Get whether new Y data overwrote the last set of data before it was read + * @return True if the last set of Y data was overwritten before being read, + * false otherwise + * @see L3G4200D_RA_STATUS + * @see L3G4200D_YOR_BIT + */ +bool L3G4200D::getYOverrun() { + I2Cdev::readBit(devAddr, L3G4200D_RA_STATUS, L3G4200D_YOR_BIT, + buffer); + return buffer[0]; +} + +/** Get whether new X data overwrote the last set of data before it was read + * @return True if the last set of X data was overwritten before being read, + * false otherwise + * @see L3G4200D_RA_STATUS + * @see L3G4200D_XOR_BIT + */ +bool L3G4200D::getXOverrun() { + I2Cdev::readBit(devAddr, L3G4200D_RA_STATUS, L3G4200D_XOR_BIT, + buffer); + return buffer[0]; +} + +/** Get whether there is new data avaialable + * @return True if there is new data available, false otherwise + * @see L3G4200D_RA_STATUS + * @see L3G4200D_ZYXDA_BIT + */ +bool L3G4200D::getXYZDataAvailable() { + I2Cdev::readBit(devAddr, L3G4200D_RA_STATUS, L3G4200D_ZYXDA_BIT, + buffer); + return buffer[0]; +} + +/** Get whether there is new Z data avaialable + * @return True if there is new Z data available, false otherwise + * @see L3G4200D_RA_STATUS + * @see L3G4200D_ZDA_BIT + */ +bool L3G4200D::getZDataAvailable() { + I2Cdev::readBit(devAddr, L3G4200D_RA_STATUS, L3G4200D_ZDA_BIT, + buffer); + return buffer[0]; +} + +/** Get whether there is new Y data avaialable + * @return True if there is new Y data available, false otherwise + * @see L3G4200D_RA_STATUS + * @see L3G4200D_YDA_BIT + */ +bool L3G4200D::getYDataAvailable() { + I2Cdev::readBit(devAddr, L3G4200D_RA_STATUS, L3G4200D_YDA_BIT, + buffer); + return buffer[0]; +} + +/** Get whether there is new X data avaialable + * @return True if there is new X data available, false otherwise + * @see L3G4200D_RA_STATUS + * @see L3G4200D_XDA_BIT + */ +bool L3G4200D::getXDataAvailable() { + I2Cdev::readBit(devAddr, L3G4200D_RA_STATUS, L3G4200D_XDA_BIT, + buffer); + return buffer[0]; +} + +// OUT_* registers, read-only + +/** Get the angular velocity for all 3 axes + * Due to the fact that this device supports two difference Endian modes, both + * must be accounted for when reading data. In Little Endian mode, the first + * byte (lowest address) is the least significant and in Big Endian mode the + * first byte is the most significant. + * @param x 16-bit integer container for the X-axis angular velocity + * @param y 16-bit integer container for the Y-axis angular velocity + * @param z 16-bit integer container for the Z-axis angular velocity + */ +void L3G4200D::getAngularVelocity(int16_t* x, int16_t* y, int16_t* z) { + *x = getAngularVelocityX(); + *y = getAngularVelocityY(); + *z = getAngularVelocityZ(); +} + +/** Get the angular velocity about the X-axis + * @return Angular velocity about the X-axis + * @see L3G4200D_RA_OUT_X_L + * @see L3G4200D_RA_OUT_X_H + */ +int16_t L3G4200D::getAngularVelocityX() { + uint8_t bufferL[6]; + uint8_t bufferH[6]; + I2Cdev::readBytes(devAddr, L3G4200D_RA_OUT_X_L, 1, bufferL); + I2Cdev::readBytes(devAddr, L3G4200D_RA_OUT_X_H, 1, bufferH); + if (getEndianMode() == L3G4200D_BIG_ENDIAN) { + return (((int16_t) bufferL[0]) << 8) | bufferH[0]; + } else { + return (((int16_t) bufferH[0]) << 8) | bufferL[0]; + } +} + +/** Get the angular velocity about the Y-axis + * @return Angular velocity about the Y-axis + * @see L3G4200D_RA_OUT_Y_L + * @see L3G4200D_RA_OUT_Y_H + */ +int16_t L3G4200D::getAngularVelocityY() { + uint8_t bufferL[6]; + uint8_t bufferH[6]; + I2Cdev::readBytes(devAddr, L3G4200D_RA_OUT_Y_L, 1, bufferL); + I2Cdev::readBytes(devAddr, L3G4200D_RA_OUT_Y_H, 1, bufferH); + if (getEndianMode() == L3G4200D_BIG_ENDIAN) { + return (((int16_t) bufferL[0]) << 8) | bufferH[0]; + } else { + return (((int16_t) bufferH[0]) << 8) | bufferL[0]; + } +} + +/** Get the angular velocity about the Z-axis + * @return Angular velocity about the Z-axis + * @see L3G4200D_RA_OUT_Z_L + * @see L3G4200D_RA_OUT_Z_H + */ +int16_t L3G4200D::getAngularVelocityZ() { + uint8_t bufferL[6]; + uint8_t bufferH[6]; + I2Cdev::readBytes(devAddr, L3G4200D_RA_OUT_Z_L, 1, bufferL); + I2Cdev::readBytes(devAddr, L3G4200D_RA_OUT_Z_H, 1, bufferH); + if (getEndianMode() == L3G4200D_BIG_ENDIAN) { + return (((int16_t) bufferL[0]) << 8) | bufferH[0]; + } else { + return (((int16_t) bufferH[0]) << 8) | bufferL[0]; + } +} + +// FIFO_CTRL register, r/w + +/** Set the FIFO mode to one of the defined modes + * @param mode New FIFO mode + * @see L3G4200D_RA_FIFO_CTRL + * @see L3G4200D_FIFO_MODE_BIT + * @see L3G4200D_FIFO_MODE_LENGTH + * @see L3G4200D_FM_BYPASS + * @see L3G4200D_FM_FIFO + * @see L3G4200D_FM_STREAM + * @see L3G4200D_FM_STREAM_FIFO + * @see L3G4200D_FM_BYPASS_STREAM + */ +void L3G4200D::setFIFOMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, L3G4200D_RA_FIFO_CTRL, L3G4200D_FIFO_MODE_BIT, + L3G4200D_FIFO_MODE_LENGTH, mode); +} + +/** Get the FIFO mode to one of the defined modes + * @return Current FIFO mode + * @see L3G4200D_RA_FIFO_CTRL + * @see L3G4200D_FIFO_MODE_BIT + * @see L3G4200D_FIFO_MODE_LENGTH + * @see L3G4200D_FM_BYPASS + * @see L3G4200D_FM_FIFO + * @see L3G4200D_FM_STREAM + * @see L3G4200D_FM_STREAM_FIFO + * @see L3G4200D_FM_BYPASS_STREAM + */ +uint8_t L3G4200D::getFIFOMode() { + I2Cdev::readBits(devAddr, L3G4200D_RA_FIFO_CTRL, + L3G4200D_FIFO_MODE_BIT, L3G4200D_FIFO_MODE_LENGTH, buffer); + return buffer[0]; +} + +/** Set the FIFO watermark threshold + * @param wtm New FIFO watermark threshold + * @see L3G4200D_RA_FIFO_CTRL + * @see L3G4200D_FIFO_WTM_BIT + * @see L3G4200D_FIFO_WTM_LENGTH + */ +void L3G4200D::setFIFOThreshold(uint8_t wtm) { + I2Cdev::writeBits(devAddr, L3G4200D_RA_FIFO_CTRL, L3G4200D_FIFO_WTM_BIT, + L3G4200D_FIFO_WTM_LENGTH, wtm); +} + +/** Get the FIFO watermark threshold + * @return FIFO watermark threshold + * @see L3G4200D_RA_FIFO_CTRL + * @see L3G4200D_FIFO_WTM_BIT + * @see L3G4200D_FIFO_WTM_LENGTH + */ +uint8_t L3G4200D::getFIFOThreshold() { + I2Cdev::readBits(devAddr, L3G4200D_RA_FIFO_CTRL, L3G4200D_FIFO_WTM_BIT, + L3G4200D_FIFO_WTM_LENGTH, buffer); + return buffer[0]; +} + +// FIFO_SRC register, read-only + +/** Get whether the number of data sets in the FIFO buffer is less than the + * watermark + * @return True if the number of data sets in the FIFO buffer is more than or + * equal to the watermark, false otherwise. + * @see L3G4200D_RA_FIFO_SRC + * @see L3G4200D_FIFO_STATUS_BIT + */ +bool L3G4200D::getFIFOAtWatermark() { + I2Cdev::readBit(devAddr, L3G4200D_RA_FIFO_SRC, L3G4200D_FIFO_STATUS_BIT, + buffer); + return buffer[0]; +} + +/** Get whether the FIFO buffer is full + * @return True if the FIFO buffer is full, false otherwise + * @see L3G4200D_RA_FIFO_SRC + * @see L3G4200D_FIFO_OVRN_BIT + */ +bool L3G4200D::getFIFOOverrun() { + I2Cdev::readBit(devAddr, L3G4200D_RA_FIFO_SRC, + L3G4200D_FIFO_OVRN_BIT, buffer); + return buffer[0]; +} + +/** Get whether the FIFO buffer is empty + * @return True if the FIFO buffer is empty, false otherwise + * @see L3G4200D_RA_FIFO_SRC + * @see L3G4200D_FIFO_EMPTY_BIT + */ +bool L3G4200D::getFIFOEmpty() { + I2Cdev::readBit(devAddr, L3G4200D_RA_FIFO_SRC, + L3G4200D_FIFO_EMPTY_BIT, buffer); + return buffer[0]; +} + +/** Get the number of filled FIFO buffer slots + * @return Number of filled slots in the FIFO buffer + * @see L3G4200D_RA_FIFO_SRC + * @see L3G4200D_FIFO_FSS_BIT + * @see L3G4200D_FIFO_FSS_LENGTH + */ +uint8_t L3G4200D::getFIFOStoredDataLevel() { + I2Cdev::readBits(devAddr, L3G4200D_RA_FIFO_SRC, + L3G4200D_FIFO_FSS_BIT, L3G4200D_FIFO_FSS_LENGTH, buffer); + return buffer[0]; +} + +// INT1_CFG register, r/w + +/** Set the combination mode for interrupt events + * @param combination New combination mode for interrupt events. + * L3G4200D_INT1_OR for OR and L3G4200D_INT1_AND for AND + * @see L3G4200D_RA_INT1_CFG + * @see L3G4200D_INT1_AND_OR_BIT + * @see L3G4200D_INT1_OR + * @see L3G4200D_INT1_AND + */ +void L3G4200D::setInterruptCombination(bool combination) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_INT1_AND_OR_BIT, + combination); +} + +/** Get the combination mode for interrupt events + * @return Combination mode for interrupt events. L3G4200D_INT1_OR for OR and + * L3G4200D_INT1_AND for AND + * @see L3G4200D_RA_INT1_CFG + * @see L3G4200D_INT1_AND_OR_BIT + * @see L3G4200D_INT1_OR + * @see L3G4200D_INT1_AND + */ +bool L3G4200D::getInterruptCombination() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_INT1_AND_OR_BIT, + buffer); + return buffer[0]; +} + +/** Set whether an interrupt request is latched + * This bit is cleared when the INT1_SRC register is read + * @param latched New status of the latched request + * @see L3G4200D_RA_INT1_CFG + * @see L3G4200D_INT1_LIR_BIT + */ +void L3G4200D::setInterruptRequestLatched(bool latched) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_INT1_LIR_BIT, latched); +} + +/** Get whether an interrupt request is latched + * @return True if an interrupt request is latched, false otherwise + * @see L3G4200D_RA_INT1_CFG + * @see L3G4200D_INT1_LIR_BIT + */ +bool L3G4200D::getInterruptRequestLatched() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_INT1_LIR_BIT, + buffer); + return buffer[0]; +}; + +/** Set whether the interrupt for Z high is enabled + * @param enabled New enabled state for Z high interrupt. + * @see L3G4200D_INT1_CFG + * @see L3G4200D_ZHIE_BIT + */ +void L3G4200D::setZHighInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_ZHIE_BIT, enabled); +} + +/** Get whether the interrupt for Z high is enabled + * @return True if the interrupt for Z high is enabled, false otherwise + * @see L3G4200D_INT1_CFG + * @see L3G4200D_ZHIE_BIT + */ +bool L3G4200D::getZHighInterruptEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_ZHIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt for Z low is enabled + * @param enabled New enabled state for Z low interrupt. + * @see L3G4200D_INT1_CFG + * @see L3G4200D_ZLIE_BIT + */ +void L3G4200D::setZLowInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_ZLIE_BIT, enabled); +} + +/** Get whether the interrupt for Z low is enabled + * @return True if the interrupt for Z low is enabled, false otherwise + * @see L3G4200D_INT1_CFG + * @see L3G4200D_ZLIE_BIT + */ +bool L3G4200D::getZLowInterruptEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_ZLIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt for Y high is enabled + * @param enabled New enabled state for Y high interrupt. + * @see L3G4200D_INT1_CFG + * @see L3G4200D_YHIE_BIT + */ +void L3G4200D::setYHighInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_YHIE_BIT, enabled); +} + +/** Get whether the interrupt for Y high is enabled + * @return True if the interrupt for Y high is enabled, false otherwise + * @see L3G4200D_INT1_CFG + * @see L3G4200D_YHIE_BIT + */ +bool L3G4200D::getYHighInterruptEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_YHIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt for Y low is enabled + * @param enabled New enabled state for Y low interrupt. + * @see L3G4200D_INT1_CFG + * @see L3G4200D_YLIE_BIT + */ +void L3G4200D::setYLowInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_YLIE_BIT, enabled); +} + +/** Get whether the interrupt for Y low is enabled + * @return True if the interrupt for Y low is enabled, false otherwise + * @see L3G4200D_INT1_CFG + * @see L3G4200D_YLIE_BIT + */ +bool L3G4200D::getYLowInterruptEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_YLIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt for X high is enabled + * @param enabled New enabled state for X high interrupt. + * @see L3G4200D_INT1_CFG + * @see L3G4200D_XHIE_BIT + */ +void L3G4200D::setXHighInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_XHIE_BIT, enabled); +} + +/** Get whether the interrupt for X high is enabled + * @return True if the interrupt for X high is enabled, false otherwise + * @see L3G4200D_INT1_CFG + * @see L3G4200D_XHIE_BIT + */ +bool L3G4200D::getXHighInterruptEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_XHIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt for X low is enabled + * @param enabled New enabled state for X low interrupt. + * @see L3G4200D_INT1_CFG + * @see L3G4200D_XLIE_BIT + */ +void L3G4200D::setXLowInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_XLIE_BIT, enabled); +} + +/** Get whether the interrupt for X low is enabled + * @return True if the interrupt for X low is enabled, false otherwise + * @see L3G4200D_INT1_CFG + * @see L3G4200D_XLIE_BIT + */ +bool L3G4200D::getXLowInterruptEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_CFG, L3G4200D_XLIE_BIT, + buffer); + return buffer[0]; +} + +// INT1_SRC register, read-only + +/** Get whether an interrupt has been generated + * @return True if one or more interrupts has been generated, false otherwise + * @see L3G4200D_RA_INT1_SRC + * @see L3G4200D_INT1_IA_BIT + */ +bool L3G4200D::getInterruptActive() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_SRC, L3G4200D_INT1_IA_BIT, + buffer); + return buffer[0]; +} + +/** Get whether a Z high event has occurred + * @return True if a Z high event has occurred, false otherwise + * @see L3G4200D_RA_INT1_SRC + * @see L3G4200D_INT1_ZH_BIT + */ +bool L3G4200D::getZHigh() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_SRC, L3G4200D_INT1_ZH_BIT, + buffer); + return buffer[0]; +} + +/** Get whether a Z low event has occurred + * @return True if a Z low event has occurred, false otherwise + * @see L3G4200D_RA_INT1_SRC + * @see L3G4200D_INT1_ZL_BIT + */ +bool L3G4200D::getZLow() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_SRC, L3G4200D_INT1_ZL_BIT, + buffer); + return buffer[0]; +} + +/** Get whether a Y high event has occurred + * @return True if a Y high event has occurred, false otherwise + * @see L3G4200D_RA_INT1_SRC + * @see L3G4200D_INT1_YH_BIT + */ +bool L3G4200D::getYHigh() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_SRC, L3G4200D_INT1_YH_BIT, + buffer); + return buffer[0]; +} + +/** Get whether a Y low event has occurred + * @return True if a Y low event has occurred, false otherwise + * @see L3G4200D_RA_INT1_SRC + * @see L3G4200D_INT1_YL_BIT + */ +bool L3G4200D::getYLow() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_SRC, L3G4200D_INT1_YL_BIT, + buffer); + return buffer[0]; +} + +/** Get whether a X high event has occurred + * @return True if a X high event has occurred, false otherwise + * @see L3G4200D_RA_INT1_SRC + * @see L3G4200D_INT1_XH_BIT + */ +bool L3G4200D::getXHigh() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_SRC, L3G4200D_INT1_XH_BIT, + buffer); + return buffer[0]; +} + +/** Get whether a X low event has occurred + * @return True if a X low event has occurred, false otherwise + * @see L3G4200D_RA_INT1_SRC + * @see L3G4200D_INT1_XL_BIT + */ +bool L3G4200D::getXLow() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_SRC, L3G4200D_INT1_XL_BIT, + buffer); + return buffer[0]; +} + +// INT1_THS_* registers, r/w + +/** Set the threshold for a high interrupt on the X axis + * @param threshold New threshold for a high interrupt on the X axis + * @see L3G4200D_INT1_THS_XH + */ +void L3G4200D::setXHighThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, L3G4200D_RA_INT1_THS_XH, threshold); +} + +/** Retrieve the threshold for a high interrupt on the X axis + * @return X high interrupt threshold + * @see L3G4200D_INT1_THS_XH + */ +uint8_t L3G4200D::getXHighThreshold() { + I2Cdev::readByte(devAddr, L3G4200D_RA_INT1_THS_XH, buffer); + return buffer[0]; +} + +/** Set the threshold for a low interrupt on the X axis + * @param threshold New threshold for a low interrupt on the X axis + * @see L3G4200D_INT1_THS_XL + */ +void L3G4200D::setXLowThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, L3G4200D_RA_INT1_THS_XL, threshold); +} + +/** Retrieve the threshold for a low interrupt on the X axis + * @return X low interrupt threshold + * @see L3G4200D_INT1_THS_XL + */ +uint8_t L3G4200D::getXLowThreshold() { + I2Cdev::readByte(devAddr, L3G4200D_RA_INT1_THS_XL, buffer); + return buffer[0]; +} + +/** Set the threshold for a high interrupt on the Y axis + * @param threshold New threshold for a high interrupt on the Y axis + * @see L3G4200D_INT1_THS_YH + */ +void L3G4200D::setYHighThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, L3G4200D_RA_INT1_THS_YH, threshold); +} + +/** Retrieve the threshold for a high interrupt on the Y axis + * @return Y high interrupt threshold + * @see L3G4200D_INT1_THS_YH + */ +uint8_t L3G4200D::getYHighThreshold() { + I2Cdev::readByte(devAddr, L3G4200D_RA_INT1_THS_YH, buffer); + return buffer[0]; +} + +/** Set the threshold for a low interrupt on the Y axis + * @param threshold New threshold for a low interrupt on the Y axis + * @see L3G4200D_INT1_THS_YL + */ +void L3G4200D::setYLowThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, L3G4200D_RA_INT1_THS_YL, threshold); +} + +/** Retrieve the threshold for a low interrupt on the Y axis + * @return Y low interrupt threshold + * @see L3G4200D_INT1_THS_YL + */ +uint8_t L3G4200D::getYLowThreshold() { + I2Cdev::readByte(devAddr, L3G4200D_RA_INT1_THS_YL, buffer); + return buffer[0]; +} + +/** Set the threshold for a high interrupt on the Z axis + * @param threshold New threshold for a high interrupt on the Z axis + * @see L3G4200D_INT1_THS_ZH + */ +void L3G4200D::setZHighThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, L3G4200D_RA_INT1_THS_ZH, threshold); +} + +/** Retrieve the threshold for a high interrupt on the Z axis + * @return Z high interrupt threshold + * @see L3G4200D_INT1_THS_ZH + */ +uint8_t L3G4200D::getZHighThreshold() { + I2Cdev::readByte(devAddr, L3G4200D_RA_INT1_THS_ZH, buffer); + return buffer[0]; +} + +/** Set the threshold for a low interrupt on the Z axis + * @param threshold New threshold for a low interrupt on the Z axis + * @see L3G4200D_RA_INT1_THS_ZL + */ +void L3G4200D::setZLowThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, L3G4200D_RA_INT1_THS_ZL, threshold); +} + +/** Retrieve the threshold for a low interrupt on the Z axis + * @return Z low interrupt threshold + * @see L3G4200D_INT1_THS_ZL + */ +uint8_t L3G4200D::getZLowThreshold() { + I2Cdev::readByte(devAddr, L3G4200D_RA_INT1_THS_ZL, buffer); + return buffer[0]; +} + +// INT1_DURATION register, r/w + +/* Set the minimum duration for an interrupt event to be recognized + * This depends on the chosen output data rate + * @param duration New duration necessary for an interrupt event to be + * recognized + * @see L3G4200D_RA_INT1_DURATION + * @see L3G4200D_INT1_DUR_BIT + * @see L3G4200D_INT1_DUR_LENGTH + */ +void L3G4200D::setDuration(uint8_t duration) { + I2Cdev::writeBits(devAddr, L3G4200D_RA_INT1_DURATION, L3G4200D_INT1_DUR_BIT, + L3G4200D_INT1_DUR_LENGTH, duration); +} + +/** Get the minimum duration for an interrupt event to be recognized + * @return Duration necessary for an interrupt event to be recognized + * @see L3G4200D_RA_INT1_DURATION + * @see L3G4200D_INT1_DUR_BIT + * @see L3G4200D_INT1_DUR_LENGTH + */ +uint8_t L3G4200D::getDuration() { + I2Cdev::readBits(devAddr, L3G4200D_RA_INT1_DURATION, + L3G4200D_INT1_DUR_BIT, L3G4200D_INT1_DUR_LENGTH, buffer); + return buffer[0]; +} + +/** Set whether the interrupt wait feature is enabled + * If false, the interrupt falls immediately if signal crosses the selected + * threshold. Otherwise, if signal crosses the selected threshold, the interrupt + * falls only after the duration has counted number of samples at the selected + * data rate, written into the duration counter register. + * @param enabled New enabled state of the interrupt wait + * @see L3G4200D_RA_INT1_DURATION + * @see L3G4200D_INT1_WAIT_BIT + */ +void L3G4200D::setWaitEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3G4200D_RA_INT1_DURATION, L3G4200D_INT1_WAIT_BIT, + enabled); +} + +/** Get whether the interrupt wait feature is enabled + * @return True if the wait feature is enabled, false otherwise + * @see L3G4200D_RA_INT1_DURATION + * @see L3G4200D_INT1_WAIT_BIT + */ +bool L3G4200D::getWaitEnabled() { + I2Cdev::readBit(devAddr, L3G4200D_RA_INT1_DURATION, + L3G4200D_INT1_WAIT_BIT, buffer); + return buffer[0]; +} diff --git a/libraries/L3G4200D/L3G4200D.h b/libraries/L3G4200D/L3G4200D.h new file mode 100644 index 0000000..8bc937f --- /dev/null +++ b/libraries/L3G4200D/L3G4200D.h @@ -0,0 +1,363 @@ +// I2Cdev library collection - L3G4200D I2C device class header file +// Based on STMicroelectronics L3G4200D datasheet rev. 3, 12/2010 +// 7/31/2013 by Jonathan Arnett +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2013-07-31 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Jonathan Arnett, 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 _L3G4200D_H_ +#define _L3G4200D_H_ + +#include "I2Cdev.h" + +#define L3G4200D_ADDRESS 0x69 +#define L3G4200D_DEFAULT_ADDRESS 0x69 + +#define L3G4200D_RA_WHO_AM_I 0x0F +#define L3G4200D_RA_CTRL_REG1 0x20 +#define L3G4200D_RA_CTRL_REG2 0x21 +#define L3G4200D_RA_CTRL_REG3 0x22 +#define L3G4200D_RA_CTRL_REG4 0x23 +#define L3G4200D_RA_CTRL_REG5 0x24 +#define L3G4200D_RA_REFERENCE 0x25 +#define L3G4200D_RA_OUT_TEMP 0x26 +#define L3G4200D_RA_STATUS 0x27 +#define L3G4200D_RA_OUT_X_L 0x28 +#define L3G4200D_RA_OUT_X_H 0x29 +#define L3G4200D_RA_OUT_Y_L 0x2A +#define L3G4200D_RA_OUT_Y_H 0x2B +#define L3G4200D_RA_OUT_Z_L 0x2C +#define L3G4200D_RA_OUT_Z_H 0x2D +#define L3G4200D_RA_FIFO_CTRL 0x2E +#define L3G4200D_RA_FIFO_SRC 0x2F +#define L3G4200D_RA_INT1_CFG 0x30 +#define L3G4200D_RA_INT1_SRC 0x31 +#define L3G4200D_RA_INT1_THS_XH 0x32 +#define L3G4200D_RA_INT1_THS_XL 0X33 +#define L3G4200D_RA_INT1_THS_YH 0X34 +#define L3G4200D_RA_INT1_THS_YL 0x35 +#define L3G4200D_RA_INT1_THS_ZH 0X36 +#define L3G4200D_RA_INT1_THS_ZL 0x37 +#define L3G4200D_RA_INT1_DURATION 0X38 + +#define L3G4200D_ODR_BIT 7 +#define L3G4200D_ODR_LENGTH 2 +#define L3G4200D_BW_BIT 5 +#define L3G4200D_BW_LENGTH 2 +#define L3G4200D_PD_BIT 3 +#define L3G4200D_ZEN_BIT 2 +#define L3G4200D_YEN_BIT 1 +#define L3G4200D_XEN_BIT 0 + +#define L3G4200D_RATE_100 0b00 +#define L3G4200D_RATE_200 0b01 +#define L3G4200D_RATE_400 0b10 +#define L3G4200D_RATE_800 0b11 + +#define L3G4200D_BW_LOW 0b00 +#define L3G4200D_BW_MED_LOW 0b01 +#define L3G4200D_BW_MED_HIGH 0b10 +#define L3G4200D_BW_HIGH 0b11 + +#define L3G4200D_HPM_BIT 5 +#define L3G4200D_HPM_LENGTH 2 +#define L3G4200D_HPCF_BIT 3 +#define L3G4200D_HPCF_LENGTH 4 + +#define L3G4200D_HPM_HRF 0b00 +#define L3G4200D_HPM_REFERENCE 0b01 +#define L3G4200D_HPM_NORMAL 0b10 +#define L3G4200D_HPM_AUTORESET 0b11 + +#define L3G4200D_HPCF1 0b0000 +#define L3G4200D_HPCF2 0b0001 +#define L3G4200D_HPCF3 0b0010 +#define L3G4200D_HPCF4 0b0011 +#define L3G4200D_HPCF5 0b0100 +#define L3G4200D_HPCF6 0b0101 +#define L3G4200D_HPCF7 0b0110 +#define L3G4200D_HPCF8 0b0111 +#define L3G4200D_HPCF9 0b1000 +#define L3G4200D_HPCF10 0b1001 + +#define L3G4200D_I1_INT1_BIT 7 +#define L3G4200D_I1_BOOT_BIT 6 +#define L3G4200D_H_LACTIVE_BIT 5 +#define L3G4200D_PP_OD_BIT 4 +#define L3G4200D_I2_DRDY_BIT 3 +#define L3G4200D_I2_WTM_BIT 2 +#define L3G4200D_I2_ORUN_BIT 1 +#define L3G4200D_I2_EMPTY_BIT 0 + +#define L3G4200D_PUSH_PULL 1 +#define L3G4200D_OPEN_DRAIN 0 + +#define L3G4200D_BDU_BIT 7 +#define L3G4200D_BLE_BIT 6 +#define L3G4200D_FS_BIT 5 +#define L3G4200D_FS_LENGTH 2 +#define L3G4200D_ST_BIT 2 +#define L3G4200D_ST_LENGTH 2 +#define L3G4200D_SIM_BIT 0 + +#define L3G4200D_BIG_ENDIAN 1 +#define L3G4200D_LITTLE_ENDIAN 0 + +#define L3G4200D_FS_250 0b00 +#define L3G4200D_FS_500 0b01 +#define L3G4200D_FS_2000 0b10 + +#define L3G4200D_SELF_TEST_NORMAL 0b00 +#define L3G4200D_SELF_TEST_0 0b01 +#define L3G4200D_SELF_TEST_1 0b11 + +#define L3G4200D_SPI_4_WIRE 1 +#define L3G4200D_SPI_3_WIRE 0 + +#define L3G4200D_BOOT_BIT 7 +#define L3G4200D_FIFO_EN_BIT 6 +#define L3G4200D_HPEN_BIT 4 +#define L3G4200D_INT1_SEL_BIT 3 +#define L3G4200D_INT1_SEL_LENGTH 2 +#define L3G4200D_OUT_SEL_BIT 1 +#define L3G4200D_OUT_SEL_LENGTH 2 + +#define L3G4200D_NON_HIGH_PASS 0b00 +#define L3G4200D_HIGH_PASS 0b01 +#define L3G4200D_LOW_PASS 0b10 +#define L3G4200D_LOW_HIGH_PASS 0b11 + +#define L3G4200D_ZYXOR_BIT 7 +#define L3G4200D_ZOR_BIT 6 +#define L3G4200D_YOR_BIT 5 +#define L3G4200D_XOR_BIT 4 +#define L3G4200D_ZYXDA_BIT 3 +#define L3G4200D_ZDA_BIT 2 +#define L3G4200D_YDA_BIT 1 +#define L3G4200D_XDA_BIT 0 + +#define L3G4200D_FIFO_MODE_BIT 7 +#define L3G4200D_FIFO_MODE_LENGTH 3 +#define L3G4200D_FIFO_WTM_BIT 4 +#define L3G4200D_FIFO_WTM_LENGTH 5 + +#define L3G4200D_FM_BYPASS 0b000 +#define L3G4200D_FM_FIFO 0b001 +#define L3G4200D_FM_STREAM 0b010 +#define L3G4200D_FM_STREAM_FIFO 0b011 +#define L3G4200D_FM_BYPASS_STREAM 0b100 + +#define L3G4200D_FIFO_STATUS_BIT 7 +#define L3G4200D_FIFO_OVRN_BIT 6 +#define L3G4200D_FIFO_EMPTY_BIT 5 +#define L3G4200D_FIFO_FSS_BIT 4 +#define L3G4200D_FIFO_FSS_LENGTH 5 + +#define L3G4200D_INT1_AND_OR_BIT 7 +#define L3G4200D_INT1_LIR_BIT 6 +#define L3G4200D_ZHIE_BIT 5 +#define L3G4200D_ZLIE_BIT 4 +#define L3G4200D_YHIE_BIT 3 +#define L3G4200D_YLIE_BIT 2 +#define L3G4200D_XHIE_BIT 1 +#define L3G4200D_XLIE_BIT 0 + +#define L3G4200D_INT1_OR 0 +#define L3G4200D_INT1_AND 1 + +#define L3G4200D_INT1_IA_BIT 6 +#define L3G4200D_INT1_ZH_BIT 5 +#define L3G4200D_INT1_ZL_BIT 4 +#define L3G4200D_INT1_YH_BIT 3 +#define L3G4200D_INT1_YL_BIT 2 +#define L3G4200D_INT1_XH_BIT 1 +#define L3G4200D_INT1_XL_BIT 0 + +#define L3G4200D_INT1_WAIT_BIT 7 +#define L3G4200D_INT1_DUR_BIT 6 +#define L3G4200D_INT1_DUR_LENGTH 7 + + +class L3G4200D { + public: + L3G4200D(); + L3G4200D(uint8_t address); + + void initialize(); + bool testConnection(); + + // WHO_AM_I register, read-only + uint8_t getDeviceID(); + + // CTRL_REG1 register, r/w + void setOutputDataRate(uint16_t rate); + uint16_t getOutputDataRate(); + void setBandwidthCutOffMode(uint8_t mode); + uint8_t getBandwidthCutOffMode(); + float getBandwidthCutOff(); + void setPowerOn(bool on); + bool getPowerOn(); + void setZEnabled(bool enabled); + bool getZEnabled(); + void setYEnabled(bool enabled); + bool getYEnabled(); + void setXEnabled(bool enabled); + bool getXEnabled(); + + // CTRL_REG2 register, r/w + void setHighPassMode(uint8_t mode); + uint8_t getHighPassMode(); + void setHighPassFilterCutOffFrequencyLevel(uint8_t level); + uint8_t getHighPassFilterCutOffFrequencyLevel(); + + // CTRL_REG3 register, r/w + void setINT1InterruptEnabled(bool enabled); + bool getINT1InterruptEnabled(); + void setINT1BootStatusEnabled(bool enabled); + bool getINT1BootStatusEnabled(); + void interruptActiveINT1Config(); + void setOutputMode(bool mode); + bool getOutputMode(); + void setINT2DataReadyEnabled(bool enabled); + bool getINT2DataReadyEnabled(); + void setINT2FIFOWatermarkInterruptEnabled(bool enabled); + bool getINT2FIFOWatermarkInterruptEnabled(); + void setINT2FIFOOverrunInterruptEnabled(bool enabled); + bool getINT2FIFOOverrunInterruptEnabled(); + void setINT2FIFOEmptyInterruptEnabled(bool enabled); + bool getINT2FIFOEmptyInterruptEnabled(); + + // CTRL_REG4 register, r/w + void setBlockDataUpdateEnabled(bool enabled); + bool getBlockDataUpdateEnabled(); + void setEndianMode(bool endianness); + bool getEndianMode(); + void setFullScale(uint16_t scale); + uint16_t getFullScale(); + void setSelfTestMode(uint8_t mode); + uint8_t getSelfTestMode(); + void setSPIMode(bool mode); + bool getSPIMode(); + + // CTRL_REG5 register, r/w + void rebootMemoryContent(); + void setFIFOEnabled(bool enabled); + bool getFIFOEnabled(); + void setHighPassFilterEnabled(bool enabled); + bool getHighPassFilterEnabled(); + void setDataFilter(uint8_t filter); + uint8_t getDataFilter(); + + // REFERENCE/DATACAPTURE register, r/w + void setInterruptReference(uint8_t reference); + uint8_t getInterruptReference(); + + // OUT_TEMP register, read-only + uint8_t getTemperature(); + + // STATUS register, read-only + bool getXYZOverrun(); + bool getZOverrun(); + bool getYOverrun(); + bool getXOverrun(); + bool getXYZDataAvailable(); + bool getZDataAvailable(); + bool getYDataAvailable(); + bool getXDataAvailable(); + + // OUT_* registers, read-only + void getAngularVelocity(int16_t* x, int16_t* y, int16_t* z); + int16_t getAngularVelocityX(); + int16_t getAngularVelocityY(); + int16_t getAngularVelocityZ(); + + // FIFO_CTRL register, r/w + void setFIFOMode(uint8_t mode); + uint8_t getFIFOMode(); + void setFIFOThreshold(uint8_t wtm); + uint8_t getFIFOThreshold(); + + // FIFO_SRC register, read-only + bool getFIFOAtWatermark(); + bool getFIFOOverrun(); + bool getFIFOEmpty(); + uint8_t getFIFOStoredDataLevel(); + + // INT1_CFG register, r/w + void setInterruptCombination(bool combination); + bool getInterruptCombination(); + void setInterruptRequestLatched(bool latched); + bool getInterruptRequestLatched(); + void setZHighInterruptEnabled(bool enabled); + bool getZHighInterruptEnabled(); + void setYHighInterruptEnabled(bool enabled); + bool getYHighInterruptEnabled(); + void setXHighInterruptEnabled(bool enabled); + bool getXHighInterruptEnabled(); + void setZLowInterruptEnabled(bool enabled); + bool getZLowInterruptEnabled(); + void setYLowInterruptEnabled(bool enabled); + bool getYLowInterruptEnabled(); + void setXLowInterruptEnabled(bool enabled); + bool getXLowInterruptEnabled(); + + // INT1_SRC register, read-only + bool getInterruptActive(); + bool getZHigh(); + bool getZLow(); + bool getYHigh(); + bool getYLow(); + bool getXHigh(); + bool getXLow(); + + // INT1_THS_* registers, r/w + void setXHighThreshold(uint8_t threshold); + uint8_t getXHighThreshold(); + void setXLowThreshold(uint8_t threshold); + uint8_t getXLowThreshold(); + void setYHighThreshold(uint8_t threshold); + uint8_t getYHighThreshold(); + void setYLowThreshold(uint8_t threshold); + uint8_t getYLowThreshold(); + void setZHighThreshold(uint8_t threshold); + uint8_t getZHighThreshold(); + void setZLowThreshold(uint8_t threshold); + uint8_t getZLowThreshold(); + + // INT1_DURATION register, r/w + void setDuration(uint8_t duration); + uint8_t getDuration(); + void setWaitEnabled(bool enabled); + bool getWaitEnabled(); + + private: + uint8_t devAddr; + uint8_t buffer[6]; +}; + +#endif /* _L3G4200D_H_ */ diff --git a/libraries/L3G4200D/examples/L3G4200D_raw/L3G4200D_raw.ino b/libraries/L3G4200D/examples/L3G4200D_raw/L3G4200D_raw.ino new file mode 100644 index 0000000..0202282 --- /dev/null +++ b/libraries/L3G4200D/examples/L3G4200D_raw/L3G4200D_raw.ino @@ -0,0 +1,88 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for L3G4200D class +// 7/31/2013 by Jonathan Arnett +// 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 Jonathan Arnett, 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 + +// I2Cdev and L3G4200D must be installed as libraries, or else the .cpp/.h files +// for both classes must be in the include path of your project +#include +#include + +// default address is 105 +// specific I2C address may be passed here +L3G4200D gyro; + +int16_t avx, avy, avz; + +#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(9600); + + // initialize device + Serial.println("Initializing I2C devices..."); + gyro.initialize(); + + // verify connection + Serial.println("Testing device connections..."); + Serial.println(gyro.testConnection() ? "L3G4200D connection successful" : "L3G4200D connection failed"); + + // configure LED for output + pinMode(LED_PIN, OUTPUT); + + // data seems to be best when full scale is 2000 + gyro.setFullScale(2000); +} + +void loop() { + // read raw angular velocity measurements from device + gyro.getAngularVelocity(&avx, &avy, &avz); + + Serial.print("angular velocity:\t"); + Serial.print(avx); Serial.print("\t"); + Serial.print(avy); Serial.print("\t"); + Serial.println(avz); + + // blink LED to indicate activity + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); +} + + diff --git a/libraries/L3G4200D/library.json b/libraries/L3G4200D/library.json new file mode 100644 index 0000000..f899e31 --- /dev/null +++ b/libraries/L3G4200D/library.json @@ -0,0 +1,18 @@ +{ + "name": "I2Cdevlib-L3G4200D", + "keywords": "accelerometer, sensor, i2cdevlib, i2c", + "description": "The L3G4200D is a low-power three-axis angular rate sensor able to provide unprecedented stablility of zero rate level and sensitivity over temperature and time", + "include": "Arduino/L3G4200D", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "dependencies": + { + "name": "I2Cdevlib-Core", + "frameworks": "arduino" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/L3GD20H/L3GD20H.cpp b/libraries/L3GD20H/L3GD20H.cpp new file mode 100644 index 0000000..bd5d888 --- /dev/null +++ b/libraries/L3GD20H/L3GD20H.cpp @@ -0,0 +1,1695 @@ +// I2Cdev library collection - L3GD20H I2C device class +// Based on STMicroelectronics L3GD20H datasheet rev. 2, 3/2013 +// 3/05/2015 by Nate Costello +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2015-03-05 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Jonathan Arnett, 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 "L3GD20H.h" + +/** Default constructor, uses default I2C address. + * @see L3GD20H_DEFAULT_ADDRESS + */ +L3GD20H::L3GD20H() { + devAddr = L3GD20H_DEFAULT_ADDRESS; + endianMode = 0; +} + +/** Specific address constructor. + * @param address I2C address + * @see L3GD20H_DEFAULT_ADDRESS + * @see L3GD20H_ADDRESS + */ +L3GD20H::L3GD20H(uint8_t address) { + devAddr = address; + endianMode = 0; +} + +/** Power on and prepare for general usage. + * All values are defaults except for the power on bit in CTRL_1 + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_RA_CTRL2 + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_RA_CTRL4 + * @see L3GD20H_RA_CTRL5 + */ +void L3GD20H::initialize() { + I2Cdev::writeByte(devAddr, L3GD20H_RA_CTRL1, 0b00001111); + I2Cdev::writeByte(devAddr, L3GD20H_RA_CTRL2, 0b00000000); + I2Cdev::writeByte(devAddr, L3GD20H_RA_CTRL3, 0b00000000); + I2Cdev::writeByte(devAddr, L3GD20H_RA_CTRL4, 0b00000000); + I2Cdev::writeByte(devAddr, L3GD20H_RA_CTRL5, 0b00000000); +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool L3GD20H::testConnection() { + return getDeviceID() == 0b11010111; +} + +// WHO_AM_I register, read-only + +/** Get the Device ID. + * The WHO_AM_I register holds the device's id + * @return Device ID (should be 0b11010011, 109, 0x69) + * @see L3GD20H_RA_WHO_AM_I + */ +uint8_t L3GD20H::getDeviceID() { + I2Cdev::readByte(devAddr, L3GD20H_RA_WHO_AM_I, buffer); + return buffer[0]; +} + +// CTRL1 register, r/w + +/** Set the output data rate. Makes use of the setLowODREnabled function. + * @param rate The new data output rate (can be 12, 25, 50, 100, 200, 400, or 800) + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_ODR_BIT + * @see L3GD20H_ODR_LENGTH + * @see L3GD20H_RATE_100_12 + * @see L3GD20H_RATE_200_25 + * @see L3GD20H_RATE_400_50 + * @see L3GD20H_RATE_800_50 + * @see L3GD20H_RA_LOW_ODR + * @see L3GD20H_LOW_ODR_BIT + */ +void L3GD20H::setOutputDataRate(uint16_t rate) { + uint8_t writeVal; + bool lowODRwriteVal; + + if (rate ==12) { + writeVal = L3GD20H_RATE_100_12; + setLowODREnabled(true); + } else if (rate == 25) { + writeVal = L3GD20H_RATE_200_25; + setLowODREnabled(true); + } else if (rate == 50) { + writeVal = L3GD20H_RATE_400_50; + setLowODREnabled(true); + } else if (rate == 100) { + writeVal = L3GD20H_RATE_100_12; + setLowODREnabled(false); + } else if (rate == 200) { + writeVal = L3GD20H_RATE_200_25; + setLowODREnabled(false); + } else if (rate == 400) { + writeVal = L3GD20H_RATE_400_50; + setLowODREnabled(false); + } else { + writeVal = L3GD20H_RATE_800_50; + setLowODREnabled(false); + } + + I2Cdev::writeBits(devAddr, L3GD20H_RA_CTRL1, L3GD20H_ODR_BIT, + L3GD20H_ODR_LENGTH, writeVal); +} + +/** Get the current output data rate + * @return Current data output rate + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_ODR_BIT + * @see L3GD20H_ODR_LENGTH + * @see L3GD20H_RATE_100_12 + * @see L3GD20H_RATE_200_25 + * @see L3GD20H_RATE_400_50 + * @see L3GD20H_RATE_800_50 + * @see L3GD20H_RA_LOW_ODR + * @see L3GD20H_LOW_ODR_BIT + */ +uint16_t L3GD20H::getOutputDataRate() { + I2Cdev::readBits(devAddr, L3GD20H_RA_CTRL1, L3GD20H_ODR_BIT, + L3GD20H_ODR_LENGTH, buffer); + uint8_t rate = buffer[0]; + + if (rate == L3GD20H_RATE_100_12) { + if (getLowODREnabled() == true) { + return 12; + } else { + return 100; + } + } else if (rate == L3GD20H_RATE_200_25) { + if (getLowODREnabled() == true) { + return 25; + } else { + return 200; + } + } else if (rate == L3GD20H_RATE_400_50) { + if (getLowODREnabled() == true) { + return 50; + } else { + return 400; + } + } else if (rate == L3GD20H_RATE_800_50) { + if (getLowODREnabled() == true) { + return 50; + } else { + return 800; + } + } + return 800; +} + +/** Set the bandwidth cut-off mode + * @param mode The new bandwidth cut-off mode + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_BW_BIT + * @see L3GD20H_BW_LENGTH + * @see L3GD20H_BW_LOW + * @see L3GD20H_BW_MED_LOW + * @see L3GD20H_BW_MED_HIGH + * @see L3GD20H_BW_HIGH + */ +void L3GD20H::setBandwidthCutOffMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, L3GD20H_RA_CTRL1, L3GD20H_BW_BIT, + L3GD20H_BW_LENGTH, mode); +} + +/** Get the current bandwidth cut-off mode + * @return Current bandwidth cut off mode + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_BW_BIT + * @see L3GD20H_BW_LENGTH + * @see L3GD20H_BW_LOW + * @see L3GD20H_BW_MED_LOW + * @see L3GD20H_BW_MED_HIGH + * @see L3GD20H_BW_HIGH + */ +uint8_t L3GD20H::getBandwidthCutOffMode() { + I2Cdev::readBits(devAddr, L3GD20H_RA_CTRL1, L3GD20H_BW_BIT, + L3GD20H_BW_LENGTH, buffer); + return buffer[0]; +} + +// /** Gets the current bandwidth cutoff based on ODR and BW +// * @return Float value of the bandwidth cut off +// * @see L3GD20H_RA_CTRL1 +// * @see L3GD20H_ODR_BIT +// * @see L3GD20H_ODR_LENGTH +// * @see L3GD20H_RATE_100_12 +// * @see L3GD20H_RATE_200_25 +// * @see L3GD20H_RATE_400_50 +// * @see L3GD20H_RATE_800_50 +// * @see L3GD20H_BW_BIT +// * @see L3GD20H_BW_LENGTH +// * @see L3GD20H_BW_LOW +// * @see L3GD20H_BW_MED_LOW +// * @see L3GD20H_BW_MED_HIGH +// * @see L3GD20H_BW_HIGH +// */ +// float L3GD20H::getBandwidthCutOff() { +// uint16_t dataRate = getOutputDataRate(); +// uint8_t bandwidthMode = getBandwidthCutOffMode(); + +// if (dataRate == 50) { +// return 16.6; +// } else if (dataRate == 100) { +// if (bandwidthMode == L3GD20H_BW_LOW) { +// return 12.5; +// } else { +// return 25.0; +// } +// } else if (dataRate == 200) { +// if (bandwidthMode == L3GD20H_BW_LOW) { +// return 12.5; +// } else if (bandwidthMode == L3GD20H_BW_MED_LOW) { +// return 0.0; +// } else if (bandwidthMode == L3GD20H_BW_MED_HIGH) { +// return 0.0; +// } else { +// return 70.0; +// } +// } else if (dataRate == 400) { +// if (bandwidthMode == L3GD20H_BW_LOW) { +// return 20.0; +// } else if (bandwidthMode == L3GD20H_BW_MED_LOW) { +// return 25.0; +// } else if (bandwidthMode == L3GD20H_BW_MED_HIGH) { +// return 50.0; +// } else { +// return 110.0; +// } +// } else if (dataRate == 800) { +// if (bandwidthMode == L3GD20H_BW_LOW) { +// return 30.0; +// } else if (bandwidthMode == L3GD20H_BW_MED_LOW) { +// return 35.0; +// } else if (bandwidthMode == L3GD20H_BW_MED_HIGH) { +// return 0.0; +// } else { +// return 110.0; +// } +// } else { +// return 0.0 +// } +// } + +/** Set power on or off + * @param enabled The new power setting (true for on, false for off) + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_PD_BIT + */ +void L3GD20H::setPowerOn(bool on) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL1, L3GD20H_PD_BIT, on); +} + +/** Get the current power state + * @return Powered on state (true for on, false for off) + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_PD_BIT + */ +bool L3GD20H::getPowerOn() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL1, L3GD20H_PD_BIT, buffer); + return buffer[0]; +} + +/** Enables or disables the ability to get Z data + * @param enabled The new enabled state of the Z axis + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_ZEN_BIT + */ +void L3GD20H::setZEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL1, L3GD20H_ZEN_BIT, enabled); +} + +/** Get whether Z axis data is enabled + * @return True if the Z axis is enabled, false otherwise + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_ZEN_BIT + */ +bool L3GD20H::getZEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL1, L3GD20H_ZEN_BIT, buffer); + return buffer[0]; +} + +/** Enables or disables the ability to get Y data + * @param enabled The new enabled state of the Y axis + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_YEN_BIT + */ +void L3GD20H::setYEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL1, L3GD20H_YEN_BIT, enabled); +} + +/** Get whether Y axis data is enabled + * @return True if the Y axis is enabled, false otherwise + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_YEN_BIT + */ +bool L3GD20H::getYEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL1, L3GD20H_YEN_BIT, buffer); + return buffer[0]; +} + +/** Enables or disables the ability to get X data + * @param enabled The new enabled state of the X axis + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_XEN_BIT + */ +void L3GD20H::setXEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL1, L3GD20H_XEN_BIT, enabled); +} + +/** Get whether X axis data is enabled + * @return True if the X axis is enabled, false otherwise + * @see L3GD20H_RA_CTRL1 + * @see L3GD20H_XEN_BIT + */ +bool L3GD20H::getXEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL1, L3GD20H_XEN_BIT, buffer); + return buffer[0]; +} + +// CTRL2 register, r/w + +/** Set the high pass mode + * @param mode The new high pass mode + * @see L3GD20H_RA_CTRL2 + * @see L3GD20H_HPM_BIT + * @see L3GD20H_HPM_LENGTH + * @see L3GD20H_HPM_HRF + * @see L3GD20H_HPM_REFERENCE + * @see L3GD20H_HPM_NORMAL + * @see L3GD20H_HPM_AUTORESET + */ +void L3GD20H::setHighPassMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, L3GD20H_RA_CTRL2, L3GD20H_HPM_BIT, + L3GD20H_HPM_LENGTH, mode); +} + +/** Get the high pass mode + * @return High pass mode + * @see L3GD20H_RA_CTRL2 + * @see L3GD20H_HPM_BIT + * @see L3GD20H_HPM_LENGTH + * @see L3GD20H_HPM_HRF + * @see L3GD20H_HPM_REFERENCE + * @see L3GD20H_HPM_NORMAL + * @see L3GD20H_HPM_AUTORESET + */ +uint8_t L3GD20H::getHighPassMode() { + I2Cdev::readBits(devAddr, L3GD20H_RA_CTRL2, L3GD20H_HPM_BIT, + L3GD20H_HPM_LENGTH, buffer); + return buffer[0]; +} + +/** Set the high pass filter cut off frequency level (1 - 10) + * @param level The new level for the hpcf, using one of the defined levels + * @see L3GD20H_RA_CTRL2 + * @see L3GD20H_HPCF_BIT + * @see L3GD20H_HPCF_LENGTH + * @see L3GD20H_HPCF1 + * @see L3GD20H_HPCF2 + * @see L3GD20H_HPCF3 + * @see L3GD20H_HPCF4 + * @see L3GD20H_HPCF5 + * @see L3GD20H_HPCF6 + * @see L3GD20H_HPCF7 + * @see L3GD20H_HPCF8 + * @see L3GD20H_HPCF9 + * @see L3GD20H_HPCF10 + */ +void L3GD20H::setHighPassFilterCutOffFrequencyLevel(uint8_t level) { + I2Cdev::writeBits(devAddr, L3GD20H_RA_CTRL2, L3GD20H_HPCF_BIT, + L3GD20H_HPCF_LENGTH, level); +} + +/** Get the high pass filter cut off frequency level (1 - 10) + * @return High pass filter cut off frequency level + * @see L3GD20H_RA_CTRL2 + * @see L3GD20H_HPCF_BIT + * @see L3GD20H_HPCF_LENGTH + * @see L3GD20H_HPCF1 + * @see L3GD20H_HPCF2 + * @see L3GD20H_HPCF3 + * @see L3GD20H_HPCF4 + * @see L3GD20H_HPCF5 + * @see L3GD20H_HPCF6 + * @see L3GD20H_HPCF7 + * @see L3GD20H_HPCF8 + * @see L3GD20H_HPCF9 + * @see L3GD20H_HPCF10 + */ +uint8_t L3GD20H::getHighPassFilterCutOffFrequencyLevel() { + I2Cdev::readBits(devAddr, L3GD20H_RA_CTRL2, L3GD20H_HPCF_BIT, + L3GD20H_HPCF_LENGTH, buffer); + return buffer[0]; +} + +// CTRL3 register, r/w + +/** Set the INT1 interrupt enabled state + * @param enabled New enabled state for the INT1 interrupt + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_INT1_IG_BIT + */ +void L3GD20H::setINT1InterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_INT1_IG_BIT, + enabled); +} + +/** Get the INT1 interrupt enabled state + * @return True if the INT1 interrupt is enabled, false otherwise + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_INT1_IG_BIT + */ +bool L3GD20H::getINT1InterruptEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_INT1_IG_BIT, + buffer); + return buffer[0]; +} + +/** Set the INT1 boot status enabled state + * @param enabled New enabled state for the INT1 boot status + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_INT1_BOOT_BIT + */ +void L3GD20H::setINT1BootStatusEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_INT1_BOOT_BIT, + enabled); +} + +/** Get the INT1 boot status enabled state + * @return INT1 boot status status + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_INT1_BOOT_BIT + */ +bool L3GD20H::getINT1BootStatusEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_INT1_BOOT_BIT, + buffer); + return buffer[0]; +} + +/** Interrupts the active INT1 configuration + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_H_LACTIVE_BIT + */ +void L3GD20H::interruptActiveINT1Config() { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_H_LACTIVE_BIT, 1); +} + +/** Set output mode to push-pull or open-drain + * @param mode New output mode + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_PP_OD_BIT + * @see L3GD20H_PUSH_PULL + * @see L3GD20H_OPEN_DRAIN + */ +void L3GD20H::setOutputMode(bool mode) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_PP_OD_BIT, + mode); +} + +/** Get whether mode is push-pull or open drain + * @return Output mode (TRUE for open-drain, FALSE for push-pull) + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_PP_OD_BIT + * @see L3GD20H_PUSH_PULL + * @see L3GD20H_OPEN_DRAIN + */ +bool L3GD20H::getOutputMode() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_PP_OD_BIT, + buffer); + return buffer[0]; +} + +/** Set data ready interrupt enabled state on INT2 pin + * @param enabled New INT2 data ready interrupt enabled state + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_INT2_DRDY_BIT + */ +void L3GD20H::setINT2DataReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_INT2_DRDY_BIT, + enabled); +} + +/** Get whether the data ready interrupt is enabled on the INT2 pin + * @return True if the INT2 data ready interrupt is enabled, false otherwise + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_INT2_DRDY_BIT + */ +bool L3GD20H::getINT2DataReadyEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_INT2_DRDY_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the INT2 FIFO threshold (watermark) interrupt is enabled + * The sensor contains a 32-slot FIFO buffer for storing data so that it may be + * read later. If enabled, the sensor will generate an interrupt on the + * INT2/DRDY pin when the threshold has been reached. The threshold can be + * configured through the setFIFOWatermark function. + * @param enabled New enabled state of the INT2 FIFO threshold (watermark) + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_I2_WTM_BIT + */ +void L3GD20H::setINT2FIFOWatermarkInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_INT2_FTH_BIT, + enabled); +} + +/** Get the INT2 FIFO threshold (watermark) interrupt enabled state + * @return true if the FIFO watermark is enabled, false otherwise + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_INT2_FTH_BIT + */ +bool L3GD20H::getINT2FIFOWatermarkInterruptEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_INT2_FTH_BIT, + buffer); + return buffer[0]; +} + +/** Set whether an interrupt is triggered on INT2 when the FIFO is overrun + * @param enabled New FIFO overrun interrupt enabled state + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_INT2_ORUN_BIT + */ +void L3GD20H::setINT2FIFOOverrunInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_INT2_ORUN_BIT, + enabled); +} + +/** Get whether an interrupt is triggered on INT2 when the FIFO is overrun + * @return True if the INT2 FIFO overrun interrupt is enabled, false otherwise + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_INT2_ORUN_BIT + */ +bool L3GD20H::getINT2FIFOOverrunInterruptEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_INT2_ORUN_BIT, + buffer); + return buffer[0]; +} + +/** Set whether an interrupt is triggered on INT2 when the FIFO buffer is empty + * @param enabled New INT2 FIFO empty interrupt state + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_INT2_EMPTY_BIT + */ +void L3GD20H::setINT2FIFOEmptyInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_INT2_EMPTY_BIT, + enabled); +} + +/** Get whether the INT2 FIFO empty interrupt is enabled + * @returns True if the INT2 FIFO empty interrupt is enabled, false otherwise + * @see L3GD20H_RA_CTRL3 + * @see L3GD20H_INT2_EMPTY_BIT + */ +bool L3GD20H::getINT2FIFOEmptyInterruptEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL3, L3GD20H_INT2_EMPTY_BIT, + buffer); + return buffer[0]; +} + +// CTRL4 register, r/w + +/** Set the Block Data Update (BDU) enabled state + * @param enabled New BDU enabled state + * @see L3GD20H_RA_CTRL4 + * @see L3GD20H_BDU_BIT + */ +void L3GD20H::setBlockDataUpdateEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL4, L3GD20H_BDU_BIT, enabled); +} + +/** Get the BDU enabled state + * @return True if Block Data Update is enabled, false otherwise + * @see L3GD20H_RA_CTRL4 + * @see L3GD20H_BDU_BIT + */ +bool L3GD20H::getBlockDataUpdateEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL4, L3GD20H_BDU_BIT, buffer); + return buffer[0]; +} + +/** Set the data endian modes + * In Big Endian mode, the Most Significat Byte (MSB) is on the lower address, + * and the Least Significant Byte (LSB) is on the higher address. Little Endian + * mode reverses this order. Little Endian is the default mode. + * @param endianness New endian mode + * @see L3GD20H_RA_CTRL4 + * @see L3GD20H_BLE_BIT + * @see L3GD20H_BIG_ENDIAN + * @see L3GD20H_LITTLE_ENDIAN + */ +void L3GD20H::setEndianMode(bool endianness) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL4, L3GD20H_BLE_BIT, + endianness); + endianMode = getEndianMode(); +} + +/** Get the data endian mode + * @return Current endian mode + * @see L3GD20H_RA_CTRL4 + * @see L3GD20H_BLE_BIT + * @see L3GD20H_BIG_ENDIAN + * @see L3GD20H_LITTLE_ENDIAN + */ +bool L3GD20H::getEndianMode() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL4, L3GD20H_BLE_BIT, + buffer); + return buffer[0]; +} + +/** Set the full scale of the data output (in dps) + * @param scale The new scale of the data output (250 [actual 245], 500, 2000) + * @see L3GD20H_RA_CTRL4 + * @see L3GD20H_FS_BIT + * @see L3GD20H_FS_LENGTH + * @see L3GD20H_FS_250 + * @see L3GD20H_FS_500 + * @see L3GD20H_FS_2000 + */ +void L3GD20H::setFullScale(uint16_t scale) { + uint8_t writeBits; + + if (scale == 250) { + writeBits = L3GD20H_FS_250; + } else if (scale == 500) { + writeBits = L3GD20H_FS_500; + } else { + writeBits = L3GD20H_FS_2000; + } + + I2Cdev::writeBits(devAddr, L3GD20H_RA_CTRL4, L3GD20H_FS_BIT, + L3GD20H_FS_LENGTH, writeBits); +} + +/** Get the current full scale of the output data (in dps) + * @return Current scale of the output data + * @see L3GD20H_RA_CTRL4 + * @see L3GD20H_FS_BIT + * @see L3GD20H_FS_LENGTH + * @see L3GD20H_FS_250 + * @see L3GD20H_FS_500 + * @see L3GD20H_FS_2000 + */ +uint16_t L3GD20H::getFullScale() { + I2Cdev::readBits(devAddr, L3GD20H_RA_CTRL4, + L3GD20H_FS_BIT, L3GD20H_FS_LENGTH, buffer); + uint8_t readBits = buffer[0]; + + if (readBits == L3GD20H_FS_250) { + return 250; + } else if (readBits == L3GD20H_FS_500) { + return 500; + } else { + return 2000; + } +} + +//TODO +//Implement +//L3GD20H::setLevelSensitiveLatchedEnabled() and +//L3GD20H::getLevelSensitiveLatchedEnabled() +// + +/** Set the self test mode + * @param mode New self test mode (Normal, 0, 1) + * @see L3GD20H_RA_CTRL4 + * @see L3GD20H_ST_BIT + * @see L3GD20H_ST_LENGTH + * @see L3GD20H_SELF_TEST_NORMAL + * @see L3GD20H_SELF_TEST_0 + * @see L3GD20H_SELF_TEST_1 + */ +void L3GD20H::setSelfTestMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, L3GD20H_RA_CTRL4, L3GD20H_ST_BIT, + L3GD20H_ST_LENGTH, mode); +} + +/** Get the current self test mode + * @return Current self test mode + * @see L3GD20H_RA_CTRL4 + * @see L3GD20H_ST_BIT + * @see L3GD20H_ST_LENGTH + * @see L3GD20H_SELF_TEST_NORMAL + * @see L3GD20H_SELF_TEST_0 + * @see L3GD20H_SELF_TEST_1 + */ +uint8_t L3GD20H::getSelfTestMode() { + I2Cdev::readBits(devAddr, L3GD20H_RA_CTRL4, L3GD20H_ST_BIT, + L3GD20H_ST_LENGTH, buffer); + return buffer[0]; +} + +/** Set the SPI mode + * @param mode New SPI mode + * @see L3GD20H_RA_CTRL4 + * @see L3GD20H_SIM_BIT + * @see L3GD20H_SPI_4_WIRE + * @see L3GD20H_SPI_3_WIRE + */ +void L3GD20H::setSPIMode(bool mode) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL4, L3GD20H_SIM_BIT, mode); +} + +/** Get the SPI mode + * @return Current SPI mode + * @see L3GD20H_RA_CTRL4 + * @see L3GD20H_SIM_BIT + * @see L3GD20H_SPI_4_WIRE + * @see L3GD20H_SPI_3_WIRE + */ +bool L3GD20H::getSPIMode() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL4, L3GD20H_SIM_BIT, + buffer); + return buffer[0]; +} + +// CTRL5 register, r/w + +/** Reboots the FIFO memory content + * @see L3GD20H_RA_CTRL5 + * @see L3GD20H_BOOT_BIT + */ +void L3GD20H::rebootMemoryContent() { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL5, L3GD20H_BOOT_BIT, true); +} + +/** Set whether the FIFO buffer is enabled + * @param enabled New enabled state of the FIFO buffer + * @see L3GD20H_RA_CTRL5 + * @see L3GD20H_FIFO_EN_BIT + */ +void L3GD20H::setFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL5, L3GD20H_FIFO_EN_BIT, + enabled); +} + +/** Get whether the FIFO buffer is enabled + * @return True if the FIFO buffer is enabled, false otherwise + * @see L3GD20H_RA_CTRL5 + * @see L3GD20H_FIFO_EN_BIT + */ +bool L3GD20H::getFIFOEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL5, L3GD20H_FIFO_EN_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the sensing chain FIFO stops writing new values once + * the FIFO Threshold (watermark) is reached + * @param enabled New state of the StopOnFTH bit + * @see L3GD20H_RA_CTRL5 + * @see L3GD20H_FIFO_STOPONFTH_BIT + */ +void L3GD20H::setStopOnFIFOThresholdEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL5, L3GD20H_STOPONFTH_BIT, + enabled); +} + +/** Get whether the sensing chain FIFO stopping writing new values once + * the FIFO Threshold (watermark) is enabled + * @return True if the state of the StopOnFTH bit is high (enabled) + * @see L3GD20H_RA_CTRL5 + * @see L3GD20H_FIFO_STOPONFTH_BIT + */ +bool L3GD20H::getStopOnFIFOThresholdEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL5, L3GD20H_STOPONFTH_BIT, + buffer); + return buffer[0]; +} + + +/** Set the high pass filter enabled state + * @param enabled New high pass filter enabled state + * @see L3GD20H_RA_CTRL5 + * @see L3GD20H_HPEN_BIT + */ +void L3GD20H::setHighPassFilterEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_CTRL5, L3GD20H_HPEN_BIT, + enabled); +} + +/** Get whether the high pass filter is enabled + * @return True if the high pass filter is enabled, false otherwise + * @see L3GD20H_RA_CTRL5 + * @see L3GD20H_HPEN_BIT + */ +bool L3GD20H::getHighPassFilterEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_CTRL5, L3GD20H_HPEN_BIT, + buffer); + return buffer[0]; +} + +/** Sets the filter mode to one of the four provided. + * This function also uses the setHighPassFilterEnabled function in order to set + * the mode. That function does not have to be called in addition to this one. + * In addition to setting the filter for the data in the FIFO buffer + * (controlled by the bits written to OUT_SEL), this function also sets the + * filter used for interrupt generation (the bits written to IG_SEL) to be the + * same as the filter used for the FIFO buffer. The filter used for interrupt + * generation can be set separately with the setInterruptFilter function. + * @param filter New method to be used when filtering data + * @see L3GD20H_RA_CTRL5 + * @see L3GD20H_IG_SEL_BIT + * @see L3GD20H_IG_SEL_LENGTH + * @see L3GD20H_OUT_SEL_BIT + * @see L3GD20H_OUT_SEL_LENGTH + * @see L3GD20H_NON_HIGH_PASS + * @see L3GD20H_HIGH_PASS + * @see L3GD20H_LOW_PASS + * @see L3GD20H_LOW_HIGH_PASS + */ +void L3GD20H::setDataFilter(uint8_t filter) { + if (filter == L3GD20H_HIGH_PASS || filter == L3GD20H_LOW_HIGH_PASS) { + setHighPassFilterEnabled(true); + } else { + setHighPassFilterEnabled(false); + } + + I2Cdev::writeBits(devAddr, L3GD20H_RA_CTRL5, L3GD20H_OUT_SEL_BIT, + L3GD20H_OUT_SEL_LENGTH, filter); + I2Cdev::writeBits(devAddr, L3GD20H_RA_CTRL5, L3GD20H_IG_SEL_BIT, + L3GD20H_IG_SEL_LENGTH, filter); +} + +/** Gets the data filter currently in use + * @return Defined value that represents the filter in use + * @see L3GD20H_RA_CTRL5 + * @see L3GD20H_OUT_SEL_BIT + * @see L3GD20H_OUT_SEL_LENGTH + * @see L3GD20H_NON_HIGH_PASS + * @see L3GD20H_HIGH_PASS + * @see L3GD20H_LOW_PASS + * @see L3GD20H_LOW_HIGH_PASS + */ +uint8_t L3GD20H::getDataFilter() { + I2Cdev::readBits(devAddr, L3GD20H_RA_CTRL5, L3GD20H_OUT_SEL_BIT, + L3GD20H_OUT_SEL_LENGTH, buffer); + uint8_t outBits = buffer[0]; + + if (outBits == L3GD20H_NON_HIGH_PASS || outBits == L3GD20H_HIGH_PASS) { + return outBits; + } + + if (getHighPassFilterEnabled()) { + return L3GD20H_LOW_HIGH_PASS; + } else { + return L3GD20H_LOW_PASS; + } +} + +//ToDo: +//setInterruptFilter +//getInterruptFilter + +// REFERENCE register, r/w + +/** Set the reference value for the high pass filter + * @param reference New 8-bit digital high pass filter reference value + * @see L3GD20H_RA_REFERENCE + */ +void L3GD20H::setHighPassFilterReference(uint8_t reference) { + I2Cdev::writeByte(devAddr, L3GD20H_RA_REFERENCE, reference); +} + +/** Get the 8-bit reference value for the high pass filter + * @return 8-bit reference value for the high pass filter + * @see L3GD20H_RA_REFERENCE + */ +uint8_t L3GD20H::getHighPassFilterReference() { + I2Cdev::readByte(devAddr, L3GD20H_RA_REFERENCE, buffer); + return buffer[0]; +} + +// void L3GD20H::setInterruptReference(uint8_t reference) { +// I2Cdev::writeByte(devAddr, L3GD20H_RA_REFERENCE, reference); +// } + +// uint8_t L3GD20H::getInterruptReference() { +// I2Cdev::readByte(devAddr, L3GD20H_RA_REFERENCE, buffer); +// return buffer[0]; +// } + +// OUT_TEMP register, read-only + +/** Gets the current temperature reading from the sensor + * @return Current temperature + * @see L3GD20H_RA_OUT_TEMP + */ +uint8_t L3GD20H::getTemperature() { + I2Cdev::readByte(devAddr, L3GD20H_RA_OUT_TEMP, buffer); + return buffer[0]; +} + +// STATUS register, read-only + +/** Get whether new data overwrote the last set of data before it was read + * @return True if the last set of data was overwritten before being read, false + * otherwise + * @see L3GD20H_RA_STATUS + * @see L3GD20H_ZYXOR_BIT + */ +bool L3GD20H::getXYZOverrun() { + I2Cdev::readBit(devAddr, L3GD20H_RA_STATUS, L3GD20H_ZYXOR_BIT, + buffer); + return buffer[0]; +} + +/** Get whether new Z data overwrote the last set of data before it was read + * @return True if the last set of Z data was overwritten before being read, + * false otherwise + * @see L3GD20H_RA_STATUS + * @see L3GD20H_ZOR_BIT + */ +bool L3GD20H::getZOverrun() { + I2Cdev::readBit(devAddr, L3GD20H_RA_STATUS, L3GD20H_ZOR_BIT, + buffer); + return buffer[0]; +} + +/** Get whether new Y data overwrote the last set of data before it was read + * @return True if the last set of Y data was overwritten before being read, + * false otherwise + * @see L3GD20H_RA_STATUS + * @see L3GD20H_YOR_BIT + */ +bool L3GD20H::getYOverrun() { + I2Cdev::readBit(devAddr, L3GD20H_RA_STATUS, L3GD20H_YOR_BIT, + buffer); + return buffer[0]; +} + +/** Get whether new X data overwrote the last set of data before it was read + * @return True if the last set of X data was overwritten before being read, + * false otherwise + * @see L3GD20H_RA_STATUS + * @see L3GD20H_XOR_BIT + */ +bool L3GD20H::getXOverrun() { + I2Cdev::readBit(devAddr, L3GD20H_RA_STATUS, L3GD20H_XOR_BIT, + buffer); + return buffer[0]; +} + +/** Get whether there is new data avaialable + * @return True if there is new data available, false otherwise + * @see L3GD20H_RA_STATUS + * @see L3GD20H_ZYXDA_BIT + */ +bool L3GD20H::getXYZDataAvailable() { + I2Cdev::readBit(devAddr, L3GD20H_RA_STATUS, L3GD20H_ZYXDA_BIT, + buffer); + return buffer[0]; +} + +/** Get whether there is new Z data avaialable + * @return True if there is new Z data available, false otherwise + * @see L3GD20H_RA_STATUS + * @see L3GD20H_ZDA_BIT + */ +bool L3GD20H::getZDataAvailable() { + I2Cdev::readBit(devAddr, L3GD20H_RA_STATUS, L3GD20H_ZDA_BIT, + buffer); + return buffer[0]; +} + +/** Get whether there is new Y data avaialable + * @return True if there is new Y data available, false otherwise + * @see L3GD20H_RA_STATUS + * @see L3GD20H_YDA_BIT + */ +bool L3GD20H::getYDataAvailable() { + I2Cdev::readBit(devAddr, L3GD20H_RA_STATUS, L3GD20H_YDA_BIT, + buffer); + return buffer[0]; +} + +/** Get whether there is new X data avaialable + * @return True if there is new X data available, false otherwise + * @see L3GD20H_RA_STATUS + * @see L3GD20H_XDA_BIT + */ +bool L3GD20H::getXDataAvailable() { + I2Cdev::readBit(devAddr, L3GD20H_RA_STATUS, L3GD20H_XDA_BIT, + buffer); + return buffer[0]; +} + +// OUT_* registers, read-only + +/** Get the angular velocity for all 3 axes + * Due to the fact that this device supports two difference Endian modes, both + * must be accounted for when reading data. In Little Endian mode, the first + * byte (lowest address) is the least significant and in Big Endian mode the + * first byte is the most significant. + * @param x 16-bit integer container for the X-axis angular velocity + * @param y 16-bit integer container for the Y-axis angular velocity + * @param z 16-bit integer container for the Z-axis angular velocity + */ +void L3GD20H::getAngularVelocity(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, L3GD20H_RA_OUT_X_L | 0x80, 6, buffer); + if (endianMode == L3GD20H_LITTLE_ENDIAN) { + *x = (((int16_t)buffer[1]) << 8) | buffer[0]; + *y = (((int16_t)buffer[3]) << 8) | buffer[2]; + *z = (((int16_t)buffer[5]) << 8) | buffer[4]; + } else { + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; + } +} + +/** Get the angular velocity about the X-axis + * @return Angular velocity about the X-axis + * @see L3GD20H_RA_OUT_X_L + * @see L3GD20H_RA_OUT_X_H + */ +int16_t L3GD20H::getAngularVelocityX() { + I2Cdev::readBytes(devAddr, L3GD20H_RA_OUT_X_L | 0x80, 2, buffer); + if (endianMode == L3GD20H_LITTLE_ENDIAN) { + return (((int16_t)buffer[1]) << 8) | buffer[0]; + } else { + return (((int16_t)buffer[0]) << 8) | buffer[1]; + } +} + +/** Get the angular velocity about the Y-axis + * @return Angular velocity about the Y-axis + * @see L3GD20H_RA_OUT_Y_L + * @see L3GD20H_RA_OUT_Y_H + */ +int16_t L3GD20H::getAngularVelocityY() { + I2Cdev::readBytes(devAddr, L3GD20H_RA_OUT_Y_L | 0x80, 2, buffer); + if (endianMode == L3GD20H_LITTLE_ENDIAN) { + return (((int16_t)buffer[1]) << 8) | buffer[0]; + } else { + return (((int16_t)buffer[0]) << 8) | buffer[1]; + } +} + +/** Get the angular velocity about the Z-axis + * @return Angular velocity about the Z-axis + * @see L3GD20H_RA_OUT_Z_L + * @see L3GD20H_RA_OUT_Z_H + */ +int16_t L3GD20H::getAngularVelocityZ() { + I2Cdev::readBytes(devAddr, L3GD20H_RA_OUT_Z_L | 0x80, 2, buffer); + if (endianMode == L3GD20H_LITTLE_ENDIAN) { + return (((int16_t)buffer[1]) << 8) | buffer[0]; + } else { + return (((int16_t)buffer[0]) << 8) | buffer[1]; + } +} + +// FIFO_CTRL register, r/w + +/** Set the FIFO mode to one of the defined modes + * @param mode New FIFO mode + * @see L3GD20H_RA_FIFO_CTRL + * @see L3GD20H_FIFO_MODE_BIT + * @see L3GD20H_FIFO_MODE_LENGTH + * @see L3GD20H_FM_BYPASS + * @see L3GD20H_FM_FIFO + * @see L3GD20H_FM_STREAM + * @see L3GD20H_FM_STREAM_FIFO + * @see L3GD20H_FM_BYPASS_STREAM + * @see L3GD20H_FM_DYNAMIC_STREAM + * @see L3GD20H_FM_BYPASS_FIFO + */ +void L3GD20H::setFIFOMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, L3GD20H_RA_FIFO_CTRL, L3GD20H_FIFO_MODE_BIT, + L3GD20H_FIFO_MODE_LENGTH, mode); +} + +/** Get the FIFO mode to one of the defined modes + * @return Current FIFO mode + * @see L3GD20H_RA_FIFO_CTRL + * @see L3GD20H_FIFO_MODE_BIT + * @see L3GD20H_FIFO_MODE_LENGTH + * @see L3GD20H_FM_BYPASS + * @see L3GD20H_FM_FIFO + * @see L3GD20H_FM_STREAM + * @see L3GD20H_FM_STREAM_FIFO + * @see L3GD20H_FM_BYPASS_STREAM + * @see L3GD20H_FM_DYNAMIC_STREAM + * @see L3GD20H_FM_BYPASS_FIFO + */ +uint8_t L3GD20H::getFIFOMode() { + I2Cdev::readBits(devAddr, L3GD20H_RA_FIFO_CTRL, + L3GD20H_FIFO_MODE_BIT, L3GD20H_FIFO_MODE_LENGTH, buffer); + return buffer[0]; +} + +/** Set the 5-bit FIFO (watermark) threshold + * @param fth New 5-bit FIFO (watermark) threshold + * @see L3GD20H_RA_FIFO_CTRL + * @see L3GD20H_FIFO_TH_BIT + * @see L3GD20H_FIFO_TH_LENGTH + */ +void L3GD20H::setFIFOThreshold(uint8_t fth) { + I2Cdev::writeBits(devAddr, L3GD20H_RA_FIFO_CTRL, L3GD20H_FIFO_TH_BIT, + L3GD20H_FIFO_TH_LENGTH, fth); +} + +/** Get the FIFO watermark threshold + * @return FIFO watermark threshold + * @see L3GD20H_RA_FIFO_CTRL + * @see L3GD20H_FIFO_TH_BIT + * @see L3GD20H_FIFO_TH_LENGTH + */ +uint8_t L3GD20H::getFIFOThreshold() { + I2Cdev::readBits(devAddr, L3GD20H_RA_FIFO_CTRL, L3GD20H_FIFO_TH_BIT, + L3GD20H_FIFO_TH_LENGTH, buffer); + return buffer[0]; +} + +// FIFO_SRC register, read-only + +/** Get whether the number of data sets in the FIFO buffer is less than the + * watermark + * @return True if the number of data sets in the FIFO buffer is more than or + * equal to the watermark, false otherwise. + * @see L3GD20H_RA_FIFO_SRC + * @see L3GD20H_FIFO_TH_STATUS_BIT + */ +bool L3GD20H::getFIFOAtWatermark() { + I2Cdev::readBit(devAddr, L3GD20H_RA_FIFO_SRC, L3GD20H_FIFO_TH_STATUS_BIT, + buffer); + return buffer[0]; +} + +/** Get whether the FIFO buffer is full + * @return True if the FIFO buffer is full, false otherwise + * @see L3GD20H_RA_FIFO_SRC + * @see L3GD20H_FIFO_OVRN_BIT + */ +bool L3GD20H::getFIFOOverrun() { + I2Cdev::readBit(devAddr, L3GD20H_RA_FIFO_SRC, + L3GD20H_OVRN_BIT, buffer); + return buffer[0]; +} + +/** Get whether the FIFO buffer is empty + * @return True if the FIFO buffer is empty, false otherwise + * @see L3GD20H_RA_FIFO_SRC + * @see L3GD20H_FIFO_EMPTY_BIT + */ +bool L3GD20H::getFIFOEmpty() { + I2Cdev::readBit(devAddr, L3GD20H_RA_FIFO_SRC, + L3GD20H_EMPTY_BIT, buffer); + return buffer[0]; +} + +/** Get the number of filled FIFO buffer slots + * @return Number of filled slots in the FIFO buffer + * @see L3GD20H_RA_FIFO_SRC + * @see L3GD20H_FIFO_FSS_BIT + * @see L3GD20H_FIFO_FSS_LENGTH + */ +uint8_t L3GD20H::getFIFOStoredDataLevel() { + I2Cdev::readBits(devAddr, L3GD20H_RA_FIFO_SRC, + L3GD20H_FIFO_FSS_BIT, L3GD20H_FIFO_FSS_LENGTH, buffer); + return buffer[0]; +} + +// IG_CFG register, r/w + +/** Set the combination mode for interrupt events + * @param combination New combination mode for interrupt events. + * L3GD20H_AND_OR_OR for OR and L3GD20H_AND_OR_AND for AND + * @see L3GD20H_RA_IG_CFG + * @see L3GD20H_AND_OR_BIT + * @see L3GD20H_AND_OR_OR + * @see L3GD20H_AND_OR_AND + */ +void L3GD20H::setInterruptCombination(bool combination) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_AND_OR_BIT, + combination); +} + +/** Get the combination mode for interrupt events + * @return Combination mode for interrupt events. L3GD20H_AND_OR_OR for OR and + * L3GD20H_AND_OR_AND for AND + * @see L3GD20H_RA_IG_CFG + * @see L3GD20H_AND_OR_BIT + * @see L3GD20H_AND_OR_OR + * @see L3GD20H_AND_OR_AND + */ +bool L3GD20H::getInterruptCombination() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_AND_OR_BIT, + buffer); + return buffer[0]; +} + +/** Set whether an interrupt request is latched + * This bit is cleared when the IG_SRC register is read + * @param latched New status of the latched request + * @see L3GD20H_RA_IG_CFG + * @see L3GD20H_LIR_BIT + */ +void L3GD20H::setInterruptRequestLatched(bool latched) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_LIR_BIT, latched); +} + +/** Get whether an interrupt request is latched + * @return True if an interrupt request is latched, false otherwise + * @see L3GD20H_RA_IG_CFG + * @see L3GD20H_LIR_BIT + */ +bool L3GD20H::getInterruptRequestLatched() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_LIR_BIT, + buffer); + return buffer[0]; +}; + +/** Set whether the interrupt for Z high is enabled + * @param enabled New enabled state for Z high interrupt. + * @see L3GD20H_IG_CFG + * @see L3GD20H_ZHIE_BIT + */ +void L3GD20H::setZHighInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_ZHIE_BIT, enabled); +} + +/** Get whether the interrupt for Z high is enabled + * @return True if the interrupt for Z high is enabled, false otherwise + * @see L3GD20H_IG_CFG + * @see L3GD20H_ZHIE_BIT + */ +bool L3GD20H::getZHighInterruptEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_ZHIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt for Z low is enabled + * @param enabled New enabled state for Z low interrupt. + * @see L3GD20H_IG_CFG + * @see L3GD20H_ZLIE_BIT + */ +void L3GD20H::setZLowInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_ZLIE_BIT, enabled); +} + +/** Get whether the interrupt for Z low is enabled + * @return True if the interrupt for Z low is enabled, false otherwise + * @see L3GD20H_IG_CFG + * @see L3GD20H_ZLIE_BIT + */ +bool L3GD20H::getZLowInterruptEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_ZLIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt for Y high is enabled + * @param enabled New enabled state for Y high interrupt. + * @see L3GD20H_IG_CFG + * @see L3GD20H_YHIE_BIT + */ +void L3GD20H::setYHighInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_YHIE_BIT, enabled); +} + +/** Get whether the interrupt for Y high is enabled + * @return True if the interrupt for Y high is enabled, false otherwise + * @see L3GD20H_IG_CFG + * @see L3GD20H_YHIE_BIT + */ +bool L3GD20H::getYHighInterruptEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_YHIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt for Y low is enabled + * @param enabled New enabled state for Y low interrupt. + * @see L3GD20H_IG_CFG + * @see L3GD20H_YLIE_BIT + */ +void L3GD20H::setYLowInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_YLIE_BIT, enabled); +} + +/** Get whether the interrupt for Y low is enabled + * @return True if the interrupt for Y low is enabled, false otherwise + * @see L3GD20H_IG_CFG + * @see L3GD20H_YLIE_BIT + */ +bool L3GD20H::getYLowInterruptEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_YLIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt for X high is enabled + * @param enabled New enabled state for X high interrupt. + * @see L3GD20H_IG_CFG + * @see L3GD20H_XHIE_BIT + */ +void L3GD20H::setXHighInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_XHIE_BIT, enabled); +} + +/** Get whether the interrupt for X high is enabled + * @return True if the interrupt for X high is enabled, false otherwise + * @see L3GD20H_IG_CFG + * @see L3GD20H_XHIE_BIT + */ +bool L3GD20H::getXHighInterruptEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_XHIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt for X low is enabled + * @param enabled New enabled state for X low interrupt. + * @see L3GD20H_IG_CFG + * @see L3GD20H_XLIE_BIT + */ +void L3GD20H::setXLowInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_XLIE_BIT, enabled); +} + +/** Get whether the interrupt for X low is enabled + * @return True if the interrupt for X low is enabled, false otherwise + * @see L3GD20H_IG_CFG + * @see L3GD20H_XLIE_BIT + */ +bool L3GD20H::getXLowInterruptEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_CFG, L3GD20H_XLIE_BIT, + buffer); + return buffer[0]; +} + +// IG_SRC register, read-only + +/** Get whether an interrupt has been generated + * @return True if one or more interrupts has been generated, false otherwise + * @see L3GD20H_RA_IG_SRC + * @see L3GD20H_IA_BIT + */ +bool L3GD20H::getInterruptActive() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_SRC, L3GD20H_IA_BIT, + buffer); + return buffer[0]; +} + +/** Get whether a Z high event has occurred + * @return True if a Z high event has occurred, false otherwise + * @see L3GD20H_RA_IG_SRC + * @see L3GD20H_ZH_BIT + */ +bool L3GD20H::getZHigh() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_SRC, L3GD20H_ZH_BIT, + buffer); + return buffer[0]; +} + +/** Get whether a Z low event has occurred + * @return True if a Z low event has occurred, false otherwise + * @see L3GD20H_RA_IG_SRC + * @see L3GD20H_ZL_BIT + */ +bool L3GD20H::getZLow() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_SRC, L3GD20H_ZL_BIT, + buffer); + return buffer[0]; +} + +/** Get whether a Y high event has occurred + * @return True if a Y high event has occurred, false otherwise + * @see L3GD20H_RA_IG_SRC + * @see L3GD20H_YH_BIT + */ +bool L3GD20H::getYHigh() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_SRC, L3GD20H_YH_BIT, + buffer); + return buffer[0]; +} + +/** Get whether a Y low event has occurred + * @return True if a Y low event has occurred, false otherwise + * @see L3GD20H_RA_IG_SRC + * @see L3GD20H_YL_BIT + */ +bool L3GD20H::getYLow() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_SRC, L3GD20H_YL_BIT, + buffer); + return buffer[0]; +} + +/** Get whether a X high event has occurred + * @return True if a X high event has occurred, false otherwise + * @see L3GD20H_RA_IG_SRC + * @see L3GD20H_XH_BIT + */ +bool L3GD20H::getXHigh() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_SRC, L3GD20H_XH_BIT, + buffer); + return buffer[0]; +} + +/** Get whether a X low event has occurred + * @return True if a X low event has occurred, false otherwise + * @see L3GD20H_RA_IG_SRC + * @see L3GD20H_XL_BIT + */ +bool L3GD20H::getXLow() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_SRC, L3GD20H_XL_BIT, + buffer); + return buffer[0]; +} + +// IG_THS_* registers, r/w + +/** Set the interrupt generation counter mode selection. + * @param enabled New enabled state for X low interrupt. + * @see L3GD20H_IG_THS_XH + * @see L3GD20H_DCRM_BIT + * @see L3GD20H_DCRM_RESET + * @see L3GD20H_DCRM_DEC + */ +void L3GD20H::setDecrementMode(bool mode) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_IG_THS_XH, L3GD20H_DCRM_BIT, mode); +} + +/** Get the interrupt generation counter mode selection. + * @return Mode Interrupt generation counter mode + * @see L3GD20H_IG_THS_XH + * @see L3GD20H_DCRM_BIT + * @see L3GD20H_DCRM_RESET + * @see L3GD20H_DCRM_DEC + */ +bool L3GD20H::getDecrementMode() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_THS_XH, L3GD20H_DCRM_BIT, + buffer); + return buffer[0]; +} + +/** Set the 7-bit threshold for a high interrupt on the X axis + * @param threshold New 7-bit threshold for a high interrupt on the X axis + * @see L3GD20H_IG_THS_XH + */ +void L3GD20H::setXHighThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, L3GD20H_RA_IG_THS_XH, threshold); +} + +/** Retrieve the threshold for a high interrupt on the X axis + * @return X high interrupt threshold + * @see L3GD20H_IG_THS_XH + */ +uint8_t L3GD20H::getXHighThreshold() { + I2Cdev::readByte(devAddr, L3GD20H_RA_IG_THS_XH, buffer); + return buffer[0]; +} + +/** Set the 8-bit threshold for a low interrupt on the X axis + * @param threshold New 8-bit threshold for a low interrupt on the X axis + * @see L3GD20H_IG_THS_XL + */ +void L3GD20H::setXLowThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, L3GD20H_RA_IG_THS_XL, threshold); +} + +/** Retrieve the threshold for a low interrupt on the X axis + * @return X low interrupt threshold + * @see L3GD20H_IG_THS_XL + */ +uint8_t L3GD20H::getXLowThreshold() { + I2Cdev::readByte(devAddr, L3GD20H_RA_IG_THS_XL, buffer); + return buffer[0]; +} + +/** Set the 7-bit threshold for a high interrupt on the Y axis + * @param threshold New 7-bit threshold for a high interrupt on the Y axis + * @see L3GD20H_IG_THS_YH + */ +void L3GD20H::setYHighThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, L3GD20H_RA_IG_THS_YH, threshold); +} + +/** Retrieve the threshold for a high interrupt on the Y axis + * @return Y high interrupt threshold + * @see L3GD20H_IG_THS_YH + */ +uint8_t L3GD20H::getYHighThreshold() { + I2Cdev::readByte(devAddr, L3GD20H_RA_IG_THS_YH, buffer); + return buffer[0]; +} + +/** Set the 8-bit threshold for a low interrupt on the Y axis + * @param threshold New 8-bit threshold for a low interrupt on the Y axis + * @see L3GD20H_IG_THS_YL + */ +void L3GD20H::setYLowThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, L3GD20H_RA_IG_THS_YL, threshold); +} + +/** Retrieve the threshold for a low interrupt on the Y axis + * @return Y low interrupt threshold + * @see L3GD20H_IG_THS_YL + */ +uint8_t L3GD20H::getYLowThreshold() { + I2Cdev::readByte(devAddr, L3GD20H_RA_IG_THS_YL, buffer); + return buffer[0]; +} + +/** Set the 7-bit threshold for a high interrupt on the Z axis + * @param threshold New 7-bit threshold for a high interrupt on the Z axis + * @see L3GD20H_IG_THS_ZH + */ +void L3GD20H::setZHighThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, L3GD20H_RA_IG_THS_ZH, threshold); +} + +/** Retrieve the threshold for a high interrupt on the Z axis + * @return Z high interrupt threshold + * @see L3GD20H_IG_THS_ZH + */ +uint8_t L3GD20H::getZHighThreshold() { + I2Cdev::readByte(devAddr, L3GD20H_RA_IG_THS_ZH, buffer); + return buffer[0]; +} + +/** Set the 8-bit threshold for a low interrupt on the Z axis + * @param threshold New 8-bit threshold for a low interrupt on the Z axis + * @see L3GD20H_RA_IG_THS_ZL + */ +void L3GD20H::setZLowThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, L3GD20H_RA_IG_THS_ZL, threshold); +} + +/** Retrieve the threshold for a low interrupt on the Z axis + * @return Z low interrupt threshold + * @see L3GD20H_IG_THS_ZL + */ +uint8_t L3GD20H::getZLowThreshold() { + I2Cdev::readByte(devAddr, L3GD20H_RA_IG_THS_ZL, buffer); + return buffer[0]; +} + +// IG_DURATION register, r/w + +/* Set the minimum duration for an interrupt event to be recognized + * This depends on the chosen output data rate + * @param duration New 7-bit duration value necessary for an interrupt event to be + * recognized + * @see L3GD20H_RA_IG_DURATION + * @see L3GD20H_DUR_BIT + * @see L3GD20H_DUR_LENGTH + */ +void L3GD20H::setDuration(uint8_t duration) { + I2Cdev::writeBits(devAddr, L3GD20H_RA_IG_DURATION, L3GD20H_DUR_BIT, + L3GD20H_DUR_LENGTH, duration); +} + +/** Get the minimum duration for an interrupt event to be recognized + * @return Duration value necessary for an interrupt event to be recognized + * @see L3GD20H_RA_IG_DURATION + * @see L3GD20H_DUR_BIT + * @see L3GD20H_DUR_LENGTH + */ +uint8_t L3GD20H::getDuration() { + I2Cdev::readBits(devAddr, L3GD20H_RA_IG_DURATION, + L3GD20H_DUR_BIT, L3GD20H_DUR_LENGTH, buffer); + return buffer[0]; +} + +/** Set whether the interrupt wait feature is enabled + * If false, the interrupt falls immediately if signal crosses the selected + * threshold. Otherwise, if signal crosses the selected threshold, the interrupt + * falls only after the duration has counted number of samples at the selected + * data rate, written into the duration counter register. + * @param enabled New enabled state of the interrupt wait + * @see L3GD20H_RA_IG_DURATION + * @see L3GD20H_WAIT_BIT + */ +void L3GD20H::setWaitEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, L3GD20H_RA_IG_DURATION, L3GD20H_WAIT_BIT, + enabled); +} + +/** Get whether the interrupt wait feature is enabled + * @return True if the wait feature is enabled, false otherwise + * @see L3GD20H_RA_IG_DURATION + * @see L3GD20H_WAIT_BIT + */ +bool L3GD20H::getWaitEnabled() { + I2Cdev::readBit(devAddr, L3GD20H_RA_IG_DURATION, + L3GD20H_WAIT_BIT, buffer); + return buffer[0]; +} + +// LOW_ODR register, r/w + +/** Set whether the DRDY/INT2 pin is active low. If enabled is true then the + * DRDY/INT2 pin will be active low. + * @param enabled New enabled DRDY/INT2 active low configuration + * @see L3GD20H_RA_LOW_ODR + * @see L3GD20H_DRDY_HL_BIT + */ +void L3GD20H::setINT2DataReadyActiveLowEnabled(bool enabled){ + I2Cdev::writeBit(devAddr, L3GD20H_RA_LOW_ODR, L3GD20H_DRDY_HL_BIT, + enabled); +} + +/** Get whether the DRDY/INT2 pin is active low. If true then the + * DRDY/INT2 pin IS active low. + * @see L3GD20H_RA_LOW_ODR + * @see L3GD20H_I2C_DIS_BIT + */ +bool L3GD20H::getINT2DataReadyActiveLowEnabled(){ + I2Cdev::readBit(devAddr, L3GD20H_RA_LOW_ODR, + L3GD20H_DRDY_HL_BIT, buffer); + return buffer[0]; +} + +/** Set whether only the SPI interface is enabled (i.e., I2C interface disabled) + * @param enabled New SPI interface only enabled + * @see L3GD20H_RA_LOW_ODR + * @see L3GD20H_I2C_DIS_BIT + */ +void L3GD20H::setSPIOnlyEnabled(bool enabled){ + I2Cdev::writeBit(devAddr, L3GD20H_RA_LOW_ODR, L3GD20H_I2C_DIS_BIT, + enabled); +} + +/** Get whether only the SPI interface is enabled (i.e., I2C interface disabled) + * @see L3GD20H_RA_LOW_ODR + * @see L3GD20H_I2C_DIS_BIT + */ +bool L3GD20H::getSPIOnlyEnabled(){ + I2Cdev::readBit(devAddr, L3GD20H_RA_LOW_ODR, + L3GD20H_I2C_DIS_BIT, buffer); + return buffer[0]; +} + +/** Reset the device. Sets a software reset flag which is auto cleared upon boot. + * @param reset Value that resets the device if true + * @see L3GD20H_RA_LOW_ODR + * @see L3GD20H_SW_RESET_BIT + */ +void L3GD20H::setSoftwareReset(bool reset){ + I2Cdev::writeBit(devAddr, L3GD20H_RA_LOW_ODR, L3GD20H_SW_RESET_BIT, + reset); +} + +/** Set whether the low output data rate is enabled. + * @param enabled New low output data rate enabled + * @see L3GD20H_RA_LOW_ODR + * @see L3GD20H_LOW_ODR_BIT + */ +void L3GD20H::setLowODREnabled(bool enabled){ + I2Cdev::writeBit(devAddr, L3GD20H_RA_LOW_ODR, L3GD20H_LOW_ODR_BIT, + enabled); +} + +/** Get whether the low output data rate is enabled. + * @see L3GD20H_RA_LOW_ODR + * @see L3GD20H_LOW_ODR_BIT + */ +bool L3GD20H::getLowODREnabled(){ + I2Cdev::readBit(devAddr, L3GD20H_RA_LOW_ODR, + L3GD20H_LOW_ODR_BIT, buffer); + return buffer[0]; +} diff --git a/libraries/L3GD20H/L3GD20H.h b/libraries/L3GD20H/L3GD20H.h new file mode 100644 index 0000000..329890e --- /dev/null +++ b/libraries/L3GD20H/L3GD20H.h @@ -0,0 +1,398 @@ +// I2Cdev library collection - L3GD20H I2C device class header file +// Based on STMicroelectronics L3GD20H datasheet rev. 2, 3/2013 +// 3/05/2015 by Nate Costello +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2015-03-05 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Jonathan Arnett, 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 _L3GD20H_H_ +#define _L3GD20H_H_ + +#include "I2Cdev.h" + +#define L3GD20H_ADDRESS 0x6B // I think this is correct. See SAD in doc. +#define L3GD20H_DEFAULT_ADDRESS 0x6B // I think this is correct. See SAD in doc. + +#define L3GD20H_RA_WHO_AM_I 0x0F +#define L3GD20H_RA_CTRL1 0x20 +#define L3GD20H_RA_CTRL2 0x21 +#define L3GD20H_RA_CTRL3 0x22 +#define L3GD20H_RA_CTRL4 0x23 +#define L3GD20H_RA_CTRL5 0x24 +#define L3GD20H_RA_REFERENCE 0x25 +#define L3GD20H_RA_OUT_TEMP 0x26 +#define L3GD20H_RA_STATUS 0x27 +#define L3GD20H_RA_OUT_X_L 0x28 +#define L3GD20H_RA_OUT_X_H 0x29 +#define L3GD20H_RA_OUT_Y_L 0x2A +#define L3GD20H_RA_OUT_Y_H 0x2B +#define L3GD20H_RA_OUT_Z_L 0x2C +#define L3GD20H_RA_OUT_Z_H 0x2D +#define L3GD20H_RA_FIFO_CTRL 0x2E +#define L3GD20H_RA_FIFO_SRC 0x2F +#define L3GD20H_RA_IG_CFG 0x30 +#define L3GD20H_RA_IG_SRC 0x31 +#define L3GD20H_RA_IG_THS_XH 0x32 +#define L3GD20H_RA_IG_THS_XL 0X33 +#define L3GD20H_RA_IG_THS_YH 0X34 +#define L3GD20H_RA_IG_THS_YL 0x35 +#define L3GD20H_RA_IG_THS_ZH 0X36 +#define L3GD20H_RA_IG_THS_ZL 0x37 +#define L3GD20H_RA_IG_DURATION 0X38 +#define L3GD20H_RA_LOW_ODR 0x39 + +#define L3GD20H_ODR_BIT 7 +#define L3GD20H_ODR_LENGTH 2 +#define L3GD20H_BW_BIT 5 +#define L3GD20H_BW_LENGTH 2 +#define L3GD20H_PD_BIT 3 +#define L3GD20H_ZEN_BIT 2 +#define L3GD20H_YEN_BIT 1 +#define L3GD20H_XEN_BIT 0 + +#define L3GD20H_RATE_100_12 0b00 //selection of high vs low rate is via Low_ODR +#define L3GD20H_RATE_200_25 0b01 //selection of high vs low rate is via Low_ODR +#define L3GD20H_RATE_400_50 0b10 //selection of high vs low rate is via Low_ODR +#define L3GD20H_RATE_800_50 0b11 //selection of high vs low rate is via Low_ODR + +#define L3GD20H_BW_LOW 0b00 +#define L3GD20H_BW_MED_LOW 0b01 +#define L3GD20H_BW_MED_HIGH 0b10 +#define L3GD20H_BW_HIGH 0b11 + +#define L3GD20H_HPM_BIT 5 +#define L3GD20H_HPM_LENGTH 2 +#define L3GD20H_HPCF_BIT 3 +#define L3GD20H_HPCF_LENGTH 4 + +#define L3GD20H_HPM_HRF 0b00 //this resets on reading REFERENCE +#define L3GD20H_HPM_REFERENCE 0b01 +#define L3GD20H_HPM_NORMAL 0b10 +#define L3GD20H_HPM_AUTORESET 0b11 + +#define L3GD20H_HPCF1 0b0000 +#define L3GD20H_HPCF2 0b0001 +#define L3GD20H_HPCF3 0b0010 +#define L3GD20H_HPCF4 0b0011 +#define L3GD20H_HPCF5 0b0100 +#define L3GD20H_HPCF6 0b0101 +#define L3GD20H_HPCF7 0b0110 +#define L3GD20H_HPCF8 0b0111 +#define L3GD20H_HPCF9 0b1000 +#define L3GD20H_HPCF10 0b1001 + +#define L3GD20H_INT1_IG_BIT 7 +#define L3GD20H_INT1_BOOT_BIT 6 +#define L3GD20H_H_LACTIVE_BIT 5 +#define L3GD20H_PP_OD_BIT 4 +#define L3GD20H_INT2_DRDY_BIT 3 +#define L3GD20H_INT2_FTH_BIT 2 +#define L3GD20H_INT2_ORUN_BIT 1 +#define L3GD20H_INT2_EMPTY_BIT 0 + +#define L3GD20H_PUSH_PULL 0 +#define L3GD20H_OPEN_DRAIN 1 + +#define L3GD20H_BDU_BIT 7 +#define L3GD20H_BLE_BIT 6 +#define L3GD20H_FS_BIT 5 +#define L3GD20H_FS_LENGTH 2 +#define L3GD20H_IMPEN_BIT 3 //new for this IC: Level sensitive latched enalble +#define L3GD20H_ST_BIT 2 +#define L3GD20H_ST_LENGTH 2 +#define L3GD20H_SIM_BIT 0 + +#define L3GD20H_BIG_ENDIAN 1 +#define L3GD20H_LITTLE_ENDIAN 0 + +#define L3GD20H_FS_250 0b00 +#define L3GD20H_FS_500 0b01 +#define L3GD20H_FS_2000 0b10 + +#define L3GD20H_SELF_TEST_NORMAL 0b00 +#define L3GD20H_SELF_TEST_0 0b01 +#define L3GD20H_SELF_TEST_1 0b11 + +#define L3GD20H_SPI_4_WIRE 0 +#define L3GD20H_SPI_3_WIRE 1 + +#define L3GD20H_BOOT_BIT 7 +#define L3GD20H_FIFO_EN_BIT 6 +#define L3GD20H_STOPONFTH_BIT 5 +#define L3GD20H_HPEN_BIT 4 +#define L3GD20H_IG_SEL_BIT 3 +#define L3GD20H_IG_SEL_LENGTH 2 +#define L3GD20H_OUT_SEL_BIT 1 +#define L3GD20H_OUT_SEL_LENGTH 2 + +#define L3GD20H_NON_HIGH_PASS 0b00 +#define L3GD20H_HIGH_PASS 0b01 +#define L3GD20H_LOW_PASS 0b10 //depends on HPEN +#define L3GD20H_LOW_HIGH_PASS 0b11 //depends on HPEN + +#define L3GD20H_ZYXOR_BIT 7 +#define L3GD20H_ZOR_BIT 6 +#define L3GD20H_YOR_BIT 5 +#define L3GD20H_XOR_BIT 4 +#define L3GD20H_ZYXDA_BIT 3 +#define L3GD20H_ZDA_BIT 2 +#define L3GD20H_YDA_BIT 1 +#define L3GD20H_XDA_BIT 0 + +#define L3GD20H_FIFO_MODE_BIT 7 +#define L3GD20H_FIFO_MODE_LENGTH 3 +#define L3GD20H_FIFO_TH_BIT 4 +#define L3GD20H_FIFO_TH_LENGTH 5 + +#define L3GD20H_FM_BYPASS 0b000 +#define L3GD20H_FM_FIFO 0b001 +#define L3GD20H_FM_STREAM 0b010 +#define L3GD20H_FM_STREAM_FIFO 0b011 +#define L3GD20H_FM_BYPASS_STREAM 0b100 +#define L3GD20H_FM_DYNAMIC_STREAM 0b110 +#define L3GD20H_FM_BYPASS_FIFO 0b111 + + +#define L3GD20H_FIFO_TH_STATUS_BIT 7 +#define L3GD20H_OVRN_BIT 6 +#define L3GD20H_EMPTY_BIT 5 +#define L3GD20H_FIFO_FSS_BIT 4 +#define L3GD20H_FIFO_FSS_LENGTH 5 + +#define L3GD20H_AND_OR_BIT 7 +#define L3GD20H_LIR_BIT 6 +#define L3GD20H_ZHIE_BIT 5 +#define L3GD20H_ZLIE_BIT 4 +#define L3GD20H_YHIE_BIT 3 +#define L3GD20H_YLIE_BIT 2 +#define L3GD20H_XHIE_BIT 1 +#define L3GD20H_XLIE_BIT 0 + +#define L3GD20H_AND_OR_OR 0 +#define L3GD20H_AND_OR_AND 1 + +#define L3GD20H_IA_BIT 6 +#define L3GD20H_ZH_BIT 5 +#define L3GD20H_ZL_BIT 4 +#define L3GD20H_YH_BIT 3 +#define L3GD20H_YL_BIT 2 +#define L3GD20H_XH_BIT 1 +#define L3GD20H_XL_BIT 0 + +#define L3GD20H_DCRM_BIT 7 + +#define L3GD20H_DCRM_RESET 0 +#define L3GD20H_DCRM_DEC 1 + +#define L3GD20H_WAIT_BIT 7 +#define L3GD20H_DUR_BIT 6 +#define L3GD20H_DUR_LENGTH 7 + +#define L3GD20H_LOW_ODR_BIT 0 +#define L3GD20H_SW_RESET_BIT 2 +#define L3GD20H_I2C_DIS_BIT 3 +#define L3GD20H_DRDY_HL_BIT 5 + + + +class L3GD20H { + public: + L3GD20H(); + L3GD20H(uint8_t address); + + void initialize(); + bool testConnection(); + + // WHO_AM_I register, read-only + uint8_t getDeviceID(); + + // CTRL1 register, r/w + void setOutputDataRate(uint16_t rate); + uint16_t getOutputDataRate(); + void setBandwidthCutOffMode(uint8_t mode); + uint8_t getBandwidthCutOffMode(); + // float getBandwidthCutOff(); + void setPowerOn(bool on); + bool getPowerOn(); + void setZEnabled(bool enabled); + bool getZEnabled(); + void setYEnabled(bool enabled); + bool getYEnabled(); + void setXEnabled(bool enabled); + bool getXEnabled(); + + // CTRL2 register, r/w + void setHighPassMode(uint8_t mode); + uint8_t getHighPassMode(); + void setHighPassFilterCutOffFrequencyLevel(uint8_t level); + uint8_t getHighPassFilterCutOffFrequencyLevel(); + + // CTRL3 register, r/w + void setINT1InterruptEnabled(bool enabled); + bool getINT1InterruptEnabled(); + void setINT1BootStatusEnabled(bool enabled); + bool getINT1BootStatusEnabled(); + void interruptActiveINT1Config(); + void setOutputMode(bool mode); + bool getOutputMode(); + void setINT2DataReadyEnabled(bool enabled); + bool getINT2DataReadyEnabled(); + void setINT2FIFOWatermarkInterruptEnabled(bool enabled); + bool getINT2FIFOWatermarkInterruptEnabled(); + void setINT2FIFOOverrunInterruptEnabled(bool enabled); + bool getINT2FIFOOverrunInterruptEnabled(); + void setINT2FIFOEmptyInterruptEnabled(bool enabled); + bool getINT2FIFOEmptyInterruptEnabled(); + + // CTRL4 register, r/w + void setBlockDataUpdateEnabled(bool enabled); + bool getBlockDataUpdateEnabled(); + void setEndianMode(bool endianness); + bool getEndianMode(); + void setFullScale(uint16_t scale); + uint16_t getFullScale(); + void setSelfTestMode(uint8_t mode); + uint8_t getSelfTestMode(); + void setSPIMode(bool mode); + bool getSPIMode(); + + // CTRL5 register, r/w + void rebootMemoryContent(); + void setFIFOEnabled(bool enabled); + bool getFIFOEnabled(); + void setStopOnFIFOThresholdEnabled(bool enabled); + bool getStopOnFIFOThresholdEnabled(); + void setHighPassFilterEnabled(bool enabled); + bool getHighPassFilterEnabled(); + void setDataFilter(uint8_t filter); + uint8_t getDataFilter(); + + // REFERENCE/DATACAPTURE register, r/w + void setHighPassFilterReference(uint8_t reference); + uint8_t getHighPassFilterReference(); + + // OUT_TEMP register, read-only + uint8_t getTemperature(); + + // STATUS register, read-only + bool getXYZOverrun(); + bool getZOverrun(); + bool getYOverrun(); + bool getXOverrun(); + bool getXYZDataAvailable(); + bool getZDataAvailable(); + bool getYDataAvailable(); + bool getXDataAvailable(); + + // OUT_* registers, read-only + void getAngularVelocity(int16_t* x, int16_t* y, int16_t* z); + int16_t getAngularVelocityX(); + int16_t getAngularVelocityY(); + int16_t getAngularVelocityZ(); + + // FIFO_CTRL register, r/w + void setFIFOMode(uint8_t mode); + uint8_t getFIFOMode(); + void setFIFOThreshold(uint8_t wtm); + uint8_t getFIFOThreshold(); + + // FIFO_SRC register, read-only + bool getFIFOAtWatermark(); + bool getFIFOOverrun(); + bool getFIFOEmpty(); + uint8_t getFIFOStoredDataLevel(); + + // IG_CFG register, r/w + void setInterruptCombination(bool combination); + bool getInterruptCombination(); + void setInterruptRequestLatched(bool latched); + bool getInterruptRequestLatched(); + void setZHighInterruptEnabled(bool enabled); + bool getZHighInterruptEnabled(); + void setYHighInterruptEnabled(bool enabled); + bool getYHighInterruptEnabled(); + void setXHighInterruptEnabled(bool enabled); + bool getXHighInterruptEnabled(); + void setZLowInterruptEnabled(bool enabled); + bool getZLowInterruptEnabled(); + void setYLowInterruptEnabled(bool enabled); + bool getYLowInterruptEnabled(); + void setXLowInterruptEnabled(bool enabled); + bool getXLowInterruptEnabled(); + + // IG_SRC register, read-only + bool getInterruptActive(); + bool getZHigh(); + bool getZLow(); + bool getYHigh(); + bool getYLow(); + bool getXHigh(); + bool getXLow(); + + // IG_THS_* registers, r/w + void setDecrementMode(bool mode); + bool getDecrementMode(); + void setXHighThreshold(uint8_t threshold); + uint8_t getXHighThreshold(); + void setXLowThreshold(uint8_t threshold); + uint8_t getXLowThreshold(); + void setYHighThreshold(uint8_t threshold); + uint8_t getYHighThreshold(); + void setYLowThreshold(uint8_t threshold); + uint8_t getYLowThreshold(); + void setZHighThreshold(uint8_t threshold); + uint8_t getZHighThreshold(); + void setZLowThreshold(uint8_t threshold); + uint8_t getZLowThreshold(); + + // IG_DURATION register, r/w + void setDuration(uint8_t duration); + uint8_t getDuration(); + void setWaitEnabled(bool enabled); + bool getWaitEnabled(); + + // LOW_ODR register, r/w + void setINT2DataReadyActiveLowEnabled(bool enabled); + bool getINT2DataReadyActiveLowEnabled(); + void setSPIOnlyEnabled(bool enabled); + bool getSPIOnlyEnabled(); + void setSoftwareReset(bool reset); + void setLowODREnabled(bool enabled); + bool getLowODREnabled(); + + + + + + private: + uint8_t devAddr; + uint8_t buffer[6]; + bool endianMode; +}; + +#endif /* _L3GD20H_H_ */ diff --git a/libraries/L3GD20H/examples/L3GD20H_basic/L3GD20H_basic.ino b/libraries/L3GD20H/examples/L3GD20H_basic/L3GD20H_basic.ino new file mode 100644 index 0000000..8295349 --- /dev/null +++ b/libraries/L3GD20H/examples/L3GD20H_basic/L3GD20H_basic.ino @@ -0,0 +1,122 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for L3GD20H class +// 3/05/2015 by Nate Costello +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2015-03-05 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Jonathan Arnett, 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 + +// I2Cdev and L3GD20H must be installed as libraries, or else the .cpp/.h files +// for both classes must be in the include path of your project +#include +#include + +// specific I2C address may be passed here +L3GD20H gyro; + +int16_t avx, avy, avz; + +#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 + Serial.begin(9600); + + // initialize device + Serial.println("Initializing I2C devices..."); + gyro.initialize(); + + // verify connection + Serial.println("Testing device connections..."); + Serial.println(gyro.testConnection() ? "L3GD20H connection successful" : "L3GD20H connection failed"); + + //test endian functions + gyro.setEndianMode(not gyro.getEndianMode()); + Serial.print("EndianMode: "); + Serial.print(gyro.getEndianMode()); + gyro.setEndianMode(not gyro.getEndianMode()); + Serial.print(" EndianMode: "); + Serial.println(gyro.getEndianMode()); + + + // configure LED for output + pinMode(LED_PIN, OUTPUT); + + // set scale to 250 + gyro.setFullScale(250); + +} + +void loop() { + // read raw angular velocity measurements from device + gyro.getAngularVelocity(&avx, &avy, &avz); + // int16_t x_single = gyro.getAngularVelocityX(); + // int16_t y_single = gyro.getAngularVelocityY(); + + // //read X memory address directly + // uint8_t xval_l, xval_h; + // uint8_t devAddress = 0x6B; + // uint8_t regAddXL = 0x28; + // uint8_t regAddXH = 0x29; + // I2Cdev::readByte(devAddress, regAddXL, &xval_l); + // I2Cdev::readByte(devAddress, regAddXH, &xval_h); + // //read X memory addresses in single sequential + // uint8_t data[2]; + // I2Cdev::readBytes(devAddress, regAddXL| 0x80, 2, data); + + + // Serial.print("Direct Mem Read: Xl: "); + // Serial.print(xval_l); Serial.print("\tXh: "); + // Serial.print(xval_h); Serial.print("\t"); + // Serial.print("Direct readBytes data[0] data[1]: "); + // Serial.print(data[0]); Serial.print("\t"); + // Serial.print(data[1]); Serial.print("\t"); + // Serial.print("Bitshifted: "); Serial.print((((int16_t)data[1]) << 8) | data[0]); + Serial.print("angular velocity (dps):\t"); + Serial.print(avx*0.00875F,DEC); Serial.print("\t"); + Serial.print(avy*0.00875F,DEC); Serial.print("\t"); + Serial.print(avz*0.00875F,DEC); Serial.print("\t"); + // Serial.print(" x read only: "); Serial.print(x_single); + // Serial.print(" y read only: "); Serial.println(y_single); + Serial.println(); + + // blink LED to indicate activity + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); + + + +} + + diff --git a/libraries/LM73/LM73.cpp b/libraries/LM73/LM73.cpp new file mode 100644 index 0000000..e41f5ae --- /dev/null +++ b/libraries/LM73/LM73.cpp @@ -0,0 +1,68 @@ +// LM73 I2C class +// Based on Texas Instruments datasheet http://www.ti.com/lit/ds/symlink/lm73.pdf +// Note that this is a bare-bones driver and does not support all of the features +// of the LM73. I only added what I needed. +// 12/03/2012 Abe Erdos (abe@erdosmiller.com) + +#include "LM73.h" + +LM73::LM73() { + devAddr = LM73_DEFAULT_ADDRESS; + devConfig.all = 0x40; // reset state + devCtrlStat.all = 0x08; // reset state +} + +LM73::LM73(uint8_t address) { + devAddr = address; + devConfig.all = 0x40; // reset state + devCtrlStat.all = 0x08; // reset state +} + +void LM73::initialize() { + // there's nothing to do, really +} + +bool LM73::testConnection() { + uint16_t buf; + I2Cdev::readWord(devAddr, LM73_RA_ID, &buf); + return buf == 0x0190; +} + +LM73ConfigReg LM73::getConfig() { + I2Cdev::readByte(devAddr, LM73_RA_CONFIG, buffer); + devConfig.all = buffer[0]; + return devConfig; +} + +LM73CtrlStatReg LM73::getCtrlStat() { + I2Cdev::readByte(devAddr, LM73_RA_CTRL_STAT, buffer); + devCtrlStat.all = buffer[0]; + return devCtrlStat; +} + +void LM73::setCtrlStat(LM73CtrlStatReg value) { + I2Cdev::writeByte(devAddr, LM73_RA_CTRL_STAT, value.all); +} + +uint8_t LM73::getResolution() { + LM73::getCtrlStat(); + return devCtrlStat.bit.RES + 11; +} + +float LM73::getTemp() { + uint16_t buf; + int16_t temp; + I2Cdev::readWord(devAddr, LM73_RA_TEMP, &buf); + temp = buf; + temp = (temp>>2); + return 0.03125f * (float)temp; +} + +void LM73::setResolution(uint8_t resolution) { + if(10 < resolution && resolution < 15) { + LM73::getCtrlStat(); + devCtrlStat.bit.RES = resolution - 11; + LM73::setCtrlStat(devCtrlStat); + } +} + diff --git a/libraries/LM73/LM73.h b/libraries/LM73/LM73.h new file mode 100644 index 0000000..3849629 --- /dev/null +++ b/libraries/LM73/LM73.h @@ -0,0 +1,81 @@ +// LM73 I2C class +// Based on Texas Instruments datasheet http://www.ti.com/lit/ds/symlink/lm73.pdf +// Note that this is a bare-bones driver and does not support all of the features +// of the LM73. I only added what I needed. +// 12/03/2012 Abe Erdos (abe@erdosmiller.com) + +#ifndef _LM73_H_ +#define _LM73_H_ + +#include "I2Cdev.h" + +// LM73-0 +#define LM73_0_ADDRESS_ADDR_FLT 0x48 // address pin is floating +#define LM73_0_ADDRESS_ADDR_GND 0x49 // address pin low (GND) +#define LM73_0_ADDRESS_ADDR_VDD 0x4A // address pin high (VDD) +#define LM73_1_ADDRESS_ADDR_FLT 0x4C // address pin if floating +#define LM73_1_ADDRESS_ADDR_GND 0x4D // address pin low (GND) +#define LM73_1_ADDRESS_ADDR_VDD 0x4E // address pin high (VDD) +#define LM73_DEFAULT_ADDRESS LM73_0_ADDRESS_ADDR_FLT + +#define LM73_RA_TEMP 0x00 +#define LM73_RA_CONFIG 0x01 +#define LM73_RA_HI_THRESH 0x02 +#define LM73_RA_LO_THRESH 0x03 +#define LM73_RA_CTRL_STAT 0x04 +#define LM73_RA_ID 0x07 + +typedef struct { + unsigned :2; // reserved + unsigned ONE_SHOT:1; // one shot (write 1 to start a conversion when PD == 1) + unsigned ALRT_RST:1; // alert reset (write 1 to reset, always reads 0) + unsigned ALRT_POL:1; // alert polarity (1 == active high, 0 == active low0 + unsigned nALRT_EN:1; // alert enable (0 == alert enabled) + unsigned :1; // reserved + unsigned PD:1; // power down bit (0 == enabled) +} LM73ConfigBits; + +typedef union { + LM73ConfigBits bit; + uint8_t all; +} LM73ConfigReg; + +typedef struct { + unsigned DAV:1; // data available flag + unsigned TLOW:1; // temperature low flag + unsigned THI:1; // temperature high flag + unsigned ALRT_STAT:1; // alert pin status + unsigned :1; // reserved + unsigned RES:2; // resolution (00 == 11 bit res, 11 == 14 bit res) + unsigned TO_DIS:1; // SMB timeout disable +} LM73CtrlStatBits; + +typedef union { + LM73CtrlStatBits bit; + uint8_t all; +} LM73CtrlStatReg; + +class LM73 { + public: + LM73(); + LM73(uint8_t address); + + void initialize(); + bool testConnection(); + + LM73ConfigReg getConfig(); + void setConfig(LM73ConfigReg value); + LM73CtrlStatReg getCtrlStat(); + void setCtrlStat(LM73CtrlStatReg value); + uint8_t getResolution(); // returns resolution in bits (including sign bit) + void setResolution(uint8_t resolution); // enter resolution in bits (including sign bit) + float getTemp(); // return temperature in C + + private: + uint8_t devAddr; + uint8_t buffer[1]; + LM73ConfigReg devConfig; + LM73CtrlStatReg devCtrlStat; +}; + +#endif diff --git a/libraries/LM73/library.json b/libraries/LM73/library.json new file mode 100644 index 0000000..f547a77 --- /dev/null +++ b/libraries/LM73/library.json @@ -0,0 +1,18 @@ +{ + "name": "I2Cdevlib-LM73", + "keywords": "temperature, sensor, i2cdevlib, i2c", + "description": "The LM73 is an integrated, digital-output temperature sensor featuring an incremental Delta-Sigma ADC", + "include": "Arduino/LM73", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "dependencies": + { + "name": "I2Cdevlib-Core", + "frameworks": "arduino" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/LSM303DLHC/LSM303DLHC.cpp b/libraries/LSM303DLHC/LSM303DLHC.cpp new file mode 100644 index 0000000..26e121c --- /dev/null +++ b/libraries/LSM303DLHC/LSM303DLHC.cpp @@ -0,0 +1,2149 @@ +// I2Cdev library collection - LSM303DLHC I2C device class +// Based on ST LSM303DLHC datasheet, REV 2, 11/2013 +// [current release date] by Nate Costello +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2015-03-10 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 [Author Name], 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 "LSM303DLHC.h" + +/** Default constructor, uses default I2C address. + * @see LSM303DLHC_DEFAULT_ADDRESS_A + * @see LSM303DLHC_DEFAULT_ADDRESS_M + */ +LSM303DLHC::LSM303DLHC() { + devAddrA = LSM303DLHC_DEFAULT_ADDRESS_A; + devAddrM = LSM303DLHC_DEFAULT_ADDRESS_M; + endianMode = 0; +} + +/** Specific address constructor. +@param addressA I2C accelerometer address +@param addressM I2C magnetometer address +@see LSM303DLHC_DEFAULT_ADDRESS_A +@see LSM303DLHC_DEFAULT_ADDRESS_M +@see LSM303DLHC_ADDRESS_A +@see LSM303DLHC_ADDRESS_M + */ +LSM303DLHC::LSM303DLHC(uint8_t addressA, uint8_t addressM) { + devAddrA = addressA; + devAddrM = addressM; + endianMode = 0; +} + +/** Power on and prepare for general usage. +All values are defaults except for the data rates for the accelerometer and +magnetometer data rates (200hz and 220hz respectively). +@see LSM303DLHC_RA_CTRL_REG1_A +@see LSM303DLHC_RA_CRA_REG_M +*/ +void LSM303DLHC::initialize() { + I2Cdev::writeByte(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, 0b01100111); + I2Cdev::writeByte(devAddrM, LSM303DLHC_RA_CRA_REG_M, 0b00011100); + // ---------------------------------------------------------------------------- + // STUB TODO: + // Perform any important initialization here. Maybe nothing is required, but + // the method should exist anyway. + // ---------------------------------------------------------------------------- +} + +/** Verify the I2C connection. +Make sure the device is connected and responds as expected. This device has no +device ID or WHO_AM_I register. To test the connection, bits are written to control +register, checked, and then the original contents are written back. + * @return True if connection is valid, false otherwise + */ +bool LSM303DLHC::testConnection() { + I2Cdev::readByte(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, buffer); + uint8_t origValA = buffer[0]; + I2Cdev::readByte(devAddrM, LSM303DLHC_RA_CRA_REG_M, buffer); + uint8_t origValM = buffer[0]; + + uint8_t zeros = 0b00000000; + I2Cdev::writeByte(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, zeros); + I2Cdev::writeByte(devAddrM, LSM303DLHC_RA_CRA_REG_M, zeros); + + I2Cdev::readByte(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, buffer); + uint8_t newValA = buffer[0]; + I2Cdev::readByte(devAddrM, LSM303DLHC_RA_CRA_REG_M, buffer); + uint8_t newValM = buffer[0]; + + I2Cdev::writeByte(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, origValA); + I2Cdev::writeByte(devAddrM, LSM303DLHC_RA_CRA_REG_M, origValM); + + if ((newValM == zeros) and (newValA == zeros)) { + return true; + } + return false; +} + +// ---------------------------------------------------------------------------- +// STUB TODO: +// Define methods to fully cover all available functionality provided by the +// device, according to the datasheet and/or register map. Unless there is very +// clear reason not to, try to follow the get/set naming convention for all +// values, for instance: +// - uint8_t getThreshold() +// - void setThreshold(uint8_t threshold) +// - uint8_t getRate() +// - void setRate(uint8_t rate) +// +// Some methods may be named differently if it makes sense. As long as all +// functionality is covered, that's the important part. The methods here are +// only examples and should not be kept for your real device. +// ---------------------------------------------------------------------------- + +//CTRL_REG1_A, r/w + +/** Set the output data rate + * @param rate The new data output rate (can be 1, 10, 25, 50, 100, 200, 400, 1620, 1344, or 5376) + * @see LSM303DLHC_RA_CTRL_REG1_A + * @see LSM303DLHC_ODR_BIT + * @see LSM303DLHC_ODR_LENGTH + * @see LSM303DLHC_RATE_1 + * @see LSM303DLHC_RATE_10 + * @see LSM303DLHC_RATE_25 + * @see LSM303DLHC_RATE_50 + * @see LSM303DLHC_RATE_100 + * @see LSM303DLHC_RATE_200 + * @see LSM303DLHC_RATE_400 + * @see LSM303DLHC_RATE_1620_LP + * @see LSM303DLHC_RATE_1344_N_5376_LP + */ +void LSM303DLHC::setAccelOutputDataRate(uint16_t rate) { + uint8_t writeVal; + + if (rate == 0) { + writeVal = LSM303DLHC_ODR_RATE_POWERDOWN; + } else if (rate == 1) { + writeVal = LSM303DLHC_ODR_RATE_1; + } else if (rate == 10) { + writeVal = LSM303DLHC_ODR_RATE_10; + } else if (rate == 25) { + writeVal = LSM303DLHC_ODR_RATE_25; + } else if (rate == 50) { + writeVal = LSM303DLHC_ODR_RATE_50; + } else if (rate == 100) { + writeVal = LSM303DLHC_ODR_RATE_100; + } else if (rate == 200) { + writeVal = LSM303DLHC_ODR_RATE_200; + } else if (rate == 400) { + writeVal = LSM303DLHC_ODR_RATE_400; + } else if (rate == 1620) { + writeVal = LSM303DLHC_ODR_RATE_1620_LP; + } else if (rate == 1344) { + writeVal = LSM303DLHC_ODR_RATE_1344_N_5376_LP; + } else if (rate == 5376) { + writeVal = LSM303DLHC_ODR_RATE_1344_N_5376_LP; + } + + I2Cdev::writeBits(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, LSM303DLHC_ODR_BIT, + LSM303DLHC_ODR_LENGTH, writeVal); +} + +/** Get the output data rate + * @return The current data output rate (can be 1, 10, 25, 50, 100, 200, 400, 1620, or 1344 (implies 5376)) + * @see LSM303DLHC_RA_CTRL_REG1_A + * @see LSM303DLHC_ODR_BIT + * @see LSM303DLHC_ODR_LENGTH + * @see LSM303DLHC_RATE_1 + * @see LSM303DLHC_RATE_10 + * @see LSM303DLHC_RATE_25 + * @see LSM303DLHC_RATE_50 + * @see LSM303DLHC_RATE_100 + * @see LSM303DLHC_RATE_200 + * @see LSM303DLHC_RATE_400 + * @see LSM303DLHC_RATE_1620_LP + * @see LSM303DLHC_RATE_1344_N_5376_LP + */ +uint16_t LSM303DLHC::getAccelOutputDataRate() { + I2Cdev::readBits(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, LSM303DLHC_ODR_BIT, + LSM303DLHC_ODR_LENGTH, buffer); + uint8_t rate = buffer[0]; + + if (rate == LSM303DLHC_ODR_RATE_POWERDOWN) { + return 0; + } else if (rate == LSM303DLHC_ODR_RATE_1) { + return 1; + } else if (rate == LSM303DLHC_ODR_RATE_10) { + return 10; + } else if (rate == LSM303DLHC_ODR_RATE_25) { + return 25; + } else if (rate == LSM303DLHC_ODR_RATE_50) { + return 50; + } else if (rate == LSM303DLHC_ODR_RATE_100) { + return 100; + } else if (rate == LSM303DLHC_ODR_RATE_200) { + return 200; + } else if (rate == LSM303DLHC_ODR_RATE_400) { + return 400; + } else if (rate == LSM303DLHC_ODR_RATE_1620_LP) { + return 1620; + } else if (rate == LSM303DLHC_ODR_RATE_1344_N_5376_LP) { + return 1344; + } else if (rate == LSM303DLHC_ODR_RATE_1344_N_5376_LP) { + return 5376; + } +} + +/*Enables or disables the accelerometer low power mode +@param enabled The new enabled state of the low power mode +@see LSM303DLHC_RA_CTRL_REG1_A +@see LSM303DLHC_LPEN_BIT +*/ +void LSM303DLHC::setAccelLowPowerEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, LSM303DLHC_LPEN_BIT, enabled); +} + +/*Get whether the accelerometer low power mode is enabled +@return True if the acceleromer low power mode is enabled +@see LSM303DLHC_RA_CTRL_REG1_A +@see LSM303DLHC_LPEN_BIT +*/ +bool LSM303DLHC::getAccelLowPowerEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, LSM303DLHC_LPEN_BIT, buffer); + return buffer[0]; +} + +/** Enables or disables the ability to get Z data + * @param enabled The new enabled state of the Z axis + * @see LSM303DLHC_RA_CTRL_REG1_A + * @see LSM303DLHC_ZEN_BIT + */ +void LSM303DLHC::setAccelZEnabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, LSM303DLHC_ZEN_BIT, enabled); +} + +/** Get whether Z axis data is enabled + * @return True if the Z axis is enabled, false otherwise + * @see LSM303DLHC_RA_CTRL_REG1_A + * @see LSM303DLHC_ZEN_BIT + */ +bool LSM303DLHC::getAccelZEnabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, LSM303DLHC_ZEN_BIT, buffer); + return buffer[0]; +} + +/** Enables or disables the ability to get Y data + * @param enabled The new enabled state of the Y axis + * @see LSM303DLHC_RA_CTRL_REG1_A + * @see LSM303DLHC_YEN_BIT + */ +void LSM303DLHC::setAccelYEnabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, LSM303DLHC_YEN_BIT, enabled); +} + +/** Get whether Y axis data is enabled + * @return True if the Y axis is enabled, false otherwise + * @see LSM303DLHC_RA_CTRL_REG1_A + * @see LSM303DLHC_YEN_BIT + */ +bool LSM303DLHC::getAccelYEnabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, LSM303DLHC_YEN_BIT, buffer); + return buffer[0]; +} + +/** Enables or disables the ability to get X data + * @param enabled The new enabled state of the X axis + * @see LSM303DLHC_RA_CTRL_REG1_A + * @see LSM303DLHC_XEN_BIT + */ +void LSM303DLHC::setAccelXEnabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, LSM303DLHC_XEN_BIT, enabled); +} + +/** Get whether X axis data is enabled + * @return True if the X axis is enabled, false otherwise + * @see LSM303DLHC_RA_CTRL_REG1_A + * @see LSM303DLHC_XEN_BIT + */ +bool LSM303DLHC::getAccelXEnabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG1_A, LSM303DLHC_XEN_BIT, buffer); + return buffer[0]; +} + +//CTRL_REG2_A r/w + +/** Set the high pass mode + * @param mode The new high pass mode + * @see LSM303DLHC_RA_CTRL_REG2 + * @see LSM303DLHC_HPM_BIT + * @see LSM303DLHC_HPM_LENGTH + * @see LSM303DLHC_HPM_HRF + * @see LSM303DLHC_HPM_REFERENCE + * @see LSM303DLHC_HPM_NORMAL + * @see LSM303DLHC_HPM_AUTORESET + */ +void LSM303DLHC::setAccelHighPassMode(uint8_t mode) { + I2Cdev::writeBits(devAddrA, LSM303DLHC_RA_CTRL_REG2_A, LSM303DLHC_HPM_BIT, + LSM303DLHC_HPM_LENGTH, mode); +} + +/** Get the high pass mode + * @return High pass mode + * @see LSM303DLHC_RA_CTRL_REG2_A + * @see LSM303DLHC_HPM_BIT + * @see LSM303DLHC_HPM_LENGTH + * @see LSM303DLHC_HPM_HRF + * @see LSM303DLHC_HPM_REFERENCE + * @see LSM303DLHC_HPM_NORMAL + * @see LSM303DLHC_HPM_AUTORESET + */ +uint8_t LSM303DLHC::getAccelHighPassMode() { + I2Cdev::readBits(devAddrA, LSM303DLHC_RA_CTRL_REG2_A, LSM303DLHC_HPM_BIT, + LSM303DLHC_HPM_LENGTH, buffer); + return buffer[0]; +} + +/** Set the high pass filter cut off frequency level (1 - 10) + * @param level The new level for the hpcf, using one of the defined levels + * @see LSM303DLHC_RA_CTRL_REG2_A + * @see LSM303DLHC_HPCF_BIT + * @see LSM303DLHC_HPCF_LENGTH + * @see LSM303DLHC_HPCF1 + * @see LSM303DLHC_HPCF2 + * @see LSM303DLHC_HPCF3 + * @see LSM303DLHC_HPCF4 + */ +void LSM303DLHC::setAccelHighPassFilterCutOffFrequencyLevel(uint8_t level) { + I2Cdev::writeBits(devAddrA, LSM303DLHC_RA_CTRL_REG2_A, LSM303DLHC_HPCF_BIT, + LSM303DLHC_HPCF_LENGTH, level); +} + +/** Get the high pass filter cut off frequency level (1 - 10) + * @return High pass filter cut off frequency level + * @see LSM303DLHC_RA_CTRL_REG2_A + * @see LSM303DLHC_HPCF_BIT + * @see LSM303DLHC_HPCF_LENGTH + * @see LSM303DLHC_HPCF1 + * @see LSM303DLHC_HPCF2 + * @see LSM303DLHC_HPCF3 + * @see LSM303DLHC_HPCF4 + */ +uint8_t LSM303DLHC::getAccelHighPassFilterCutOffFrequencyLevel() { + I2Cdev::readBits(devAddrA, LSM303DLHC_RA_CTRL_REG2_A, LSM303DLHC_HPCF_BIT, + LSM303DLHC_HPCF_LENGTH, buffer); + return buffer[0]; +} + +//CTRL_REG3_A r/w + +/*Enable the Click interrupt routed to the INT1 pin. +@param enabled The new enabled state of the Click interrupt routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_CLICK_BIT +*/ +void LSM303DLHC::setAccelINT1ClickEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_CLICK_BIT, enabled); +} + +/*Get whether the Click interrupt is routed to the INT1 pin. +@return True if the Click interrupt is routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_CLICK_BIT +*/ +bool LSM303DLHC::getAccelINT1ClickEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_CLICK_BIT, buffer); + return buffer[0]; +} + +/*Enable the AOR1 interrupt routed to the INT1 pin. +@param enabled The new enabled state of the AOR1 interrupt routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_AOI1_BIT +*/ +void LSM303DLHC::setAccelINT1AOI1Enabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_AOI1_BIT, enabled); +} + +/*Get whether the AOR1 interrupt is routed to the INT1 pin. +@return True if the AOR1 interrupt is routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_AOI1_BIT +*/ +bool LSM303DLHC::getAccelINT1AOI1Enabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_AOI1_BIT, buffer); + return buffer[0]; +} + +/*Enable the AOR2 interrupt routed to the INT1 pin. +@param enabled The new enabled state of the AOR2 interrupt routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_AOI2_BIT +*/ +void LSM303DLHC::setAccelINT1AOI2Enabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_AOI2_BIT, enabled); +} + +/*Get whether the AOR2 interrupt is routed to the INT1 pin. +@return True if the AOR2 interrupt is routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_AOI2_BIT +*/ +bool LSM303DLHC::getAccelINT1AOI2Enabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_AOI2_BIT, buffer); + return buffer[0]; +} + +/*Enable the Data Ready 1 interrupt routed to the INT1 pin. +@param enabled The new enabled state of the Data Ready 1 interrupt routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_DRDY1_BIT +*/ +void LSM303DLHC::setAccelINT1DataReady1Enabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_DRDY1_BIT, enabled); +} + +/*Get whether the Data Ready 1 interrupt is routed to the INT1 pin. +@return True if the Data Ready 1 interrupt is routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_DRDY1_BIT +*/ +bool LSM303DLHC::getAccelINT1DataReady1Enabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_DRDY1_BIT, buffer); + return buffer[0]; +} + +/*Enable the Data Ready 2 interrupt routed to the INT1 pin. +@param enabled The new enabled state of the Data Ready 2 interrupt routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_DRDY2_BIT +*/ +void LSM303DLHC::setAccelINT1DataReady2Enabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_DRDY2_BIT, enabled); +} + +/*Get whether the Data Ready 2 interrupt is routed to the INT1 pin. +@return True if the Data Ready 2 interrupt is routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_DRDY2_BIT +*/ +bool LSM303DLHC::getAccelINT1DataReady2Enabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_DRDY2_BIT, buffer); + return buffer[0]; +} + +/*Enable the FIFO watermark interrupt routed to the INT1 pin. +@param enabled The new enabled state of the FIFO watermark interrupt routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_WTM_BIT +*/ +void LSM303DLHC::setAccelINT1FIFOWatermarkEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_WTM_BIT, enabled); +} + +/*Get whether the FIFO watermark interrupt is routed to the INT1 pin. +@return True if the FIFO watermark interrupt is routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_WTM_BIT +*/ +bool LSM303DLHC::getAccelINT1FIFOWatermarkEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_WTM_BIT, buffer); + return buffer[0]; +} + +/*Enable the FIFO overrun interrupt routed to the INT1 pin. +@param enabled The new enabled state of the FIFO overrun interrupt routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_OVERRUN_BIT +*/ +void LSM303DLHC::setAccelINT1FIFOOverunEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_OVERRUN_BIT, enabled); +} + +/*Get whether the FIFO overrun interrupt is routed to the INT1 pin. +@return True if the FIFO overrun interrupt is routed to the INT1 pin +@see LSM303DLHC_RA_CTRL_REG3_A +@see LSM303DLHC_I1_OVERRUN_BIT +*/ +bool LSM303DLHC::getAccelINT1FIFOOverunEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG3_A, LSM303DLHC_I1_OVERRUN_BIT, buffer); + return buffer[0]; +} + +//CTRL_REG4_A r/w + +/** Set the Block Data Update (BDU) enabled state + * @param enabled New BDU enabled state + * @see LSM303DLHC_RA_CTRL_REG4_A + * @see LSM303DLHC_BDU_BIT + */ +void LSM303DLHC::setAccelBlockDataUpdateEnabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG4_A, LSM303DLHC_BDU_BIT, enabled); +} + +/** Get the BDU enabled state + * @return True if Block Data Update is enabled, false otherwise + * @see LSM303DLHC_RA_CTRL_REG4_A + * @see LSM303DLHC_BDU_BIT + */ +bool LSM303DLHC::getAccelBlockDataUpdateEnabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG4_A, LSM303DLHC_BDU_BIT, buffer); + return buffer[0]; +} + +/** Set the data endian modes + * In Big Endian mode, the Most Significat Byte (MSB) is on the lower address, + * and the Least Significant Byte (LSB) is on the higher address. Little Endian + * mode reverses this order. Little Endian is the default mode. + * @param endianness New endian mode + * @see LSM303DLHC_RA_CTRL_REG4_A + * @see LSM303DLHC_BLE_BIT + * @see LSM303DLHC_BIG_ENDIAN + * @see LSM303DLHC_LITTLE_ENDIAN + */ +void LSM303DLHC::setAccelEndianMode(bool endianness) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG4_A, LSM303DLHC_BLE_BIT, + endianness); + endianMode = getAccelEndianMode(); +} + +/** Get the data endian mode + * @return Current endian mode + * @see LSM303DLHC_RA_CTRL_REG4_A + * @see LSM303DLHC_BLE_BIT + * @see LSM303DLHC_BIG_ENDIAN + * @see LSM303DLHC_LITTLE_ENDIAN + */ +bool LSM303DLHC::getAccelEndianMode() { + return endianMode; + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG4_A, LSM303DLHC_BLE_BIT, + buffer); + return buffer[0]; +} + +/** Set the full scale of the data output (in dps) + * @param scale The new scale of the data output (250, 500, 2000) + * @see LSM303DLHC_RA_CTRL_REG4_A + * @see LSM303DLHC_FS_BIT + * @see LSM303DLHC_FS_LENGTH + * @see LSM303DLHC_FS_2 + * @see LSM303DLHC_FS_4 + * @see LSM303DLHC_FS_8 + * @see LSM303DLHC_FS_16 + */ +void LSM303DLHC::setAccelFullScale(uint8_t scale) { + uint8_t writeBits; + + if (scale == 2) { + writeBits = LSM303DLHC_FS_2; + } else if (scale == 4) { + writeBits = LSM303DLHC_FS_4; + } else if (scale == 8) { + writeBits = LSM303DLHC_FS_8; + } else { + writeBits = LSM303DLHC_FS_16; + } + + I2Cdev::writeBits(devAddrA, LSM303DLHC_RA_CTRL_REG4_A, LSM303DLHC_FS_BIT, + LSM303DLHC_FS_LENGTH, writeBits); +} + +/** Get the current full scale of the output data (in dps) + * @return Current scale of the output data + * @see LSM303DLHC_RA_CTRL_REG4_A + * @see LSM303DLHC_FS_BIT + * @see LSM303DLHC_FS_LENGTH + * @see LSM303DLHC_FS_2 + * @see LSM303DLHC_FS_4 + * @see LSM303DLHC_FS_8 + * @see LSM303DLHC_FS_16 + */ +uint8_t LSM303DLHC::getAccelFullScale() { + I2Cdev::readBits(devAddrA, LSM303DLHC_RA_CTRL_REG4_A, + LSM303DLHC_FS_BIT, LSM303DLHC_FS_LENGTH, buffer); + uint8_t readBits = buffer[0]; + + if (readBits == LSM303DLHC_FS_2) { + return 2; + } else if (readBits == LSM303DLHC_FS_4) { + return 4; + } else if (readBits == LSM303DLHC_FS_8) { + return 8; + } else { + return 16; + } +} + +/*Enables or disables high resolution output. +@param enabled New enabled state of high resolution output +@see LSM303DLHC_RA_CTRL_REG4_A +@see LSM303DLHC_HR_BIT +*/ +void LSM303DLHC::setAccelHighResOutputEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG4_A, LSM303DLHC_HR_BIT, + enabled); +} + +/*Gets whether high resolution output is enabled. +@return True if high resolution output is enabled +@see LSM303DLHC_RA_CTRL_REG4_A +@see LSM303DLHC_HR_BIT +*/ +bool LSM303DLHC::getAccelHighResOutputEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG4_A, LSM303DLHC_HR_BIT, + buffer); + return buffer[0]; +} + +/** Set the SPI mode + * @param mode New SPI mode + * @see LSM303DLHC_RA_CTRL_REG4_A + * @see LSM303DLHC_SIM_BIT + * @see LSM303DLHC_SIM_4W + * @see LSM303DLHC_SIM_3W + */ +void LSM303DLHC::setAccelSPIMode(bool mode) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG4_A, LSM303DLHC_SIM_BIT, mode); +} + +/** Get the SPI mode + * @return Current SPI mode + * @see LSM303DLHC_RA_CTRL_REG4_A + * @see LSM303DLHC_SIM_BIT + * @see LSM303DLHC_SIM_4W + * @see LSM303DLHC_SIM_3W + */ +bool LSM303DLHC::getAccelSPIMode() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG4_A, LSM303DLHC_SIM_BIT, + buffer); + return buffer[0]; +} + +//CTRL_REG5_A r/w + +/** Reboots the FIFO memory content + * @see LSM303DLHC_RA_CTRL_REG5_A + * @see LSM303DLHC_BOOT_BIT + */ +void LSM303DLHC::rebootAccelMemoryContent() { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG5_A, LSM303DLHC_BOOT_BIT, true); +} + +/** Set whether the FIFO buffer is enabled + * @param enabled New enabled state of the FIFO buffer + * @see LSM303DLHC_RA_CTRL_REG5_A + * @see LSM303DLHC_FIFO_EN_BIT + */ +void LSM303DLHC::setAccelFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG5_A, LSM303DLHC_FIFO_EN_BIT, + enabled); +} + +/** Get whether the FIFO buffer is enabled + * @return True if the FIFO buffer is enabled, false otherwise + * @see LSM303DLHC_RA_CTRL_REG5_A + * @see LSM303DLHC_FIFO_EN_BIT + */ +bool LSM303DLHC::getAccelFIFOEnabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG5_A, LSM303DLHC_FIFO_EN_BIT, + buffer); + return buffer[0]; +} + +/*Enable latching of interrupt requrest 1 +@param latched New enabled state of latching interrupt request 1 +@see LSM303DLHC_RA_CTRL_REG5_A +@see LSM303DLHC_LIR_INT1_BIT +*/ +void LSM303DLHC::setAccelInterrupt1RequestLatched(bool latched){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG5_A, LSM303DLHC_LIR_INT1_BIT, + latched); +} + +/*Get whether latching of interrupt request 1 is enabled. +@return True if latching of interrupt request 1 is enabled +@see LSM303DLHC_RA_CTRL_REG5_A +@see LSM303DLHC_LIR_INT1_BIT +*/ +bool LSM303DLHC::getAccelInterrupt1RequestLatched(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG5_A, LSM303DLHC_LIR_INT1_BIT, + buffer); + return buffer[0]; +} + +/*Enable latching of interrupt requrest 2 +@param latched New enabled state of latching interrupt request 2 +@see LSM303DLHC_RA_CTRL_REG5_A +@see LSM303DLHC_LIR_INT2_BIT +*/ +void LSM303DLHC::setAccelInterrupt2RequestLatched(bool latched){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG5_A, LSM303DLHC_LIR_INT2_BIT, + latched); +} + +/*Get whether latching of interrupt request 2 is enabled. +@return True if latching of interrupt request 2 is enabled +@see LSM303DLHC_RA_CTRL_REG5_A +@see LSM303DLHC_LIR_INT2_BIT +*/ +bool LSM303DLHC::getAccelInterrupt2RequestLatched(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG5_A, LSM303DLHC_LIR_INT2_BIT, + buffer); + return buffer[0]; +} + +/*Enable 4D dectection interrupt 1 +@param enabled New enabled state of the 4D detection interrupt 1 +@see LSM303DLHC_RA_CTRL_REG5_A +@see LSM303DLHC_D4D_INT1_BIT +*/ +void LSM303DLHC::setAccelDetect4DInterrupt1Enabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG5_A, LSM303DLHC_D4D_INT1_BIT, + enabled); +} + +/*Get whether 4D detection interrupt 1 is enabled. +@return True if 4D detection interrupt 1 is enabled +@see LSM303DLHC_RA_CTRL_REG5_A +@see LSM303DLHC_D4D_INT1_BIT +*/ +bool LSM303DLHC::getAccelDetect4DInterrupt1Enabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG5_A, LSM303DLHC_D4D_INT1_BIT, + buffer); + return buffer[0]; +} + +/*Enable 4D dectection interrupt 2 +@param enabled New enabled state of the 4D detection interrupt 2 +@see LSM303DLHC_RA_CTRL_REG5_A +@see LSM303DLHC_D4D_INT2_BIT +*/ +void LSM303DLHC::setAccelDetect4DInterrupt2Enabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG5_A, LSM303DLHC_D4D_INT2_BIT, + enabled); +} + +/*Get whether 4D detection interrupt 2 is enabled. +@return True if 4D detection interrupt 2 is enabled +@see LSM303DLHC_RA_CTRL_REG5_A +@see LSM303DLHC_D4D_INT2_BIT +*/ +bool LSM303DLHC::getAccelDetect4DInterrupt2Enabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG5_A, LSM303DLHC_D4D_INT2_BIT, + buffer); + return buffer[0]; +} + +//CTRL_REG6_A r/w + +//TODO: +/*Enable the Click interrupt routed to the INT2 pin. +@param enabled The new enabled state of the Click interrupt routed to the INT2 pin +@see LSM303DLHC_RA_CTRL_REG6_A +@see LSM303DLHC_I2_CLICK_BIT +*/ +void LSM303DLHC::setAccelINT2ClickEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG6_A, LSM303DLHC_I2_CLICK_BIT, enabled); +} + +/*Get whether the Click interrupt is routed to the INT2 pin. +@return True if the Click interrupt is routed to the INT2 pin +@see LSM303DLHC_RA_CTRL_REG6_A +@see LSM303DLHC_I2_CLICK_BIT +*/ +bool LSM303DLHC::getAccelINT2ClickEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG6_A, LSM303DLHC_I2_CLICK_BIT, buffer); + return buffer[0]; +} + +/*Enable interrupt 1 routed to the INT2 pin. +@param enabled The new enabled state of whether interrupt 1 routed to the INT2 pin +@see LSM303DLHC_RA_CTRL_REG6_A +@see LSM303DLHC_I2_INT1_BIT +*/ +void LSM303DLHC::setAccelINT2Interrupt1Enabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG6_A, LSM303DLHC_I2_INT1_BIT, enabled); +} + +/*Get whether interrupt 1 is routed to the INT2 pin. +@return True if interrupt 1 is routed to the INT2 pin +@see LSM303DLHC_RA_CTRL_REG6_A +@see LSM303DLHC_I2_INT1_BIT +*/ +bool LSM303DLHC::getAccelINT2Interrupt1Enabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG6_A, LSM303DLHC_I2_INT1_BIT, buffer); + return buffer[0]; +} + +/*Enable interrupt 2 routed to the INT2 pin. +@param enabled The new enabled state of whether interrupt 2 routed to the INT2 pin +@see LSM303DLHC_RA_CTRL_REG6_A +@see LSM303DLHC_I2_INT2_BIT +*/ +void LSM303DLHC::setAccelINT2Interrupt2Enabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG6_A, LSM303DLHC_I2_INT2_BIT, enabled); +} + +/*Get whether interrupt 2 is routed to the INT2 pin. +@return True if interrupt 2 is routed to the INT2 pin +@see LSM303DLHC_RA_CTRL_REG6_A +@see LSM303DLHC_I2_INT2_BIT +*/ +bool LSM303DLHC::getAccelINT2Interrupt2Enabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG6_A, LSM303DLHC_I2_INT2_BIT, buffer); + return buffer[0]; +} + +/*Enable memory content reboot via INT2 pin +@param enabled The new state of whether memory content is rebooted via INT2 pin +@see LSM303DLHC_RA_CTRL_REG6_A +@see LSM303DLHC_BOOT_I1_BIT +*/ +void LSM303DLHC::setAccelRebootMemoryContentINT2Enabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG6_A, LSM303DLHC_BOOT_I1_BIT, enabled); +} + +/*Get whether memory content reboot is enabled via INT2 pin +@return True if memory content reboot is via INT2 pin is enabled +@see LSM303DLHC_RA_CTRL_REG6_A +@see LSM303DLHC_BOOT_I1_BIT +*/ +bool LSM303DLHC::getAccelRebootMemoryContentINT2Enabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG6_A, LSM303DLHC_BOOT_I1_BIT, buffer); + return buffer[0]; +} + +// // TODO Documentation +// void setAccelActiveFunctionStatusINT2Enabled(bool enabled); + +// // TODO Documentation +// bool getAccelActiveFunctionStatusINT2Enabled(); + +/*Enable active low interrupts. +@param enable The new state of whether active low interrupts are enabled +@see LSM303DLHC_RA_CTRL_REG6_A +@see LSM303DLHC_H_ACTIVE_BIT +*/ +void LSM303DLHC::setAccelInterruptActiveLowEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CTRL_REG6_A, LSM303DLHC_H_ACTIVE_BIT, enabled); +} + +/*Get whether active low interrupts are enabled. +@return True if active low interrupts are enabled. +@see LSM303DLHC_RA_CTRL_REG6_A +@see LSM303DLHC_H_ACTIVE_BIT +*/ +bool LSM303DLHC::getAccelInterruptActiveLowEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CTRL_REG6_A, LSM303DLHC_H_ACTIVE_BIT, buffer); + return buffer[0]; +} + +//REFERENCE_A, r/w + +/** Set the reference value for interrupt generation + * @param reference New reference value for interrupt generation + * @see LSM303DLHC_RA_REFERENCE_A + */ +void LSM303DLHC::setAccelInterruptReference(uint8_t reference) { + I2Cdev::writeByte(devAddrA, LSM303DLHC_RA_REFERENCE_A, reference); +} + +/** Get the 8-bit reference value for interrupt generation + * @return 8-bit reference value for interrupt generation + * @see LSM303DLHC_RA_REFERENCE + */ +uint8_t LSM303DLHC::getAccelInterruptReference() { + I2Cdev::readByte(devAddrA, LSM303DLHC_RA_REFERENCE_A, buffer); + return buffer[0]; +} + +//STATUS_REG_A r + +/** Get whether new data overwrote the last set of data before it was read + * @return True if the last set of data was overwritten before being read, false + * otherwise + * @see LSM303DLHC_RA_STATUS_REG_A + * @see LSM303DLHC_ZYXOR_BIT + */ +bool LSM303DLHC::getAccelXYZOverrun() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_STATUS_REG_A, LSM303DLHC_ZYXOR_BIT, + buffer); + return buffer[0]; +} + +/** Get whether new Z data overwrote the last set of data before it was read + * @return True if the last set of Z data was overwritten before being read, + * false otherwise + * @see LSM303DLHC_RA_STATUS_REG_A + * @see LSM303DLHC_ZOR_BIT + */ +bool LSM303DLHC::getAccelZOverrun() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_STATUS_REG_A, LSM303DLHC_ZOR_BIT, + buffer); + return buffer[0]; +} + +/** Get whether new Y data overwrote the last set of data before it was read + * @return True if the last set of Y data was overwritten before being read, + * false otherwise + * @see LSM303DLHC_RA_STATUS_REG_A + * @see LSM303DLHC_YOR_BIT + */ +bool LSM303DLHC::getAccelYOverrun() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_STATUS_REG_A, LSM303DLHC_YOR_BIT, + buffer); + return buffer[0]; +} + +/** Get whether new X data overwrote the last set of data before it was read + * @return True if the last set of X data was overwritten before being read, + * false otherwise + * @see LSM303DLHC_RA_STATUS_REG_A + * @see LSM303DLHC_XOR_BIT + */ +bool LSM303DLHC::getAccelXOverrun() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_STATUS_REG_A, LSM303DLHC_XOR_BIT, + buffer); + return buffer[0]; +} + +/** Get whether there is new data avaialable + * @return True if there is new data available, false otherwise + * @see LSM303DLHC_RA_STATUS_REG_A + * @see LSM303DLHC_ZYXDA_BIT + */ +bool LSM303DLHC::getAccelXYZDataAvailable() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_STATUS_REG_A, LSM303DLHC_ZYXDA_BIT, + buffer); + return buffer[0]; +} + +/** Get whether there is new Z data avaialable + * @return True if there is new Z data available, false otherwise + * @see LSM303DLHC_RA_STATUS_REG_A + * @see LSM303DLHC_ZDA_BIT + */ +bool LSM303DLHC::getAccelZDataAvailable() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_STATUS_REG_A, LSM303DLHC_ZDA_BIT, + buffer); + return buffer[0]; +} + +/** Get whether there is new Y data avaialable + * @return True if there is new Y data available, false otherwise + * @see LSM303DLHC_RA_STATUS_REG_A + * @see LSM303DLHC_YDA_BIT + */ +bool LSM303DLHC::getAccelYDataAvailable() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_STATUS_REG_A, LSM303DLHC_YDA_BIT, + buffer); + return buffer[0]; +} + +/** Get whether there is new X data avaialable + * @return True if there is new X data available, false otherwise + * @see LSM303DLHC_RA_STATUS_REG_A + * @see LSM303DLHC_XDA_BIT + */ +bool LSM303DLHC::getAccelXDataAvailable() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_STATUS_REG_A, LSM303DLHC_XDA_BIT, + buffer); + return buffer[0]; +} + +//OUT_*_A, r + +//TODO: +//Fix getAccerlation to read all 6 regs, and fix endian internal state + +/** Get the acceleration for all 3 axes + * Due to the fact that this device supports two difference Endian modes, both + * must be accounted for when reading data. In Little Endian mode, the first + * byte (lowest address) is the least significant and in Big Endian mode the + * first byte is the most significant. + * @param x 16-bit integer container for the X-axis acceleration + * @param y 16-bit integer container for the Y-axis acceleration + * @param z 16-bit integer container for the Z-axis acceleration + */ +void LSM303DLHC::getAcceleration(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddrA, LSM303DLHC_RA_OUT_X_L_A | 0x80, 6, buffer); + if (endianMode == LSM303DLHC_LITTLE_ENDIAN) { + *x = (((int16_t)buffer[1]) << 8) | buffer[0]; + *y = (((int16_t)buffer[3]) << 8) | buffer[2]; + *z = (((int16_t)buffer[5]) << 8) | buffer[4]; + } else { + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; + } +} + +/** Get the acceleration along the X-axis + * @return acceleration along the X-axis + * @see LSM303DLHC_RA_OUT_X_L_A + * @see LSM303DLHC_RA_OUT_X_H_A + */ +int16_t LSM303DLHC::getAccelerationX() { + I2Cdev::readBytes(devAddrA, LSM303DLHC_RA_OUT_X_L_A | 0x80, 2, buffer); + if (endianMode == LSM303DLHC_LITTLE_ENDIAN) { + return (((int16_t)buffer[1]) << 8) | buffer[0]; + } else { + return (((int16_t)buffer[0]) << 8) | buffer[1]; + } +} + +/** Get the acceleration along the Y-axis + * @return acceleration along the Y-axis + * @see LSM303DLHC_RA_OUT_Y_L_A + * @see LSM303DLHC_RA_OUT_Y_H_A + */ +int16_t LSM303DLHC::getAccelerationY() { + I2Cdev::readBytes(devAddrA, LSM303DLHC_RA_OUT_Y_L_A | 0x80, 2, buffer); + if (endianMode == LSM303DLHC_LITTLE_ENDIAN) { + return (((int16_t)buffer[1]) << 8) | buffer[0]; + } else { + return (((int16_t)buffer[0]) << 8) | buffer[1]; + } +} + +/** Get the acceleration along the Z-axis + * @return acceleration along the Z-axis + * @see LSM303DLHC_RA_OUT_Z_L_A + * @see LSM303DLHC_RA_OUT_Z_H_A + */ +int16_t LSM303DLHC::getAccelerationZ() { + I2Cdev::readBytes(devAddrA, LSM303DLHC_RA_OUT_Z_L_A | 0x80, 2, buffer); + if (endianMode == LSM303DLHC_LITTLE_ENDIAN) { + return (((int16_t)buffer[1]) << 8) | buffer[0]; + } else { + return (((int16_t)buffer[0]) << 8) | buffer[1]; + } +} + +//FIFO_CTRL_REG_A, rw + +/** Set the FIFO mode to one of the defined modes + * @param mode New FIFO mode + * @see LSM303DLHC_RA_FIFO_CTRL_REG_A + * @see LSM303DLHC_FM_BIT + * @see LSM303DLHC_FM_LENGTH + * @see LSM303DLHC_FM_BYPASS + * @see LSM303DLHC_FM_FIFO + * @see LSM303DLHC_FM_STREAM + * @see LSM303DLHC_FM_TRIGGER + */ +void LSM303DLHC::setAccelFIFOMode(uint8_t mode) { + I2Cdev::writeBits(devAddrA, LSM303DLHC_RA_FIFO_CTRL_REG_A, LSM303DLHC_FM_BIT, + LSM303DLHC_FM_LENGTH, mode); +} + +/** Get the FIFO mode to one of the defined modes + * @return Current FIFO mode + * @see LSM303DLHC_RA_FIFO_CTRL_REG_A + * @see LSM303DLHC_FM_BIT + * @see LSM303DLHC_FM_LENGTH + * @see LSM303DLHC_FM_BYPASS + * @see LSM303DLHC_FM_FIFO + * @see LSM303DLHC_FM_STREAM + * @see LSM303DLHC_FM_TRIGGER + */ +uint8_t LSM303DLHC::getAccelFIFOMode() { + I2Cdev::readBits(devAddrA, LSM303DLHC_RA_FIFO_CTRL_REG_A, + LSM303DLHC_FM_BIT, LSM303DLHC_FM_LENGTH, buffer); + return buffer[0]; +} + +/*Set the trigger selection to INT1 or INT2 +@param trigger The new trigger selection +@see LSM303DLHC_RA_FIFO_CTRL_REG_A +@see LSM303DLHC_TR_BIT +@see LSM303DLHC_TR_INT1 +@see LSM303DLHC_TR_INT2 +*/ +void LSM303DLHC::setAccelFIFOTriggerINT(bool trigger){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_FIFO_CTRL_REG_A, + LSM303DLHC_TR_BIT, trigger); +} + +/*Get the trigger selection (INT1 or INT2) +@return trigger The new trigger selection (0 for INT1, 1 for INT2) +@see LSM303DLHC_RA_FIFO_CTRL_REG_A +@see LSM303DLHC_TR_BIT +@see LSM303DLHC_TR_INT1 +@see LSM303DLHC_TR_INT2 +*/ +bool LSM303DLHC::getAccelFIFOTriggerINT(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_FIFO_CTRL_REG_A, + LSM303DLHC_TR_BIT, buffer); + return buffer[0]; +} + +/** Set the FIFO watermark threshold + * @param wtm New FIFO watermark threshold + * @see LSM303DLHC_RA_FIFO_CTRL_REG_A + * @see LSM303DLHC_FTH_BIT + * @see LSM303DLHC_FTH_LENGTH + */ +void LSM303DLHC::setAccelFIFOThreshold(uint8_t wtm) { + I2Cdev::writeBits(devAddrA, LSM303DLHC_RA_FIFO_CTRL_REG_A, LSM303DLHC_FTH_BIT, + LSM303DLHC_FTH_LENGTH, wtm); +} + +/** Get the FIFO watermark threshold + * @return FIFO watermark threshold + * @see LSM303DLHC_RA_FIFO_CTRL_REG_A + * @see LSM303DLHC_FTH_BIT + * @see LSM303DLHC_FTH_LENGTH + */ +uint8_t LSM303DLHC::getAccelFIFOThreshold() { + I2Cdev::readBits(devAddrA, LSM303DLHC_RA_FIFO_CTRL_REG_A, LSM303DLHC_FTH_BIT, + LSM303DLHC_FTH_LENGTH, buffer); + return buffer[0]; +} + + +//FIFO_SRC_REG_A, r + +/** Get whether the number of data sets in the FIFO buffer is less than the + * watermark + * @return True if the number of data sets in the FIFO buffer is more than or + * equal to the watermark, false otherwise. + * @see LSM303DLHC_RA_FIFO_SRC_REG_A + * @see LSM303DLHC_WTM_BIT + */ +bool LSM303DLHC::getAccelFIFOAtWatermark() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_FIFO_SRC_REG_A, LSM303DLHC_WTM_BIT, + buffer); + return buffer[0]; +} + +/** Get whether the FIFO buffer is full + * @return True if the FIFO buffer is full, false otherwise + * @see LSM303DLHC_RA_FIFO_SRC_REG_A + * @see LSM303DLHC_OVRN_FIFO_BIT + */ +bool LSM303DLHC::getAccelFIFOOverrun() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_FIFO_SRC_REG_A, + LSM303DLHC_OVRN_FIFO_BIT, buffer); + return buffer[0]; +} + +/** Get whether the FIFO buffer is empty + * @return True if the FIFO buffer is empty, false otherwise + * @see LSM303DLHC_RA_FIFO_SRC_REG_A + * @see LSM303DLHC_EMPTY_BIT + */ +bool LSM303DLHC::getAccelFIFOEmpty() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_FIFO_SRC_REG_A, + LSM303DLHC_EMPTY_BIT, buffer); + return buffer[0]; +} + +/** Get the number of filled FIFO buffer slots + * @return Number of filled slots in the FIFO buffer + * @see LSM303DLHC_RA_FIFO_SRC_REG_A + * @see LSM303DLHC_FSS_BIT + * @see LSM303DLHC_FSS_LENGTH + */ +uint8_t LSM303DLHC::getAccelFIFOStoredSamples() { + I2Cdev::readBits(devAddrA, LSM303DLHC_RA_FIFO_SRC_REG_A, + LSM303DLHC_FSS_BIT, LSM303DLHC_FSS_LENGTH, buffer); + return buffer[0]; +} + +//INT1_CFG_A, w/r + +/** Set the combination mode for interrupt 1events + * @param combination New combination mode for interrupt 1 events. + * LSM303DLHC_INT1_OR for OR and LSM303DLHC_INT1_AND for AND + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_AOI_BIT + * @see LSM303DLHC_INT1_OR + * @see LSM303DLHC_INT1_AND + */ +void LSM303DLHC::setAccelInterrupt1Combination(bool combination) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_AOI_BIT, + combination); +} + +/** Get the combination mode for interrupt 1 events + * @return Combination mode for interrupt 1 events. LSM303DLHC_INT1_OR for OR and + * LSM303DLHC_INT1_AND for AND + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_AOI_BIT + * @see LSM303DLHC_INT1_OR + * @see LSM303DLHC_INT1_AND + */ +bool LSM303DLHC::getAccelInterrupt1Combination() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_AOI_BIT, + buffer); + return buffer[0]; +} + +/*Enable 6D dectection interrupt 1. See datasheet for how 4D detection is affected. +@param enabled New enabled state of the 6D detection interrupt 1 +@see LSM303DLHC_RA_INT1_CFG_A +@see LSM303DLHC_INT1_6D_BIT +*/ +void LSM303DLHC::setAccelInterrupt16DEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_6D_BIT, enabled); +} + +/*Get enable status of 6D dectection interrupt 1. See datasheet for how 4D detection is affected. +@return True if 6D detection interrupt 1 is enabled +@see LSM303DLHC_RA_INT1_CFG_A +@see LSM303DLHC_INT1_6D_BIT +*/ +bool LSM303DLHC::getAccelInterrupt16DEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_6D_BIT, buffer); + return buffer[0]; +} + +/** Set whether the interrupt 1 for Z high/up is enabled + * @param enabled New enabled state for Z high/up interrupt. + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_ZHIE_ZUPE_BIT + */ +void LSM303DLHC::setAccelZHighUpInterrupt1Enabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_ZHIE_ZUPE_BIT, enabled); +} + +/** Get whether the interrupt 1 for Z high/up is enabled + * @return True if the interrupt 1 for Z high/up is enabled, false otherwise + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_ZHIE_ZUPE_BIT + */ +bool LSM303DLHC::getAccelZHighUpInterrupt1Enabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_ZHIE_ZUPE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt 1 for Z low/down is enabled + * @param enabled New enabled state for Z low/down interrupt. + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_ZLIE_ZDOWNE_BIT + */ +void LSM303DLHC::setAccelZLowDownInterrupt1Enabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_ZLIE_ZDOWNE_BIT, enabled); +} + +/** Get whether the interrupt 1 for Z low/down is enabled + * @return True if the interrupt 1 for Z low/down is enabled, false otherwise + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_ZLIE_ZDOWNE_BIT + */ +bool LSM303DLHC::getAccelZLowDownInterrupt1Enabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_ZLIE_ZDOWNE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt 1 for Y high/up is enabled + * @param enabled New enabled state for Y high/up interrupt. + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_YHIE_YUPE_BIT + */ +void LSM303DLHC::setAccelYHighUpInterrupt1Enabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_YHIE_YUPE_BIT, enabled); +} + +/** Get whether the interrupt 1 for Y high/up is enabled + * @return True if the interrupt 1 for Y high/up is enabled, false otherwise + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_YHIE_YUPE_BIT + */ +bool LSM303DLHC::getAccelYHighUpInterrupt1Enabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_YHIE_YUPE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt 1 for Y low/down is enabled + * @param enabled New enabled state for Y low/down interrupt. + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_YLIE_YDOWNE_BIT + */ +void LSM303DLHC::setAccelYLowDownInterrupt1Enabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_YLIE_YDOWNE_BIT, enabled); +} + +/** Get whether the interrupt 1 for Y low/down is enabled + * @return True if the interrupt 1 for Y low/down is enabled, false otherwise + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_YLIE_YDOWNE_BIT + */ +bool LSM303DLHC::getAccelYLowDownInterrupt1Enabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_YLIE_YDOWNE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt 1 for X high/up is enabled + * @param enabled New enabled state for X high/up interrupt. + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_XHIE_XUPE_BIT + */ +void LSM303DLHC::setAccelXHighUpInterrupt1Enabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_XHIE_XUPE_BIT, enabled); +} + +/** Get whether the interrupt 1 for X high/up is enabled + * @return True if the interrupt 1 for X high/up is enabled, false otherwise + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_XHIE_XUPE_BIT + */ +bool LSM303DLHC::getAccelXHighUpInterrupt1Enabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_XHIE_XUPE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt 1 for X low/down is enabled + * @param enabled New enabled state for/down X low interrupt. + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_XLIE_XDOWNE_BIT + */ +void LSM303DLHC::setAccelXLowDownInterrupt1Enabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_XLIE_XDOWNE_BIT, enabled); +} + +/** Get whether the interrupt 1 for X low/down is enabled + * @return True if the interrupt 1 for X low/down is enabled, false otherwise + * @see LSM303DLHC_RA_INT1_CFG_A + * @see LSM303DLHC_INT1_XLIE_XDOWNE_BIT + */ +bool LSM303DLHC::getAccelXLowDownInterrupt1Enabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT1_CFG_A, LSM303DLHC_INT1_XLIE_XDOWNE_BIT, + buffer); + return buffer[0]; +} + +//INT1_SRC_A, r + +/*Get the contents of the INT1_SRC_A register to determine if any and which interrupts have occured. +Reading this register will clear any interrupts that were lateched. +@return the 8 bit contents of the INT1_SRC_a register +@see LSM303DLHC_RA_INT1_SRC_A +@see LSM303DLHC_INT1_IA_BIT +@see LSM303DLHC_INT1_ZH_BIT +@see LSM303DLHC_INT1_ZL_BIT +@see LSM303DLHC_INT1_YH_BIT +@see LSM303DLHC_INT1_YL_BIT +@see LSM303DLHC_INT1_XH_BIT +@see LSM303DLHC_INT1_XL_BIT +*/ +uint8_t LSM303DLHC::getAccelInterrupt1Source() { + I2Cdev::readByte(devAddrA, LSM303DLHC_RA_INT1_SRC_A, buffer); + return buffer[0]; +} + +//INT1_THS_A, w/r + +/** Set the threshold for interrupt 1 + * @param threshold New threshold for interrupt 1 + * @see LSM303DLHC_RA_INT1_THS_A + */ +void LSM303DLHC::setAccelInterrupt1Threshold(uint8_t value){ + I2Cdev::writeByte(devAddrA, LSM303DLHC_RA_INT1_THS_A, value); +} + +/** Retrieve the threshold interrupt 1 + * @return interrupt 1 threshold + * @see LSM303DLHC_RA_INT1_THS_A + */ +uint8_t LSM303DLHC::getAccelInterupt1Threshold(){ + I2Cdev::readByte(devAddrA, LSM303DLHC_RA_INT1_THS_A, buffer); + return buffer[0]; +} + +//INT1_DURATION_A, r/w + +/* Set the minimum event duration for interrupt 1 to be generated + * This depends on the chosen output data rate + * @param duration New duration necessary for interrupt 1 to be + * generated + * @see LSM303DLHC_RA_INT1_DURATION_A + * @see LSM303DLHC_INT1_DURATION_BIT + * @see LSM303DLHC_INT1_DURATION_LENGTH + */ +void LSM303DLHC::setAccelInterrupt1Duration(uint8_t duration) { + I2Cdev::writeBits(devAddrA, LSM303DLHC_RA_INT1_DURATION_A, LSM303DLHC_INT1_DURATION_BIT, + LSM303DLHC_INT1_DURATION_LENGTH, duration); +} + +/** Get the minimum event duration for interrupt 1 to be generated + * @return Duration necessary for interrupt 1 to be generated + * @see LSM303DLHC_RA_INT1_DURATION_A + * @see LSM303DLHC_INT1_DURATION_BIT + * @see LSM303DLHC_INT1_DURATION_LENGTH + */ +uint8_t LSM303DLHC::getAccelInterrupt1Duration() { + I2Cdev::readBits(devAddrA, LSM303DLHC_RA_INT1_DURATION_A, + LSM303DLHC_INT1_DURATION_BIT, LSM303DLHC_INT1_DURATION_LENGTH, buffer); + return buffer[0]; +} + +//INT2_CFG_A, r/w + +/** Set the combination mode for interrupt 2 events + * @param combination New combination mode for interrupt events. + * LSM303DLHC_INT1_OR for OR and LSM303DLHC_INT1_AND for AND + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_AOI_BIT + * @see LSM303DLHC_INT1_OR + * @see LSM303DLHC_INT1_AND + */ +void LSM303DLHC::setAccelInterrupt2Combination(bool combination) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_AOI_BIT, + combination); +} + +/** Get the combination mode for interrupt 2 events + * @return Combination mode for interrupt events. LSM303DLHC_INT1_OR for OR and + * LSM303DLHC_INT1_AND for AND + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_AOI_BIT + * @see LSM303DLHC_INT1_OR + * @see LSM303DLHC_INT1_AND + */ +bool LSM303DLHC::getAccelInterrupt2Combination() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_AOI_BIT, + buffer); + return buffer[0]; +} + +/*Enable 6D dectection interrupt 2. See datasheet for how 4D detection is affected. +@param enabled New enabled state of the 6D detection interrupt 1 +@see LSM303DLHC_RA_INT2_CFG_A +@see LSM303DLHC_INT2_6D_BIT +*/ +void LSM303DLHC::setAccelInterrupt26DEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_6D_BIT, enabled); +} + +/*Get enable status of 6D dectection interrupt 2. See datasheet for how 4D detection is affected. +@return True if 6D detection interrupt 1 is enabled +@see LSM303DLHC_RA_INT2_CFG_A +@see LSM303DLHC_INT2_6D_BIT +*/ +bool LSM303DLHC::getAccelInterrupt26DEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_6D_BIT, buffer); + return buffer[0]; +} + +/** Set whether the interrupt 2 for Z high is enabled + * @param enabled New enabled state for Z high interrupt 2. + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_ZHIE_BIT + */ +void LSM303DLHC::setAccelZHighInterrupt2Enabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_ZHIE_BIT, enabled); +} + +/** Get whether the interrupt 2 for Z high is enabled + * @return True if the interrupt 2 for Z high is enabled, false otherwise + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_ZHIE_BIT + */ +bool LSM303DLHC::getAccelZHighInterrupt2Enabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_ZHIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt 2 for Z low is enabled + * @param enabled New enabled state for Z low interrupt 2. + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_ZLIE_BIT + */ +void LSM303DLHC::setAccelZLowInterrupt2Enabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_ZLIE_BIT, enabled); +} + +/** Get whether the interrupt 2 for Z low is enabled + * @return True if the interrupt 2 for Z low is enabled, false otherwise + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_ZLIE_BIT + */ +bool LSM303DLHC::getAccelZLowInterrupt2Enabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_ZLIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt 2 for Y high is enabled + * @param enabled New enabled state for Y high interrupt 2. + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_YHIE_BIT + */ +void LSM303DLHC::setAccelYHighInterrupt2Enabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_YHIE_BIT, enabled); +} + +/** Get whether the interrupt 2 for Y high is enabled + * @return True if the interrupt 2 for Y high is enabled, false otherwise + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_YHIE_BIT + */ +bool LSM303DLHC::getAccelYHighInterrupt2Enabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_YHIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt 2 for Y low is enabled + * @param enabled New enabled state for Y low interrupt 2. + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_YLIE_BIT + */ +void LSM303DLHC::setAccelYLowInterrupt2Enabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_YLIE_BIT, enabled); +} + +/** Get whether the interrupt 2 for Y low is enabled + * @return True if the interrupt 2 for Y low is enabled, false otherwise + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_YLIE_BIT + */ +bool LSM303DLHC::getAccelYLowInterrupt2Enabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_YLIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt 2 for X high is enabled + * @param enabled New enabled state for X high interrupt 2. + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_XHIE_BIT + */ +void LSM303DLHC::setAccelXHighInterrupt2Enabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_XHIE_BIT, enabled); +} + +/** Get whether the interrupt 2 for X high is enabled + * @return True if the interrupt 2 for X high is enabled, false otherwise + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_XHIE_BIT + */ +bool LSM303DLHC::getAccelXHighInterrupt2Enabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_XHIE_BIT, + buffer); + return buffer[0]; +} + +/** Set whether the interrupt 2 for X low is enabled + * @param enabled New enabled state for X low interrupt 2. + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_XLIE_BIT + */ +void LSM303DLHC::setAccelXLowInterrupt2Enabled(bool enabled) { + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_XLIE_BIT, enabled); +} + +/** Get whether the interrupt 2 for X low is enabled + * @return True if the interrupt 2 for X low is enabled, false otherwise + * @see LSM303DLHC_RA_INT2_CFG_A + * @see LSM303DLHC_INT2_XLIE_BIT + */ +bool LSM303DLHC::getAccelXLowInterrupt2Enabled() { + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_INT2_CFG_A, LSM303DLHC_INT2_XLIE_BIT, + buffer); + return buffer[0]; +} + + +//INT2_SRC_A, r + +/*Get the contents of the INT2_SRC_A register to determine if any and which interrupts have occured. +Reading this register will clear any interrupts that were lateched. +@return the 8 bit contents of the INT2_SRC_a register +@see LSM303DLHC_RA_INT2_SRC_A +@see LSM303DLHC_INT2_IA_BIT +@see LSM303DLHC_INT2_ZH_BIT +@see LSM303DLHC_INT2_ZL_BIT +@see LSM303DLHC_INT2_YH_BIT +@see LSM303DLHC_INT2_YL_BIT +@see LSM303DLHC_INT2_XH_BIT +@see LSM303DLHC_INT2_XL_BIT +*/ +uint8_t LSM303DLHC::getAccelInterrupt2Source() { + I2Cdev::readByte(devAddrA, LSM303DLHC_RA_INT2_SRC_A, buffer); + return buffer[0]; +} + +//INT2_THS_A, r/w + +/** Set the threshold for interrupt 2 + * @param threshold New threshold for interrupt 2 + * @see LSM303DLHC_RA_INT2_THS_A + */ +void LSM303DLHC::setAccelInterrupt2Threshold(uint8_t value){ + I2Cdev::writeByte(devAddrA, LSM303DLHC_RA_INT2_THS_A, value); +} + +/** Retrieve the threshold interrupt 2 + * @return interrupt 2 threshold + * @see LSM303DLHC_RA_INT2_THS_A + */ +uint8_t LSM303DLHC::getAccelInterupt2Threshold(){ + I2Cdev::readByte(devAddrA, LSM303DLHC_RA_INT2_THS_A, buffer); + return buffer[0]; +} + +//INT2_DURATION_A, r/w + +/* Set the minimum event duration for interrupt 2 to be generated + * This depends on the chosen output data rate + * @param duration New duration necessary for interrupt 2 to be + * generated + * @see LSM303DLHC_RA_INT2_DURATION_A + * @see LSM303DLHC_INT2_DURATION_BIT + * @see LSM303DLHC_INT2_DURATION_LENGTH + */ +void LSM303DLHC::setAccelInterrupt2Duration(uint8_t duration) { + I2Cdev::writeBits(devAddrA, LSM303DLHC_RA_INT2_DURATION_A, LSM303DLHC_INT2_DURATION_BIT, + LSM303DLHC_INT2_DURATION_LENGTH, duration); +} + +/** Get the minimum event duration for interrupt 2 to be generated + * @return Duration necessary for interrupt 2 to be generated + * @see LSM303DLHC_RA_INT2_DURATION_A + * @see LSM303DLHC_INT2_DURATION_BIT + * @see LSM303DLHC_INT2_DURATION_LENGTH + */ +uint8_t LSM303DLHC::getAccelInterrupt2Duration() { + I2Cdev::readBits(devAddrA, LSM303DLHC_RA_INT2_DURATION_A, + LSM303DLHC_INT2_DURATION_BIT, LSM303DLHC_INT2_DURATION_LENGTH, buffer); + return buffer[0]; +} + +//CLICK_CFG_A, r/w + +/*Enables interrupt double click on the Z axis. +@param enable The new status of double click interrupt on the Z axis +@see LSM303DLHC_RA_CLICK_CFG_A +@see LSM303DLHC_CLICK_ZD_BIT +*/ +void LSM303DLHC::setAccelZDoubleClickEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CLICK_CFG_A, LSM303DLHC_CLICK_ZD_BIT, enabled); +} + +/*Get status of interrupt double click on the Z axis. +@return True if double click interrupt on the Z axis is enabled +@see LSM303DLHC_RA_CLICK_CFG_A +@see LSM303DLHC_CLICK_ZD_BIT +*/ +bool LSM303DLHC::getAccelZDoubleClickEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CLICK_CFG_A, LSM303DLHC_CLICK_ZD_BIT, buffer); + return buffer[0]; +} + +/*Enables interrupt single click on the Z axis. +@param enable The new status of single click interrupt on the Z axis +@see LSM303DLHC_RA_CLICK_CFG_A +@see LSM303DLHC_CLICK_ZS_BIT +*/ +void LSM303DLHC::setAccelZSingleClickEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CLICK_CFG_A, LSM303DLHC_CLICK_ZS_BIT, enabled); +} + +/*Get status of interrupt single click on the Z axis. +@return True if single click interrupt on the Z axis is enabled +@see LSM303DLHC_RA_CLICK_CFG_A +@see LSM303DLHC_CLICK_ZS_BIT +*/ +bool LSM303DLHC::getAccelZSingleClickEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CLICK_CFG_A, LSM303DLHC_CLICK_ZS_BIT, buffer); + return buffer[0]; +} + +/*Enables interrupt double click on the Y axis. +@param enable The new status of double click interrupt on the Y axis +@see LSM303DLHC_RA_CLICK_CFG_A +@see LSM303DLHC_CLICK_YD_BIT +*/ +void LSM303DLHC::setAccelYDoubleClickEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CLICK_CFG_A, LSM303DLHC_CLICK_YD_BIT, enabled); +} + +/*Get status of interrupt double click on the Y axis. +@return True if double click interrupt on the Y axis is enabled +@see LSM303DLHC_RA_CLICK_CFG_A +@see LSM303DLHC_CLICK_YD_BIT +*/ +bool LSM303DLHC::getAccelYDoubleClickEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CLICK_CFG_A, LSM303DLHC_CLICK_YD_BIT, buffer); + return buffer[0]; +} + +/*Enables interrupt single click on the Y axis. +@param enable The new status of single click interrupt on the Y axis +@see LSM303DLHC_RA_CLICK_CFG_A +@see LSM303DLHC_CLICK_YS_BIT +*/ +void LSM303DLHC::setAccelYSingleClickEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CLICK_CFG_A, LSM303DLHC_CLICK_YS_BIT, enabled); +} + +/*Get status of interrupt single click on the Y axis. +@return True if single click interrupt on the Y axis is enabled +@see LSM303DLHC_RA_CLICK_CFG_A +@see LSM303DLHC_CLICK_YS_BIT +*/ +bool LSM303DLHC::getAccelYSingleClickEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CLICK_CFG_A, LSM303DLHC_CLICK_YS_BIT, buffer); + return buffer[0]; +} + +/*Enables interrupt double click on the X axis. +@param enable The new status of double click interrupt on the X axis +@see LSM303DLHC_RA_CLICK_CFG_A +@see LSM303DLHC_CLICK_XD_BIT +*/ +void LSM303DLHC::setAccelXDoubleClickEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CLICK_CFG_A, LSM303DLHC_CLICK_XD_BIT, enabled); +} + +/*Get status of interrupt double click on the X axis. +@return True if double click interrupt on the X axis is enabled +@see LSM303DLHC_RA_CLICK_CFG_A +@see LSM303DLHC_CLICK_XD_BIT +*/ +bool LSM303DLHC::getAccelXDoubleClickEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CLICK_CFG_A, LSM303DLHC_CLICK_XD_BIT, buffer); + return buffer[0]; +} + +/*Enables interrupt single click on the X axis. +@param enable The new status of single click interrupt on the X axis +@see LSM303DLHC_RA_CLICK_CFG_A +@see LSM303DLHC_CLICK_XS_BIT +*/ +void LSM303DLHC::setAccelXSingleClickEnabled(bool enabled){ + I2Cdev::writeBit(devAddrA, LSM303DLHC_RA_CLICK_CFG_A, LSM303DLHC_CLICK_XS_BIT, enabled); +} + +/*Get status of interrupt single click on the X axis. +@return True if single click interrupt on the X axis is enabled +@see LSM303DLHC_RA_CLICK_CFG_A +@see LSM303DLHC_CLICK_XS_BIT +*/ + +bool LSM303DLHC::getAccelXSingleClickEnabled(){ + I2Cdev::readBit(devAddrA, LSM303DLHC_RA_CLICK_CFG_A, LSM303DLHC_CLICK_XS_BIT, buffer); + return buffer[0]; +} + + +//CLICK_SRC_A, r + +/*Get the contents of the CLICK_SRC_A register to determine if any and which interrupts have occured. +Reading this register may (not sure) clear any interrupts that were lateched. +@return the 7 bit contents of the CLICK_SRC_A register +@see LSM303DLHC_RA_CLICK_SRC_A +@see LSM303DLHC_CLICK_IA_BIT +@see LSM303DLHC_CLICK_DCLICK_BIT +@see LSM303DLHC_CLICK_SCLICK_BIT +@see LSM303DLHC_CLICK_SIGN_BIT +@see LSM303DLHC_CLICK_Z_BIT +@see LSM303DLHC_CLICK_Y_BIT +@see LSM303DLHC_CLICK_X_BIT +*/ +uint8_t LSM303DLHC::getAccelClickSource(){ + I2Cdev::readByte(devAddrA, LSM303DLHC_RA_CLICK_SRC_A, buffer); + return buffer[0]; +} + +//CLICK_THS_A, r/w + +/*Set the threshold which is used to start the click-detection procedure. The threshold +value is expressed over 7 bits as an unsigned number. +@param value The value of the click detection threshold +@see LSM303DLHC_RA_CLICK_THS_A +*/ +void LSM303DLHC::setAcceLClickThreshold(uint8_t value){ + I2Cdev::writeByte(devAddrA, LSM303DLHC_RA_CLICK_THS_A, value); +} + +/*Get the threshold which is used to start the click-detection procedure. The threshold +value is a 7 bit unsigned number. +@return The value of the click detection threshold +@see LSM303DLHC_RA_CLICK_THS_A +*/ +uint8_t LSM303DLHC::getAccelClickThreshold(){ + I2Cdev::readByte(devAddrA, LSM303DLHC_RA_CLICK_THS_A, buffer); + return buffer[0]; +} + +//TIME_LIMIT_A, r/w + +/*Set the maximum time interval that can elapse between the start of the click-detection +procedure (the acceleration on the selected channel exceeds the programmed threshold) +and when the acceleration falls below the threshold. +@param value The value of the maximum time interval for click detection +@see LSM303DLHC_RA_TIME_LIMIT_A +*/ +void LSM303DLHC::setAcceLClickTimeLimit(uint8_t value){ + I2Cdev::writeByte(devAddrA, LSM303DLHC_RA_TIME_LIMIT_A, value); +} + +/*Get the maximum time interval that can elapse between the start of the click-detection +procedure (the acceleration on the selected channel exceeds the programmed threshold) +and when the acceleration falls below the threshold. +@return The value of the maximum time interval for click detection +@see LSM303DLHC_RA_TIME_LIMIT_A +*/ +uint8_t LSM303DLHC::getAccelClickTimeLimit(){ + I2Cdev::readByte(devAddrA, LSM303DLHC_RA_TIME_LIMIT_A, buffer); + return buffer[0]; +} + +//TIME_LATENCY_A, r/w + +/*Set the time interval that starts after the first click detection where the +click-detection procedure is disabled, in cases where the device is configured +for double-click detection. +@param value The double click interval +@see LSM303DLHC_RA_TIME_LATENCY_A +*/ +void LSM303DLHC::setAcceLClickTimeLatency(uint8_t value){ + I2Cdev::writeByte(devAddrA, LSM303DLHC_RA_TIME_LATENCY_A, value); +} + +/*Get the time interval that starts after the first click detection where the +click-detection procedure is disabled, in cases where the device is configured +for double-click detection. +@return The double click interval +@see LSM303DLHC_RA_TIME_LATENCY_A +*/ +uint8_t LSM303DLHC::getAccelClickTimeLatency(){ + I2Cdev::readByte(devAddrA, LSM303DLHC_RA_TIME_LATENCY_A, buffer); + return buffer[0]; +} + +//TIME_WINDOW_A, r/w + +/*Set the maximum interval of time that can elapse after the end of the latency +interval in which the click detection procedure can start, in cases where the device +is configured for double-click detection. +@param value The time window +@see LSM303DLHC_RA_TIME_WINDOW_A +*/ +void LSM303DLHC::setAcceLClickTimeWindow(uint8_t value){ + I2Cdev::writeByte(devAddrA, LSM303DLHC_RA_TIME_WINDOW_A, value); +} + +/*Get the maximum interval of time that can elapse after the end of the latency +interval in which the click detection procedure can start, in cases where the device +is configured for double-click detection. +@return The double click time window +@see LSM303DLHC_RA_TIME_WINDOW_A +*/ +uint8_t LSM303DLHC::getAccelClickTimeWindow(){ + I2Cdev::readByte(devAddrA, LSM303DLHC_RA_TIME_WINDOW_A, buffer); + return buffer[0]; +} + +//CRA_REG_M_A, rw + +/*Set the temperature sensor to be enabled. +@param enabled The new enabled state of the temperature sensor. +@see LSM303DLHC_RA_CRA_REG_M +@see LSM303DLHC_TEMP_EN_BIT +*/ +void LSM303DLHC::setMagTemperatureEnabled(bool enabled){ + I2Cdev::writeBit(devAddrM, LSM303DLHC_RA_CRA_REG_M, LSM303DLHC_TEMP_EN_BIT, enabled); +} + +/*Get whether the temperature sensor is enabled. +@return The state of the temperature sensor. +@see LSM303DLHC_RA_CRA_REG_M +@see LSM303DLHC_TEMP_EN_BIT +*/ +bool LSM303DLHC::getMagTemperatureEnabled(){ + I2Cdev::readBit(devAddrM, LSM303DLHC_RA_CRA_REG_M, LSM303DLHC_TEMP_EN_BIT, buffer); + return buffer[0]; +} + +/*Set the magetometer output data rate. Valid rates are 0, 1, 3, 7, 15, 30, 75, 220. +@param rate The new output data rate of the magnetometer. +@see LSM303DLHC_RA_CRA_REG_M +@see LSM303DLHC_DO_BIT +@see LSM303DLHC_DO_LENGTH +@see LSM303DLHC_DO_RATE_0 +@see LSM303DLHC_DO_RATE_1 +@see LSM303DLHC_DO_RATE_3 +@see LSM303DLHC_DO_RATE_7 +@see LSM303DLHC_DO_RATE_15 +@see LSM303DLHC_DO_RATE_30 +@see LSM303DLHC_DO_RATE_75 +@see LSM303DLHC_DO_RATE_220 +*/ +void LSM303DLHC::setMagOutputDataRate(uint8_t rate){ + uint8_t writeBit; + if (rate == 0){ + writeBit = LSM303DLHC_DO_RATE_0; + } else if (rate == 1){ + writeBit = LSM303DLHC_DO_RATE_1; + } else if (rate == 3){ + writeBit = LSM303DLHC_DO_RATE_3; + } else if (rate == 7){ + writeBit = LSM303DLHC_DO_RATE_7; + } else if (rate == 15){ + writeBit = LSM303DLHC_DO_RATE_15; + } else if (rate == 30){ + writeBit = LSM303DLHC_DO_RATE_30; + } else if (rate == 75){ + writeBit = LSM303DLHC_DO_RATE_75; + } else if (rate == 220){ + writeBit = LSM303DLHC_DO_RATE_220; + } + + I2Cdev::writeBits(devAddrM, LSM303DLHC_RA_CRA_REG_M, LSM303DLHC_DO_BIT, + LSM303DLHC_DO_LENGTH, writeBit); +} + +/*Get the magetometer output data rate. +@return The output data rate of the magnetometer. +@see LSM303DLHC_RA_CRA_REG_M +@see LSM303DLHC_DO_BIT +@see LSM303DLHC_DO_LENGTH +@see LSM303DLHC_DO_RATE_0 +@see LSM303DLHC_DO_RATE_1 +@see LSM303DLHC_DO_RATE_3 +@see LSM303DLHC_DO_RATE_7 +@see LSM303DLHC_DO_RATE_15 +@see LSM303DLHC_DO_RATE_30 +@see LSM303DLHC_DO_RATE_75 +@see LSM303DLHC_DO_RATE_220 +*/ +uint8_t LSM303DLHC::getMagOutputDataRate(){ + I2Cdev::readBits(devAddrM, LSM303DLHC_RA_CRA_REG_M, LSM303DLHC_DO_BIT, + LSM303DLHC_DO_LENGTH, buffer); + uint8_t rate = buffer[0]; + + if (rate == LSM303DLHC_DO_RATE_0){ + return 0; + } else if (rate == LSM303DLHC_DO_RATE_1){ + return 1; + } else if (rate == LSM303DLHC_DO_RATE_3){ + return 3; + } else if (rate == LSM303DLHC_DO_RATE_7){ + return 7; + } else if (rate == LSM303DLHC_DO_RATE_15){ + return 15; + } else if (rate == LSM303DLHC_DO_RATE_30){ + return 30; + } else if (rate == LSM303DLHC_DO_RATE_75){ + return 75; + } else if (rate == LSM303DLHC_DO_RATE_220){ + return 220; + } +} + +//CRB_REG_M, rws + +/*Set the magnetometer gain. +@param gain The new gain of the magnetometer +@see LSM303DLHC_RA_CRB_REG_M +@see LSM303DLHC_GN_BIT +@see LSM303DLHC_GN_LENGTH +@see LSM303DLHC_GN_230 +@see LSM303DLHC_GN_330 +@see LSM303DLHC_GN_400 +@see LSM303DLHC_GN_450 +@see LSM303DLHC_GN_670 +@see LSM303DLHC_GN_855 +@see LSM303DLHC_GN_1100 +*/ +void LSM303DLHC::setMagGain(uint16_t gain){ + uint8_t writeBit; + if (gain == 230){ + writeBit = LSM303DLHC_GN_230; + } else if (gain == 330){ + writeBit = LSM303DLHC_GN_330; + } else if (gain == 400){ + writeBit = LSM303DLHC_GN_400; + } else if (gain == 450){ + writeBit = LSM303DLHC_GN_450; + } else if (gain == 670){ + writeBit = LSM303DLHC_GN_670; + } else if (gain == 855){ + writeBit = LSM303DLHC_GN_855; + } else if (gain == 1100){ + writeBit = LSM303DLHC_GN_1100; + } + + I2Cdev::writeBits(devAddrM, LSM303DLHC_RA_CRB_REG_M, LSM303DLHC_GN_BIT, LSM303DLHC_GN_LENGTH, + writeBit); +} + +/*Get the magnetometer gain. +@return The gain of the magnetometer +@see LSM303DLHC_RA_CRB_REG_M +@see LSM303DLHC_GN_230 +@see LSM303DLHC_GN_330 +@see LSM303DLHC_GN_400 +@see LSM303DLHC_GN_450 +@see LSM303DLHC_GN_670 +@see LSM303DLHC_GN_855 +@see LSM303DLHC_GN_1100 +*/ +uint16_t LSM303DLHC::getMagGain(){ + I2Cdev::readBits(devAddrM, LSM303DLHC_RA_CRB_REG_M, LSM303DLHC_GN_BIT, LSM303DLHC_GN_LENGTH, + buffer); + uint8_t gain = buffer[0]; + if (gain == LSM303DLHC_GN_230){ + return 230; + } else if (gain == LSM303DLHC_GN_330){ + return 330; + } else if (gain == LSM303DLHC_GN_400){ + return 400; + } else if (gain == LSM303DLHC_GN_450){ + return 450; + } else if (gain == LSM303DLHC_GN_670){ + return 670; + } else if (gain == LSM303DLHC_GN_855){ + return 855; + } else if (gain == LSM303DLHC_GN_1100){ + return 1100; + } +} + +//MR_REG_M, rw + +/*Set the magnetometer mode. +@param mode The new mode for the magnetometer. +@see LSM303DLHC_RA_MR_REG_M +@see LSM303DLHC_MD_BIT +@see LSM303DLHC_MD_LENGTH +@see LSM303DLHC_MD_CONTINUOUS +@see LSM303DLHC_MD_SINGLE +@see LSM303DLHC_MD_SLEEP +*/ +void LSM303DLHC::setMagMode(uint8_t mode){ + I2Cdev::writeBits(devAddrM, LSM303DLHC_RA_MR_REG_M, LSM303DLHC_MD_BIT, LSM303DLHC_MD_LENGTH, + mode); +} + +/*Get the magnetometer mode. +@return The mode for the magnetometer. +@see LSM303DLHC_RA_MR_REG_M +@see LSM303DLHC_MD_BIT +@see LSM303DLHC_MD_LENGTH +@see LSM303DLHC_MD_CONTINUOUS +@see LSM303DLHC_MD_SINGLE +@see LSM303DLHC_MD_SLEEP +*/ +uint8_t LSM303DLHC::getMagMode(){ + I2Cdev::readBits(devAddrM, LSM303DLHC_RA_MR_REG_M, LSM303DLHC_MD_BIT, LSM303DLHC_MD_LENGTH, + buffer); + return buffer[0]; +} + +//OUT_____M, r + +//TODO +/** Get the magnetic field for all 3 axes + * @param x 16-bit integer container for the X-axis magnetic field + * @param y 16-bit integer container for the Y-axis magnetic field + * @param z 16-bit integer container for the Z-axis magnetic field + */ +void LSM303DLHC::getMag(int16_t* x, int16_t* y, int16_t* z){ + I2Cdev::readBytes(devAddrM, LSM303DLHC_RA_OUT_X_H_M, 6, buffer); + *x = ((((int16_t)buffer[0]) << 8) | buffer[1]); + *z = ((((int16_t)buffer[2]) << 8) | buffer[3]); + *y = ((((int16_t)buffer[4]) << 8) | buffer[5]); + +} + +/** Get the magnetic field along the X-axis + * @return magnetic field along the X-axis + * @see LSM303DLHC_RA_OUT_X_L_M + * @see LSM303DLHC_RA_OUT_X_H_M + */ +int16_t LSM303DLHC::getMagX(){ + I2Cdev::readBytes(devAddrM, LSM303DLHC_RA_OUT_X_H_M, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +/** Get the magnetic field along the X-axis + * @return magnetic field along the X-axis + * @see LSM303DLHC_RA_OUT_Y_L_M + * @see LSM303DLHC_RA_OUT_Y_H_M + */ +int16_t LSM303DLHC::getMagY(){ + I2Cdev::readBytes(devAddrM, LSM303DLHC_RA_OUT_Y_H_M, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +/** Get the magnetic field along the X-axis + * @return magnetic field along the X-axis + * @see LSM303DLHC_RA_OUT_Z_L_M + * @see LSM303DLHC_RA_OUT_Z_H_M + */ +int16_t LSM303DLHC::getMagZ(){ + I2Cdev::readBytes(devAddrM, LSM303DLHC_RA_OUT_Z_H_M, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +//SR_REG_M, r + +/*Get data output register lock. This bit is set when the first magnetic file +data register has been read. +@return the output data register lock +@see LSM303DLHC_RA_SR_REG_M +@see LSM303DLHC_RA_M_LOCK_BIT +*/ +bool LSM303DLHC::getMagOutputDataRegisterLock(){ + I2Cdev::readBit(devAddrM, LSM303DLHC_RA_SR_REG_M, LSM303DLHC_M_LOCK_BIT, buffer); + return buffer[0]; +} + +/*Get data ready bit. This bit is when a new set of measurements is available. +@return the data ready bit status +@see LSM303DLHC_RA_SR_REG_M +@see LSM303DLHC_RA_M_DRDY_BIT +*/ +bool LSM303DLHC::getMagDataReady(){ + I2Cdev::readBit(devAddrM, LSM303DLHC_RA_SR_REG_M, LSM303DLHC_M_DRDY_BIT, buffer); + return buffer[0]; +} + +//TEMP_OUT_*_M + +/*Get the tempearture data. 12-bit resolution. 8LSB/deg +@return The temperature data. +@see LSM303DLHC_RA_TEMP_OUT_H_M +@see LSM303DLHC_RA_TEMP_OUT_L_M +*/ +int16_t LSM303DLHC::getTemperature(){ + I2Cdev::readBytes(devAddrM, LSM303DLHC_RA_TEMP_OUT_H_M | 0x80, 2, buffer); + return ((((int16_t)buffer[0]) << 8) | buffer[1]) >> 4; +} + +// WHO_AM_I register, read-only +// There is no ID register for this device. +uint8_t LSM303DLHC::getDeviceID() { + return 0; + // read a single byte and return it + // I2Cdev::readByte(devAddrA, LSM303DLHC_RA_WHO_AM_I, buffer); + // return buffer[0]; +} diff --git a/libraries/LSM303DLHC/LSM303DLHC.h b/libraries/LSM303DLHC/LSM303DLHC.h new file mode 100644 index 0000000..8c3469c --- /dev/null +++ b/libraries/LSM303DLHC/LSM303DLHC.h @@ -0,0 +1,658 @@ +// I2Cdev library collection - LSM303DLHC I2C device class header file +// Based on ST LSM303DLHC datasheet REV 2, 11/2013 +// 3/10/2015 by Nate Costello +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2015-03-15 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 [Author Name], 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 _LSM303DLHC_H_ +#define _LSM303DLHC_H_ + +#include "I2Cdev.h" + +// ---------------------------------------------------------------------------- +// STUB TODO: +// List all possible device I2C addresses here, if they are predefined. Some +// devices only have one possible address, in which case that one should be +// defined as both [LSM303DLHC]_ADDRESS and [LSM303DLHC]_DEFAULT_ADDRESS for +// consistency. The *_DEFAULT address will be used if a device object is +// created without an address provided in the constructor. Note that I2C +// devices conventionally use 7-bit addresses, so these will generally be +// between 0x00 and 0x7F. +// The LSM303DLHC uses two device addresses, one for the accerometer, and on +// for the megnetometer. +// ---------------------------------------------------------------------------- +#define LSM303DLHC_ADDRESS_A 0x19 +#define LSM303DLHC_ADDRESS_M 0x1E +#define LSM303DLHC_DEFAULT_ADDRESS_A 0x19 +#define LSM303DLHC_DEFAULT_ADDRESS_M 0x1E + +// ---------------------------------------------------------------------------- +// STUB TODO: +// List all registers that this device has. The goal for all device libraries +// is to have complete coverage of all possible functions, so be sure to add +// everything in the datasheet. Register address constants should use the extra +// prefix "RA_", followed by the datasheet's given name for each register. +// ---------------------------------------------------------------------------- +#define LSM303DLHC_RA_CTRL_REG1_A 0x20 // rw 0000 0111 +#define LSM303DLHC_RA_CTRL_REG2_A 0x21 // rw 0000 0000 +#define LSM303DLHC_RA_CTRL_REG3_A 0x22 // rw 0000 0000 +#define LSM303DLHC_RA_CTRL_REG4_A 0x23 // rw 0000 0000 +#define LSM303DLHC_RA_CTRL_REG5_A 0x24 // rw 0000 0000 +#define LSM303DLHC_RA_CTRL_REG6_A 0x25 // rw 0000 0000 +#define LSM303DLHC_RA_REFERENCE_A 0x06 // rw 0000 0000 +#define LSM303DLHC_RA_STATUS_REG_A 0x27 // r 0000 0000 +#define LSM303DLHC_RA_OUT_X_L_A 0x28 // r +#define LSM303DLHC_RA_OUT_X_H_A 0x29 // r +#define LSM303DLHC_RA_OUT_Y_L_A 0x2A // r +#define LSM303DLHC_RA_OUT_Y_H_A 0x2B // r +#define LSM303DLHC_RA_OUT_Z_L_A 0x2C // r +#define LSM303DLHC_RA_OUT_Z_H_A 0x2D // r +#define LSM303DLHC_RA_FIFO_CTRL_REG_A 0x2E // rw 0000 0000 +#define LSM303DLHC_RA_FIFO_SRC_REG_A 0x2F // r +#define LSM303DLHC_RA_INT1_CFG_A 0x30 // rw 0000 0000 +#define LSM303DLHC_RA_INT1_SRC_A 0x31 // r 0000 0000 +#define LSM303DLHC_RA_INT1_THS_A 0x32 // rw 0000 0000 +#define LSM303DLHC_RA_INT1_DURATION_A 0x33 // rw 0000 0000 +#define LSM303DLHC_RA_INT2_CFG_A 0x34 // rw 0000 0000 +#define LSM303DLHC_RA_INT2_SRC_A 0x35 // r 0000 0000 +#define LSM303DLHC_RA_INT2_THS_A 0x36 // rw 0000 0000 +#define LSM303DLHC_RA_INT2_DURATION_A 0x37 // rw 0000 0000 +#define LSM303DLHC_RA_CLICK_CFG_A 0x38 // rw 0000 0000 +#define LSM303DLHC_RA_CLICK_SRC_A 0x39 // rw 0000 0000 +#define LSM303DLHC_RA_CLICK_THS_A 0x3A // rw 0000 0000 +#define LSM303DLHC_RA_TIME_LIMIT_A 0x3B // rw 0000 0000 +#define LSM303DLHC_RA_TIME_LATENCY_A 0x3C // rw 0000 0000 +#define LSM303DLHC_RA_TIME_WINDOW_A 0x3D // rw 0000 0000 + +#define LSM303DLHC_RA_CRA_REG_M 0x00 // rw 0001 0000 +#define LSM303DLHC_RA_CRB_REG_M 0x01 // rw 0010 0000 +#define LSM303DLHC_RA_MR_REG_M 0x02 // rw 0000 0011 +#define LSM303DLHC_RA_OUT_X_H_M 0x03 // r +#define LSM303DLHC_RA_OUT_X_L_M 0x04 // r +#define LSM303DLHC_RA_OUT_Z_H_M 0x05 // r +#define LSM303DLHC_RA_OUT_Z_L_M 0x06 // r +#define LSM303DLHC_RA_OUT_Y_H_M 0x07 // r +#define LSM303DLHC_RA_OUT_Y_L_M 0x08 // r +#define LSM303DLHC_RA_SR_REG_M 0x09 // r 0000 0000 +#define LSM303DLHC_RA_IRA_REG_M 0x0A // r 0100 1000 +#define LSM303DLHC_RA_IRB_REG_M 0x0B // r 0011 0100 +#define LSM303DLHC_RA_IRC_REG_M 0x0C // r 0011 0011 +#define LSM303DLHC_RA_TEMP_OUT_H_M 0x31 // r +#define LSM303DLHC_RA_TEMP_OUT_L_M 0x32 // r + +// ---------------------------------------------------------------------------- +// STUB TODO: +// List register structures wherever necessary. Bit position constants should +// end in "_BIT", and are defined from 7 to 0, with 7 being the left/MSB and +// 0 being the right/LSB. If the device uses 16-bit registers instead of the +// more common 8-bit registers, the range is 15 to 0. Field length constants +// should end in "_LENGTH", but otherwise match the name of bit position +// constant that it complements. Fields that are a single bit in length don't +// need a separate field length constant. +// ---------------------------------------------------------------------------- +// ---------------------------------------------------------------------------- +// STUB TODO: +// List any special predefined values for each register according to the +// datasheet. For example, MEMS devices often provide different options for +// measurement rates, say 25Hz, 50Hz, 100Hz, and 200Hz. These are typically +// represented by arbitrary bit values, say 0b00, 0b01, 0b10, and 0b11 (or 0x0, +// 0x1, 0x2, and 0x3). Defining them here makes it easy to know which options +// are available. +// ---------------------------------------------------------------------------- + +//CTRL_REG1_A +#define LSM303DLHC_ODR_BIT 7 +#define LSM303DLHC_ODR_LENGTH 4 +#define LSM303DLHC_LPEN_BIT 3 +#define LSM303DLHC_ZEN_BIT 2 +#define LSM303DLHC_YEN_BIT 1 +#define LSM303DLHC_XEN_BIT 0 + +#define LSM303DLHC_ODR_RATE_POWERDOWN 0b0000 +#define LSM303DLHC_ODR_RATE_1 0b0001 +#define LSM303DLHC_ODR_RATE_10 0b0010 +#define LSM303DLHC_ODR_RATE_25 0b0011 +#define LSM303DLHC_ODR_RATE_50 0b0100 +#define LSM303DLHC_ODR_RATE_100 0b0101 +#define LSM303DLHC_ODR_RATE_200 0b0110 +#define LSM303DLHC_ODR_RATE_400 0b0111 +#define LSM303DLHC_ODR_RATE_1620_LP 0b1000 +#define LSM303DLHC_ODR_RATE_1344_N_5376_LP 0b1001 + +//CTRL_REG2_A +#define LSM303DLHC_HPM_BIT 7 +#define LSM303DLHC_HPM_LENGTH 2 +#define LSM303DLHC_HPCF_BIT 5 +#define LSM303DLHC_HPCF_LENGTH 2 +#define LSM303DLHC_FDS_BIT 3 +#define LSM303DLHC_HPCLICK_BIT 2 +#define LSM303DLHC_HPIS2_BIT 1 +#define LSM303DLHC_HPIS1_BIT 0 + +#define LSM303DLHC_HPM_HRF 0b00 +#define LSM303DLHC_HPM_REFERANCE 0b01 +#define LSM303DLHC_HPM_NORMAL 0b10 +#define LSM303DLHC_HPM_AUTORESET 0b11 + +#define LSM303DLHC_HPCF_1 0b00 +#define LSM303DLHC_HPCF_2 0b01 +#define LSM303DLHC_HPCF_3 0b10 +#define LSM303DLHC_HPCF_4 0b11 + +//CTRL_REG3_A +#define LSM303DLHC_I1_CLICK_BIT 7 +#define LSM303DLHC_I1_AOI1_BIT 6 +#define LSM303DLHC_I1_AOI2_BIT 5 +#define LSM303DLHC_I1_DRDY1_BIT 4 +#define LSM303DLHC_I1_DRDY2_BIT 3 +#define LSM303DLHC_I1_WTM_BIT 2 +#define LSM303DLHC_I1_OVERRUN_BIT 1 + +//CTRL_REG4_A +#define LSM303DLHC_BDU_BIT 7 +#define LSM303DLHC_BLE_BIT 6 +#define LSM303DLHC_FS_BIT 5 +#define LSM303DLHC_FS_LENGTH 2 +#define LSM303DLHC_HR_BIT 3 +#define LSM303DLHC_SIM_BIT 0 + +#define LSM303DLHC_LITTLE_ENDIAN 0 +#define LSM303DLHC_BIG_ENDIAN 1 +#define LSM303DLHC_FS_2 0b00 +#define LSM303DLHC_FS_4 0b01 +#define LSM303DLHC_FS_8 0b10 +#define LSM303DLHC_FS_16 0b11 +#define LSM303DLHC_SIM_3W 1 +#define LSM303DLHC_SIM_4W 0 + +//CTRL_REG5_A +#define LSM303DLHC_BOOT_BIT 7 +#define LSM303DLHC_FIFO_EN_BIT 6 +#define LSM303DLHC_LIR_INT1_BIT 3 +#define LSM303DLHC_D4D_INT1_BIT 2 +#define LSM303DLHC_LIR_INT2_BIT 1 +#define LSM303DLHC_D4D_INT2_BIT 0 + +//CTRL_REG6_A +#define LSM303DLHC_I2_CLICK_BIT 7 +#define LSM303DLHC_I2_INT1_BIT 6 +#define LSM303DLHC_I2_INT2_BIT 5 +#define LSM303DLHC_BOOT_I1_BIT 4 +#define LSM303DLHC_P2_ACT_BIT 3 +#define LSM303DLHC_H_ACTIVE_BIT 1 + +//REFERENCE_A + +//STATUS_REG_A +#define LSM303DLHC_ZYXOR_BIT 7 +#define LSM303DLHC_ZOR_BIT 6 +#define LSM303DLHC_YOR_BIT 5 +#define LSM303DLHC_XOR_BIT 4 +#define LSM303DLHC_ZYXDA_BIT 3 +#define LSM303DLHC_ZDA_BIT 2 +#define LSM303DLHC_YDA_BIT 1 +#define LSM303DLHC_XDA_BIT 0 + +//FIFO_CTRL_REG_A +#define LSM303DLHC_FM_BIT 7 +#define LSM303DLHC_FM_LENGTH 2 +#define LSM303DLHC_TR_BIT 5 +#define LSM303DLHC_FTH_BIT 4 +#define LSM303DLHC_FTH_LENGTH 5 + +#define LSM303DLHC_FM_BYBASS 0b00 +#define LSM303DLHC_FM_FIFO 0b01 +#define LSM303DLHC_FM_STREAM 0b10 +#define LSM303DLHC_FM_TRIGGER 0b11 +#define LSM303DLHC_TR_INT1 0 +#define LSM303DLHC_TR_INT2 1 + +//FIFO_SRC_REG_A +#define LSM303DLHC_WTM_BIT 7 +#define LSM303DLHC_OVRN_FIFO_BIT 6 +#define LSM303DLHC_EMPTY_BIT 5 +#define LSM303DLHC_FSS_BIT 4 +#define LSM303DLHC_FSS_LENGTH 5 + +//INT1_CFG_A +#define LSM303DLHC_INT1_AOI_BIT 7 +#define LSM303DLHC_INT1_6D_BIT 6 +#define LSM303DLHC_INT1_ZHIE_ZUPE_BIT 5 +#define LSM303DLHC_INT1_ZLIE_ZDOWNE_BIT 4 +#define LSM303DLHC_INT1_YHIE_YUPE_BIT 3 +#define LSM303DLHC_INT1_YLIE_YDOWNE_BIT 2 +#define LSM303DLHC_INT1_XHIE_XUPE_BIT 1 +#define LSM303DLHC_INT1_XLIE_XDOWNE_BIT 0 + +//INT1_SRC_A +#define LSM303DLHC_INT1_IA_BIT 6 +#define LSM303DLHC_INT1_ZH_BIT 5 +#define LSM303DLHC_INT1_ZL_BIT 4 +#define LSM303DLHC_INT1_YH_BIT 3 +#define LSM303DLHC_INT1_YL_BIT 2 +#define LSM303DLHC_INT1_XH_BIT 1 +#define LSM303DLHC_INT1_XL_BIT 0 + +//INT1_THS_A +#define LSM303DLHC_INT1_THS_BIT 6 +#define LSM303DLHC_INT1_THS_LENGTH 7 + +//INT1_DURATION_A +#define LSM303DLHC_INT1_DURATION_BIT 6 +#define LSM303DLHC_INT1_DURATION_LENGTH 7 + +//INT2_CFG_A +#define LSM303DLHC_INT2_AOI_BIT 7 +#define LSM303DLHC_INT2_6D_BIT 6 +#define LSM303DLHC_INT2_ZHIE_BIT 5 +#define LSM303DLHC_INT2_ZLIE_BIT 4 +#define LSM303DLHC_INT2_YHIE_BIT 3 +#define LSM303DLHC_INT2_YLIE_BIT 2 +#define LSM303DLHC_INT2_XHIE_BIT 1 +#define LSM303DLHC_INT2_XLIE_BIT 0 + +//INT2_SRC_A +#define LSM303DLHC_INT2_IA_BIT 6 +#define LSM303DLHC_INT2_ZH_BIT 5 +#define LSM303DLHC_INT2_ZL_BIT 4 +#define LSM303DLHC_INT2_YH_BIT 3 +#define LSM303DLHC_INT2_YL_BIT 2 +#define LSM303DLHC_INT2_XH_BIT 1 +#define LSM303DLHC_INT2_XL_BIT 0 + +//INT2_THS_A +#define LSM303DLHC_INT2_THS_BIT 6 +#define LSM303DLHC_INT2_THS_LENGTH 7 + +//INT2_DURATION_A +#define LSM303DLHC_INT2_DURATION_BIT 6 +#define LSM303DLHC_INT2_DURATION_LENGTH 7 + +//CLICK_CFG_A +#define LSM303DLHC_CLICK_ZD_BIT 5 +#define LSM303DLHC_CLICK_ZS_BIT 4 +#define LSM303DLHC_CLICK_YD_BIT 3 +#define LSM303DLHC_CLICK_YS_BIT 2 +#define LSM303DLHC_CLICK_XD_BIT 1 +#define LSM303DLHC_CLICK_XS_BIT 0 + +//CLICK_SRC_A +#define LSM303DLHC_CLICK_IA_BIT 6 +#define LSM303DLHC_CLICK_DCLICK_BIT 5 +#define LSM303DLHC_CLICK_SCLICK_BIT 4 +#define LSM303DLHC_CLICK_SIGN_BIT 3 +#define LSM303DLHC_CLICK_Z_BIT 2 +#define LSM303DLHC_CLICK_Y_BIT 1 +#define LSM303DLHC_CLICK_X_BIT 0 + +//CLICK_THS_A +#define LSM303DLHC_CLICK_THS_BIT 6 +#define LSM303DLHC_CLICK_THS_LENGTH 7 + +//TIME_LIMIT_A +#define LSM303DLHC_TLI_BIT 6 +#define LSM303DLHC_TLI_LENGTH 7 + +//TIME_LATENCY_A + +//TIME_WINDOW_A + +//CRA_REG_M +#define LSM303DLHC_TEMP_EN_BIT 7 +#define LSM303DLHC_DO_BIT 4 +#define LSM303DLHC_DO_LENGTH 3 + +#define LSM303DLHC_DO_RATE_0 0b000 +#define LSM303DLHC_DO_RATE_1 0b001 +#define LSM303DLHC_DO_RATE_3 0b010 +#define LSM303DLHC_DO_RATE_7 0b011 +#define LSM303DLHC_DO_RATE_15 0b100 +#define LSM303DLHC_DO_RATE_30 0b101 +#define LSM303DLHC_DO_RATE_75 0b110 +#define LSM303DLHC_DO_RATE_220 0b111 + +//CRB_REG_M +#define LSM303DLHC_GN_BIT 7 +#define LSM303DLHC_GN_LENGTH 3 + +#define LSM303DLHC_GN_1100 0b001 +#define LSM303DLHC_GN_855 0b010 +#define LSM303DLHC_GN_670 0b011 +#define LSM303DLHC_GN_450 0b100 +#define LSM303DLHC_GN_400 0b101 +#define LSM303DLHC_GN_330 0b110 +#define LSM303DLHC_GN_230 0b111 + +//MR_REG_M +#define LSM303DLHC_MD_BIT 1 +#define LSM303DLHC_MD_LENGTH 2 + +#define LSM303DLHC_MD_CONTINUOUS 0b00 +#define LSM303DLHC_MD_SINGLE 0b01 +#define LSM303DLHC_MD_SLEEP 0b10 + +//OUT_X_H_M +//OUT_X_L_M +//OUT_Y_H_M +//OUT_Y_L_M +//OUT_Z_H_M +//OUT_Z_L_M + +//SR_REG_M +#define LSM303DLHC_M_DRDY_BIT 0 +#define LSM303DLHC_M_LOCK_BIT 1 + +//IRA_REG_M +//IRB_REG_M +//IRC_REG_M + +//TEMP_OUT_H_M +//TEMP_OUT_L_M + + + +class LSM303DLHC { + public: + LSM303DLHC(); + LSM303DLHC(uint8_t addressA, uint8_t addressM); + + void initialize(); + bool testConnection(); + +// ---------------------------------------------------------------------------- +// STUB TODO: +// Declare methods to fully cover all available functionality provided by the +// device, according to the datasheet and/or register map. Unless there is very +// clear reason not to, try to follow the get/set naming convention for all +// values, for instance: +// - uint8_t getThreshold() +// - void setThreshold(uint8_t threshold) +// - uint8_t getRate() +// - void setRate(uint8_t rate) +// +// Some methods may be named differently if it makes sense. As long as all +// functionality is covered, that's the important part. The methods here are +// only examples and should not be kept for your real device. +// ---------------------------------------------------------------------------- + //CTRL_REG1_A, r/w + void setAccelOutputDataRate(uint16_t rate); + uint16_t getAccelOutputDataRate(); + void setAccelLowPowerEnabled(bool enabled); + bool getAccelLowPowerEnabled(); + void setAccelZEnabled(bool enabled); + bool getAccelZEnabled(); + void setAccelYEnabled(bool enabled); + bool getAccelYEnabled(); + void setAccelXEnabled(bool enabled); + bool getAccelXEnabled(); + + //CTRL_REG2_A r/w + void setAccelHighPassMode(uint8_t mode); + uint8_t getAccelHighPassMode(); + void setAccelHighPassFilterCutOffFrequencyLevel(uint8_t level); + uint8_t getAccelHighPassFilterCutOffFrequencyLevel(); + + + //CTRL_REG3_A r/w + void setAccelINT1ClickEnabled(bool enabled); //routes Click interrupt to INT1 pin + bool getAccelINT1ClickEnabled(); + void setAccelINT1AOI1Enabled(bool enabled); //routes AOI1 interrupt to INT1 pin + bool getAccelINT1AOI1Enabled(); + void setAccelINT1AOI2Enabled(bool enabled); //routes AOI2 interrupt to INT1 pin + bool getAccelINT1AOI2Enabled(); + void setAccelINT1DataReady1Enabled(bool enabled); //routes DataReady1 int to INT1.. + bool getAccelINT1DataReady1Enabled(); + void setAccelINT1DataReady2Enabled(bool enabled); //routes DataReady2 int to INT1.. + bool getAccelINT1DataReady2Enabled(); + void setAccelINT1FIFOWatermarkEnabled(bool enabled);//routes FIFO WTM int to INT1 pin + bool getAccelINT1FIFOWatermarkEnabled(); + void setAccelINT1FIFOOverunEnabled(bool enabled);//routes FIFO Overrun int to INT1.. + bool getAccelINT1FIFOOverunEnabled(); + + //CTRL_REG4_A r/w + void setAccelBlockDataUpdateEnabled(bool enabled); + bool getAccelBlockDataUpdateEnabled(); + void setAccelEndianMode(bool endianness); + bool getAccelEndianMode(); + void setAccelFullScale(uint8_t scale); + uint8_t getAccelFullScale(); + void setAccelHighResOutputEnabled(bool enabled); + bool getAccelHighResOutputEnabled(); + void setAccelSPIMode(bool mode); + bool getAccelSPIMode(); + + //CTRL_REG5_A r/w + void rebootAccelMemoryContent(); + void setAccelFIFOEnabled(bool enabled); + bool getAccelFIFOEnabled(); + void setAccelInterrupt1RequestLatched(bool latched); + bool getAccelInterrupt1RequestLatched(); + void setAccelInterrupt2RequestLatched(bool latched); + bool getAccelInterrupt2RequestLatched(); + void setAccelDetect4DInterrupt1Enabled(bool enabled); + bool getAccelDetect4DInterrupt1Enabled(); + void setAccelDetect4DInterrupt2Enabled(bool enabled); + bool getAccelDetect4DInterrupt2Enabled(); + + //CTRL_REG6_A r/w + void setAccelINT2ClickEnabled(bool enabled); + bool getAccelINT2ClickEnabled(); + void setAccelINT2Interrupt1Enabled(bool enabled); + bool getAccelINT2Interrupt1Enabled(); + void setAccelINT2Interrupt2Enabled(bool enabled); + bool getAccelINT2Interrupt2Enabled(); + + void setAccelRebootMemoryContentINT2Enabled(bool enabled); + bool getAccelRebootMemoryContentINT2Enabled(); + // void setAccelActiveFunctionStatusINT2Enabled(bool enabled); + // bool getAccelActiveFunctionStatusINT2Enabled(); + void setAccelInterruptActiveLowEnabled(bool enabled); + bool getAccelInterruptActiveLowEnabled(); + + //REFERENCE_A r/w + void setAccelInterruptReference(uint8_t reference); + uint8_t getAccelInterruptReference(); + + //STATUS_REG_A r + bool getAccelXYZOverrun(); + bool getAccelZOverrun(); + bool getAccelYOverrun(); + bool getAccelXOverrun(); + bool getAccelXYZDataAvailable(); + bool getAccelZDataAvailable(); + bool getAccelYDataAvailable(); + bool getAccelXDataAvailable(); + + //OUT_*_A, r + // OUT_* registers, read-only + void getAcceleration(int16_t* x, int16_t* y, int16_t* z); + int16_t getAccelerationX(); + int16_t getAccelerationY(); + int16_t getAccelerationZ(); + + //FIFO_CTRL_REG_A, rw + void setAccelFIFOMode(uint8_t mode); + uint8_t getAccelFIFOMode(); + void setAccelFIFOTriggerINT(bool tirgger); + bool getAccelFIFOTriggerINT(); + void setAccelFIFOThreshold(uint8_t fth); + uint8_t getAccelFIFOThreshold(); + + //FIFO_SRC_REG_A, r + bool getAccelFIFOAtWatermark(); + bool getAccelFIFOOverrun(); + bool getAccelFIFOEmpty(); + uint8_t getAccelFIFOStoredSamples(); + + //Int1_CFG_A, wr + void setAccelInterrupt1Combination(bool combination); + bool getAccelInterrupt1Combination(); + void setAccelInterrupt16DEnabled(bool enabled); + bool getAccelInterrupt16DEnabled(); + + void setAccelZHighUpInterrupt1Enabled(bool enabled); + bool getAccelZHighUpInterrupt1Enabled(); + void setAccelYHighUpInterrupt1Enabled(bool enabled); + bool getAccelYHighUpInterrupt1Enabled(); + void setAccelXHighUpInterrupt1Enabled(bool enabled); + bool getAccelXHighUpInterrupt1Enabled(); + void setAccelZLowDownInterrupt1Enabled(bool enabled); + bool getAccelZLowDownInterrupt1Enabled(); + void setAccelYLowDownInterrupt1Enabled(bool enabled); + bool getAccelYLowDownInterrupt1Enabled(); + void setAccelXLowDownInterrupt1Enabled(bool enabled); + bool getAccelXLowDownInterrupt1Enabled(); + + //INT1_SRC_A, r + uint8_t getAccelInterrupt1Source(); //this should be read entirely since it clears + + //INT1_THS_A, rw + void setAccelInterrupt1Threshold(uint8_t value); + uint8_t getAccelInterupt1Threshold(); + + //INT1_DURATION_A, rw + void setAccelInterrupt1Duration(uint8_t value); + uint8_t getAccelInterrupt1Duration(); + + //INT2_CFG_A, rw + void setAccelInterrupt2Combination(bool combination); + bool getAccelInterrupt2Combination(); + void setAccelInterrupt26DEnabled(bool enabled); + bool getAccelInterrupt26DEnabled(); + + void setAccelZHighInterrupt2Enabled(bool enabled); + bool getAccelZHighInterrupt2Enabled(); + void setAccelYHighInterrupt2Enabled(bool enabled); + bool getAccelYHighInterrupt2Enabled(); + void setAccelXHighInterrupt2Enabled(bool enabled); + bool getAccelXHighInterrupt2Enabled(); + void setAccelZLowInterrupt2Enabled(bool enabled); + bool getAccelZLowInterrupt2Enabled(); + void setAccelYLowInterrupt2Enabled(bool enabled); + bool getAccelYLowInterrupt2Enabled(); + void setAccelXLowInterrupt2Enabled(bool enabled); + bool getAccelXLowInterrupt2Enabled(); + + //INT2_SRC_A, r + uint8_t getAccelInterrupt2Source(); //this should be read entirely since it clears + + //INT2_THS_A, rw + void setAccelInterrupt2Threshold(uint8_t value); + uint8_t getAccelInterupt2Threshold(); + + //INT2_DURATION_A, rw + void setAccelInterrupt2Duration(uint8_t value); + uint8_t getAccelInterrupt2Duration(); + + //CLICK_CFG_A, rw + void setAccelZDoubleClickEnabled(bool enabled); + bool getAccelZDoubleClickEnabled(); + void setAccelZSingleClickEnabled(bool enabled); + bool getAccelZSingleClickEnabled(); + void setAccelYDoubleClickEnabled(bool enabled); + bool getAccelYDoubleClickEnabled(); + void setAccelYSingleClickEnabled(bool enabled); + bool getAccelYSingleClickEnabled(); + void setAccelXDoubleClickEnabled(bool enabled); + bool getAccelXDoubleClickEnabled(); + void setAccelXSingleClickEnabled(bool enabled); + bool getAccelXSingleClickEnabled(); + + //CLICK_SRC_A, rw? + //I think the documentation is incorrect for DCLICK + //and SCLICK. I think these are flags, not enables. + //For now we will assume this is readonly and simply + //grab the whole byte consistant with the interrupt + //source registers. + uint8_t getAccelClickSource(); + + //CLICK_THS_A, rw + void setAcceLClickThreshold(uint8_t value); + uint8_t getAccelClickThreshold(); + + //TIME_LIMIT_A, rw + void setAcceLClickTimeLimit(uint8_t value); + uint8_t getAccelClickTimeLimit(); + + //TIME_LATENCY_A, rw + void setAcceLClickTimeLatency(uint8_t value); + uint8_t getAccelClickTimeLatency(); + + //TIME_WINDOW_A, rw + void setAcceLClickTimeWindow(uint8_t value); + uint8_t getAccelClickTimeWindow(); + + //CRA_REG_M_A, rw + void setMagTemperatureEnabled(bool enabled); + bool getMagTemperatureEnabled(); + void setMagOutputDataRate(uint8_t rate); + uint8_t getMagOutputDataRate(); + + //CRB_REG_M, rw + void setMagGain(uint16_t gain); + uint16_t getMagGain(); + + //MR_REG_M, rw + void setMagMode(uint8_t); + uint8_t getMagMode(); + + //OUT_____M, r + void getMag(int16_t* x, int16_t* y, int16_t* z); + int16_t getMagX(); + int16_t getMagY(); + int16_t getMagZ(); + + //SR_REG_M, r + bool getMagOutputDataRegisterLock(); + bool getMagDataReady(); + + //TEMP_OUT_*_M + int16_t getTemperature(); + + // WHO_AM_I register, read-only + uint8_t getDeviceID(); + +// ---------------------------------------------------------------------------- +// STUB TODO: +// Declare private object helper variables or local storage for particular +// device settings, if required. All devices need a "devAddr" variable to store +// the I2C slave address for easy access. Most devices also need a buffer for +// reads (the I2Cdev class' read methods use a pointer for the storage location +// of any read data). The buffer should be of type "uint8_t" if the device uses +// 8-bit registers, or type "uint16_t" if the device uses 16-bit registers. +// Many devices will not require more member variables than this. +// ---------------------------------------------------------------------------- + private: + uint8_t devAddrA; + uint8_t devAddrM; + uint8_t buffer[6]; + bool endianMode; +}; + +#endif /* _LSM303DLHC_H_ */ diff --git a/libraries/LSM303DLHC/examples/LSM303DLHC_test/LSM303DLHC_test.ino b/libraries/LSM303DLHC/examples/LSM303DLHC_test/LSM303DLHC_test.ino new file mode 100644 index 0000000..cea4e14 --- /dev/null +++ b/libraries/LSM303DLHC/examples/LSM303DLHC_test/LSM303DLHC_test.ino @@ -0,0 +1,148 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for LSM303DLHC class +// 3/10/2015 by Nate Costello +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2015-03-10 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Jonathan Arnett, 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 + +// I2Cdev and LSM303DLHC must be installed as libraries, or else the .cpp/.h files +// for both classes must be in the include path of your project +#include +#include + +// default address is 105 +// specific I2C address may be passed here +LSM303DLHC accelMag; + +int16_t ax, ay, az; +int16_t mx, my, mz; + +#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(9600); + + // initialize device + Serial.println("Initializing I2C devices..."); + accelMag.initialize(); + + // verify connection + Serial.println("Testing device connections..."); + Serial.println(accelMag.testConnection() ? "LSM303DLHC connection successful" : "LSM303DLHC connection failed"); + + // configure LED for output + pinMode(LED_PIN, OUTPUT); + + // set scale to 2Gs + accelMag.setAccelFullScale(2); + + // set accel data rate to 200hz + accelMag.setAccelOutputDataRate(200); + + // test scale + Serial.print("Accel Scale: "); + Serial.println(accelMag.getAccelFullScale()); + + // test data rate + Serial.print("Accel Output Data Rate: "); + Serial.println(accelMag.getAccelOutputDataRate()); + + // set mag data rate to 220hz + accelMag.setMagOutputDataRate(220); + + // test mag data rate + Serial.print("Mag Output Data Rate: "); + Serial.println(accelMag.getMagOutputDataRate()); + + //set mag gain + accelMag.setMagGain(1100); + + // test mag gain + Serial.print("Mag Gain: "); + Serial.println(accelMag.getMagGain()); + + //enable mag + accelMag.setMagMode(LSM303DLHC_MD_CONTINUOUS); + Serial.println(accelMag.getMagMode()); + + +} + +void loop() { + // read raw angular velocity measurements from device + accelMag.getAcceleration(&ax, &ay, &az); + accelMag.getMag(&mx, &my, &mz); + + // Serial.print("Accelation:\t"); + // Serial.print(ax,HEX); Serial.print("\t"); + // Serial.print(ay,HEX); Serial.print("\t"); + // Serial.print(az,HEX); + + // Serial.print(" Magnetic Field:\t"); + // Serial.print(mx,HEX); Serial.print("\t"); + // Serial.print(my,HEX); Serial.print("\t"); + // Serial.println(mz,HEX); + + // Serial.print("Accelation:\t"); + // Serial.print(ax); Serial.print("\t"); + // Serial.print(ay); Serial.print("\t"); + // Serial.print(az); + + // Serial.print(" Magnetic Field:\t"); + // Serial.print(mx); Serial.print("\t"); + // Serial.print(my); Serial.print("\t"); + // Serial.println(mz); + + Serial.print("Accelation:\t"); + Serial.print(ax*0.0000625F,4); Serial.print("\t"); + Serial.print(ay*0.0000625F,4); Serial.print("\t"); + Serial.print(az*0.0000625F,4); + + Serial.print(" Magnetic Field:\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); + + delay(1000); +} + + diff --git a/libraries/MPR121/MPR121.cpp b/libraries/MPR121/MPR121.cpp new file mode 100644 index 0000000..eb03d23 --- /dev/null +++ b/libraries/MPR121/MPR121.cpp @@ -0,0 +1,221 @@ +// I2Cdev library collection - MPR121 I2C device class header file +// Based on Freescale MPR121 datasheet rev. 2, 04/2010 and Freescale App Note 3944, rev 1 3/26/2010 +// 9/3/2011 by Andrew Schamp +// +// 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: +// 2011-09-03 - add callback support +// 2011-08-20 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Andrew Schamp + +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 "MPR121.h" +#include "I2Cdev.h" + +MPR121::MPR121(uint8_t address) : + m_devAddr(address) +{ + for (int ch = 0; ch < NUM_CHANNELS; ch++) { + m_callbackMap[ch][TOUCHED] = 0; + m_callbackMap[ch][RELEASED] = 0; + } +} + +void MPR121::initialize() +{ + // These are the configuration values recommended by app note AN3944 + // along with the description in the app note. + + // Section A + // Description: + // This group of settings controls the filtering of the system + // when the data is greater than the baseline. The setting used + // allows the filter to act quickly and adjust for environmental changes. + // Additionally, if calibration happens to take place while a touch occurs, + // the value will self adjust very quickly. This auto-recovery or snap back + // provides repeated false negative for a touch detection. + // Variation: + // As the filter is sensitive to setting changes, it is recommended + // that users read AN3891 before changing the values. + // In most cases these default values will work. + I2Cdev::writeByte(m_devAddr, MHD_RISING, 0x01); + I2Cdev::writeByte(m_devAddr, NHD_AMOUNT_RISING, 0x01); + I2Cdev::writeByte(m_devAddr, NCL_RISING, 0x00); + I2Cdev::writeByte(m_devAddr, FDL_RISING, 0x00); + + // Section B + // Description: + // This group of settings controls the filtering of the system + // when the data is less than the baseline. The settings slow down + // the filter as the negative charge is in the same direction + // as a touch. By slowing down the filter, touch signals + // are "rejected" by the baseline filter. While at the same time + // long term environmental changes that occur slower than + // at a touch are accepted. This low pass filter both allows + // for touches to be detected properly while preventing false + // positives by passing environmental changes through the filter. + // Variation: + // As the filter is sensitive to setting changes, it is recommended + // that users read AN3891 before changing the values. + // In most cases these default values will work. + I2Cdev::writeByte(m_devAddr, MHD_FALLING, 0x01); + I2Cdev::writeByte(m_devAddr, NHD_AMOUNT_FALLING, 0x01); + I2Cdev::writeByte(m_devAddr, NCL_FALLING, 0xFF); + I2Cdev::writeByte(m_devAddr, FDL_FALLING, 0x02); + + // Section C + // Description: + // The touch threshold registers set the minimum delta from the baseline + // when a touch is detected. The value 0x0F (or 15 in decimal) is + // an estimate of the minimum value for touch. Most electrodes will + // work with this value even if they vary greatly in size and shape. + // The value of 0x0A or 10 in the release threshold register allowed + // for hysteresis in the touch detection. + // Variation: + // For very small electrodes, smaller values can be used and for + // very large electrodes the reverse is true. One easy method is + // to view the deltas actually seen in a system and set the touch + // at 80% and release at 70% of delta for good performance. + I2Cdev::writeByte(m_devAddr, ELE0_TOUCH_THRESHOLD, TOUCH_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE0_RELEASE_THRESHOLD, RELEASE_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE1_TOUCH_THRESHOLD, TOUCH_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE1_RELEASE_THRESHOLD, RELEASE_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE2_TOUCH_THRESHOLD, TOUCH_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE2_RELEASE_THRESHOLD, RELEASE_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE3_TOUCH_THRESHOLD, TOUCH_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE3_RELEASE_THRESHOLD, RELEASE_THRESHOLD); + + // TODO: enable setting these channels to capsense or GPIO + // for now they are all capsense + I2Cdev::writeByte(m_devAddr, ELE4_TOUCH_THRESHOLD, TOUCH_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE4_RELEASE_THRESHOLD, RELEASE_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE5_TOUCH_THRESHOLD, TOUCH_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE5_RELEASE_THRESHOLD, RELEASE_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE6_TOUCH_THRESHOLD, TOUCH_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE6_RELEASE_THRESHOLD, RELEASE_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE7_TOUCH_THRESHOLD, TOUCH_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE7_RELEASE_THRESHOLD, RELEASE_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE8_TOUCH_THRESHOLD, TOUCH_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE8_RELEASE_THRESHOLD, RELEASE_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE9_TOUCH_THRESHOLD, TOUCH_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE9_RELEASE_THRESHOLD, RELEASE_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE10_TOUCH_THRESHOLD, TOUCH_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE10_RELEASE_THRESHOLD, RELEASE_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE11_TOUCH_THRESHOLD, TOUCH_THRESHOLD); + I2Cdev::writeByte(m_devAddr, ELE11_RELEASE_THRESHOLD, RELEASE_THRESHOLD); + + // Section D + // Description: + // There are three settings embedded in this register so it is + // only necessary to pay attention to one. The ESI controls + // the sample rate of the device. In the default, the setting + // used is 0x00 for 1ms sample rate. Since the SFI is set to 00, + // resulting in 4 samples averaged, the response time will be 4 ms. + // Variation: + // To save power, the 1 ms can be increased to 128 ms by increasing + // the setting to 0x07. The values are base 2 exponential, thus + // 0x01 = 2ms, 0x02 = 4 ms; and so on to 0x07 = 128 ms. Most of + // the time, 0x04 results in the best compromise between power + // consumption and response time. + I2Cdev::writeByte(m_devAddr, FILTER_CONFIG, 0x04); + + // Section E + // Description: + // This register controls the number of electrodes being enabled + // and the mode the device is in. There are only two modes, + // Standby (when the value is 0x00) and Run (when the value of + // the lower bit is non-zero). The default value shown enables + // all 12 electrodes by writing decimal 12 or hex 0x0C to the register. + // Typically other registers cannot be changed while the part is running, + // so this register should always be written last. + // Variation: + // During debug of a system, this register will change between + // the number of electrodes and 0x00 every time a register needs + // to change. In a production system, this register will only need + // to be written when the mode is changed from Standby to Run or vice versa. + I2Cdev::writeByte(m_devAddr, ELECTRODE_CONFIG, 0x0C); + + // Section F + // Description: + // These are the settings used for the Auto Configuration. They enable + // AUTO-CONFIG and AUTO_RECONFIG. In addition, they set the target + // rate for the baseline. The upper limit is set to 190, the target + // is set to 180 and the lower limit is set to 140. + // Variation: + // In most cases these values will never need to be changed, but if + // a case arises, a full description is found in application note AN3889. + //I2Cdev::writeByte(m_devAddr, AUTO_CONFIG_CONTROL_0, 0x0B); + //I2Cdev::writeByte(m_devAddr, AUTO_CONFIG_USL, 0x9C); + //I2Cdev::writeByte(m_devAddr, AUTO_CONFIG_LSL, 0x65); + //I2Cdev::writeByte(m_devAddr, AUTO_CONFIG_TARGET_LEVEL, 0x8C); + +} + +// check to see if the filter configuration register contains 0x04, +// which is the default powerup value, and which we don't change in this library +bool MPR121::testConnection() { + uint8_t buf = 0; + I2Cdev::readByte(m_devAddr, FILTER_CONFIG, &buf); + return buf == 0x04; // default value, we don't change +} + +bool MPR121::getTouchStatus(uint8_t channel) { + const uint8_t statusReg = (channel < 8) ? ELE0_ELE7_TOUCH_STATUS : ELE8_ELE11_ELEPROX_TOUCH_STATUS; + uint8_t buf = 0; + I2Cdev::readByte(m_devAddr, statusReg, &buf); + const bool touchActive = (channel < 8) ? (buf & (1 << channel)) > 0 : (buf & (1 << (channel - 8))) > 0; + return touchActive; +} + +uint16_t MPR121::getTouchStatus() { + uint16_t statusBuf; + uint8_t buf; + I2Cdev::readByte(m_devAddr, ELE0_ELE7_TOUCH_STATUS, &buf); + statusBuf = buf; + I2Cdev::readByte(m_devAddr, ELE8_ELE11_ELEPROX_TOUCH_STATUS, &buf); + statusBuf += (buf << 8); + return statusBuf; +} + +void MPR121::setCallback(uint8_t channel, EventType event, CallbackPtrType callbackPtr) { + m_callbackMap[channel][event] = callbackPtr; +} + +void MPR121::serviceCallbacks() { + for (uint8_t channel = 0; channel < NUM_CHANNELS; channel++) { + bool touchStatus = getTouchStatus(channel); + if (touchStatus != m_prevTouchStatus[channel]) { + for (uint8_t type = 0; type < NUM_EVENTS; type++) { + const CallbackPtrType cb = touchStatus ? m_callbackMap[channel][TOUCHED] : m_callbackMap[channel][RELEASED]; + if (cb != 0) { + cb(); + } + } + m_prevTouchStatus[channel] = touchStatus; + } + } +} diff --git a/libraries/MPR121/MPR121.h b/libraries/MPR121/MPR121.h new file mode 100644 index 0000000..640e061 --- /dev/null +++ b/libraries/MPR121/MPR121.h @@ -0,0 +1,225 @@ +// I2Cdev library collection - MPR121 I2C device class header file +// Based on Freescale MPR121 datasheet rev. 2, 04/2010 and Freescale App Note 3944, rev 1 3/26/2010 +// 9/3/2011 by Andrew Schamp +// +// 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: +// 2011-09-03 - add callback support +// 2011-08-20 - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 Andrew Schamp + +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 _MPR121_h_ +#define _MPR121_h_ + +#include + +// this is the 7-bit I2C address with the ADDR pin grounded +#define MPR121_DEFAULT_ADDRESS 0x5A + +// MPR121 Registers (from data sheet) +#define ELE0_ELE7_TOUCH_STATUS 0x00 +#define ELE8_ELE11_ELEPROX_TOUCH_STATUS 0x01 + +#define ELE0_7_OOR_STATUS 0x02 +#define ELE8_11_ELEPROX_OOR_STATUS 0x03 + +#define ELE0_FILTERED_DATA_LSB 0x04 +#define ELE0_FILTERED_DATA_MSB 0x05 +#define ELE1_FILTERED_DATA_LSB 0x06 +#define ELE1_FILTERED_DATA_MSB 0x07 +#define ELE2_FILTERED_DATA_LSB 0x08 +#define ELE2_FILTERED_DATA_MSB 0x09 +#define ELE3_FILTERED_DATA_LSB 0x0A +#define ELE3_FILTERED_DATA_MSB 0x0B +#define ELE4_FILTERED_DATA_LSB 0x0C +#define ELE4_FILTERED_DATA_MSB 0x0D +#define ELE5_FILTERED_DATA_LSB 0x0E +#define ELE5_FILTERED_DATA_MSB 0x0F +#define ELE6_FILTERED_DATA_LSB 0x10 +#define ELE6_FILTERED_DATA_MSB 0x11 +#define ELE7_FILTERED_DATA_LSB 0x12 +#define ELE7_FILTERED_DATA_MSB 0x13 +#define ELE8_FILTERED_DATA_LSB 0x14 +#define ELE8_FILTERED_DATA_MSB 0x15 +#define ELE9_FILTERED_DATA_LSB 0x16 +#define ELE9_FILTERED_DATA_MSB 0x17 +#define ELE10_FILTERED_DATA_LSB 0x18 +#define ELE10_FILTERED_DATA_MSB 0x19 +#define ELE11_FILTERED_DATA_LSB 0x1A +#define ELE11_FILTERED_DATA_MSB 0x1B +#define ELEPROX_FILTERED_DATA_LSB 0x1C +#define ELEPROX_FILTERED_DATA_MSB 0x1D + +#define ELE0_BASELINE_VALUE 0x1E +#define ELE1_BASELINE_VALUE 0x1F +#define ELE2_BASELINE_VALUE 0x20 +#define ELE3_BASELINE_VALUE 0x21 +#define ELE4_BASELINE_VALUE 0x22 +#define ELE5_BASELINE_VALUE 0x23 +#define ELE6_BASELINE_VALUE 0x24 +#define ELE7_BASELINE_VALUE 0x25 +#define ELE8_BASELINE_VALUE 0x26 +#define ELE9_BASELINE_VALUE 0x27 +#define ELE10_BASELINE_VALUE 0x28 +#define ELE11_BASELINE_VALUE 0x29 +#define ELEPROX_BASELINE_VALUE 0x2A + +#define MHD_RISING 0x2B +#define NHD_AMOUNT_RISING 0x2C +#define NCL_RISING 0x2D +#define FDL_RISING 0x2E +#define MHD_FALLING 0x2F +#define NHD_AMOUNT_FALLING 0x30 +#define NCL_FALLING 0x31 +#define FDL_FALLING 0x32 +#define NHD_AMOUNT_TOUCHED 0x33 +#define NCL_TOUCHED 0x34 +#define FDL_TOUCHED 0x35 +#define ELEPROX_MHD_RISING 0x36 +#define ELEPROX_NHD_AMOUNT_RISING 0x37 +#define ELEPROX_NCL_RISING 0x38 +#define ELEPROX_FDL_RISING 0x39 +#define ELEPROX_MHD_FALLING 0x3A +#define ELEPROX_NHD_AMOUNT_FALLING 0x3B +#define ELEPROX_FDL_FALLING 0x3C +#define ELEPROX_NHD_AMOUNT_TOUCHED 0x3E +#define ELEPROX_NCL_TOUCHED 0x3F +#define ELEPROX_FDL_TOUCHED 0x40 + +#define ELE0_TOUCH_THRESHOLD 0x41 +#define ELE0_RELEASE_THRESHOLD 0x42 +#define ELE1_TOUCH_THRESHOLD 0x43 +#define ELE1_RELEASE_THRESHOLD 0x44 +#define ELE2_TOUCH_THRESHOLD 0x45 +#define ELE2_RELEASE_THRESHOLD 0x46 +#define ELE3_TOUCH_THRESHOLD 0x47 +#define ELE3_RELEASE_THRESHOLD 0x48 +#define ELE4_TOUCH_THRESHOLD 0x49 +#define ELE4_RELEASE_THRESHOLD 0x4A +#define ELE5_TOUCH_THRESHOLD 0x4B +#define ELE5_RELEASE_THRESHOLD 0x4C +#define ELE6_TOUCH_THRESHOLD 0x4D +#define ELE6_RELEASE_THRESHOLD 0x4E +#define ELE7_TOUCH_THRESHOLD 0x4F +#define ELE7_RELEASE_THRESHOLD 0x50 +#define ELE8_TOUCH_THRESHOLD 0x51 +#define ELE8_RELEASE_THRESHOLD 0x52 +#define ELE9_TOUCH_THRESHOLD 0x53 +#define ELE9_RELEASE_THRESHOLD 0x54 +#define ELE10_TOUCH_THRESHOLD 0x55 +#define ELE10_RELEASE_THRESHOLD 0x56 +#define ELE11_TOUCH_THRESHOLD 0x57 +#define ELE11_RELEASE_THRESHOLD 0x58 +#define ELEPROX_TOUCH_THRESHOLD 0x59 +#define ELEPROX_RELEASE_THRESHOLD 0x5A +#define DEBOUNCE_TOUCH_AND_RELEASE 0x5B +#define AFE_CONFIGURATION 0x5C + +#define FILTER_CONFIG 0x5D +#define ELECTRODE_CONFIG 0x5E +#define ELE0_CURRENT 0x5F +#define ELE1_CURRENT 0x60 +#define ELE2_CURRENT 0x61 +#define ELE3_CURRENT 0x62 +#define ELE4_CURRENT 0x63 +#define ELE5_CURRENT 0x64 +#define ELE6_CURRENT 0x65 +#define ELE7_CURRENT 0x66 +#define ELE8_CURRENT 0x67 +#define ELE9_CURRENT 0x68 +#define ELE10_CURRENT 0x69 +#define ELE11_CURRENT 0x6A +#define ELEPROX_CURRENT 0x6B + +#define ELE0_ELE1_CHARGE_TIME 0x6C +#define ELE2_ELE3_CHARGE_TIME 0x6D +#define ELE4_ELE5_CHARGE_TIME 0x6E +#define ELE6_ELE7_CHARGE_TIME 0x6F +#define ELE8_ELE9_CHARGE_TIME 0x70 +#define ELE10_ELE11_CHARGE_TIME 0x71 +#define ELEPROX_CHARGE_TIME 0x72 + +#define GPIO_CONTROL_0 0x73 +#define GPIO_CONTROL_1 0x74 +#define GPIO_DATA 0x75 +#define GPIO_DIRECTION 0x76 +#define GPIO_ENABLE 0x77 +#define GPIO_SET 0x78 +#define GPIO_CLEAR 0x79 +#define GPIO_TOGGLE 0x7A +#define AUTO_CONFIG_CONTROL_0 0x7B +#define AUTO_CONFIG_CONTROL_1 0x7C +#define AUTO_CONFIG_USL 0x7D +#define AUTO_CONFIG_LSL 0x7E +#define AUTO_CONFIG_TARGET_LEVEL 0x7F + +// Other Constants +// these are suggested values from app note 3944 +#define TOUCH_THRESHOLD 0x0F +#define RELEASE_THRESHOLD 0x0A +#define NUM_CHANNELS 12 + +class MPR121 +{ + public: + enum EventType { + TOUCHED = 0, + RELEASED = 1, + NUM_EVENTS = 2 + }; + + typedef void (*CallbackPtrType)(void); + + // constructor + // takes a 7-b I2C address to use (0x5A by default, assumes addr pin grounded) + MPR121(uint8_t address = MPR121_DEFAULT_ADDRESS); + + // write the configuration registers in accordance with the datasheet and app note 3944 + void initialize(); + + // returns true if the device is responding on the I2C bus + bool testConnection(); + + // getTouchStatus returns the touch status for the given channel (0 - 11) + bool getTouchStatus(uint8_t channel); + // when not given a channel, returns a bitfield of all touch channels. + uint16_t getTouchStatus(); + + void setCallback(uint8_t channel, EventType event, CallbackPtrType callbackPtr); + + void serviceCallbacks(); + + private: + uint8_t m_devAddr; // contains the I2C address of the device + CallbackPtrType m_callbackMap[NUM_CHANNELS][NUM_EVENTS]; + bool m_prevTouchStatus[NUM_CHANNELS]; + +}; + +#endif + diff --git a/libraries/MPR121/library.json b/libraries/MPR121/library.json new file mode 100644 index 0000000..afce11b --- /dev/null +++ b/libraries/MPR121/library.json @@ -0,0 +1,18 @@ +{ + "name": "I2Cdevlib-MPR121", + "keywords": "touch, capacitance, proximity, sensor, i2cdevlib, i2c", + "description": "The MPR121 is a 12-bit proximity capacitive touch sensor", + "include": "Arduino/MPR121", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "dependencies": + { + "name": "I2Cdevlib-Core", + "frameworks": "arduino" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/MPU6050/MPU6050.cpp b/libraries/MPU6050/MPU6050.cpp new file mode 100644 index 0000000..d6ad205 --- /dev/null +++ b/libraries/MPU6050/MPU6050.cpp @@ -0,0 +1,3213 @@ +// I2Cdev library collection - MPU6050 I2C device class +// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00) +// 8/24/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// ... - ongoing debug release + +// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE +// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF +// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING. + +/* ============================================ +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. +=============================================== +*/ + +#include "MPU6050.h" + +/** Default constructor, uses default I2C address. + * @see MPU6050_DEFAULT_ADDRESS + */ +MPU6050::MPU6050() { + devAddr = MPU6050_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see MPU6050_DEFAULT_ADDRESS + * @see MPU6050_ADDRESS_AD0_LOW + * @see MPU6050_ADDRESS_AD0_HIGH + */ +MPU6050::MPU6050(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * This will activate the device and take it out of sleep mode (which must be done + * after start-up). This function also sets both the accelerometer and the gyroscope + * to their most sensitive settings, namely +/- 2g and +/- 250 degrees/sec, and sets + * the clock source to use the X Gyro for reference, which is slightly better than + * the default internal clock source. + */ +void MPU6050::initialize() { + setClockSource(MPU6050_CLOCK_PLL_XGYRO); + setFullScaleGyroRange(MPU6050_GYRO_FS_250); + setFullScaleAccelRange(MPU6050_ACCEL_FS_2); + setSleepEnabled(false); // thanks to Jack Elston for pointing this one out! +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool MPU6050::testConnection() { + return getDeviceID() == 0x34; +} + +// AUX_VDDIO register (InvenSense demo code calls this RA_*G_OFFS_TC) + +/** Get the auxiliary I2C supply voltage level. + * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to + * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to + * the MPU-6000, which does not have a VLOGIC pin. + * @return I2C supply voltage level (0=VLOGIC, 1=VDD) + */ +uint8_t MPU6050::getAuxVDDIOLevel() { + I2Cdev::readBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, buffer); + return buffer[0]; +} +/** Set the auxiliary I2C supply voltage level. + * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to + * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to + * the MPU-6000, which does not have a VLOGIC pin. + * @param level I2C supply voltage level (0=VLOGIC, 1=VDD) + */ +void MPU6050::setAuxVDDIOLevel(uint8_t level) { + I2Cdev::writeBit(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_PWR_MODE_BIT, level); +} + +// SMPLRT_DIV register + +/** Get gyroscope output rate divider. + * The sensor register output, FIFO output, DMP sampling, Motion detection, Zero + * Motion detection, and Free Fall detection are all based on the Sample Rate. + * The Sample Rate is generated by dividing the gyroscope output rate by + * SMPLRT_DIV: + * + * Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV) + * + * where Gyroscope Output Rate = 8kHz when the DLPF is disabled (DLPF_CFG = 0 or + * 7), and 1kHz when the DLPF is enabled (see Register 26). + * + * Note: The accelerometer output rate is 1kHz. This means that for a Sample + * Rate greater than 1kHz, the same accelerometer sample may be output to the + * FIFO, DMP, and sensor registers more than once. + * + * For a diagram of the gyroscope and accelerometer signal paths, see Section 8 + * of the MPU-6000/MPU-6050 Product Specification document. + * + * @return Current sample rate + * @see MPU6050_RA_SMPLRT_DIV + */ +uint8_t MPU6050::getRate() { + I2Cdev::readByte(devAddr, MPU6050_RA_SMPLRT_DIV, buffer); + return buffer[0]; +} +/** Set gyroscope sample rate divider. + * @param rate New sample rate divider + * @see getRate() + * @see MPU6050_RA_SMPLRT_DIV + */ +void MPU6050::setRate(uint8_t rate) { + I2Cdev::writeByte(devAddr, MPU6050_RA_SMPLRT_DIV, rate); +} + +// CONFIG register + +/** Get external FSYNC configuration. + * Configures the external Frame Synchronization (FSYNC) pin sampling. An + * external signal connected to the FSYNC pin can be sampled by configuring + * EXT_SYNC_SET. Signal changes to the FSYNC pin are latched so that short + * strobes may be captured. The latched FSYNC signal will be sampled at the + * Sampling Rate, as defined in register 25. After sampling, the latch will + * reset to the current FSYNC signal state. + * + * The sampled value will be reported in place of the least significant bit in + * a sensor data register determined by the value of EXT_SYNC_SET according to + * the following table. + * + *
+ * EXT_SYNC_SET | FSYNC Bit Location
+ * -------------+-------------------
+ * 0            | Input disabled
+ * 1            | TEMP_OUT_L[0]
+ * 2            | GYRO_XOUT_L[0]
+ * 3            | GYRO_YOUT_L[0]
+ * 4            | GYRO_ZOUT_L[0]
+ * 5            | ACCEL_XOUT_L[0]
+ * 6            | ACCEL_YOUT_L[0]
+ * 7            | ACCEL_ZOUT_L[0]
+ * 
+ * + * @return FSYNC configuration value + */ +uint8_t MPU6050::getExternalFrameSync() { + I2Cdev::readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, buffer); + return buffer[0]; +} +/** Set external FSYNC configuration. + * @see getExternalFrameSync() + * @see MPU6050_RA_CONFIG + * @param sync New FSYNC configuration value + */ +void MPU6050::setExternalFrameSync(uint8_t sync) { + I2Cdev::writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_EXT_SYNC_SET_BIT, MPU6050_CFG_EXT_SYNC_SET_LENGTH, sync); +} +/** Get digital low-pass filter configuration. + * The DLPF_CFG parameter sets the digital low pass filter configuration. It + * also determines the internal sampling rate used by the device as shown in + * the table below. + * + * Note: The accelerometer output rate is 1kHz. This means that for a Sample + * Rate greater than 1kHz, the same accelerometer sample may be output to the + * FIFO, DMP, and sensor registers more than once. + * + *
+ *          |   ACCELEROMETER    |           GYROSCOPE
+ * DLPF_CFG | Bandwidth | Delay  | Bandwidth | Delay  | Sample Rate
+ * ---------+-----------+--------+-----------+--------+-------------
+ * 0        | 260Hz     | 0ms    | 256Hz     | 0.98ms | 8kHz
+ * 1        | 184Hz     | 2.0ms  | 188Hz     | 1.9ms  | 1kHz
+ * 2        | 94Hz      | 3.0ms  | 98Hz      | 2.8ms  | 1kHz
+ * 3        | 44Hz      | 4.9ms  | 42Hz      | 4.8ms  | 1kHz
+ * 4        | 21Hz      | 8.5ms  | 20Hz      | 8.3ms  | 1kHz
+ * 5        | 10Hz      | 13.8ms | 10Hz      | 13.4ms | 1kHz
+ * 6        | 5Hz       | 19.0ms | 5Hz       | 18.6ms | 1kHz
+ * 7        |   -- Reserved --   |   -- Reserved --   | Reserved
+ * 
+ * + * @return DLFP configuration + * @see MPU6050_RA_CONFIG + * @see MPU6050_CFG_DLPF_CFG_BIT + * @see MPU6050_CFG_DLPF_CFG_LENGTH + */ +uint8_t MPU6050::getDLPFMode() { + I2Cdev::readBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, buffer); + return buffer[0]; +} +/** Set digital low-pass filter configuration. + * @param mode New DLFP configuration setting + * @see getDLPFBandwidth() + * @see MPU6050_DLPF_BW_256 + * @see MPU6050_RA_CONFIG + * @see MPU6050_CFG_DLPF_CFG_BIT + * @see MPU6050_CFG_DLPF_CFG_LENGTH + */ +void MPU6050::setDLPFMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, MPU6050_RA_CONFIG, MPU6050_CFG_DLPF_CFG_BIT, MPU6050_CFG_DLPF_CFG_LENGTH, mode); +} + +// GYRO_CONFIG register + +/** Get full-scale gyroscope range. + * The FS_SEL parameter allows setting the full-scale range of the gyro sensors, + * as described in the table below. + * + *
+ * 0 = +/- 250 degrees/sec
+ * 1 = +/- 500 degrees/sec
+ * 2 = +/- 1000 degrees/sec
+ * 3 = +/- 2000 degrees/sec
+ * 
+ * + * @return Current full-scale gyroscope range setting + * @see MPU6050_GYRO_FS_250 + * @see MPU6050_RA_GYRO_CONFIG + * @see MPU6050_GCONFIG_FS_SEL_BIT + * @see MPU6050_GCONFIG_FS_SEL_LENGTH + */ +uint8_t MPU6050::getFullScaleGyroRange() { + I2Cdev::readBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set full-scale gyroscope range. + * @param range New full-scale gyroscope range value + * @see getFullScaleRange() + * @see MPU6050_GYRO_FS_250 + * @see MPU6050_RA_GYRO_CONFIG + * @see MPU6050_GCONFIG_FS_SEL_BIT + * @see MPU6050_GCONFIG_FS_SEL_LENGTH + */ +void MPU6050::setFullScaleGyroRange(uint8_t range) { + I2Cdev::writeBits(devAddr, MPU6050_RA_GYRO_CONFIG, MPU6050_GCONFIG_FS_SEL_BIT, MPU6050_GCONFIG_FS_SEL_LENGTH, range); +} + +// SELF TEST FACTORY TRIM VALUES + +/** Get self-test factory trim value for accelerometer X axis. + * @return factory trim value + * @see MPU6050_RA_SELF_TEST_X + */ +uint8_t MPU6050::getAccelXSelfTestFactoryTrim() { + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_X, &buffer[0]); + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_A, &buffer[1]); + return (buffer[0]>>3) | ((buffer[1]>>4) & 0x03); +} + +/** Get self-test factory trim value for accelerometer Y axis. + * @return factory trim value + * @see MPU6050_RA_SELF_TEST_Y + */ +uint8_t MPU6050::getAccelYSelfTestFactoryTrim() { + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_Y, &buffer[0]); + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_A, &buffer[1]); + return (buffer[0]>>3) | ((buffer[1]>>2) & 0x03); +} + +/** Get self-test factory trim value for accelerometer Z axis. + * @return factory trim value + * @see MPU6050_RA_SELF_TEST_Z + */ +uint8_t MPU6050::getAccelZSelfTestFactoryTrim() { + I2Cdev::readBytes(devAddr, MPU6050_RA_SELF_TEST_Z, 2, buffer); + return (buffer[0]>>3) | (buffer[1] & 0x03); +} + +/** Get self-test factory trim value for gyro X axis. + * @return factory trim value + * @see MPU6050_RA_SELF_TEST_X + */ +uint8_t MPU6050::getGyroXSelfTestFactoryTrim() { + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_X, buffer); + return (buffer[0] & 0x1F); +} + +/** Get self-test factory trim value for gyro Y axis. + * @return factory trim value + * @see MPU6050_RA_SELF_TEST_Y + */ +uint8_t MPU6050::getGyroYSelfTestFactoryTrim() { + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_Y, buffer); + return (buffer[0] & 0x1F); +} + +/** Get self-test factory trim value for gyro Z axis. + * @return factory trim value + * @see MPU6050_RA_SELF_TEST_Z + */ +uint8_t MPU6050::getGyroZSelfTestFactoryTrim() { + I2Cdev::readByte(devAddr, MPU6050_RA_SELF_TEST_Z, buffer); + return (buffer[0] & 0x1F); +} + +// ACCEL_CONFIG register + +/** Get self-test enabled setting for accelerometer X axis. + * @return Self-test enabled value + * @see MPU6050_RA_ACCEL_CONFIG + */ +bool MPU6050::getAccelXSelfTest() { + I2Cdev::readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, buffer); + return buffer[0]; +} +/** Get self-test enabled setting for accelerometer X axis. + * @param enabled Self-test enabled value + * @see MPU6050_RA_ACCEL_CONFIG + */ +void MPU6050::setAccelXSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_XA_ST_BIT, enabled); +} +/** Get self-test enabled value for accelerometer Y axis. + * @return Self-test enabled value + * @see MPU6050_RA_ACCEL_CONFIG + */ +bool MPU6050::getAccelYSelfTest() { + I2Cdev::readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, buffer); + return buffer[0]; +} +/** Get self-test enabled value for accelerometer Y axis. + * @param enabled Self-test enabled value + * @see MPU6050_RA_ACCEL_CONFIG + */ +void MPU6050::setAccelYSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_YA_ST_BIT, enabled); +} +/** Get self-test enabled value for accelerometer Z axis. + * @return Self-test enabled value + * @see MPU6050_RA_ACCEL_CONFIG + */ +bool MPU6050::getAccelZSelfTest() { + I2Cdev::readBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, buffer); + return buffer[0]; +} +/** Set self-test enabled value for accelerometer Z axis. + * @param enabled Self-test enabled value + * @see MPU6050_RA_ACCEL_CONFIG + */ +void MPU6050::setAccelZSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ZA_ST_BIT, enabled); +} +/** Get full-scale accelerometer range. + * The FS_SEL parameter allows setting the full-scale range of the accelerometer + * sensors, as described in the table below. + * + *
+ * 0 = +/- 2g
+ * 1 = +/- 4g
+ * 2 = +/- 8g
+ * 3 = +/- 16g
+ * 
+ * + * @return Current full-scale accelerometer range setting + * @see MPU6050_ACCEL_FS_2 + * @see MPU6050_RA_ACCEL_CONFIG + * @see MPU6050_ACONFIG_AFS_SEL_BIT + * @see MPU6050_ACONFIG_AFS_SEL_LENGTH + */ +uint8_t MPU6050::getFullScaleAccelRange() { + I2Cdev::readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set full-scale accelerometer range. + * @param range New full-scale accelerometer range setting + * @see getFullScaleAccelRange() + */ +void MPU6050::setFullScaleAccelRange(uint8_t range) { + I2Cdev::writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_AFS_SEL_BIT, MPU6050_ACONFIG_AFS_SEL_LENGTH, range); +} +/** Get the high-pass filter configuration. + * The DHPF is a filter module in the path leading to motion detectors (Free + * Fall, Motion threshold, and Zero Motion). The high pass filter output is not + * available to the data registers (see Figure in Section 8 of the MPU-6000/ + * MPU-6050 Product Specification document). + * + * The high pass filter has three modes: + * + *
+ *    Reset: The filter output settles to zero within one sample. This
+ *           effectively disables the high pass filter. This mode may be toggled
+ *           to quickly settle the filter.
+ *
+ *    On:    The high pass filter will pass signals above the cut off frequency.
+ *
+ *    Hold:  When triggered, the filter holds the present sample. The filter
+ *           output will be the difference between the input sample and the held
+ *           sample.
+ * 
+ * + *
+ * ACCEL_HPF | Filter Mode | Cut-off Frequency
+ * ----------+-------------+------------------
+ * 0         | Reset       | None
+ * 1         | On          | 5Hz
+ * 2         | On          | 2.5Hz
+ * 3         | On          | 1.25Hz
+ * 4         | On          | 0.63Hz
+ * 7         | Hold        | None
+ * 
+ * + * @return Current high-pass filter configuration + * @see MPU6050_DHPF_RESET + * @see MPU6050_RA_ACCEL_CONFIG + */ +uint8_t MPU6050::getDHPFMode() { + I2Cdev::readBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, buffer); + return buffer[0]; +} +/** Set the high-pass filter configuration. + * @param bandwidth New high-pass filter configuration + * @see setDHPFMode() + * @see MPU6050_DHPF_RESET + * @see MPU6050_RA_ACCEL_CONFIG + */ +void MPU6050::setDHPFMode(uint8_t bandwidth) { + I2Cdev::writeBits(devAddr, MPU6050_RA_ACCEL_CONFIG, MPU6050_ACONFIG_ACCEL_HPF_BIT, MPU6050_ACONFIG_ACCEL_HPF_LENGTH, bandwidth); +} + +// FF_THR register + +/** Get free-fall event acceleration threshold. + * This register configures the detection threshold for Free Fall event + * detection. The unit of FF_THR is 1LSB = 2mg. Free Fall is detected when the + * absolute value of the accelerometer measurements for the three axes are each + * less than the detection threshold. This condition increments the Free Fall + * duration counter (Register 30). The Free Fall interrupt is triggered when the + * Free Fall duration counter reaches the time specified in FF_DUR. + * + * For more details on the Free Fall detection interrupt, see Section 8.2 of the + * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and + * 58 of this document. + * + * @return Current free-fall acceleration threshold value (LSB = 2mg) + * @see MPU6050_RA_FF_THR + */ +uint8_t MPU6050::getFreefallDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU6050_RA_FF_THR, buffer); + return buffer[0]; +} +/** Get free-fall event acceleration threshold. + * @param threshold New free-fall acceleration threshold value (LSB = 2mg) + * @see getFreefallDetectionThreshold() + * @see MPU6050_RA_FF_THR + */ +void MPU6050::setFreefallDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU6050_RA_FF_THR, threshold); +} + +// FF_DUR register + +/** Get free-fall event duration threshold. + * This register configures the duration counter threshold for Free Fall event + * detection. The duration counter ticks at 1kHz, therefore FF_DUR has a unit + * of 1 LSB = 1 ms. + * + * The Free Fall duration counter increments while the absolute value of the + * accelerometer measurements are each less than the detection threshold + * (Register 29). The Free Fall interrupt is triggered when the Free Fall + * duration counter reaches the time specified in this register. + * + * For more details on the Free Fall detection interrupt, see Section 8.2 of + * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56 + * and 58 of this document. + * + * @return Current free-fall duration threshold value (LSB = 1ms) + * @see MPU6050_RA_FF_DUR + */ +uint8_t MPU6050::getFreefallDetectionDuration() { + I2Cdev::readByte(devAddr, MPU6050_RA_FF_DUR, buffer); + return buffer[0]; +} +/** Get free-fall event duration threshold. + * @param duration New free-fall duration threshold value (LSB = 1ms) + * @see getFreefallDetectionDuration() + * @see MPU6050_RA_FF_DUR + */ +void MPU6050::setFreefallDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU6050_RA_FF_DUR, duration); +} + +// MOT_THR register + +/** Get motion detection event acceleration threshold. + * This register configures the detection threshold for Motion interrupt + * generation. The unit of MOT_THR is 1LSB = 2mg. Motion is detected when the + * absolute value of any of the accelerometer measurements exceeds this Motion + * detection threshold. This condition increments the Motion detection duration + * counter (Register 32). The Motion detection interrupt is triggered when the + * Motion Detection counter reaches the time count specified in MOT_DUR + * (Register 32). + * + * The Motion interrupt will indicate the axis and polarity of detected motion + * in MOT_DETECT_STATUS (Register 97). + * + * For more details on the Motion detection interrupt, see Section 8.3 of the + * MPU-6000/MPU-6050 Product Specification document as well as Registers 56 and + * 58 of this document. + * + * @return Current motion detection acceleration threshold value (LSB = 2mg) + * @see MPU6050_RA_MOT_THR + */ +uint8_t MPU6050::getMotionDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU6050_RA_MOT_THR, buffer); + return buffer[0]; +} +/** Set motion detection event acceleration threshold. + * @param threshold New motion detection acceleration threshold value (LSB = 2mg) + * @see getMotionDetectionThreshold() + * @see MPU6050_RA_MOT_THR + */ +void MPU6050::setMotionDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU6050_RA_MOT_THR, threshold); +} + +// MOT_DUR register + +/** Get motion detection event duration threshold. + * This register configures the duration counter threshold for Motion interrupt + * generation. The duration counter ticks at 1 kHz, therefore MOT_DUR has a unit + * of 1LSB = 1ms. The Motion detection duration counter increments when the + * absolute value of any of the accelerometer measurements exceeds the Motion + * detection threshold (Register 31). The Motion detection interrupt is + * triggered when the Motion detection counter reaches the time count specified + * in this register. + * + * For more details on the Motion detection interrupt, see Section 8.3 of the + * MPU-6000/MPU-6050 Product Specification document. + * + * @return Current motion detection duration threshold value (LSB = 1ms) + * @see MPU6050_RA_MOT_DUR + */ +uint8_t MPU6050::getMotionDetectionDuration() { + I2Cdev::readByte(devAddr, MPU6050_RA_MOT_DUR, buffer); + return buffer[0]; +} +/** Set motion detection event duration threshold. + * @param duration New motion detection duration threshold value (LSB = 1ms) + * @see getMotionDetectionDuration() + * @see MPU6050_RA_MOT_DUR + */ +void MPU6050::setMotionDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU6050_RA_MOT_DUR, duration); +} + +// ZRMOT_THR register + +/** Get zero motion detection event acceleration threshold. + * This register configures the detection threshold for Zero Motion interrupt + * generation. The unit of ZRMOT_THR is 1LSB = 2mg. Zero Motion is detected when + * the absolute value of the accelerometer measurements for the 3 axes are each + * less than the detection threshold. This condition increments the Zero Motion + * duration counter (Register 34). The Zero Motion interrupt is triggered when + * the Zero Motion duration counter reaches the time count specified in + * ZRMOT_DUR (Register 34). + * + * Unlike Free Fall or Motion detection, Zero Motion detection triggers an + * interrupt both when Zero Motion is first detected and when Zero Motion is no + * longer detected. + * + * When a zero motion event is detected, a Zero Motion Status will be indicated + * in the MOT_DETECT_STATUS register (Register 97). When a motion-to-zero-motion + * condition is detected, the status bit is set to 1. When a zero-motion-to- + * motion condition is detected, the status bit is set to 0. + * + * For more details on the Zero Motion detection interrupt, see Section 8.4 of + * the MPU-6000/MPU-6050 Product Specification document as well as Registers 56 + * and 58 of this document. + * + * @return Current zero motion detection acceleration threshold value (LSB = 2mg) + * @see MPU6050_RA_ZRMOT_THR + */ +uint8_t MPU6050::getZeroMotionDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU6050_RA_ZRMOT_THR, buffer); + return buffer[0]; +} +/** Set zero motion detection event acceleration threshold. + * @param threshold New zero motion detection acceleration threshold value (LSB = 2mg) + * @see getZeroMotionDetectionThreshold() + * @see MPU6050_RA_ZRMOT_THR + */ +void MPU6050::setZeroMotionDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU6050_RA_ZRMOT_THR, threshold); +} + +// ZRMOT_DUR register + +/** Get zero motion detection event duration threshold. + * This register configures the duration counter threshold for Zero Motion + * interrupt generation. The duration counter ticks at 16 Hz, therefore + * ZRMOT_DUR has a unit of 1 LSB = 64 ms. The Zero Motion duration counter + * increments while the absolute value of the accelerometer measurements are + * each less than the detection threshold (Register 33). The Zero Motion + * interrupt is triggered when the Zero Motion duration counter reaches the time + * count specified in this register. + * + * For more details on the Zero Motion detection interrupt, see Section 8.4 of + * the MPU-6000/MPU-6050 Product Specification document, as well as Registers 56 + * and 58 of this document. + * + * @return Current zero motion detection duration threshold value (LSB = 64ms) + * @see MPU6050_RA_ZRMOT_DUR + */ +uint8_t MPU6050::getZeroMotionDetectionDuration() { + I2Cdev::readByte(devAddr, MPU6050_RA_ZRMOT_DUR, buffer); + return buffer[0]; +} +/** Set zero motion detection event duration threshold. + * @param duration New zero motion detection duration threshold value (LSB = 1ms) + * @see getZeroMotionDetectionDuration() + * @see MPU6050_RA_ZRMOT_DUR + */ +void MPU6050::setZeroMotionDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU6050_RA_ZRMOT_DUR, duration); +} + +// FIFO_EN register + +/** Get temperature FIFO enabled value. + * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and + * 66) to be written into the FIFO buffer. + * @return Current temperature FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getTempFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set temperature FIFO enabled value. + * @param enabled New temperature FIFO enabled value + * @see getTempFIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setTempFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_TEMP_FIFO_EN_BIT, enabled); +} +/** Get gyroscope X-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and + * 68) to be written into the FIFO buffer. + * @return Current gyroscope X-axis FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getXGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope X-axis FIFO enabled value. + * @param enabled New gyroscope X-axis FIFO enabled value + * @see getXGyroFIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setXGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_XG_FIFO_EN_BIT, enabled); +} +/** Get gyroscope Y-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and + * 70) to be written into the FIFO buffer. + * @return Current gyroscope Y-axis FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getYGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope Y-axis FIFO enabled value. + * @param enabled New gyroscope Y-axis FIFO enabled value + * @see getYGyroFIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setYGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_YG_FIFO_EN_BIT, enabled); +} +/** Get gyroscope Z-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and + * 72) to be written into the FIFO buffer. + * @return Current gyroscope Z-axis FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getZGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope Z-axis FIFO enabled value. + * @param enabled New gyroscope Z-axis FIFO enabled value + * @see getZGyroFIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setZGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ZG_FIFO_EN_BIT, enabled); +} +/** Get accelerometer FIFO enabled value. + * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H, + * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be + * written into the FIFO buffer. + * @return Current accelerometer FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getAccelFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set accelerometer FIFO enabled value. + * @param enabled New accelerometer FIFO enabled value + * @see getAccelFIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setAccelFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_ACCEL_FIFO_EN_BIT, enabled); +} +/** Get Slave 2 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 2 to be written into the FIFO buffer. + * @return Current Slave 2 FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getSlave2FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 2 FIFO enabled value. + * @param enabled New Slave 2 FIFO enabled value + * @see getSlave2FIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setSlave2FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV2_FIFO_EN_BIT, enabled); +} +/** Get Slave 1 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 1 to be written into the FIFO buffer. + * @return Current Slave 1 FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getSlave1FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 1 FIFO enabled value. + * @param enabled New Slave 1 FIFO enabled value + * @see getSlave1FIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setSlave1FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV1_FIFO_EN_BIT, enabled); +} +/** Get Slave 0 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 0 to be written into the FIFO buffer. + * @return Current Slave 0 FIFO enabled value + * @see MPU6050_RA_FIFO_EN + */ +bool MPU6050::getSlave0FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 0 FIFO enabled value. + * @param enabled New Slave 0 FIFO enabled value + * @see getSlave0FIFOEnabled() + * @see MPU6050_RA_FIFO_EN + */ +void MPU6050::setSlave0FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_FIFO_EN, MPU6050_SLV0_FIFO_EN_BIT, enabled); +} + +// I2C_MST_CTRL register + +/** Get multi-master enabled value. + * Multi-master capability allows multiple I2C masters to operate on the same + * bus. In circuits where multi-master capability is required, set MULT_MST_EN + * to 1. This will increase current drawn by approximately 30uA. + * + * In circuits where multi-master capability is required, the state of the I2C + * bus must always be monitored by each separate I2C Master. Before an I2C + * Master can assume arbitration of the bus, it must first confirm that no other + * I2C Master has arbitration of the bus. When MULT_MST_EN is set to 1, the + * MPU-60X0's bus arbitration detection logic is turned on, enabling it to + * detect when the bus is available. + * + * @return Current multi-master enabled value + * @see MPU6050_RA_I2C_MST_CTRL + */ +bool MPU6050::getMultiMasterEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, buffer); + return buffer[0]; +} +/** Set multi-master enabled value. + * @param enabled New multi-master enabled value + * @see getMultiMasterEnabled() + * @see MPU6050_RA_I2C_MST_CTRL + */ +void MPU6050::setMultiMasterEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_MULT_MST_EN_BIT, enabled); +} +/** Get wait-for-external-sensor-data enabled value. + * When the WAIT_FOR_ES bit is set to 1, the Data Ready interrupt will be + * delayed until External Sensor data from the Slave Devices are loaded into the + * EXT_SENS_DATA registers. This is used to ensure that both the internal sensor + * data (i.e. from gyro and accel) and external sensor data have been loaded to + * their respective data registers (i.e. the data is synced) when the Data Ready + * interrupt is triggered. + * + * @return Current wait-for-external-sensor-data enabled value + * @see MPU6050_RA_I2C_MST_CTRL + */ +bool MPU6050::getWaitForExternalSensorEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, buffer); + return buffer[0]; +} +/** Set wait-for-external-sensor-data enabled value. + * @param enabled New wait-for-external-sensor-data enabled value + * @see getWaitForExternalSensorEnabled() + * @see MPU6050_RA_I2C_MST_CTRL + */ +void MPU6050::setWaitForExternalSensorEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_WAIT_FOR_ES_BIT, enabled); +} +/** Get Slave 3 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 3 to be written into the FIFO buffer. + * @return Current Slave 3 FIFO enabled value + * @see MPU6050_RA_MST_CTRL + */ +bool MPU6050::getSlave3FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 3 FIFO enabled value. + * @param enabled New Slave 3 FIFO enabled value + * @see getSlave3FIFOEnabled() + * @see MPU6050_RA_MST_CTRL + */ +void MPU6050::setSlave3FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_SLV_3_FIFO_EN_BIT, enabled); +} +/** Get slave read/write transition enabled value. + * The I2C_MST_P_NSR bit configures the I2C Master's transition from one slave + * read to the next slave read. If the bit equals 0, there will be a restart + * between reads. If the bit equals 1, there will be a stop followed by a start + * of the following read. When a write transaction follows a read transaction, + * the stop followed by a start of the successive write will be always used. + * + * @return Current slave read/write transition enabled value + * @see MPU6050_RA_I2C_MST_CTRL + */ +bool MPU6050::getSlaveReadWriteTransitionEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, buffer); + return buffer[0]; +} +/** Set slave read/write transition enabled value. + * @param enabled New slave read/write transition enabled value + * @see getSlaveReadWriteTransitionEnabled() + * @see MPU6050_RA_I2C_MST_CTRL + */ +void MPU6050::setSlaveReadWriteTransitionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_P_NSR_BIT, enabled); +} +/** Get I2C master clock speed. + * I2C_MST_CLK is a 4 bit unsigned value which configures a divider on the + * MPU-60X0 internal 8MHz clock. It sets the I2C master clock speed according to + * the following table: + * + *
+ * I2C_MST_CLK | I2C Master Clock Speed | 8MHz Clock Divider
+ * ------------+------------------------+-------------------
+ * 0           | 348kHz                 | 23
+ * 1           | 333kHz                 | 24
+ * 2           | 320kHz                 | 25
+ * 3           | 308kHz                 | 26
+ * 4           | 296kHz                 | 27
+ * 5           | 286kHz                 | 28
+ * 6           | 276kHz                 | 29
+ * 7           | 267kHz                 | 30
+ * 8           | 258kHz                 | 31
+ * 9           | 500kHz                 | 16
+ * 10          | 471kHz                 | 17
+ * 11          | 444kHz                 | 18
+ * 12          | 421kHz                 | 19
+ * 13          | 400kHz                 | 20
+ * 14          | 381kHz                 | 21
+ * 15          | 364kHz                 | 22
+ * 
+ * + * @return Current I2C master clock speed + * @see MPU6050_RA_I2C_MST_CTRL + */ +uint8_t MPU6050::getMasterClockSpeed() { + I2Cdev::readBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, buffer); + return buffer[0]; +} +/** Set I2C master clock speed. + * @reparam speed Current I2C master clock speed + * @see MPU6050_RA_I2C_MST_CTRL + */ +void MPU6050::setMasterClockSpeed(uint8_t speed) { + I2Cdev::writeBits(devAddr, MPU6050_RA_I2C_MST_CTRL, MPU6050_I2C_MST_CLK_BIT, MPU6050_I2C_MST_CLK_LENGTH, speed); +} + +// I2C_SLV* registers (Slave 0-3) + +/** Get the I2C address of the specified slave (0-3). + * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read + * operation, and if it is cleared, then it's a write operation. The remaining + * bits (6-0) are the 7-bit device address of the slave device. + * + * In read mode, the result of the read is placed in the lowest available + * EXT_SENS_DATA register. For further information regarding the allocation of + * read results, please refer to the EXT_SENS_DATA register description + * (Registers 73 - 96). + * + * The MPU-6050 supports a total of five slaves, but Slave 4 has unique + * characteristics, and so it has its own functions (getSlave4* and setSlave4*). + * + * I2C data transactions are performed at the Sample Rate, as defined in + * Register 25. The user is responsible for ensuring that I2C data transactions + * to and from each enabled Slave can be completed within a single period of the + * Sample Rate. + * + * The I2C slave access rate can be reduced relative to the Sample Rate. This + * reduced access rate is determined by I2C_MST_DLY (Register 52). Whether a + * slave's access rate is reduced relative to the Sample Rate is determined by + * I2C_MST_DELAY_CTRL (Register 103). + * + * The processing order for the slaves is fixed. The sequence followed for + * processing the slaves is Slave 0, Slave 1, Slave 2, Slave 3 and Slave 4. If a + * particular Slave is disabled it will be skipped. + * + * Each slave can either be accessed at the sample rate or at a reduced sample + * rate. In a case where some slaves are accessed at the Sample Rate and some + * slaves are accessed at the reduced rate, the sequence of accessing the slaves + * (Slave 0 to Slave 4) is still followed. However, the reduced rate slaves will + * be skipped if their access rate dictates that they should not be accessed + * during that particular cycle. For further information regarding the reduced + * access rate, please refer to Register 52. Whether a slave is accessed at the + * Sample Rate or at the reduced rate is determined by the Delay Enable bits in + * Register 103. + * + * @param num Slave number (0-3) + * @return Current address for specified slave + * @see MPU6050_RA_I2C_SLV0_ADDR + */ +uint8_t MPU6050::getSlaveAddress(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, buffer); + return buffer[0]; +} +/** Set the I2C address of the specified slave (0-3). + * @param num Slave number (0-3) + * @param address New address for specified slave + * @see getSlaveAddress() + * @see MPU6050_RA_I2C_SLV0_ADDR + */ +void MPU6050::setSlaveAddress(uint8_t num, uint8_t address) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV0_ADDR + num*3, address); +} +/** Get the active internal register for the specified slave (0-3). + * Read/write operations for this slave will be done to whatever internal + * register address is stored in this MPU register. + * + * The MPU-6050 supports a total of five slaves, but Slave 4 has unique + * characteristics, and so it has its own functions. + * + * @param num Slave number (0-3) + * @return Current active register for specified slave + * @see MPU6050_RA_I2C_SLV0_REG + */ +uint8_t MPU6050::getSlaveRegister(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, buffer); + return buffer[0]; +} +/** Set the active internal register for the specified slave (0-3). + * @param num Slave number (0-3) + * @param reg New active register for specified slave + * @see getSlaveRegister() + * @see MPU6050_RA_I2C_SLV0_REG + */ +void MPU6050::setSlaveRegister(uint8_t num, uint8_t reg) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV0_REG + num*3, reg); +} +/** Get the enabled value for the specified slave (0-3). + * When set to 1, this bit enables Slave 0 for data transfer operations. When + * cleared to 0, this bit disables Slave 0 from data transfer operations. + * @param num Slave number (0-3) + * @return Current enabled value for specified slave + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +bool MPU6050::getSlaveEnabled(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New enabled value for specified slave + * @see getSlaveEnabled() + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +void MPU6050::setSlaveEnabled(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_EN_BIT, enabled); +} +/** Get word pair byte-swapping enabled for the specified slave (0-3). + * When set to 1, this bit enables byte swapping. When byte swapping is enabled, + * the high and low bytes of a word pair are swapped. Please refer to + * I2C_SLV0_GRP for the pairing convention of the word pairs. When cleared to 0, + * bytes transferred to and from Slave 0 will be written to EXT_SENS_DATA + * registers in the order they were transferred. + * + * @param num Slave number (0-3) + * @return Current word pair byte-swapping enabled value for specified slave + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +bool MPU6050::getSlaveWordByteSwap(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, buffer); + return buffer[0]; +} +/** Set word pair byte-swapping enabled for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New word pair byte-swapping enabled value for specified slave + * @see getSlaveWordByteSwap() + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +void MPU6050::setSlaveWordByteSwap(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_BYTE_SW_BIT, enabled); +} +/** Get write mode for the specified slave (0-3). + * When set to 1, the transaction will read or write data only. When cleared to + * 0, the transaction will write a register address prior to reading or writing + * data. This should equal 0 when specifying the register address within the + * Slave device to/from which the ensuing data transaction will take place. + * + * @param num Slave number (0-3) + * @return Current write mode for specified slave (0 = register address + data, 1 = data only) + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +bool MPU6050::getSlaveWriteMode(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, buffer); + return buffer[0]; +} +/** Set write mode for the specified slave (0-3). + * @param num Slave number (0-3) + * @param mode New write mode for specified slave (0 = register address + data, 1 = data only) + * @see getSlaveWriteMode() + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +void MPU6050::setSlaveWriteMode(uint8_t num, bool mode) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_REG_DIS_BIT, mode); +} +/** Get word pair grouping order offset for the specified slave (0-3). + * This sets specifies the grouping order of word pairs received from registers. + * When cleared to 0, bytes from register addresses 0 and 1, 2 and 3, etc (even, + * then odd register addresses) are paired to form a word. When set to 1, bytes + * from register addresses are paired 1 and 2, 3 and 4, etc. (odd, then even + * register addresses) are paired to form a word. + * + * @param num Slave number (0-3) + * @return Current word pair grouping order offset for specified slave + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +bool MPU6050::getSlaveWordGroupOffset(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, buffer); + return buffer[0]; +} +/** Set word pair grouping order offset for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New word pair grouping order offset for specified slave + * @see getSlaveWordGroupOffset() + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +void MPU6050::setSlaveWordGroupOffset(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_GRP_BIT, enabled); +} +/** Get number of bytes to read for the specified slave (0-3). + * Specifies the number of bytes transferred to and from Slave 0. Clearing this + * bit to 0 is equivalent to disabling the register by writing 0 to I2C_SLV0_EN. + * @param num Slave number (0-3) + * @return Number of bytes to read for specified slave + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +uint8_t MPU6050::getSlaveDataLength(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, buffer); + return buffer[0]; +} +/** Set number of bytes to read for the specified slave (0-3). + * @param num Slave number (0-3) + * @param length Number of bytes to read for specified slave + * @see getSlaveDataLength() + * @see MPU6050_RA_I2C_SLV0_CTRL + */ +void MPU6050::setSlaveDataLength(uint8_t num, uint8_t length) { + if (num > 3) return; + I2Cdev::writeBits(devAddr, MPU6050_RA_I2C_SLV0_CTRL + num*3, MPU6050_I2C_SLV_LEN_BIT, MPU6050_I2C_SLV_LEN_LENGTH, length); +} + +// I2C_SLV* registers (Slave 4) + +/** Get the I2C address of Slave 4. + * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read + * operation, and if it is cleared, then it's a write operation. The remaining + * bits (6-0) are the 7-bit device address of the slave device. + * + * @return Current address for Slave 4 + * @see getSlaveAddress() + * @see MPU6050_RA_I2C_SLV4_ADDR + */ +uint8_t MPU6050::getSlave4Address() { + I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, buffer); + return buffer[0]; +} +/** Set the I2C address of Slave 4. + * @param address New address for Slave 4 + * @see getSlave4Address() + * @see MPU6050_RA_I2C_SLV4_ADDR + */ +void MPU6050::setSlave4Address(uint8_t address) { + I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV4_ADDR, address); +} +/** Get the active internal register for the Slave 4. + * Read/write operations for this slave will be done to whatever internal + * register address is stored in this MPU register. + * + * @return Current active register for Slave 4 + * @see MPU6050_RA_I2C_SLV4_REG + */ +uint8_t MPU6050::getSlave4Register() { + I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV4_REG, buffer); + return buffer[0]; +} +/** Set the active internal register for Slave 4. + * @param reg New active register for Slave 4 + * @see getSlave4Register() + * @see MPU6050_RA_I2C_SLV4_REG + */ +void MPU6050::setSlave4Register(uint8_t reg) { + I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV4_REG, reg); +} +/** Set new byte to write to Slave 4. + * This register stores the data to be written into the Slave 4. If I2C_SLV4_RW + * is set 1 (set to read), this register has no effect. + * @param data New byte to write to Slave 4 + * @see MPU6050_RA_I2C_SLV4_DO + */ +void MPU6050::setSlave4OutputByte(uint8_t data) { + I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV4_DO, data); +} +/** Get the enabled value for the Slave 4. + * When set to 1, this bit enables Slave 4 for data transfer operations. When + * cleared to 0, this bit disables Slave 4 from data transfer operations. + * @return Current enabled value for Slave 4 + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +bool MPU6050::getSlave4Enabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for Slave 4. + * @param enabled New enabled value for Slave 4 + * @see getSlave4Enabled() + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +void MPU6050::setSlave4Enabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_EN_BIT, enabled); +} +/** Get the enabled value for Slave 4 transaction interrupts. + * When set to 1, this bit enables the generation of an interrupt signal upon + * completion of a Slave 4 transaction. When cleared to 0, this bit disables the + * generation of an interrupt signal upon completion of a Slave 4 transaction. + * The interrupt status can be observed in Register 54. + * + * @return Current enabled value for Slave 4 transaction interrupts. + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +bool MPU6050::getSlave4InterruptEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for Slave 4 transaction interrupts. + * @param enabled New enabled value for Slave 4 transaction interrupts. + * @see getSlave4InterruptEnabled() + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +void MPU6050::setSlave4InterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_INT_EN_BIT, enabled); +} +/** Get write mode for Slave 4. + * When set to 1, the transaction will read or write data only. When cleared to + * 0, the transaction will write a register address prior to reading or writing + * data. This should equal 0 when specifying the register address within the + * Slave device to/from which the ensuing data transaction will take place. + * + * @return Current write mode for Slave 4 (0 = register address + data, 1 = data only) + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +bool MPU6050::getSlave4WriteMode() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, buffer); + return buffer[0]; +} +/** Set write mode for the Slave 4. + * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only) + * @see getSlave4WriteMode() + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +void MPU6050::setSlave4WriteMode(bool mode) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_REG_DIS_BIT, mode); +} +/** Get Slave 4 master delay value. + * This configures the reduced access rate of I2C slaves relative to the Sample + * Rate. When a slave's access rate is decreased relative to the Sample Rate, + * the slave is accessed every: + * + * 1 / (1 + I2C_MST_DLY) samples + * + * This base Sample Rate in turn is determined by SMPLRT_DIV (register 25) and + * DLPF_CFG (register 26). Whether a slave's access rate is reduced relative to + * the Sample Rate is determined by I2C_MST_DELAY_CTRL (register 103). For + * further information regarding the Sample Rate, please refer to register 25. + * + * @return Current Slave 4 master delay value + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +uint8_t MPU6050::getSlave4MasterDelay() { + I2Cdev::readBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, buffer); + return buffer[0]; +} +/** Set Slave 4 master delay value. + * @param delay New Slave 4 master delay value + * @see getSlave4MasterDelay() + * @see MPU6050_RA_I2C_SLV4_CTRL + */ +void MPU6050::setSlave4MasterDelay(uint8_t delay) { + I2Cdev::writeBits(devAddr, MPU6050_RA_I2C_SLV4_CTRL, MPU6050_I2C_SLV4_MST_DLY_BIT, MPU6050_I2C_SLV4_MST_DLY_LENGTH, delay); +} +/** Get last available byte read from Slave 4. + * This register stores the data read from Slave 4. This field is populated + * after a read transaction. + * @return Last available byte read from to Slave 4 + * @see MPU6050_RA_I2C_SLV4_DI + */ +uint8_t MPU6050::getSlate4InputByte() { + I2Cdev::readByte(devAddr, MPU6050_RA_I2C_SLV4_DI, buffer); + return buffer[0]; +} + +// I2C_MST_STATUS register + +/** Get FSYNC interrupt status. + * This bit reflects the status of the FSYNC interrupt from an external device + * into the MPU-60X0. This is used as a way to pass an external interrupt + * through the MPU-60X0 to the host application processor. When set to 1, this + * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG + * (Register 55). + * @return FSYNC interrupt status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getPassthroughStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_PASS_THROUGH_BIT, buffer); + return buffer[0]; +} +/** Get Slave 4 transaction done status. + * Automatically sets to 1 when a Slave 4 transaction has completed. This + * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register + * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the + * I2C_SLV4_CTRL register (Register 52). + * @return Slave 4 transaction done status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getSlave4IsDone() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_DONE_BIT, buffer); + return buffer[0]; +} +/** Get master arbitration lost status. + * This bit automatically sets to 1 when the I2C Master has lost arbitration of + * the auxiliary I2C bus (an error condition). This triggers an interrupt if the + * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted. + * @return Master arbitration lost status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getLostArbitration() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_LOST_ARB_BIT, buffer); + return buffer[0]; +} +/** Get Slave 4 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 4 NACK interrupt status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getSlave4Nack() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV4_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 3 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 3 NACK interrupt status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getSlave3Nack() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV3_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 2 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 2 NACK interrupt status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getSlave2Nack() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV2_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 1 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 1 NACK interrupt status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getSlave1Nack() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV1_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 0 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 0 NACK interrupt status + * @see MPU6050_RA_I2C_MST_STATUS + */ +bool MPU6050::getSlave0Nack() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_STATUS, MPU6050_MST_I2C_SLV0_NACK_BIT, buffer); + return buffer[0]; +} + +// INT_PIN_CFG register + +/** Get interrupt logic level mode. + * Will be set 0 for active-high, 1 for active-low. + * @return Current interrupt mode (0=active-high, 1=active-low) + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_INT_LEVEL_BIT + */ +bool MPU6050::getInterruptMode() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, buffer); + return buffer[0]; +} +/** Set interrupt logic level mode. + * @param mode New interrupt mode (0=active-high, 1=active-low) + * @see getInterruptMode() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_INT_LEVEL_BIT + */ +void MPU6050::setInterruptMode(bool mode) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_LEVEL_BIT, mode); +} +/** Get interrupt drive mode. + * Will be set 0 for push-pull, 1 for open-drain. + * @return Current interrupt drive mode (0=push-pull, 1=open-drain) + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_INT_OPEN_BIT + */ +bool MPU6050::getInterruptDrive() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt drive mode. + * @param drive New interrupt drive mode (0=push-pull, 1=open-drain) + * @see getInterruptDrive() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_INT_OPEN_BIT + */ +void MPU6050::setInterruptDrive(bool drive) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_OPEN_BIT, drive); +} +/** Get interrupt latch mode. + * Will be set 0 for 50us-pulse, 1 for latch-until-int-cleared. + * @return Current latch mode (0=50us-pulse, 1=latch-until-int-cleared) + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_LATCH_INT_EN_BIT + */ +bool MPU6050::getInterruptLatch() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch mode. + * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared) + * @see getInterruptLatch() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_LATCH_INT_EN_BIT + */ +void MPU6050::setInterruptLatch(bool latch) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_LATCH_INT_EN_BIT, latch); +} +/** Get interrupt latch clear mode. + * Will be set 0 for status-read-only, 1 for any-register-read. + * @return Current latch clear mode (0=status-read-only, 1=any-register-read) + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT + */ +bool MPU6050::getInterruptLatchClear() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch clear mode. + * @param clear New latch clear mode (0=status-read-only, 1=any-register-read) + * @see getInterruptLatchClear() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_INT_RD_CLEAR_BIT + */ +void MPU6050::setInterruptLatchClear(bool clear) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_INT_RD_CLEAR_BIT, clear); +} +/** Get FSYNC interrupt logic level mode. + * @return Current FSYNC interrupt mode (0=active-high, 1=active-low) + * @see getFSyncInterruptMode() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT + */ +bool MPU6050::getFSyncInterruptLevel() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, buffer); + return buffer[0]; +} +/** Set FSYNC interrupt logic level mode. + * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low) + * @see getFSyncInterruptMode() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT + */ +void MPU6050::setFSyncInterruptLevel(bool level) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT, level); +} +/** Get FSYNC pin interrupt enabled setting. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled setting + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT + */ +bool MPU6050::getFSyncInterruptEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set FSYNC pin interrupt enabled setting. + * @param enabled New FSYNC pin interrupt enabled setting + * @see getFSyncInterruptEnabled() + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_FSYNC_INT_EN_BIT + */ +void MPU6050::setFSyncInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_FSYNC_INT_EN_BIT, enabled); +} +/** Get I2C bypass enabled status. + * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to + * 0, the host application processor will be able to directly access the + * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host + * application processor will not be able to directly access the auxiliary I2C + * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106 + * bit[5]). + * @return Current I2C bypass enabled status + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT + */ +bool MPU6050::getI2CBypassEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, buffer); + return buffer[0]; +} +/** Set I2C bypass enabled status. + * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to + * 0, the host application processor will be able to directly access the + * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host + * application processor will not be able to directly access the auxiliary I2C + * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106 + * bit[5]). + * @param enabled New I2C bypass enabled status + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_I2C_BYPASS_EN_BIT + */ +void MPU6050::setI2CBypassEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_I2C_BYPASS_EN_BIT, enabled); +} +/** Get reference clock output enabled status. + * When this bit is equal to 1, a reference clock output is provided at the + * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For + * further information regarding CLKOUT, please refer to the MPU-60X0 Product + * Specification document. + * @return Current reference clock output enabled status + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_CLKOUT_EN_BIT + */ +bool MPU6050::getClockOutputEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, buffer); + return buffer[0]; +} +/** Set reference clock output enabled status. + * When this bit is equal to 1, a reference clock output is provided at the + * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For + * further information regarding CLKOUT, please refer to the MPU-60X0 Product + * Specification document. + * @param enabled New reference clock output enabled status + * @see MPU6050_RA_INT_PIN_CFG + * @see MPU6050_INTCFG_CLKOUT_EN_BIT + */ +void MPU6050::setClockOutputEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_PIN_CFG, MPU6050_INTCFG_CLKOUT_EN_BIT, enabled); +} + +// INT_ENABLE register + +/** Get full interrupt enabled status. + * Full register byte for all interrupts, for quick reading. Each bit will be + * set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_FF_BIT + **/ +uint8_t MPU6050::getIntEnabled() { + I2Cdev::readByte(devAddr, MPU6050_RA_INT_ENABLE, buffer); + return buffer[0]; +} +/** Set full interrupt enabled status. + * Full register byte for all interrupts, for quick reading. Each bit should be + * set 0 for disabled, 1 for enabled. + * @param enabled New interrupt enabled status + * @see getIntFreefallEnabled() + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_FF_BIT + **/ +void MPU6050::setIntEnabled(uint8_t enabled) { + I2Cdev::writeByte(devAddr, MPU6050_RA_INT_ENABLE, enabled); +} +/** Get Free Fall interrupt enabled status. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_FF_BIT + **/ +bool MPU6050::getIntFreefallEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, buffer); + return buffer[0]; +} +/** Set Free Fall interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntFreefallEnabled() + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_FF_BIT + **/ +void MPU6050::setIntFreefallEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FF_BIT, enabled); +} +/** Get Motion Detection interrupt enabled status. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_MOT_BIT + **/ +bool MPU6050::getIntMotionEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, buffer); + return buffer[0]; +} +/** Set Motion Detection interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntMotionEnabled() + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_MOT_BIT + **/ +void MPU6050::setIntMotionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_MOT_BIT, enabled); +} +/** Get Zero Motion Detection interrupt enabled status. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_ZMOT_BIT + **/ +bool MPU6050::getIntZeroMotionEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, buffer); + return buffer[0]; +} +/** Set Zero Motion Detection interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntZeroMotionEnabled() + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_ZMOT_BIT + **/ +void MPU6050::setIntZeroMotionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_ZMOT_BIT, enabled); +} +/** Get FIFO Buffer Overflow interrupt enabled status. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT + **/ +bool MPU6050::getIntFIFOBufferOverflowEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer); + return buffer[0]; +} +/** Set FIFO Buffer Overflow interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntFIFOBufferOverflowEnabled() + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT + **/ +void MPU6050::setIntFIFOBufferOverflowEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, enabled); +} +/** Get I2C Master interrupt enabled status. + * This enables any of the I2C Master interrupt sources to generate an + * interrupt. Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT + **/ +bool MPU6050::getIntI2CMasterEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer); + return buffer[0]; +} +/** Set I2C Master interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntI2CMasterEnabled() + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT + **/ +void MPU6050::setIntI2CMasterEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_I2C_MST_INT_BIT, enabled); +} +/** Get Data Ready interrupt enabled setting. + * This event occurs each time a write operation to all of the sensor registers + * has been completed. Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU6050_RA_INT_ENABLE + * @see MPU6050_INTERRUPT_DATA_RDY_BIT + */ +bool MPU6050::getIntDataReadyEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer); + return buffer[0]; +} +/** Set Data Ready interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see MPU6050_RA_INT_CFG + * @see MPU6050_INTERRUPT_DATA_RDY_BIT + */ +void MPU6050::setIntDataReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DATA_RDY_BIT, enabled); +} + +// INT_STATUS register + +/** Get full set of interrupt status bits. + * These bits clear to 0 after the register has been read. Very useful + * for getting multiple INT statuses, since each single bit read clears + * all of them because it has to read the whole byte. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + */ +uint8_t MPU6050::getIntStatus() { + I2Cdev::readByte(devAddr, MPU6050_RA_INT_STATUS, buffer); + return buffer[0]; +} +/** Get Free Fall interrupt status. + * This bit automatically sets to 1 when a Free Fall interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + * @see MPU6050_INTERRUPT_FF_BIT + */ +bool MPU6050::getIntFreefallStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FF_BIT, buffer); + return buffer[0]; +} +/** Get Motion Detection interrupt status. + * This bit automatically sets to 1 when a Motion Detection interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + * @see MPU6050_INTERRUPT_MOT_BIT + */ +bool MPU6050::getIntMotionStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_MOT_BIT, buffer); + return buffer[0]; +} +/** Get Zero Motion Detection interrupt status. + * This bit automatically sets to 1 when a Zero Motion Detection interrupt has + * been generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + * @see MPU6050_INTERRUPT_ZMOT_BIT + */ +bool MPU6050::getIntZeroMotionStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_ZMOT_BIT, buffer); + return buffer[0]; +} +/** Get FIFO Buffer Overflow interrupt status. + * This bit automatically sets to 1 when a Free Fall interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + * @see MPU6050_INTERRUPT_FIFO_OFLOW_BIT + */ +bool MPU6050::getIntFIFOBufferOverflowStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_FIFO_OFLOW_BIT, buffer); + return buffer[0]; +} +/** Get I2C Master interrupt status. + * This bit automatically sets to 1 when an I2C Master interrupt has been + * generated. For a list of I2C Master interrupts, please refer to Register 54. + * The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + * @see MPU6050_INTERRUPT_I2C_MST_INT_BIT + */ +bool MPU6050::getIntI2CMasterStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_I2C_MST_INT_BIT, buffer); + return buffer[0]; +} +/** Get Data Ready interrupt status. + * This bit automatically sets to 1 when a Data Ready interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU6050_RA_INT_STATUS + * @see MPU6050_INTERRUPT_DATA_RDY_BIT + */ +bool MPU6050::getIntDataReadyStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DATA_RDY_BIT, buffer); + return buffer[0]; +} + +// ACCEL_*OUT_* registers + +/** Get raw 9-axis motion sensor readings (accel/gyro/compass). + * FUNCTION NOT FULLY IMPLEMENTED YET. + * @param ax 16-bit signed integer container for accelerometer X-axis value + * @param ay 16-bit signed integer container for accelerometer Y-axis value + * @param az 16-bit signed integer container for accelerometer Z-axis value + * @param gx 16-bit signed integer container for gyroscope X-axis value + * @param gy 16-bit signed integer container for gyroscope Y-axis value + * @param gz 16-bit signed integer container for gyroscope Z-axis value + * @param mx 16-bit signed integer container for magnetometer X-axis value + * @param my 16-bit signed integer container for magnetometer Y-axis value + * @param mz 16-bit signed integer container for magnetometer Z-axis value + * @see getMotion6() + * @see getAcceleration() + * @see getRotation() + * @see MPU6050_RA_ACCEL_XOUT_H + */ +void MPU6050::getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz) { + getMotion6(ax, ay, az, gx, gy, gz); + // TODO: magnetometer integration +} +/** Get raw 6-axis motion sensor readings (accel/gyro). + * Retrieves all currently available motion sensor values. + * @param ax 16-bit signed integer container for accelerometer X-axis value + * @param ay 16-bit signed integer container for accelerometer Y-axis value + * @param az 16-bit signed integer container for accelerometer Z-axis value + * @param gx 16-bit signed integer container for gyroscope X-axis value + * @param gy 16-bit signed integer container for gyroscope Y-axis value + * @param gz 16-bit signed integer container for gyroscope Z-axis value + * @see getAcceleration() + * @see getRotation() + * @see MPU6050_RA_ACCEL_XOUT_H + */ +void MPU6050::getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz) { + I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 14, buffer); + *ax = (((int16_t)buffer[0]) << 8) | buffer[1]; + *ay = (((int16_t)buffer[2]) << 8) | buffer[3]; + *az = (((int16_t)buffer[4]) << 8) | buffer[5]; + *gx = (((int16_t)buffer[8]) << 8) | buffer[9]; + *gy = (((int16_t)buffer[10]) << 8) | buffer[11]; + *gz = (((int16_t)buffer[12]) << 8) | buffer[13]; +} +/** Get 3-axis accelerometer readings. + * These registers store the most recent accelerometer measurements. + * Accelerometer measurements are written to these registers at the Sample Rate + * as defined in Register 25. + * + * The accelerometer measurement registers, along with the temperature + * measurement registers, gyroscope measurement registers, and external sensor + * data registers, are composed of two sets of registers: an internal register + * set and a user-facing read register set. + * + * The data within the accelerometer sensors' internal register set is always + * updated at the Sample Rate. Meanwhile, the user-facing read register set + * duplicates the internal register set's data values whenever the serial + * interface is idle. This guarantees that a burst read of sensor registers will + * read measurements from the same sampling instant. Note that if burst reads + * are not used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS + * (Register 28). For each full scale setting, the accelerometers' sensitivity + * per LSB in ACCEL_xOUT is shown in the table below: + * + *
+ * AFS_SEL | Full Scale Range | LSB Sensitivity
+ * --------+------------------+----------------
+ * 0       | +/- 2g           | 8192 LSB/mg
+ * 1       | +/- 4g           | 4096 LSB/mg
+ * 2       | +/- 8g           | 2048 LSB/mg
+ * 3       | +/- 16g          | 1024 LSB/mg
+ * 
+ * + * @param x 16-bit signed integer container for X-axis acceleration + * @param y 16-bit signed integer container for Y-axis acceleration + * @param z 16-bit signed integer container for Z-axis acceleration + * @see MPU6050_RA_GYRO_XOUT_H + */ +void MPU6050::getAcceleration(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 6, buffer); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis accelerometer reading. + * @return X-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU6050_RA_ACCEL_XOUT_H + */ +int16_t MPU6050::getAccelerationX() { + I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_XOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis accelerometer reading. + * @return Y-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU6050_RA_ACCEL_YOUT_H + */ +int16_t MPU6050::getAccelerationY() { + I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_YOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Z-axis accelerometer reading. + * @return Z-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU6050_RA_ACCEL_ZOUT_H + */ +int16_t MPU6050::getAccelerationZ() { + I2Cdev::readBytes(devAddr, MPU6050_RA_ACCEL_ZOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// TEMP_OUT_* registers + +/** Get current internal temperature. + * @return Temperature reading in 16-bit 2's complement format + * @see MPU6050_RA_TEMP_OUT_H + */ +int16_t MPU6050::getTemperature() { + I2Cdev::readBytes(devAddr, MPU6050_RA_TEMP_OUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// GYRO_*OUT_* registers + +/** Get 3-axis gyroscope readings. + * These gyroscope measurement registers, along with the accelerometer + * measurement registers, temperature measurement registers, and external sensor + * data registers, are composed of two sets of registers: an internal register + * set and a user-facing read register set. + * The data within the gyroscope sensors' internal register set is always + * updated at the Sample Rate. Meanwhile, the user-facing read register set + * duplicates the internal register set's data values whenever the serial + * interface is idle. This guarantees that a burst read of sensor registers will + * read measurements from the same sampling instant. Note that if burst reads + * are not used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Each 16-bit gyroscope measurement has a full scale defined in FS_SEL + * (Register 27). For each full scale setting, the gyroscopes' sensitivity per + * LSB in GYRO_xOUT is shown in the table below: + * + *
+ * FS_SEL | Full Scale Range   | LSB Sensitivity
+ * -------+--------------------+----------------
+ * 0      | +/- 250 degrees/s  | 131 LSB/deg/s
+ * 1      | +/- 500 degrees/s  | 65.5 LSB/deg/s
+ * 2      | +/- 1000 degrees/s | 32.8 LSB/deg/s
+ * 3      | +/- 2000 degrees/s | 16.4 LSB/deg/s
+ * 
+ * + * @param x 16-bit signed integer container for X-axis rotation + * @param y 16-bit signed integer container for Y-axis rotation + * @param z 16-bit signed integer container for Z-axis rotation + * @see getMotion6() + * @see MPU6050_RA_GYRO_XOUT_H + */ +void MPU6050::getRotation(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 6, buffer); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis gyroscope reading. + * @return X-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU6050_RA_GYRO_XOUT_H + */ +int16_t MPU6050::getRotationX() { + I2Cdev::readBytes(devAddr, MPU6050_RA_GYRO_XOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis gyroscope reading. + * @return Y-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU6050_RA_GYRO_YOUT_H + */ +int16_t MPU6050::getRotationY() { + I2Cdev::readBytes(devAddr, MPU6050_RA_GYRO_YOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Z-axis gyroscope reading. + * @return Z-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU6050_RA_GYRO_ZOUT_H + */ +int16_t MPU6050::getRotationZ() { + I2Cdev::readBytes(devAddr, MPU6050_RA_GYRO_ZOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// EXT_SENS_DATA_* registers + +/** Read single byte from external sensor data register. + * These registers store data read from external sensors by the Slave 0, 1, 2, + * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in + * I2C_SLV4_DI (Register 53). + * + * External sensor data is written to these registers at the Sample Rate as + * defined in Register 25. This access rate can be reduced by using the Slave + * Delay Enable registers (Register 103). + * + * External sensor data registers, along with the gyroscope measurement + * registers, accelerometer measurement registers, and temperature measurement + * registers, are composed of two sets of registers: an internal register set + * and a user-facing read register set. + * + * The data within the external sensors' internal register set is always updated + * at the Sample Rate (or the reduced access rate) whenever the serial interface + * is idle. This guarantees that a burst read of sensor registers will read + * measurements from the same sampling instant. Note that if burst reads are not + * used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Data is placed in these external sensor data registers according to + * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39, + * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from + * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as + * defined in Register 25) or delayed rate (if specified in Register 52 and + * 103). During each Sample cycle, slave reads are performed in order of Slave + * number. If all slaves are enabled with more than zero bytes to be read, the + * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3. + * + * Each enabled slave will have EXT_SENS_DATA registers associated with it by + * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from + * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may + * change the higher numbered slaves' associated registers. Furthermore, if + * fewer total bytes are being read from the external sensors as a result of + * such a change, then the data remaining in the registers which no longer have + * an associated slave device (i.e. high numbered registers) will remain in + * these previously allocated registers unless reset. + * + * If the sum of the read lengths of all SLVx transactions exceed the number of + * available EXT_SENS_DATA registers, the excess bytes will be dropped. There + * are 24 EXT_SENS_DATA registers and hence the total read lengths between all + * the slaves cannot be greater than 24 or some bytes will be lost. + * + * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further + * information regarding the characteristics of Slave 4, please refer to + * Registers 49 to 53. + * + * EXAMPLE: + * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and + * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that + * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00 + * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05 + * will be associated with Slave 1. If Slave 2 is enabled as well, registers + * starting from EXT_SENS_DATA_06 will be allocated to Slave 2. + * + * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then + * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3 + * instead. + * + * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE: + * If a slave is disabled at any time, the space initially allocated to the + * slave in the EXT_SENS_DATA register, will remain associated with that slave. + * This is to avoid dynamic adjustment of the register allocation. + * + * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all + * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106). + * + * This above is also true if one of the slaves gets NACKed and stops + * functioning. + * + * @param position Starting position (0-23) + * @return Byte read from register + */ +uint8_t MPU6050::getExternalSensorByte(int position) { + I2Cdev::readByte(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, buffer); + return buffer[0]; +} +/** Read word (2 bytes) from external sensor data registers. + * @param position Starting position (0-21) + * @return Word read from register + * @see getExternalSensorByte() + */ +uint16_t MPU6050::getExternalSensorWord(int position) { + I2Cdev::readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 2, buffer); + return (((uint16_t)buffer[0]) << 8) | buffer[1]; +} +/** Read double word (4 bytes) from external sensor data registers. + * @param position Starting position (0-20) + * @return Double word read from registers + * @see getExternalSensorByte() + */ +uint32_t MPU6050::getExternalSensorDWord(int position) { + I2Cdev::readBytes(devAddr, MPU6050_RA_EXT_SENS_DATA_00 + position, 4, buffer); + return (((uint32_t)buffer[0]) << 24) | (((uint32_t)buffer[1]) << 16) | (((uint16_t)buffer[2]) << 8) | buffer[3]; +} + +// MOT_DETECT_STATUS register + +/** Get full motion detection status register content (all bits). + * @return Motion detection status byte + * @see MPU6050_RA_MOT_DETECT_STATUS + */ +uint8_t MPU6050::getMotionStatus() { + I2Cdev::readByte(devAddr, MPU6050_RA_MOT_DETECT_STATUS, buffer); + return buffer[0]; +} +/** Get X-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_XNEG_BIT + */ +bool MPU6050::getXNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XNEG_BIT, buffer); + return buffer[0]; +} +/** Get X-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_XPOS_BIT + */ +bool MPU6050::getXPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_XPOS_BIT, buffer); + return buffer[0]; +} +/** Get Y-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_YNEG_BIT + */ +bool MPU6050::getYNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YNEG_BIT, buffer); + return buffer[0]; +} +/** Get Y-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_YPOS_BIT + */ +bool MPU6050::getYPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_YPOS_BIT, buffer); + return buffer[0]; +} +/** Get Z-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_ZNEG_BIT + */ +bool MPU6050::getZNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZNEG_BIT, buffer); + return buffer[0]; +} +/** Get Z-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_ZPOS_BIT + */ +bool MPU6050::getZPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZPOS_BIT, buffer); + return buffer[0]; +} +/** Get zero motion detection interrupt status. + * @return Motion detection status + * @see MPU6050_RA_MOT_DETECT_STATUS + * @see MPU6050_MOTION_MOT_ZRMOT_BIT + */ +bool MPU6050::getZeroMotionDetected() { + I2Cdev::readBit(devAddr, MPU6050_RA_MOT_DETECT_STATUS, MPU6050_MOTION_MOT_ZRMOT_BIT, buffer); + return buffer[0]; +} + +// I2C_SLV*_DO register + +/** Write byte to Data Output container for specified slave. + * This register holds the output data written into Slave when Slave is set to + * write mode. For further information regarding Slave control, please + * refer to Registers 37 to 39 and immediately following. + * @param num Slave number (0-3) + * @param data Byte to write + * @see MPU6050_RA_I2C_SLV0_DO + */ +void MPU6050::setSlaveOutputByte(uint8_t num, uint8_t data) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU6050_RA_I2C_SLV0_DO + num, data); +} + +// I2C_MST_DELAY_CTRL register + +/** Get external data shadow delay enabled status. + * This register is used to specify the timing of external sensor data + * shadowing. When DELAY_ES_SHADOW is set to 1, shadowing of external + * sensor data is delayed until all data has been received. + * @return Current external data shadow delay enabled status. + * @see MPU6050_RA_I2C_MST_DELAY_CTRL + * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT + */ +bool MPU6050::getExternalShadowDelayEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, buffer); + return buffer[0]; +} +/** Set external data shadow delay enabled status. + * @param enabled New external data shadow delay enabled status. + * @see getExternalShadowDelayEnabled() + * @see MPU6050_RA_I2C_MST_DELAY_CTRL + * @see MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT + */ +void MPU6050::setExternalShadowDelayEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT, enabled); +} +/** Get slave delay enabled status. + * When a particular slave delay is enabled, the rate of access for the that + * slave device is reduced. When a slave's access rate is decreased relative to + * the Sample Rate, the slave is accessed every: + * + * 1 / (1 + I2C_MST_DLY) Samples + * + * This base Sample Rate in turn is determined by SMPLRT_DIV (register * 25) + * and DLPF_CFG (register 26). + * + * For further information regarding I2C_MST_DLY, please refer to register 52. + * For further information regarding the Sample Rate, please refer to register 25. + * + * @param num Slave number (0-4) + * @return Current slave delay enabled status. + * @see MPU6050_RA_I2C_MST_DELAY_CTRL + * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT + */ +bool MPU6050::getSlaveDelayEnabled(uint8_t num) { + // MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc. + if (num > 4) return 0; + I2Cdev::readBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, buffer); + return buffer[0]; +} +/** Set slave delay enabled status. + * @param num Slave number (0-4) + * @param enabled New slave delay enabled status. + * @see MPU6050_RA_I2C_MST_DELAY_CTRL + * @see MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT + */ +void MPU6050::setSlaveDelayEnabled(uint8_t num, bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_I2C_MST_DELAY_CTRL, num, enabled); +} + +// SIGNAL_PATH_RESET register + +/** Reset gyroscope signal path. + * The reset will revert the signal path analog to digital converters and + * filters to their power up configurations. + * @see MPU6050_RA_SIGNAL_PATH_RESET + * @see MPU6050_PATHRESET_GYRO_RESET_BIT + */ +void MPU6050::resetGyroscopePath() { + I2Cdev::writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_GYRO_RESET_BIT, true); +} +/** Reset accelerometer signal path. + * The reset will revert the signal path analog to digital converters and + * filters to their power up configurations. + * @see MPU6050_RA_SIGNAL_PATH_RESET + * @see MPU6050_PATHRESET_ACCEL_RESET_BIT + */ +void MPU6050::resetAccelerometerPath() { + I2Cdev::writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_ACCEL_RESET_BIT, true); +} +/** Reset temperature sensor signal path. + * The reset will revert the signal path analog to digital converters and + * filters to their power up configurations. + * @see MPU6050_RA_SIGNAL_PATH_RESET + * @see MPU6050_PATHRESET_TEMP_RESET_BIT + */ +void MPU6050::resetTemperaturePath() { + I2Cdev::writeBit(devAddr, MPU6050_RA_SIGNAL_PATH_RESET, MPU6050_PATHRESET_TEMP_RESET_BIT, true); +} + +// MOT_DETECT_CTRL register + +/** Get accelerometer power-on delay. + * The accelerometer data path provides samples to the sensor registers, Motion + * detection, Zero Motion detection, and Free Fall detection modules. The + * signal path contains filters which must be flushed on wake-up with new + * samples before the detection modules begin operations. The default wake-up + * delay, of 4ms can be lengthened by up to 3ms. This additional delay is + * specified in ACCEL_ON_DELAY in units of 1 LSB = 1 ms. The user may select + * any value above zero unless instructed otherwise by InvenSense. Please refer + * to Section 8 of the MPU-6000/MPU-6050 Product Specification document for + * further information regarding the detection modules. + * @return Current accelerometer power-on delay + * @see MPU6050_RA_MOT_DETECT_CTRL + * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT + */ +uint8_t MPU6050::getAccelerometerPowerOnDelay() { + I2Cdev::readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, buffer); + return buffer[0]; +} +/** Set accelerometer power-on delay. + * @param delay New accelerometer power-on delay (0-3) + * @see getAccelerometerPowerOnDelay() + * @see MPU6050_RA_MOT_DETECT_CTRL + * @see MPU6050_DETECT_ACCEL_ON_DELAY_BIT + */ +void MPU6050::setAccelerometerPowerOnDelay(uint8_t delay) { + I2Cdev::writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_ACCEL_ON_DELAY_BIT, MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH, delay); +} +/** Get Free Fall detection counter decrement configuration. + * Detection is registered by the Free Fall detection module after accelerometer + * measurements meet their respective threshold conditions over a specified + * number of samples. When the threshold conditions are met, the corresponding + * detection counter increments by 1. The user may control the rate at which the + * detection counter decrements when the threshold condition is not met by + * configuring FF_COUNT. The decrement rate can be set according to the + * following table: + * + *
+ * FF_COUNT | Counter Decrement
+ * ---------+------------------
+ * 0        | Reset
+ * 1        | 1
+ * 2        | 2
+ * 3        | 4
+ * 
+ * + * When FF_COUNT is configured to 0 (reset), any non-qualifying sample will + * reset the counter to 0. For further information on Free Fall detection, + * please refer to Registers 29 to 32. + * + * @return Current decrement configuration + * @see MPU6050_RA_MOT_DETECT_CTRL + * @see MPU6050_DETECT_FF_COUNT_BIT + */ +uint8_t MPU6050::getFreefallDetectionCounterDecrement() { + I2Cdev::readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, buffer); + return buffer[0]; +} +/** Set Free Fall detection counter decrement configuration. + * @param decrement New decrement configuration value + * @see getFreefallDetectionCounterDecrement() + * @see MPU6050_RA_MOT_DETECT_CTRL + * @see MPU6050_DETECT_FF_COUNT_BIT + */ +void MPU6050::setFreefallDetectionCounterDecrement(uint8_t decrement) { + I2Cdev::writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_FF_COUNT_BIT, MPU6050_DETECT_FF_COUNT_LENGTH, decrement); +} +/** Get Motion detection counter decrement configuration. + * Detection is registered by the Motion detection module after accelerometer + * measurements meet their respective threshold conditions over a specified + * number of samples. When the threshold conditions are met, the corresponding + * detection counter increments by 1. The user may control the rate at which the + * detection counter decrements when the threshold condition is not met by + * configuring MOT_COUNT. The decrement rate can be set according to the + * following table: + * + *
+ * MOT_COUNT | Counter Decrement
+ * ----------+------------------
+ * 0         | Reset
+ * 1         | 1
+ * 2         | 2
+ * 3         | 4
+ * 
+ * + * When MOT_COUNT is configured to 0 (reset), any non-qualifying sample will + * reset the counter to 0. For further information on Motion detection, + * please refer to Registers 29 to 32. + * + */ +uint8_t MPU6050::getMotionDetectionCounterDecrement() { + I2Cdev::readBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, buffer); + return buffer[0]; +} +/** Set Motion detection counter decrement configuration. + * @param decrement New decrement configuration value + * @see getMotionDetectionCounterDecrement() + * @see MPU6050_RA_MOT_DETECT_CTRL + * @see MPU6050_DETECT_MOT_COUNT_BIT + */ +void MPU6050::setMotionDetectionCounterDecrement(uint8_t decrement) { + I2Cdev::writeBits(devAddr, MPU6050_RA_MOT_DETECT_CTRL, MPU6050_DETECT_MOT_COUNT_BIT, MPU6050_DETECT_MOT_COUNT_LENGTH, decrement); +} + +// USER_CTRL register + +/** Get FIFO enabled status. + * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer + * cannot be written to or read from while disabled. The FIFO buffer's state + * does not change unless the MPU-60X0 is power cycled. + * @return Current FIFO enabled status + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_FIFO_EN_BIT + */ +bool MPU6050::getFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set FIFO enabled status. + * @param enabled New FIFO enabled status + * @see getFIFOEnabled() + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_FIFO_EN_BIT + */ +void MPU6050::setFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_EN_BIT, enabled); +} +/** Get I2C Master Mode enabled status. + * When this mode is enabled, the MPU-60X0 acts as the I2C Master to the + * external sensor slave devices on the auxiliary I2C bus. When this bit is + * cleared to 0, the auxiliary I2C bus lines (AUX_DA and AUX_CL) are logically + * driven by the primary I2C bus (SDA and SCL). This is a precondition to + * enabling Bypass Mode. For further information regarding Bypass Mode, please + * refer to Register 55. + * @return Current I2C Master Mode enabled status + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_I2C_MST_EN_BIT + */ +bool MPU6050::getI2CMasterModeEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, buffer); + return buffer[0]; +} +/** Set I2C Master Mode enabled status. + * @param enabled New I2C Master Mode enabled status + * @see getI2CMasterModeEnabled() + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_I2C_MST_EN_BIT + */ +void MPU6050::setI2CMasterModeEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_EN_BIT, enabled); +} +/** Switch from I2C to SPI mode (MPU-6000 only) + * If this is set, the primary SPI interface will be enabled in place of the + * disabled primary I2C interface. + */ +void MPU6050::switchSPIEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_IF_DIS_BIT, enabled); +} +/** Reset the FIFO. + * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This + * bit automatically clears to 0 after the reset has been triggered. + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_FIFO_RESET_BIT + */ +void MPU6050::resetFIFO() { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_FIFO_RESET_BIT, true); +} +/** Reset the I2C Master. + * This bit resets the I2C Master when set to 1 while I2C_MST_EN equals 0. + * This bit automatically clears to 0 after the reset has been triggered. + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_I2C_MST_RESET_BIT + */ +void MPU6050::resetI2CMaster() { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_I2C_MST_RESET_BIT, true); +} +/** Reset all sensor registers and signal paths. + * When set to 1, this bit resets the signal paths for all sensors (gyroscopes, + * accelerometers, and temperature sensor). This operation will also clear the + * sensor registers. This bit automatically clears to 0 after the reset has been + * triggered. + * + * When resetting only the signal path (and not the sensor registers), please + * use Register 104, SIGNAL_PATH_RESET. + * + * @see MPU6050_RA_USER_CTRL + * @see MPU6050_USERCTRL_SIG_COND_RESET_BIT + */ +void MPU6050::resetSensors() { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_SIG_COND_RESET_BIT, true); +} + +// PWR_MGMT_1 register + +/** Trigger a full device reset. + * A small delay of ~50ms may be desirable after triggering a reset. + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_DEVICE_RESET_BIT + */ +void MPU6050::reset() { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_DEVICE_RESET_BIT, true); +} +/** Get sleep mode status. + * Setting the SLEEP bit in the register puts the device into very low power + * sleep mode. In this mode, only the serial interface and internal registers + * remain active, allowing for a very low standby current. Clearing this bit + * puts the device back into normal mode. To save power, the individual standby + * selections for each of the gyros should be used if any gyro axis is not used + * by the application. + * @return Current sleep mode enabled status + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_SLEEP_BIT + */ +bool MPU6050::getSleepEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, buffer); + return buffer[0]; +} +/** Set sleep mode status. + * @param enabled New sleep mode enabled status + * @see getSleepEnabled() + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_SLEEP_BIT + */ +void MPU6050::setSleepEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_SLEEP_BIT, enabled); +} +/** Get wake cycle enabled status. + * When this bit is set to 1 and SLEEP is disabled, the MPU-60X0 will cycle + * between sleep mode and waking up to take a single sample of data from active + * sensors at a rate determined by LP_WAKE_CTRL (register 108). + * @return Current sleep mode enabled status + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_CYCLE_BIT + */ +bool MPU6050::getWakeCycleEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, buffer); + return buffer[0]; +} +/** Set wake cycle enabled status. + * @param enabled New sleep mode enabled status + * @see getWakeCycleEnabled() + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_CYCLE_BIT + */ +void MPU6050::setWakeCycleEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CYCLE_BIT, enabled); +} +/** Get temperature sensor enabled status. + * Control the usage of the internal temperature sensor. + * + * Note: this register stores the *disabled* value, but for consistency with the + * rest of the code, the function is named and used with standard true/false + * values to indicate whether the sensor is enabled or disabled, respectively. + * + * @return Current temperature sensor enabled status + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_TEMP_DIS_BIT + */ +bool MPU6050::getTempSensorEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, buffer); + return buffer[0] == 0; // 1 is actually disabled here +} +/** Set temperature sensor enabled status. + * Note: this register stores the *disabled* value, but for consistency with the + * rest of the code, the function is named and used with standard true/false + * values to indicate whether the sensor is enabled or disabled, respectively. + * + * @param enabled New temperature sensor enabled status + * @see getTempSensorEnabled() + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_TEMP_DIS_BIT + */ +void MPU6050::setTempSensorEnabled(bool enabled) { + // 1 is actually disabled here + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_TEMP_DIS_BIT, !enabled); +} +/** Get clock source setting. + * @return Current clock source setting + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_CLKSEL_BIT + * @see MPU6050_PWR1_CLKSEL_LENGTH + */ +uint8_t MPU6050::getClockSource() { + I2Cdev::readBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, buffer); + return buffer[0]; +} +/** Set clock source setting. + * An internal 8MHz oscillator, gyroscope based clock, or external sources can + * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator + * or an external source is chosen as the clock source, the MPU-60X0 can operate + * in low power modes with the gyroscopes disabled. + * + * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator. + * However, it is highly recommended that the device be configured to use one of + * the gyroscopes (or an external clock source) as the clock reference for + * improved stability. The clock source can be selected according to the following table: + * + *
+ * CLK_SEL | Clock Source
+ * --------+--------------------------------------
+ * 0       | Internal oscillator
+ * 1       | PLL with X Gyro reference
+ * 2       | PLL with Y Gyro reference
+ * 3       | PLL with Z Gyro reference
+ * 4       | PLL with external 32.768kHz reference
+ * 5       | PLL with external 19.2MHz reference
+ * 6       | Reserved
+ * 7       | Stops the clock and keeps the timing generator in reset
+ * 
+ * + * @param source New clock source setting + * @see getClockSource() + * @see MPU6050_RA_PWR_MGMT_1 + * @see MPU6050_PWR1_CLKSEL_BIT + * @see MPU6050_PWR1_CLKSEL_LENGTH + */ +void MPU6050::setClockSource(uint8_t source) { + I2Cdev::writeBits(devAddr, MPU6050_RA_PWR_MGMT_1, MPU6050_PWR1_CLKSEL_BIT, MPU6050_PWR1_CLKSEL_LENGTH, source); +} + +// PWR_MGMT_2 register + +/** Get wake frequency in Accel-Only Low Power Mode. + * The MPU-60X0 can be put into Accerlerometer Only Low Power Mode by setting + * PWRSEL to 1 in the Power Management 1 register (Register 107). In this mode, + * the device will power off all devices except for the primary I2C interface, + * waking only the accelerometer at fixed intervals to take a single + * measurement. The frequency of wake-ups can be configured with LP_WAKE_CTRL + * as shown below: + * + *
+ * LP_WAKE_CTRL | Wake-up Frequency
+ * -------------+------------------
+ * 0            | 1.25 Hz
+ * 1            | 2.5 Hz
+ * 2            | 5 Hz
+ * 3            | 10 Hz
+ * 
+ * + * For further information regarding the MPU-60X0's power modes, please refer to + * Register 107. + * + * @return Current wake frequency + * @see MPU6050_RA_PWR_MGMT_2 + */ +uint8_t MPU6050::getWakeFrequency() { + I2Cdev::readBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, buffer); + return buffer[0]; +} +/** Set wake frequency in Accel-Only Low Power Mode. + * @param frequency New wake frequency + * @see MPU6050_RA_PWR_MGMT_2 + */ +void MPU6050::setWakeFrequency(uint8_t frequency) { + I2Cdev::writeBits(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_LP_WAKE_CTRL_BIT, MPU6050_PWR2_LP_WAKE_CTRL_LENGTH, frequency); +} + +/** Get X-axis accelerometer standby enabled status. + * If enabled, the X-axis will not gather or report data (or use power). + * @return Current X-axis standby enabled status + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_XA_BIT + */ +bool MPU6050::getStandbyXAccelEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, buffer); + return buffer[0]; +} +/** Set X-axis accelerometer standby enabled status. + * @param New X-axis standby enabled status + * @see getStandbyXAccelEnabled() + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_XA_BIT + */ +void MPU6050::setStandbyXAccelEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XA_BIT, enabled); +} +/** Get Y-axis accelerometer standby enabled status. + * If enabled, the Y-axis will not gather or report data (or use power). + * @return Current Y-axis standby enabled status + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_YA_BIT + */ +bool MPU6050::getStandbyYAccelEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, buffer); + return buffer[0]; +} +/** Set Y-axis accelerometer standby enabled status. + * @param New Y-axis standby enabled status + * @see getStandbyYAccelEnabled() + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_YA_BIT + */ +void MPU6050::setStandbyYAccelEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YA_BIT, enabled); +} +/** Get Z-axis accelerometer standby enabled status. + * If enabled, the Z-axis will not gather or report data (or use power). + * @return Current Z-axis standby enabled status + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_ZA_BIT + */ +bool MPU6050::getStandbyZAccelEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, buffer); + return buffer[0]; +} +/** Set Z-axis accelerometer standby enabled status. + * @param New Z-axis standby enabled status + * @see getStandbyZAccelEnabled() + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_ZA_BIT + */ +void MPU6050::setStandbyZAccelEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZA_BIT, enabled); +} +/** Get X-axis gyroscope standby enabled status. + * If enabled, the X-axis will not gather or report data (or use power). + * @return Current X-axis standby enabled status + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_XG_BIT + */ +bool MPU6050::getStandbyXGyroEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, buffer); + return buffer[0]; +} +/** Set X-axis gyroscope standby enabled status. + * @param New X-axis standby enabled status + * @see getStandbyXGyroEnabled() + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_XG_BIT + */ +void MPU6050::setStandbyXGyroEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_XG_BIT, enabled); +} +/** Get Y-axis gyroscope standby enabled status. + * If enabled, the Y-axis will not gather or report data (or use power). + * @return Current Y-axis standby enabled status + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_YG_BIT + */ +bool MPU6050::getStandbyYGyroEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, buffer); + return buffer[0]; +} +/** Set Y-axis gyroscope standby enabled status. + * @param New Y-axis standby enabled status + * @see getStandbyYGyroEnabled() + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_YG_BIT + */ +void MPU6050::setStandbyYGyroEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_YG_BIT, enabled); +} +/** Get Z-axis gyroscope standby enabled status. + * If enabled, the Z-axis will not gather or report data (or use power). + * @return Current Z-axis standby enabled status + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_ZG_BIT + */ +bool MPU6050::getStandbyZGyroEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, buffer); + return buffer[0]; +} +/** Set Z-axis gyroscope standby enabled status. + * @param New Z-axis standby enabled status + * @see getStandbyZGyroEnabled() + * @see MPU6050_RA_PWR_MGMT_2 + * @see MPU6050_PWR2_STBY_ZG_BIT + */ +void MPU6050::setStandbyZGyroEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_PWR_MGMT_2, MPU6050_PWR2_STBY_ZG_BIT, enabled); +} + +// FIFO_COUNT* registers + +/** Get current FIFO buffer size. + * This value indicates the number of bytes stored in the FIFO buffer. This + * number is in turn the number of bytes that can be read from the FIFO buffer + * and it is directly proportional to the number of samples available given the + * set of sensor data bound to be stored in the FIFO (register 35 and 36). + * @return Current FIFO buffer size + */ +uint16_t MPU6050::getFIFOCount() { + I2Cdev::readBytes(devAddr, MPU6050_RA_FIFO_COUNTH, 2, buffer); + return (((uint16_t)buffer[0]) << 8) | buffer[1]; +} + +// FIFO_R_W register + +/** Get byte from FIFO buffer. + * This register is used to read and write data from the FIFO buffer. Data is + * written to the FIFO in order of register number (from lowest to highest). If + * all the FIFO enable flags (see below) are enabled and all External Sensor + * Data registers (Registers 73 to 96) are associated with a Slave device, the + * contents of registers 59 through 96 will be written in order at the Sample + * Rate. + * + * The contents of the sensor data registers (Registers 59 to 96) are written + * into the FIFO buffer when their corresponding FIFO enable flags are set to 1 + * in FIFO_EN (Register 35). An additional flag for the sensor data registers + * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36). + * + * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is + * automatically set to 1. This bit is located in INT_STATUS (Register 58). + * When the FIFO buffer has overflowed, the oldest data will be lost and new + * data will be written to the FIFO. + * + * If the FIFO buffer is empty, reading this register will return the last byte + * that was previously read from the FIFO until new data is available. The user + * should check FIFO_COUNT to ensure that the FIFO buffer is not read when + * empty. + * + * @return Byte from FIFO buffer + */ +uint8_t MPU6050::getFIFOByte() { + I2Cdev::readByte(devAddr, MPU6050_RA_FIFO_R_W, buffer); + return buffer[0]; +} +void MPU6050::getFIFOBytes(uint8_t *data, uint8_t length) { + if(length > 0){ + I2Cdev::readBytes(devAddr, MPU6050_RA_FIFO_R_W, length, data); + } else { + *data = 0; + } +} +/** Write byte to FIFO buffer. + * @see getFIFOByte() + * @see MPU6050_RA_FIFO_R_W + */ +void MPU6050::setFIFOByte(uint8_t data) { + I2Cdev::writeByte(devAddr, MPU6050_RA_FIFO_R_W, data); +} + +// WHO_AM_I register + +/** Get Device ID. + * This register is used to verify the identity of the device (0b110100, 0x34). + * @return Device ID (6 bits only! should be 0x34) + * @see MPU6050_RA_WHO_AM_I + * @see MPU6050_WHO_AM_I_BIT + * @see MPU6050_WHO_AM_I_LENGTH + */ +uint8_t MPU6050::getDeviceID() { + I2Cdev::readBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, buffer); + return buffer[0]; +} +/** Set Device ID. + * Write a new ID into the WHO_AM_I register (no idea why this should ever be + * necessary though). + * @param id New device ID to set. + * @see getDeviceID() + * @see MPU6050_RA_WHO_AM_I + * @see MPU6050_WHO_AM_I_BIT + * @see MPU6050_WHO_AM_I_LENGTH + */ +void MPU6050::setDeviceID(uint8_t id) { + I2Cdev::writeBits(devAddr, MPU6050_RA_WHO_AM_I, MPU6050_WHO_AM_I_BIT, MPU6050_WHO_AM_I_LENGTH, id); +} + +// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ======== + +// XG_OFFS_TC register + +uint8_t MPU6050::getOTPBankValid() { + I2Cdev::readBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, buffer); + return buffer[0]; +} +void MPU6050::setOTPBankValid(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OTP_BNK_VLD_BIT, enabled); +} +int8_t MPU6050::getXGyroOffsetTC() { + I2Cdev::readBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer); + return buffer[0]; +} +void MPU6050::setXGyroOffsetTC(int8_t offset) { + I2Cdev::writeBits(devAddr, MPU6050_RA_XG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset); +} + +// YG_OFFS_TC register + +int8_t MPU6050::getYGyroOffsetTC() { + I2Cdev::readBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer); + return buffer[0]; +} +void MPU6050::setYGyroOffsetTC(int8_t offset) { + I2Cdev::writeBits(devAddr, MPU6050_RA_YG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset); +} + +// ZG_OFFS_TC register + +int8_t MPU6050::getZGyroOffsetTC() { + I2Cdev::readBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, buffer); + return buffer[0]; +} +void MPU6050::setZGyroOffsetTC(int8_t offset) { + I2Cdev::writeBits(devAddr, MPU6050_RA_ZG_OFFS_TC, MPU6050_TC_OFFSET_BIT, MPU6050_TC_OFFSET_LENGTH, offset); +} + +// X_FINE_GAIN register + +int8_t MPU6050::getXFineGain() { + I2Cdev::readByte(devAddr, MPU6050_RA_X_FINE_GAIN, buffer); + return buffer[0]; +} +void MPU6050::setXFineGain(int8_t gain) { + I2Cdev::writeByte(devAddr, MPU6050_RA_X_FINE_GAIN, gain); +} + +// Y_FINE_GAIN register + +int8_t MPU6050::getYFineGain() { + I2Cdev::readByte(devAddr, MPU6050_RA_Y_FINE_GAIN, buffer); + return buffer[0]; +} +void MPU6050::setYFineGain(int8_t gain) { + I2Cdev::writeByte(devAddr, MPU6050_RA_Y_FINE_GAIN, gain); +} + +// Z_FINE_GAIN register + +int8_t MPU6050::getZFineGain() { + I2Cdev::readByte(devAddr, MPU6050_RA_Z_FINE_GAIN, buffer); + return buffer[0]; +} +void MPU6050::setZFineGain(int8_t gain) { + I2Cdev::writeByte(devAddr, MPU6050_RA_Z_FINE_GAIN, gain); +} + +// XA_OFFS_* registers + +int16_t MPU6050::getXAccelOffset() { + I2Cdev::readBytes(devAddr, MPU6050_RA_XA_OFFS_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +void MPU6050::setXAccelOffset(int16_t offset) { + I2Cdev::writeWord(devAddr, MPU6050_RA_XA_OFFS_H, offset); +} + +// YA_OFFS_* register + +int16_t MPU6050::getYAccelOffset() { + I2Cdev::readBytes(devAddr, MPU6050_RA_YA_OFFS_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +void MPU6050::setYAccelOffset(int16_t offset) { + I2Cdev::writeWord(devAddr, MPU6050_RA_YA_OFFS_H, offset); +} + +// ZA_OFFS_* register + +int16_t MPU6050::getZAccelOffset() { + I2Cdev::readBytes(devAddr, MPU6050_RA_ZA_OFFS_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +void MPU6050::setZAccelOffset(int16_t offset) { + I2Cdev::writeWord(devAddr, MPU6050_RA_ZA_OFFS_H, offset); +} + +// XG_OFFS_USR* registers + +int16_t MPU6050::getXGyroOffset() { + I2Cdev::readBytes(devAddr, MPU6050_RA_XG_OFFS_USRH, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +void MPU6050::setXGyroOffset(int16_t offset) { + I2Cdev::writeWord(devAddr, MPU6050_RA_XG_OFFS_USRH, offset); +} + +// YG_OFFS_USR* register + +int16_t MPU6050::getYGyroOffset() { + I2Cdev::readBytes(devAddr, MPU6050_RA_YG_OFFS_USRH, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +void MPU6050::setYGyroOffset(int16_t offset) { + I2Cdev::writeWord(devAddr, MPU6050_RA_YG_OFFS_USRH, offset); +} + +// ZG_OFFS_USR* register + +int16_t MPU6050::getZGyroOffset() { + I2Cdev::readBytes(devAddr, MPU6050_RA_ZG_OFFS_USRH, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +void MPU6050::setZGyroOffset(int16_t offset) { + I2Cdev::writeWord(devAddr, MPU6050_RA_ZG_OFFS_USRH, offset); +} + +// INT_ENABLE register (DMP functions) + +bool MPU6050::getIntPLLReadyEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer); + return buffer[0]; +} +void MPU6050::setIntPLLReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, enabled); +} +bool MPU6050::getIntDMPEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, buffer); + return buffer[0]; +} +void MPU6050::setIntDMPEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_INT_ENABLE, MPU6050_INTERRUPT_DMP_INT_BIT, enabled); +} + +// DMP_INT_STATUS + +bool MPU6050::getDMPInt5Status() { + I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_5_BIT, buffer); + return buffer[0]; +} +bool MPU6050::getDMPInt4Status() { + I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_4_BIT, buffer); + return buffer[0]; +} +bool MPU6050::getDMPInt3Status() { + I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_3_BIT, buffer); + return buffer[0]; +} +bool MPU6050::getDMPInt2Status() { + I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_2_BIT, buffer); + return buffer[0]; +} +bool MPU6050::getDMPInt1Status() { + I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_1_BIT, buffer); + return buffer[0]; +} +bool MPU6050::getDMPInt0Status() { + I2Cdev::readBit(devAddr, MPU6050_RA_DMP_INT_STATUS, MPU6050_DMPINT_0_BIT, buffer); + return buffer[0]; +} + +// INT_STATUS register (DMP functions) + +bool MPU6050::getIntPLLReadyStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_PLL_RDY_INT_BIT, buffer); + return buffer[0]; +} +bool MPU6050::getIntDMPStatus() { + I2Cdev::readBit(devAddr, MPU6050_RA_INT_STATUS, MPU6050_INTERRUPT_DMP_INT_BIT, buffer); + return buffer[0]; +} + +// USER_CTRL register (DMP functions) + +bool MPU6050::getDMPEnabled() { + I2Cdev::readBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, buffer); + return buffer[0]; +} +void MPU6050::setDMPEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_EN_BIT, enabled); +} +void MPU6050::resetDMP() { + I2Cdev::writeBit(devAddr, MPU6050_RA_USER_CTRL, MPU6050_USERCTRL_DMP_RESET_BIT, true); +} + +// BANK_SEL register + +void MPU6050::setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank) { + bank &= 0x1F; + if (userBank) bank |= 0x20; + if (prefetchEnabled) bank |= 0x40; + I2Cdev::writeByte(devAddr, MPU6050_RA_BANK_SEL, bank); +} + +// MEM_START_ADDR register + +void MPU6050::setMemoryStartAddress(uint8_t address) { + I2Cdev::writeByte(devAddr, MPU6050_RA_MEM_START_ADDR, address); +} + +// MEM_R_W register + +uint8_t MPU6050::readMemoryByte() { + I2Cdev::readByte(devAddr, MPU6050_RA_MEM_R_W, buffer); + return buffer[0]; +} +void MPU6050::writeMemoryByte(uint8_t data) { + I2Cdev::writeByte(devAddr, MPU6050_RA_MEM_R_W, data); +} +void MPU6050::readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address) { + setMemoryBank(bank); + setMemoryStartAddress(address); + uint8_t chunkSize; + for (uint16_t i = 0; i < dataSize;) { + // determine correct chunk size according to bank position and data size + chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE; + + // make sure we don't go past the data size + if (i + chunkSize > dataSize) chunkSize = dataSize - i; + + // make sure this chunk doesn't go past the bank boundary (256 bytes) + if (chunkSize > 256 - address) chunkSize = 256 - address; + + // read the chunk of data as specified + I2Cdev::readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, data + i); + + // increase byte index by [chunkSize] + i += chunkSize; + + // uint8_t automatically wraps to 0 at 256 + address += chunkSize; + + // if we aren't done, update bank (if necessary) and address + if (i < dataSize) { + if (address == 0) bank++; + setMemoryBank(bank); + setMemoryStartAddress(address); + } + } +} +bool MPU6050::writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem) { + setMemoryBank(bank); + setMemoryStartAddress(address); + uint8_t chunkSize; + uint8_t *verifyBuffer; + uint8_t *progBuffer=0; + uint16_t i; + uint8_t j; + if (verify) verifyBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE); + if (useProgMem) progBuffer = (uint8_t *)malloc(MPU6050_DMP_MEMORY_CHUNK_SIZE); + for (i = 0; i < dataSize;) { + // determine correct chunk size according to bank position and data size + chunkSize = MPU6050_DMP_MEMORY_CHUNK_SIZE; + + // make sure we don't go past the data size + if (i + chunkSize > dataSize) chunkSize = dataSize - i; + + // make sure this chunk doesn't go past the bank boundary (256 bytes) + if (chunkSize > 256 - address) chunkSize = 256 - address; + + if (useProgMem) { + // write the chunk of data as specified + for (j = 0; j < chunkSize; j++) progBuffer[j] = pgm_read_byte(data + i + j); + } else { + // write the chunk of data as specified + progBuffer = (uint8_t *)data + i; + } + + I2Cdev::writeBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, progBuffer); + + // verify data if needed + if (verify && verifyBuffer) { + setMemoryBank(bank); + setMemoryStartAddress(address); + I2Cdev::readBytes(devAddr, MPU6050_RA_MEM_R_W, chunkSize, verifyBuffer); + if (memcmp(progBuffer, verifyBuffer, chunkSize) != 0) { + /*Serial.print("Block write verification error, bank "); + Serial.print(bank, DEC); + Serial.print(", address "); + Serial.print(address, DEC); + Serial.print("!\nExpected:"); + for (j = 0; j < chunkSize; j++) { + Serial.print(" 0x"); + if (progBuffer[j] < 16) Serial.print("0"); + Serial.print(progBuffer[j], HEX); + } + Serial.print("\nReceived:"); + for (uint8_t j = 0; j < chunkSize; j++) { + Serial.print(" 0x"); + if (verifyBuffer[i + j] < 16) Serial.print("0"); + Serial.print(verifyBuffer[i + j], HEX); + } + Serial.print("\n");*/ + free(verifyBuffer); + if (useProgMem) free(progBuffer); + return false; // uh oh. + } + } + + // increase byte index by [chunkSize] + i += chunkSize; + + // uint8_t automatically wraps to 0 at 256 + address += chunkSize; + + // if we aren't done, update bank (if necessary) and address + if (i < dataSize) { + if (address == 0) bank++; + setMemoryBank(bank); + setMemoryStartAddress(address); + } + } + if (verify) free(verifyBuffer); + if (useProgMem) free(progBuffer); + return true; +} +bool MPU6050::writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify) { + return writeMemoryBlock(data, dataSize, bank, address, verify, true); +} +bool MPU6050::writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem) { + uint8_t *progBuffer = 0; + uint8_t success, special; + uint16_t i, j; + if (useProgMem) { + progBuffer = (uint8_t *)malloc(8); // assume 8-byte blocks, realloc later if necessary + } + + // config set data is a long string of blocks with the following structure: + // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]] + uint8_t bank, offset, length; + for (i = 0; i < dataSize;) { + if (useProgMem) { + bank = pgm_read_byte(data + i++); + offset = pgm_read_byte(data + i++); + length = pgm_read_byte(data + i++); + } else { + bank = data[i++]; + offset = data[i++]; + length = data[i++]; + } + + // write data or perform special action + if (length > 0) { + // regular block of data to write + /*Serial.print("Writing config block to bank "); + Serial.print(bank); + Serial.print(", offset "); + Serial.print(offset); + Serial.print(", length="); + Serial.println(length);*/ + if (useProgMem) { + if (sizeof(progBuffer) < length) progBuffer = (uint8_t *)realloc(progBuffer, length); + for (j = 0; j < length; j++) progBuffer[j] = pgm_read_byte(data + i + j); + } else { + progBuffer = (uint8_t *)data + i; + } + success = writeMemoryBlock(progBuffer, length, bank, offset, true); + i += length; + } else { + // special instruction + // NOTE: this kind of behavior (what and when to do certain things) + // is totally undocumented. This code is in here based on observed + // behavior only, and exactly why (or even whether) it has to be here + // is anybody's guess for now. + if (useProgMem) { + special = pgm_read_byte(data + i++); + } else { + special = data[i++]; + } + /*Serial.print("Special command code "); + Serial.print(special, HEX); + Serial.println(" found...");*/ + if (special == 0x01) { + // enable DMP-related interrupts + + //setIntZeroMotionEnabled(true); + //setIntFIFOBufferOverflowEnabled(true); + //setIntDMPEnabled(true); + I2Cdev::writeByte(devAddr, MPU6050_RA_INT_ENABLE, 0x32); // single operation + + success = true; + } else { + // unknown special command + success = false; + } + } + + if (!success) { + if (useProgMem) free(progBuffer); + return false; // uh oh + } + } + if (useProgMem) free(progBuffer); + return true; +} +bool MPU6050::writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize) { + return writeDMPConfigurationSet(data, dataSize, true); +} + +// DMP_CFG_1 register + +uint8_t MPU6050::getDMPConfig1() { + I2Cdev::readByte(devAddr, MPU6050_RA_DMP_CFG_1, buffer); + return buffer[0]; +} +void MPU6050::setDMPConfig1(uint8_t config) { + I2Cdev::writeByte(devAddr, MPU6050_RA_DMP_CFG_1, config); +} + +// DMP_CFG_2 register + +uint8_t MPU6050::getDMPConfig2() { + I2Cdev::readByte(devAddr, MPU6050_RA_DMP_CFG_2, buffer); + return buffer[0]; +} +void MPU6050::setDMPConfig2(uint8_t config) { + I2Cdev::writeByte(devAddr, MPU6050_RA_DMP_CFG_2, config); +} diff --git a/libraries/MPU6050/MPU6050.h b/libraries/MPU6050/MPU6050.h new file mode 100644 index 0000000..194c237 --- /dev/null +++ b/libraries/MPU6050/MPU6050.h @@ -0,0 +1,1033 @@ +// I2Cdev library collection - MPU6050 I2C device class +// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00) +// 10/3/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// ... - ongoing debug release + +// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE +// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF +// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING. + +/* ============================================ +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. +=============================================== +*/ + +#ifndef _MPU6050_H_ +#define _MPU6050_H_ + +#include "I2Cdev.h" + +// supporting link: http://forum.arduino.cc/index.php?&topic=143444.msg1079517#msg1079517 +// also: http://forum.arduino.cc/index.php?&topic=141571.msg1062899#msg1062899s + +#ifdef __AVR__ +#include +#else +//#define PROGMEM /* empty */ +//#define pgm_read_byte(x) (*(x)) +//#define pgm_read_word(x) (*(x)) +//#define pgm_read_float(x) (*(x)) +//#define PSTR(STR) STR +#endif + + +#define MPU6050_ADDRESS_AD0_LOW 0x68 // address pin low (GND), default for InvenSense evaluation board +#define MPU6050_ADDRESS_AD0_HIGH 0x69 // address pin high (VCC) +#define MPU6050_DEFAULT_ADDRESS MPU6050_ADDRESS_AD0_LOW + +#define MPU6050_RA_XG_OFFS_TC 0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD +#define MPU6050_RA_YG_OFFS_TC 0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD +#define MPU6050_RA_ZG_OFFS_TC 0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD +#define MPU6050_RA_X_FINE_GAIN 0x03 //[7:0] X_FINE_GAIN +#define MPU6050_RA_Y_FINE_GAIN 0x04 //[7:0] Y_FINE_GAIN +#define MPU6050_RA_Z_FINE_GAIN 0x05 //[7:0] Z_FINE_GAIN +#define MPU6050_RA_XA_OFFS_H 0x06 //[15:0] XA_OFFS +#define MPU6050_RA_XA_OFFS_L_TC 0x07 +#define MPU6050_RA_YA_OFFS_H 0x08 //[15:0] YA_OFFS +#define MPU6050_RA_YA_OFFS_L_TC 0x09 +#define MPU6050_RA_ZA_OFFS_H 0x0A //[15:0] ZA_OFFS +#define MPU6050_RA_ZA_OFFS_L_TC 0x0B +#define MPU6050_RA_SELF_TEST_X 0x0D //[7:5] XA_TEST[4-2], [4:0] XG_TEST[4-0] +#define MPU6050_RA_SELF_TEST_Y 0x0E //[7:5] YA_TEST[4-2], [4:0] YG_TEST[4-0] +#define MPU6050_RA_SELF_TEST_Z 0x0F //[7:5] ZA_TEST[4-2], [4:0] ZG_TEST[4-0] +#define MPU6050_RA_SELF_TEST_A 0x10 //[5:4] XA_TEST[1-0], [3:2] YA_TEST[1-0], [1:0] ZA_TEST[1-0] +#define MPU6050_RA_XG_OFFS_USRH 0x13 //[15:0] XG_OFFS_USR +#define MPU6050_RA_XG_OFFS_USRL 0x14 +#define MPU6050_RA_YG_OFFS_USRH 0x15 //[15:0] YG_OFFS_USR +#define MPU6050_RA_YG_OFFS_USRL 0x16 +#define MPU6050_RA_ZG_OFFS_USRH 0x17 //[15:0] ZG_OFFS_USR +#define MPU6050_RA_ZG_OFFS_USRL 0x18 +#define MPU6050_RA_SMPLRT_DIV 0x19 +#define MPU6050_RA_CONFIG 0x1A +#define MPU6050_RA_GYRO_CONFIG 0x1B +#define MPU6050_RA_ACCEL_CONFIG 0x1C +#define MPU6050_RA_FF_THR 0x1D +#define MPU6050_RA_FF_DUR 0x1E +#define MPU6050_RA_MOT_THR 0x1F +#define MPU6050_RA_MOT_DUR 0x20 +#define MPU6050_RA_ZRMOT_THR 0x21 +#define MPU6050_RA_ZRMOT_DUR 0x22 +#define MPU6050_RA_FIFO_EN 0x23 +#define MPU6050_RA_I2C_MST_CTRL 0x24 +#define MPU6050_RA_I2C_SLV0_ADDR 0x25 +#define MPU6050_RA_I2C_SLV0_REG 0x26 +#define MPU6050_RA_I2C_SLV0_CTRL 0x27 +#define MPU6050_RA_I2C_SLV1_ADDR 0x28 +#define MPU6050_RA_I2C_SLV1_REG 0x29 +#define MPU6050_RA_I2C_SLV1_CTRL 0x2A +#define MPU6050_RA_I2C_SLV2_ADDR 0x2B +#define MPU6050_RA_I2C_SLV2_REG 0x2C +#define MPU6050_RA_I2C_SLV2_CTRL 0x2D +#define MPU6050_RA_I2C_SLV3_ADDR 0x2E +#define MPU6050_RA_I2C_SLV3_REG 0x2F +#define MPU6050_RA_I2C_SLV3_CTRL 0x30 +#define MPU6050_RA_I2C_SLV4_ADDR 0x31 +#define MPU6050_RA_I2C_SLV4_REG 0x32 +#define MPU6050_RA_I2C_SLV4_DO 0x33 +#define MPU6050_RA_I2C_SLV4_CTRL 0x34 +#define MPU6050_RA_I2C_SLV4_DI 0x35 +#define MPU6050_RA_I2C_MST_STATUS 0x36 +#define MPU6050_RA_INT_PIN_CFG 0x37 +#define MPU6050_RA_INT_ENABLE 0x38 +#define MPU6050_RA_DMP_INT_STATUS 0x39 +#define MPU6050_RA_INT_STATUS 0x3A +#define MPU6050_RA_ACCEL_XOUT_H 0x3B +#define MPU6050_RA_ACCEL_XOUT_L 0x3C +#define MPU6050_RA_ACCEL_YOUT_H 0x3D +#define MPU6050_RA_ACCEL_YOUT_L 0x3E +#define MPU6050_RA_ACCEL_ZOUT_H 0x3F +#define MPU6050_RA_ACCEL_ZOUT_L 0x40 +#define MPU6050_RA_TEMP_OUT_H 0x41 +#define MPU6050_RA_TEMP_OUT_L 0x42 +#define MPU6050_RA_GYRO_XOUT_H 0x43 +#define MPU6050_RA_GYRO_XOUT_L 0x44 +#define MPU6050_RA_GYRO_YOUT_H 0x45 +#define MPU6050_RA_GYRO_YOUT_L 0x46 +#define MPU6050_RA_GYRO_ZOUT_H 0x47 +#define MPU6050_RA_GYRO_ZOUT_L 0x48 +#define MPU6050_RA_EXT_SENS_DATA_00 0x49 +#define MPU6050_RA_EXT_SENS_DATA_01 0x4A +#define MPU6050_RA_EXT_SENS_DATA_02 0x4B +#define MPU6050_RA_EXT_SENS_DATA_03 0x4C +#define MPU6050_RA_EXT_SENS_DATA_04 0x4D +#define MPU6050_RA_EXT_SENS_DATA_05 0x4E +#define MPU6050_RA_EXT_SENS_DATA_06 0x4F +#define MPU6050_RA_EXT_SENS_DATA_07 0x50 +#define MPU6050_RA_EXT_SENS_DATA_08 0x51 +#define MPU6050_RA_EXT_SENS_DATA_09 0x52 +#define MPU6050_RA_EXT_SENS_DATA_10 0x53 +#define MPU6050_RA_EXT_SENS_DATA_11 0x54 +#define MPU6050_RA_EXT_SENS_DATA_12 0x55 +#define MPU6050_RA_EXT_SENS_DATA_13 0x56 +#define MPU6050_RA_EXT_SENS_DATA_14 0x57 +#define MPU6050_RA_EXT_SENS_DATA_15 0x58 +#define MPU6050_RA_EXT_SENS_DATA_16 0x59 +#define MPU6050_RA_EXT_SENS_DATA_17 0x5A +#define MPU6050_RA_EXT_SENS_DATA_18 0x5B +#define MPU6050_RA_EXT_SENS_DATA_19 0x5C +#define MPU6050_RA_EXT_SENS_DATA_20 0x5D +#define MPU6050_RA_EXT_SENS_DATA_21 0x5E +#define MPU6050_RA_EXT_SENS_DATA_22 0x5F +#define MPU6050_RA_EXT_SENS_DATA_23 0x60 +#define MPU6050_RA_MOT_DETECT_STATUS 0x61 +#define MPU6050_RA_I2C_SLV0_DO 0x63 +#define MPU6050_RA_I2C_SLV1_DO 0x64 +#define MPU6050_RA_I2C_SLV2_DO 0x65 +#define MPU6050_RA_I2C_SLV3_DO 0x66 +#define MPU6050_RA_I2C_MST_DELAY_CTRL 0x67 +#define MPU6050_RA_SIGNAL_PATH_RESET 0x68 +#define MPU6050_RA_MOT_DETECT_CTRL 0x69 +#define MPU6050_RA_USER_CTRL 0x6A +#define MPU6050_RA_PWR_MGMT_1 0x6B +#define MPU6050_RA_PWR_MGMT_2 0x6C +#define MPU6050_RA_BANK_SEL 0x6D +#define MPU6050_RA_MEM_START_ADDR 0x6E +#define MPU6050_RA_MEM_R_W 0x6F +#define MPU6050_RA_DMP_CFG_1 0x70 +#define MPU6050_RA_DMP_CFG_2 0x71 +#define MPU6050_RA_FIFO_COUNTH 0x72 +#define MPU6050_RA_FIFO_COUNTL 0x73 +#define MPU6050_RA_FIFO_R_W 0x74 +#define MPU6050_RA_WHO_AM_I 0x75 + +#define MPU6050_SELF_TEST_XA_1_BIT 0x07 +#define MPU6050_SELF_TEST_XA_1_LENGTH 0x03 +#define MPU6050_SELF_TEST_XA_2_BIT 0x05 +#define MPU6050_SELF_TEST_XA_2_LENGTH 0x02 +#define MPU6050_SELF_TEST_YA_1_BIT 0x07 +#define MPU6050_SELF_TEST_YA_1_LENGTH 0x03 +#define MPU6050_SELF_TEST_YA_2_BIT 0x03 +#define MPU6050_SELF_TEST_YA_2_LENGTH 0x02 +#define MPU6050_SELF_TEST_ZA_1_BIT 0x07 +#define MPU6050_SELF_TEST_ZA_1_LENGTH 0x03 +#define MPU6050_SELF_TEST_ZA_2_BIT 0x01 +#define MPU6050_SELF_TEST_ZA_2_LENGTH 0x02 + +#define MPU6050_SELF_TEST_XG_1_BIT 0x04 +#define MPU6050_SELF_TEST_XG_1_LENGTH 0x05 +#define MPU6050_SELF_TEST_YG_1_BIT 0x04 +#define MPU6050_SELF_TEST_YG_1_LENGTH 0x05 +#define MPU6050_SELF_TEST_ZG_1_BIT 0x04 +#define MPU6050_SELF_TEST_ZG_1_LENGTH 0x05 + +#define MPU6050_TC_PWR_MODE_BIT 7 +#define MPU6050_TC_OFFSET_BIT 6 +#define MPU6050_TC_OFFSET_LENGTH 6 +#define MPU6050_TC_OTP_BNK_VLD_BIT 0 + +#define MPU6050_VDDIO_LEVEL_VLOGIC 0 +#define MPU6050_VDDIO_LEVEL_VDD 1 + +#define MPU6050_CFG_EXT_SYNC_SET_BIT 5 +#define MPU6050_CFG_EXT_SYNC_SET_LENGTH 3 +#define MPU6050_CFG_DLPF_CFG_BIT 2 +#define MPU6050_CFG_DLPF_CFG_LENGTH 3 + +#define MPU6050_EXT_SYNC_DISABLED 0x0 +#define MPU6050_EXT_SYNC_TEMP_OUT_L 0x1 +#define MPU6050_EXT_SYNC_GYRO_XOUT_L 0x2 +#define MPU6050_EXT_SYNC_GYRO_YOUT_L 0x3 +#define MPU6050_EXT_SYNC_GYRO_ZOUT_L 0x4 +#define MPU6050_EXT_SYNC_ACCEL_XOUT_L 0x5 +#define MPU6050_EXT_SYNC_ACCEL_YOUT_L 0x6 +#define MPU6050_EXT_SYNC_ACCEL_ZOUT_L 0x7 + +#define MPU6050_DLPF_BW_256 0x00 +#define MPU6050_DLPF_BW_188 0x01 +#define MPU6050_DLPF_BW_98 0x02 +#define MPU6050_DLPF_BW_42 0x03 +#define MPU6050_DLPF_BW_20 0x04 +#define MPU6050_DLPF_BW_10 0x05 +#define MPU6050_DLPF_BW_5 0x06 + +#define MPU6050_GCONFIG_FS_SEL_BIT 4 +#define MPU6050_GCONFIG_FS_SEL_LENGTH 2 + +#define MPU6050_GYRO_FS_250 0x00 +#define MPU6050_GYRO_FS_500 0x01 +#define MPU6050_GYRO_FS_1000 0x02 +#define MPU6050_GYRO_FS_2000 0x03 + +#define MPU6050_ACONFIG_XA_ST_BIT 7 +#define MPU6050_ACONFIG_YA_ST_BIT 6 +#define MPU6050_ACONFIG_ZA_ST_BIT 5 +#define MPU6050_ACONFIG_AFS_SEL_BIT 4 +#define MPU6050_ACONFIG_AFS_SEL_LENGTH 2 +#define MPU6050_ACONFIG_ACCEL_HPF_BIT 2 +#define MPU6050_ACONFIG_ACCEL_HPF_LENGTH 3 + +#define MPU6050_ACCEL_FS_2 0x00 +#define MPU6050_ACCEL_FS_4 0x01 +#define MPU6050_ACCEL_FS_8 0x02 +#define MPU6050_ACCEL_FS_16 0x03 + +#define MPU6050_DHPF_RESET 0x00 +#define MPU6050_DHPF_5 0x01 +#define MPU6050_DHPF_2P5 0x02 +#define MPU6050_DHPF_1P25 0x03 +#define MPU6050_DHPF_0P63 0x04 +#define MPU6050_DHPF_HOLD 0x07 + +#define MPU6050_TEMP_FIFO_EN_BIT 7 +#define MPU6050_XG_FIFO_EN_BIT 6 +#define MPU6050_YG_FIFO_EN_BIT 5 +#define MPU6050_ZG_FIFO_EN_BIT 4 +#define MPU6050_ACCEL_FIFO_EN_BIT 3 +#define MPU6050_SLV2_FIFO_EN_BIT 2 +#define MPU6050_SLV1_FIFO_EN_BIT 1 +#define MPU6050_SLV0_FIFO_EN_BIT 0 + +#define MPU6050_MULT_MST_EN_BIT 7 +#define MPU6050_WAIT_FOR_ES_BIT 6 +#define MPU6050_SLV_3_FIFO_EN_BIT 5 +#define MPU6050_I2C_MST_P_NSR_BIT 4 +#define MPU6050_I2C_MST_CLK_BIT 3 +#define MPU6050_I2C_MST_CLK_LENGTH 4 + +#define MPU6050_CLOCK_DIV_348 0x0 +#define MPU6050_CLOCK_DIV_333 0x1 +#define MPU6050_CLOCK_DIV_320 0x2 +#define MPU6050_CLOCK_DIV_308 0x3 +#define MPU6050_CLOCK_DIV_296 0x4 +#define MPU6050_CLOCK_DIV_286 0x5 +#define MPU6050_CLOCK_DIV_276 0x6 +#define MPU6050_CLOCK_DIV_267 0x7 +#define MPU6050_CLOCK_DIV_258 0x8 +#define MPU6050_CLOCK_DIV_500 0x9 +#define MPU6050_CLOCK_DIV_471 0xA +#define MPU6050_CLOCK_DIV_444 0xB +#define MPU6050_CLOCK_DIV_421 0xC +#define MPU6050_CLOCK_DIV_400 0xD +#define MPU6050_CLOCK_DIV_381 0xE +#define MPU6050_CLOCK_DIV_364 0xF + +#define MPU6050_I2C_SLV_RW_BIT 7 +#define MPU6050_I2C_SLV_ADDR_BIT 6 +#define MPU6050_I2C_SLV_ADDR_LENGTH 7 +#define MPU6050_I2C_SLV_EN_BIT 7 +#define MPU6050_I2C_SLV_BYTE_SW_BIT 6 +#define MPU6050_I2C_SLV_REG_DIS_BIT 5 +#define MPU6050_I2C_SLV_GRP_BIT 4 +#define MPU6050_I2C_SLV_LEN_BIT 3 +#define MPU6050_I2C_SLV_LEN_LENGTH 4 + +#define MPU6050_I2C_SLV4_RW_BIT 7 +#define MPU6050_I2C_SLV4_ADDR_BIT 6 +#define MPU6050_I2C_SLV4_ADDR_LENGTH 7 +#define MPU6050_I2C_SLV4_EN_BIT 7 +#define MPU6050_I2C_SLV4_INT_EN_BIT 6 +#define MPU6050_I2C_SLV4_REG_DIS_BIT 5 +#define MPU6050_I2C_SLV4_MST_DLY_BIT 4 +#define MPU6050_I2C_SLV4_MST_DLY_LENGTH 5 + +#define MPU6050_MST_PASS_THROUGH_BIT 7 +#define MPU6050_MST_I2C_SLV4_DONE_BIT 6 +#define MPU6050_MST_I2C_LOST_ARB_BIT 5 +#define MPU6050_MST_I2C_SLV4_NACK_BIT 4 +#define MPU6050_MST_I2C_SLV3_NACK_BIT 3 +#define MPU6050_MST_I2C_SLV2_NACK_BIT 2 +#define MPU6050_MST_I2C_SLV1_NACK_BIT 1 +#define MPU6050_MST_I2C_SLV0_NACK_BIT 0 + +#define MPU6050_INTCFG_INT_LEVEL_BIT 7 +#define MPU6050_INTCFG_INT_OPEN_BIT 6 +#define MPU6050_INTCFG_LATCH_INT_EN_BIT 5 +#define MPU6050_INTCFG_INT_RD_CLEAR_BIT 4 +#define MPU6050_INTCFG_FSYNC_INT_LEVEL_BIT 3 +#define MPU6050_INTCFG_FSYNC_INT_EN_BIT 2 +#define MPU6050_INTCFG_I2C_BYPASS_EN_BIT 1 +#define MPU6050_INTCFG_CLKOUT_EN_BIT 0 + +#define MPU6050_INTMODE_ACTIVEHIGH 0x00 +#define MPU6050_INTMODE_ACTIVELOW 0x01 + +#define MPU6050_INTDRV_PUSHPULL 0x00 +#define MPU6050_INTDRV_OPENDRAIN 0x01 + +#define MPU6050_INTLATCH_50USPULSE 0x00 +#define MPU6050_INTLATCH_WAITCLEAR 0x01 + +#define MPU6050_INTCLEAR_STATUSREAD 0x00 +#define MPU6050_INTCLEAR_ANYREAD 0x01 + +#define MPU6050_INTERRUPT_FF_BIT 7 +#define MPU6050_INTERRUPT_MOT_BIT 6 +#define MPU6050_INTERRUPT_ZMOT_BIT 5 +#define MPU6050_INTERRUPT_FIFO_OFLOW_BIT 4 +#define MPU6050_INTERRUPT_I2C_MST_INT_BIT 3 +#define MPU6050_INTERRUPT_PLL_RDY_INT_BIT 2 +#define MPU6050_INTERRUPT_DMP_INT_BIT 1 +#define MPU6050_INTERRUPT_DATA_RDY_BIT 0 + +// TODO: figure out what these actually do +// UMPL source code is not very obivous +#define MPU6050_DMPINT_5_BIT 5 +#define MPU6050_DMPINT_4_BIT 4 +#define MPU6050_DMPINT_3_BIT 3 +#define MPU6050_DMPINT_2_BIT 2 +#define MPU6050_DMPINT_1_BIT 1 +#define MPU6050_DMPINT_0_BIT 0 + +#define MPU6050_MOTION_MOT_XNEG_BIT 7 +#define MPU6050_MOTION_MOT_XPOS_BIT 6 +#define MPU6050_MOTION_MOT_YNEG_BIT 5 +#define MPU6050_MOTION_MOT_YPOS_BIT 4 +#define MPU6050_MOTION_MOT_ZNEG_BIT 3 +#define MPU6050_MOTION_MOT_ZPOS_BIT 2 +#define MPU6050_MOTION_MOT_ZRMOT_BIT 0 + +#define MPU6050_DELAYCTRL_DELAY_ES_SHADOW_BIT 7 +#define MPU6050_DELAYCTRL_I2C_SLV4_DLY_EN_BIT 4 +#define MPU6050_DELAYCTRL_I2C_SLV3_DLY_EN_BIT 3 +#define MPU6050_DELAYCTRL_I2C_SLV2_DLY_EN_BIT 2 +#define MPU6050_DELAYCTRL_I2C_SLV1_DLY_EN_BIT 1 +#define MPU6050_DELAYCTRL_I2C_SLV0_DLY_EN_BIT 0 + +#define MPU6050_PATHRESET_GYRO_RESET_BIT 2 +#define MPU6050_PATHRESET_ACCEL_RESET_BIT 1 +#define MPU6050_PATHRESET_TEMP_RESET_BIT 0 + +#define MPU6050_DETECT_ACCEL_ON_DELAY_BIT 5 +#define MPU6050_DETECT_ACCEL_ON_DELAY_LENGTH 2 +#define MPU6050_DETECT_FF_COUNT_BIT 3 +#define MPU6050_DETECT_FF_COUNT_LENGTH 2 +#define MPU6050_DETECT_MOT_COUNT_BIT 1 +#define MPU6050_DETECT_MOT_COUNT_LENGTH 2 + +#define MPU6050_DETECT_DECREMENT_RESET 0x0 +#define MPU6050_DETECT_DECREMENT_1 0x1 +#define MPU6050_DETECT_DECREMENT_2 0x2 +#define MPU6050_DETECT_DECREMENT_4 0x3 + +#define MPU6050_USERCTRL_DMP_EN_BIT 7 +#define MPU6050_USERCTRL_FIFO_EN_BIT 6 +#define MPU6050_USERCTRL_I2C_MST_EN_BIT 5 +#define MPU6050_USERCTRL_I2C_IF_DIS_BIT 4 +#define MPU6050_USERCTRL_DMP_RESET_BIT 3 +#define MPU6050_USERCTRL_FIFO_RESET_BIT 2 +#define MPU6050_USERCTRL_I2C_MST_RESET_BIT 1 +#define MPU6050_USERCTRL_SIG_COND_RESET_BIT 0 + +#define MPU6050_PWR1_DEVICE_RESET_BIT 7 +#define MPU6050_PWR1_SLEEP_BIT 6 +#define MPU6050_PWR1_CYCLE_BIT 5 +#define MPU6050_PWR1_TEMP_DIS_BIT 3 +#define MPU6050_PWR1_CLKSEL_BIT 2 +#define MPU6050_PWR1_CLKSEL_LENGTH 3 + +#define MPU6050_CLOCK_INTERNAL 0x00 +#define MPU6050_CLOCK_PLL_XGYRO 0x01 +#define MPU6050_CLOCK_PLL_YGYRO 0x02 +#define MPU6050_CLOCK_PLL_ZGYRO 0x03 +#define MPU6050_CLOCK_PLL_EXT32K 0x04 +#define MPU6050_CLOCK_PLL_EXT19M 0x05 +#define MPU6050_CLOCK_KEEP_RESET 0x07 + +#define MPU6050_PWR2_LP_WAKE_CTRL_BIT 7 +#define MPU6050_PWR2_LP_WAKE_CTRL_LENGTH 2 +#define MPU6050_PWR2_STBY_XA_BIT 5 +#define MPU6050_PWR2_STBY_YA_BIT 4 +#define MPU6050_PWR2_STBY_ZA_BIT 3 +#define MPU6050_PWR2_STBY_XG_BIT 2 +#define MPU6050_PWR2_STBY_YG_BIT 1 +#define MPU6050_PWR2_STBY_ZG_BIT 0 + +#define MPU6050_WAKE_FREQ_1P25 0x0 +#define MPU6050_WAKE_FREQ_2P5 0x1 +#define MPU6050_WAKE_FREQ_5 0x2 +#define MPU6050_WAKE_FREQ_10 0x3 + +#define MPU6050_BANKSEL_PRFTCH_EN_BIT 6 +#define MPU6050_BANKSEL_CFG_USER_BANK_BIT 5 +#define MPU6050_BANKSEL_MEM_SEL_BIT 4 +#define MPU6050_BANKSEL_MEM_SEL_LENGTH 5 + +#define MPU6050_WHO_AM_I_BIT 6 +#define MPU6050_WHO_AM_I_LENGTH 6 + +#define MPU6050_DMP_MEMORY_BANKS 8 +#define MPU6050_DMP_MEMORY_BANK_SIZE 256 +#define MPU6050_DMP_MEMORY_CHUNK_SIZE 16 + +// note: DMP code memory blocks defined at end of header file + +class MPU6050 { + public: + MPU6050(); + MPU6050(uint8_t address); + + void initialize(); + bool testConnection(); + + // AUX_VDDIO register + uint8_t getAuxVDDIOLevel(); + void setAuxVDDIOLevel(uint8_t level); + + // SMPLRT_DIV register + uint8_t getRate(); + void setRate(uint8_t rate); + + // CONFIG register + uint8_t getExternalFrameSync(); + void setExternalFrameSync(uint8_t sync); + uint8_t getDLPFMode(); + void setDLPFMode(uint8_t bandwidth); + + // GYRO_CONFIG register + uint8_t getFullScaleGyroRange(); + void setFullScaleGyroRange(uint8_t range); + + // SELF_TEST registers + uint8_t getAccelXSelfTestFactoryTrim(); + uint8_t getAccelYSelfTestFactoryTrim(); + uint8_t getAccelZSelfTestFactoryTrim(); + + uint8_t getGyroXSelfTestFactoryTrim(); + uint8_t getGyroYSelfTestFactoryTrim(); + uint8_t getGyroZSelfTestFactoryTrim(); + + // ACCEL_CONFIG register + bool getAccelXSelfTest(); + void setAccelXSelfTest(bool enabled); + bool getAccelYSelfTest(); + void setAccelYSelfTest(bool enabled); + bool getAccelZSelfTest(); + void setAccelZSelfTest(bool enabled); + uint8_t getFullScaleAccelRange(); + void setFullScaleAccelRange(uint8_t range); + uint8_t getDHPFMode(); + void setDHPFMode(uint8_t mode); + + // FF_THR register + uint8_t getFreefallDetectionThreshold(); + void setFreefallDetectionThreshold(uint8_t threshold); + + // FF_DUR register + uint8_t getFreefallDetectionDuration(); + void setFreefallDetectionDuration(uint8_t duration); + + // MOT_THR register + uint8_t getMotionDetectionThreshold(); + void setMotionDetectionThreshold(uint8_t threshold); + + // MOT_DUR register + uint8_t getMotionDetectionDuration(); + void setMotionDetectionDuration(uint8_t duration); + + // ZRMOT_THR register + uint8_t getZeroMotionDetectionThreshold(); + void setZeroMotionDetectionThreshold(uint8_t threshold); + + // ZRMOT_DUR register + uint8_t getZeroMotionDetectionDuration(); + void setZeroMotionDetectionDuration(uint8_t duration); + + // FIFO_EN register + bool getTempFIFOEnabled(); + void setTempFIFOEnabled(bool enabled); + bool getXGyroFIFOEnabled(); + void setXGyroFIFOEnabled(bool enabled); + bool getYGyroFIFOEnabled(); + void setYGyroFIFOEnabled(bool enabled); + bool getZGyroFIFOEnabled(); + void setZGyroFIFOEnabled(bool enabled); + bool getAccelFIFOEnabled(); + void setAccelFIFOEnabled(bool enabled); + bool getSlave2FIFOEnabled(); + void setSlave2FIFOEnabled(bool enabled); + bool getSlave1FIFOEnabled(); + void setSlave1FIFOEnabled(bool enabled); + bool getSlave0FIFOEnabled(); + void setSlave0FIFOEnabled(bool enabled); + + // I2C_MST_CTRL register + bool getMultiMasterEnabled(); + void setMultiMasterEnabled(bool enabled); + bool getWaitForExternalSensorEnabled(); + void setWaitForExternalSensorEnabled(bool enabled); + bool getSlave3FIFOEnabled(); + void setSlave3FIFOEnabled(bool enabled); + bool getSlaveReadWriteTransitionEnabled(); + void setSlaveReadWriteTransitionEnabled(bool enabled); + uint8_t getMasterClockSpeed(); + void setMasterClockSpeed(uint8_t speed); + + // I2C_SLV* registers (Slave 0-3) + uint8_t getSlaveAddress(uint8_t num); + void setSlaveAddress(uint8_t num, uint8_t address); + uint8_t getSlaveRegister(uint8_t num); + void setSlaveRegister(uint8_t num, uint8_t reg); + bool getSlaveEnabled(uint8_t num); + void setSlaveEnabled(uint8_t num, bool enabled); + bool getSlaveWordByteSwap(uint8_t num); + void setSlaveWordByteSwap(uint8_t num, bool enabled); + bool getSlaveWriteMode(uint8_t num); + void setSlaveWriteMode(uint8_t num, bool mode); + bool getSlaveWordGroupOffset(uint8_t num); + void setSlaveWordGroupOffset(uint8_t num, bool enabled); + uint8_t getSlaveDataLength(uint8_t num); + void setSlaveDataLength(uint8_t num, uint8_t length); + + // I2C_SLV* registers (Slave 4) + uint8_t getSlave4Address(); + void setSlave4Address(uint8_t address); + uint8_t getSlave4Register(); + void setSlave4Register(uint8_t reg); + void setSlave4OutputByte(uint8_t data); + bool getSlave4Enabled(); + void setSlave4Enabled(bool enabled); + bool getSlave4InterruptEnabled(); + void setSlave4InterruptEnabled(bool enabled); + bool getSlave4WriteMode(); + void setSlave4WriteMode(bool mode); + uint8_t getSlave4MasterDelay(); + void setSlave4MasterDelay(uint8_t delay); + uint8_t getSlate4InputByte(); + + // I2C_MST_STATUS register + bool getPassthroughStatus(); + bool getSlave4IsDone(); + bool getLostArbitration(); + bool getSlave4Nack(); + bool getSlave3Nack(); + bool getSlave2Nack(); + bool getSlave1Nack(); + bool getSlave0Nack(); + + // INT_PIN_CFG register + bool getInterruptMode(); + void setInterruptMode(bool mode); + bool getInterruptDrive(); + void setInterruptDrive(bool drive); + bool getInterruptLatch(); + void setInterruptLatch(bool latch); + bool getInterruptLatchClear(); + void setInterruptLatchClear(bool clear); + bool getFSyncInterruptLevel(); + void setFSyncInterruptLevel(bool level); + bool getFSyncInterruptEnabled(); + void setFSyncInterruptEnabled(bool enabled); + bool getI2CBypassEnabled(); + void setI2CBypassEnabled(bool enabled); + bool getClockOutputEnabled(); + void setClockOutputEnabled(bool enabled); + + // INT_ENABLE register + uint8_t getIntEnabled(); + void setIntEnabled(uint8_t enabled); + bool getIntFreefallEnabled(); + void setIntFreefallEnabled(bool enabled); + bool getIntMotionEnabled(); + void setIntMotionEnabled(bool enabled); + bool getIntZeroMotionEnabled(); + void setIntZeroMotionEnabled(bool enabled); + bool getIntFIFOBufferOverflowEnabled(); + void setIntFIFOBufferOverflowEnabled(bool enabled); + bool getIntI2CMasterEnabled(); + void setIntI2CMasterEnabled(bool enabled); + bool getIntDataReadyEnabled(); + void setIntDataReadyEnabled(bool enabled); + + // INT_STATUS register + uint8_t getIntStatus(); + bool getIntFreefallStatus(); + bool getIntMotionStatus(); + bool getIntZeroMotionStatus(); + bool getIntFIFOBufferOverflowStatus(); + bool getIntI2CMasterStatus(); + bool getIntDataReadyStatus(); + + // ACCEL_*OUT_* registers + void getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz); + void getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz); + void getAcceleration(int16_t* x, int16_t* y, int16_t* z); + int16_t getAccelerationX(); + int16_t getAccelerationY(); + int16_t getAccelerationZ(); + + // TEMP_OUT_* registers + int16_t getTemperature(); + + // GYRO_*OUT_* registers + void getRotation(int16_t* x, int16_t* y, int16_t* z); + int16_t getRotationX(); + int16_t getRotationY(); + int16_t getRotationZ(); + + // EXT_SENS_DATA_* registers + uint8_t getExternalSensorByte(int position); + uint16_t getExternalSensorWord(int position); + uint32_t getExternalSensorDWord(int position); + + // MOT_DETECT_STATUS register + uint8_t getMotionStatus(); + bool getXNegMotionDetected(); + bool getXPosMotionDetected(); + bool getYNegMotionDetected(); + bool getYPosMotionDetected(); + bool getZNegMotionDetected(); + bool getZPosMotionDetected(); + bool getZeroMotionDetected(); + + // I2C_SLV*_DO register + void setSlaveOutputByte(uint8_t num, uint8_t data); + + // I2C_MST_DELAY_CTRL register + bool getExternalShadowDelayEnabled(); + void setExternalShadowDelayEnabled(bool enabled); + bool getSlaveDelayEnabled(uint8_t num); + void setSlaveDelayEnabled(uint8_t num, bool enabled); + + // SIGNAL_PATH_RESET register + void resetGyroscopePath(); + void resetAccelerometerPath(); + void resetTemperaturePath(); + + // MOT_DETECT_CTRL register + uint8_t getAccelerometerPowerOnDelay(); + void setAccelerometerPowerOnDelay(uint8_t delay); + uint8_t getFreefallDetectionCounterDecrement(); + void setFreefallDetectionCounterDecrement(uint8_t decrement); + uint8_t getMotionDetectionCounterDecrement(); + void setMotionDetectionCounterDecrement(uint8_t decrement); + + // USER_CTRL register + bool getFIFOEnabled(); + void setFIFOEnabled(bool enabled); + bool getI2CMasterModeEnabled(); + void setI2CMasterModeEnabled(bool enabled); + void switchSPIEnabled(bool enabled); + void resetFIFO(); + void resetI2CMaster(); + void resetSensors(); + + // PWR_MGMT_1 register + void reset(); + bool getSleepEnabled(); + void setSleepEnabled(bool enabled); + bool getWakeCycleEnabled(); + void setWakeCycleEnabled(bool enabled); + bool getTempSensorEnabled(); + void setTempSensorEnabled(bool enabled); + uint8_t getClockSource(); + void setClockSource(uint8_t source); + + // PWR_MGMT_2 register + uint8_t getWakeFrequency(); + void setWakeFrequency(uint8_t frequency); + bool getStandbyXAccelEnabled(); + void setStandbyXAccelEnabled(bool enabled); + bool getStandbyYAccelEnabled(); + void setStandbyYAccelEnabled(bool enabled); + bool getStandbyZAccelEnabled(); + void setStandbyZAccelEnabled(bool enabled); + bool getStandbyXGyroEnabled(); + void setStandbyXGyroEnabled(bool enabled); + bool getStandbyYGyroEnabled(); + void setStandbyYGyroEnabled(bool enabled); + bool getStandbyZGyroEnabled(); + void setStandbyZGyroEnabled(bool enabled); + + // FIFO_COUNT_* registers + uint16_t getFIFOCount(); + + // FIFO_R_W register + uint8_t getFIFOByte(); + void setFIFOByte(uint8_t data); + void getFIFOBytes(uint8_t *data, uint8_t length); + + // WHO_AM_I register + uint8_t getDeviceID(); + void setDeviceID(uint8_t id); + + // ======== UNDOCUMENTED/DMP REGISTERS/METHODS ======== + + // XG_OFFS_TC register + uint8_t getOTPBankValid(); + void setOTPBankValid(bool enabled); + int8_t getXGyroOffsetTC(); + void setXGyroOffsetTC(int8_t offset); + + // YG_OFFS_TC register + int8_t getYGyroOffsetTC(); + void setYGyroOffsetTC(int8_t offset); + + // ZG_OFFS_TC register + int8_t getZGyroOffsetTC(); + void setZGyroOffsetTC(int8_t offset); + + // X_FINE_GAIN register + int8_t getXFineGain(); + void setXFineGain(int8_t gain); + + // Y_FINE_GAIN register + int8_t getYFineGain(); + void setYFineGain(int8_t gain); + + // Z_FINE_GAIN register + int8_t getZFineGain(); + void setZFineGain(int8_t gain); + + // XA_OFFS_* registers + int16_t getXAccelOffset(); + void setXAccelOffset(int16_t offset); + + // YA_OFFS_* register + int16_t getYAccelOffset(); + void setYAccelOffset(int16_t offset); + + // ZA_OFFS_* register + int16_t getZAccelOffset(); + void setZAccelOffset(int16_t offset); + + // XG_OFFS_USR* registers + int16_t getXGyroOffset(); + void setXGyroOffset(int16_t offset); + + // YG_OFFS_USR* register + int16_t getYGyroOffset(); + void setYGyroOffset(int16_t offset); + + // ZG_OFFS_USR* register + int16_t getZGyroOffset(); + void setZGyroOffset(int16_t offset); + + // INT_ENABLE register (DMP functions) + bool getIntPLLReadyEnabled(); + void setIntPLLReadyEnabled(bool enabled); + bool getIntDMPEnabled(); + void setIntDMPEnabled(bool enabled); + + // DMP_INT_STATUS + bool getDMPInt5Status(); + bool getDMPInt4Status(); + bool getDMPInt3Status(); + bool getDMPInt2Status(); + bool getDMPInt1Status(); + bool getDMPInt0Status(); + + // INT_STATUS register (DMP functions) + bool getIntPLLReadyStatus(); + bool getIntDMPStatus(); + + // USER_CTRL register (DMP functions) + bool getDMPEnabled(); + void setDMPEnabled(bool enabled); + void resetDMP(); + + // BANK_SEL register + void setMemoryBank(uint8_t bank, bool prefetchEnabled=false, bool userBank=false); + + // MEM_START_ADDR register + void setMemoryStartAddress(uint8_t address); + + // MEM_R_W register + uint8_t readMemoryByte(); + void writeMemoryByte(uint8_t data); + void readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0); + bool writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true, bool useProgMem=false); + bool writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true); + + bool writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem=false); + bool writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize); + + // DMP_CFG_1 register + uint8_t getDMPConfig1(); + void setDMPConfig1(uint8_t config); + + // DMP_CFG_2 register + uint8_t getDMPConfig2(); + void setDMPConfig2(uint8_t config); + + // special methods for MotionApps 2.0 implementation + #ifdef MPU6050_INCLUDE_DMP_MOTIONAPPS20 + uint8_t *dmpPacketBuffer; + uint16_t dmpPacketSize; + + uint8_t dmpInitialize(); + bool dmpPacketAvailable(); + + uint8_t dmpSetFIFORate(uint8_t fifoRate); + uint8_t dmpGetFIFORate(); + uint8_t dmpGetSampleStepSizeMS(); + uint8_t dmpGetSampleFrequency(); + int32_t dmpDecodeTemperature(int8_t tempReg); + + // Register callbacks after a packet of FIFO data is processed + //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority); + //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func); + uint8_t dmpRunFIFORateProcesses(); + + // Setup FIFO for various output + uint8_t dmpSendQuaternion(uint_fast16_t accuracy); + uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendPacketNumber(uint_fast16_t accuracy); + uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy); + + // Get Fixed Point data from FIFO + uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0); + uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0); + uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0); + uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpSetLinearAccelFilterCoefficient(float coef); + uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity); + uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q); + uint8_t dmpGetMag(int16_t *data, const uint8_t* packet); + uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0); + uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q); + uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0); + uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0); + + uint8_t dmpGetEuler(float *data, Quaternion *q); + uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity); + + // Get Floating Point data from FIFO + uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0); + uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0); + + uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData); + uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL); + + uint8_t dmpSetFIFOProcessedCallback(void (*func) (void)); + + uint8_t dmpInitFIFOParam(); + uint8_t dmpCloseFIFO(); + uint8_t dmpSetGyroDataSource(uint8_t source); + uint8_t dmpDecodeQuantizedAccel(); + uint32_t dmpGetGyroSumOfSquare(); + uint32_t dmpGetAccelSumOfSquare(); + void dmpOverrideQuaternion(long *q); + uint16_t dmpGetFIFOPacketSize(); + #endif + + // special methods for MotionApps 4.1 implementation + #ifdef MPU6050_INCLUDE_DMP_MOTIONAPPS41 + uint8_t *dmpPacketBuffer; + uint16_t dmpPacketSize; + + uint8_t dmpInitialize(); + bool dmpPacketAvailable(); + + uint8_t dmpSetFIFORate(uint8_t fifoRate); + uint8_t dmpGetFIFORate(); + uint8_t dmpGetSampleStepSizeMS(); + uint8_t dmpGetSampleFrequency(); + int32_t dmpDecodeTemperature(int8_t tempReg); + + // Register callbacks after a packet of FIFO data is processed + //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority); + //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func); + uint8_t dmpRunFIFORateProcesses(); + + // Setup FIFO for various output + uint8_t dmpSendQuaternion(uint_fast16_t accuracy); + uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendPacketNumber(uint_fast16_t accuracy); + uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy); + uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy); + + // Get Fixed Point data from FIFO + uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0); + uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0); + uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0); + uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetMag(int16_t *data, const uint8_t* packet=0); + uint8_t dmpSetLinearAccelFilterCoefficient(float coef); + uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity); + uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q); + uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0); + uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q); + uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0); + uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0); + uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0); + uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0); + + uint8_t dmpGetEuler(float *data, Quaternion *q); + uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity); + + // Get Floating Point data from FIFO + uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0); + uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0); + + uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData); + uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL); + + uint8_t dmpSetFIFOProcessedCallback(void (*func) (void)); + + uint8_t dmpInitFIFOParam(); + uint8_t dmpCloseFIFO(); + uint8_t dmpSetGyroDataSource(uint8_t source); + uint8_t dmpDecodeQuantizedAccel(); + uint32_t dmpGetGyroSumOfSquare(); + uint32_t dmpGetAccelSumOfSquare(); + void dmpOverrideQuaternion(long *q); + uint16_t dmpGetFIFOPacketSize(); + #endif + + private: + uint8_t devAddr; + uint8_t buffer[14]; +}; + +#endif /* _MPU6050_H_ */ diff --git a/libraries/MPU6050/MPU6050_6Axis_MotionApps20.h b/libraries/MPU6050/MPU6050_6Axis_MotionApps20.h new file mode 100644 index 0000000..285f8ce --- /dev/null +++ b/libraries/MPU6050/MPU6050_6Axis_MotionApps20.h @@ -0,0 +1,756 @@ +// I2Cdev library collection - MPU6050 I2C device class, 6-axis MotionApps 2.0 implementation +// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00) +// 5/20/2013 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// ... - ongoing debug 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. +=============================================== +*/ + +#ifndef _MPU6050_6AXIS_MOTIONAPPS20_H_ +#define _MPU6050_6AXIS_MOTIONAPPS20_H_ + +#include "I2Cdev.h" +#include "helper_3dmath.h" + +// MotionApps 2.0 DMP implementation, built using the MPU-6050EVB evaluation board +#define MPU6050_INCLUDE_DMP_MOTIONAPPS20 + +#include "MPU6050.h" + +// Tom Carpenter's conditional PROGMEM code +// http://forum.arduino.cc/index.php?topic=129407.0 +#ifdef __AVR__ + #include +#else + // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen + #ifndef __PGMSPACE_H_ + #define __PGMSPACE_H_ 1 + #include + + #define PROGMEM + #define PGM_P const char * + #define PSTR(str) (str) + #define F(x) x + + typedef void prog_void; + typedef char prog_char; + typedef unsigned char prog_uchar; + typedef int8_t prog_int8_t; + typedef uint8_t prog_uint8_t; + typedef int16_t prog_int16_t; + typedef uint16_t prog_uint16_t; + typedef int32_t prog_int32_t; + typedef uint32_t prog_uint32_t; + + #define strcpy_P(dest, src) strcpy((dest), (src)) + #define strcat_P(dest, src) strcat((dest), (src)) + #define strcmp_P(a, b) strcmp((a), (b)) + + #define pgm_read_byte(addr) (*(const unsigned char *)(addr)) + #define pgm_read_word(addr) (*(const unsigned short *)(addr)) + #define pgm_read_dword(addr) (*(const unsigned long *)(addr)) + #define pgm_read_float(addr) (*(const float *)(addr)) + + #define pgm_read_byte_near(addr) pgm_read_byte(addr) + #define pgm_read_word_near(addr) pgm_read_word(addr) + #define pgm_read_dword_near(addr) pgm_read_dword(addr) + #define pgm_read_float_near(addr) pgm_read_float(addr) + #define pgm_read_byte_far(addr) pgm_read_byte(addr) + #define pgm_read_word_far(addr) pgm_read_word(addr) + #define pgm_read_dword_far(addr) pgm_read_dword(addr) + #define pgm_read_float_far(addr) pgm_read_float(addr) + #endif +#endif + +/* Source is from the InvenSense MotionApps v2 demo code. Original source is + * unavailable, unless you happen to be amazing as decompiling binary by + * hand (in which case, please contact me, and I'm totally serious). + * + * Also, I'd like to offer many, many thanks to Noah Zerkin for all of the + * DMP reverse-engineering he did to help make this bit of wizardry + * possible. + */ + +// NOTE! Enabling DEBUG adds about 3.3kB to the flash program size. +// Debug output is now working even on ATMega328P MCUs (e.g. Arduino Uno) +// after moving string constants to flash memory storage using the F() +// compiler macro (Arduino IDE 1.0+ required). + +//#define DEBUG +#ifdef DEBUG + #define DEBUG_PRINT(x) Serial.print(x) + #define DEBUG_PRINTF(x, y) Serial.print(x, y) + #define DEBUG_PRINTLN(x) Serial.println(x) + #define DEBUG_PRINTLNF(x, y) Serial.println(x, y) +#else + #define DEBUG_PRINT(x) + #define DEBUG_PRINTF(x, y) + #define DEBUG_PRINTLN(x) + #define DEBUG_PRINTLNF(x, y) +#endif + +#define MPU6050_DMP_CODE_SIZE 1929 // dmpMemory[] +#define MPU6050_DMP_CONFIG_SIZE 192 // dmpConfig[] +#define MPU6050_DMP_UPDATES_SIZE 47 // dmpUpdates[] + +/* ================================================================================================ * + | Default MotionApps v2.0 42-byte FIFO packet structure: | + | | + | [QUAT W][ ][QUAT X][ ][QUAT Y][ ][QUAT Z][ ][GYRO X][ ][GYRO Y][ ] | + | 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 | + | | + | [GYRO Z][ ][ACC X ][ ][ACC Y ][ ][ACC Z ][ ][ ] | + | 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 | + * ================================================================================================ */ + +// this block of memory gets written to the MPU on start-up, and it seems +// to be volatile memory, so it has to be done each time (it only takes ~1 +// second though) +const unsigned char dmpMemory[MPU6050_DMP_CODE_SIZE] PROGMEM = { + // bank 0, 256 bytes + 0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00, + 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01, + 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01, + 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82, + 0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC, + 0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4, + 0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10, + + // bank 1, 256 bytes + 0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8, + 0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C, + 0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C, + 0x80, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0, + + // bank 2, 256 bytes + 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x01, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + + // bank 3, 256 bytes + 0xD8, 0xDC, 0xBA, 0xA2, 0xF1, 0xDE, 0xB2, 0xB8, 0xB4, 0xA8, 0x81, 0x91, 0xF7, 0x4A, 0x90, 0x7F, + 0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA, 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2, + 0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80, 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF, + 0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0, 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C, + 0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1, 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1, + 0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3, 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01, + 0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88, 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80, + 0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF, 0xF2, 0xAA, 0xC5, 0xCD, 0xC7, 0xA9, 0x0C, + 0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89, 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80, + 0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9, 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E, + 0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A, 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9, + 0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11, 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24, + 0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55, 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xAF, 0xF0, + 0x00, 0x28, 0x50, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xD9, 0xFA, 0xA3, 0x86, + 0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1, + 0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86, + + // bank 4, 256 bytes + 0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA, + 0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C, + 0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8, + 0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3, + 0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84, + 0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5, + 0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3, + 0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1, + 0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5, + 0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D, + 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9, + 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D, + 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9, + 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A, + 0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8, + 0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87, + + // bank 5, 256 bytes + 0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8, + 0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68, + 0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D, + 0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94, + 0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA, + 0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56, + 0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, + 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA, + 0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0xA8, 0x8A, + 0x9A, 0xF5, 0x20, 0xAA, 0xDA, 0xDF, 0xD8, 0xA8, 0x40, 0xAA, 0xD0, 0xDA, 0xDE, 0xD8, 0xA8, 0x60, + 0xAA, 0xDA, 0xD0, 0xDF, 0xD8, 0xF1, 0x97, 0x86, 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97, + 0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40, 0xB8, 0xB0, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04, + 0x28, 0x51, 0x79, 0x1D, 0x30, 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78, + 0x78, 0x9B, 0xF1, 0x1A, 0xB0, 0xF0, 0x8A, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x8B, 0x29, 0x51, 0x79, + 0x8A, 0x24, 0x70, 0x59, 0x8B, 0x20, 0x58, 0x71, 0x8A, 0x44, 0x69, 0x38, 0x8B, 0x39, 0x40, 0x68, + 0x8A, 0x64, 0x48, 0x31, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71, 0x58, 0x44, 0x68, + + // bank 6, 256 bytes + 0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, 0x8C, 0xA8, 0x04, + 0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, 0x26, 0x46, 0x66, + 0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31, + 0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, 0x31, 0x48, 0x60, + 0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, 0xA8, 0x6E, 0x76, + 0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A, 0x6E, 0x8A, 0x56, + 0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E, 0x9D, 0xB8, 0xAD, + 0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0x81, 0x91, + 0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8, + 0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51, 0xD9, 0x04, 0xAE, + 0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19, 0x81, 0xAD, 0xD9, + 0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9, 0xAD, 0xAD, 0xAD, + 0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76, 0xF3, 0xAC, 0x2E, + 0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC, 0x30, 0x18, 0xA8, + 0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24, 0xF2, 0xB0, 0x89, + 0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9, 0xD8, 0xD8, 0x79, + + // bank 7, 138 bytes (remainder) + 0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D, 0xD9, 0x28, 0xD8, + 0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D, 0x80, 0x25, 0xDA, + 0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34, 0x3C, 0xF3, 0xAB, + 0x8B, 0xF8, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xFA, 0xB0, 0x87, 0x9C, 0xB9, 0xA3, + 0xDD, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x95, 0xF1, 0xA3, 0xA3, 0xA3, 0x9D, 0xF1, 0xA3, 0xA3, 0xA3, + 0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, + 0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0xA3, 0xA3, 0xA3, + 0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0xA3, 0xDC, + 0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xD8, 0xD8, 0xFF +}; + +// thanks to Noah Zerkin for piecing this stuff together! +const unsigned char dmpConfig[MPU6050_DMP_CONFIG_SIZE] PROGMEM = { +// BANK OFFSET LENGTH [DATA] + 0x03, 0x7B, 0x03, 0x4C, 0xCD, 0x6C, // FCFG_1 inv_set_gyro_calibration + 0x03, 0xAB, 0x03, 0x36, 0x56, 0x76, // FCFG_3 inv_set_gyro_calibration + 0x00, 0x68, 0x04, 0x02, 0xCB, 0x47, 0xA2, // D_0_104 inv_set_gyro_calibration + 0x02, 0x18, 0x04, 0x00, 0x05, 0x8B, 0xC1, // D_0_24 inv_set_gyro_calibration + 0x01, 0x0C, 0x04, 0x00, 0x00, 0x00, 0x00, // D_1_152 inv_set_accel_calibration + 0x03, 0x7F, 0x06, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_accel_calibration + 0x03, 0x89, 0x03, 0x26, 0x46, 0x66, // FCFG_7 inv_set_accel_calibration + 0x00, 0x6C, 0x02, 0x20, 0x00, // D_0_108 inv_set_accel_calibration + 0x02, 0x40, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_00 inv_set_compass_calibration + 0x02, 0x44, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_01 + 0x02, 0x48, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_02 + 0x02, 0x4C, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_10 + 0x02, 0x50, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_11 + 0x02, 0x54, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_12 + 0x02, 0x58, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_20 + 0x02, 0x5C, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_21 + 0x02, 0xBC, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_22 + 0x01, 0xEC, 0x04, 0x00, 0x00, 0x40, 0x00, // D_1_236 inv_apply_endian_accel + 0x03, 0x7F, 0x06, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_mpu_sensors + 0x04, 0x02, 0x03, 0x0D, 0x35, 0x5D, // CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion + 0x04, 0x09, 0x04, 0x87, 0x2D, 0x35, 0x3D, // FCFG_5 inv_set_bias_update + 0x00, 0xA3, 0x01, 0x00, // D_0_163 inv_set_dead_zone + // SPECIAL 0x01 = enable interrupts + 0x00, 0x00, 0x00, 0x01, // SET INT_ENABLE at i=22, SPECIAL INSTRUCTION + 0x07, 0x86, 0x01, 0xFE, // CFG_6 inv_set_fifo_interupt + 0x07, 0x41, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38, // CFG_8 inv_send_quaternion + 0x07, 0x7E, 0x01, 0x30, // CFG_16 inv_set_footer + 0x07, 0x46, 0x01, 0x9A, // CFG_GYRO_SOURCE inv_send_gyro + 0x07, 0x47, 0x04, 0xF1, 0x28, 0x30, 0x38, // CFG_9 inv_send_gyro -> inv_construct3_fifo + 0x07, 0x6C, 0x04, 0xF1, 0x28, 0x30, 0x38, // CFG_12 inv_send_accel -> inv_construct3_fifo + 0x02, 0x16, 0x02, 0x00, 0x01 // D_0_22 inv_set_fifo_rate + + // This very last 0x01 WAS a 0x09, which drops the FIFO rate down to 20 Hz. 0x07 is 25 Hz, + // 0x01 is 100Hz. Going faster than 100Hz (0x00=200Hz) tends to result in very noisy data. + // DMP output frequency is calculated easily using this equation: (200Hz / (1 + value)) + + // It is important to make sure the host processor can keep up with reading and processing + // the FIFO output at the desired rate. Handling FIFO overflow cleanly is also a good idea. +}; + +const unsigned char dmpUpdates[MPU6050_DMP_UPDATES_SIZE] PROGMEM = { + 0x01, 0xB2, 0x02, 0xFF, 0xFF, + 0x01, 0x90, 0x04, 0x09, 0x23, 0xA1, 0x35, + 0x01, 0x6A, 0x02, 0x06, 0x00, + 0x01, 0x60, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x60, 0x04, 0x40, 0x00, 0x00, 0x00, + 0x01, 0x62, 0x02, 0x00, 0x00, + 0x00, 0x60, 0x04, 0x00, 0x40, 0x00, 0x00 +}; + +uint8_t MPU6050::dmpInitialize() { + // reset device + DEBUG_PRINTLN(F("\n\nResetting MPU6050...")); + reset(); + delay(30); // wait after reset + + // enable sleep mode and wake cycle + /*Serial.println(F("Enabling sleep mode...")); + setSleepEnabled(true); + Serial.println(F("Enabling wake cycle...")); + setWakeCycleEnabled(true);*/ + + // disable sleep mode + DEBUG_PRINTLN(F("Disabling sleep mode...")); + setSleepEnabled(false); + + // get MPU hardware revision + DEBUG_PRINTLN(F("Selecting user bank 16...")); + setMemoryBank(0x10, true, true); + DEBUG_PRINTLN(F("Selecting memory byte 6...")); + setMemoryStartAddress(0x06); + DEBUG_PRINTLN(F("Checking hardware revision...")); + DEBUG_PRINT(F("Revision @ user[16][6] = ")); + DEBUG_PRINTLNF(readMemoryByte(), HEX); + DEBUG_PRINTLN(F("Resetting memory bank selection to 0...")); + setMemoryBank(0, false, false); + + // check OTP bank valid + DEBUG_PRINTLN(F("Reading OTP bank valid flag...")); + DEBUG_PRINT(F("OTP bank is ")); + DEBUG_PRINTLN(getOTPBankValid() ? F("valid!") : F("invalid!")); + + // get X/Y/Z gyro offsets + DEBUG_PRINTLN(F("Reading gyro offset TC values...")); + int8_t xgOffsetTC = getXGyroOffsetTC(); + int8_t ygOffsetTC = getYGyroOffsetTC(); + int8_t zgOffsetTC = getZGyroOffsetTC(); + DEBUG_PRINT(F("X gyro offset = ")); + DEBUG_PRINTLN(xgOffsetTC); + DEBUG_PRINT(F("Y gyro offset = ")); + DEBUG_PRINTLN(ygOffsetTC); + DEBUG_PRINT(F("Z gyro offset = ")); + DEBUG_PRINTLN(zgOffsetTC); + + // setup weird slave stuff (?) + DEBUG_PRINTLN(F("Setting slave 0 address to 0x7F...")); + setSlaveAddress(0, 0x7F); + DEBUG_PRINTLN(F("Disabling I2C Master mode...")); + setI2CMasterModeEnabled(false); + DEBUG_PRINTLN(F("Setting slave 0 address to 0x68 (self)...")); + setSlaveAddress(0, 0x68); + DEBUG_PRINTLN(F("Resetting I2C Master control...")); + resetI2CMaster(); + delay(20); + + // load DMP code into memory banks + DEBUG_PRINT(F("Writing DMP code to MPU memory banks (")); + DEBUG_PRINT(MPU6050_DMP_CODE_SIZE); + DEBUG_PRINTLN(F(" bytes)")); + if (writeProgMemoryBlock(dmpMemory, MPU6050_DMP_CODE_SIZE)) { + DEBUG_PRINTLN(F("Success! DMP code written and verified.")); + + // write DMP configuration + DEBUG_PRINT(F("Writing DMP configuration to MPU memory banks (")); + DEBUG_PRINT(MPU6050_DMP_CONFIG_SIZE); + DEBUG_PRINTLN(F(" bytes in config def)")); + if (writeProgDMPConfigurationSet(dmpConfig, MPU6050_DMP_CONFIG_SIZE)) { + DEBUG_PRINTLN(F("Success! DMP configuration written and verified.")); + + DEBUG_PRINTLN(F("Setting clock source to Z Gyro...")); + setClockSource(MPU6050_CLOCK_PLL_ZGYRO); + + DEBUG_PRINTLN(F("Setting DMP and FIFO_OFLOW interrupts enabled...")); + setIntEnabled(0x12); + + DEBUG_PRINTLN(F("Setting sample rate to 200Hz...")); + setRate(4); // 1khz / (1 + 4) = 200 Hz + + DEBUG_PRINTLN(F("Setting external frame sync to TEMP_OUT_L[0]...")); + setExternalFrameSync(MPU6050_EXT_SYNC_TEMP_OUT_L); + + DEBUG_PRINTLN(F("Setting DLPF bandwidth to 42Hz...")); + setDLPFMode(MPU6050_DLPF_BW_42); + + DEBUG_PRINTLN(F("Setting gyro sensitivity to +/- 2000 deg/sec...")); + setFullScaleGyroRange(MPU6050_GYRO_FS_2000); + + DEBUG_PRINTLN(F("Setting DMP programm start address")); + //write start address MSB into register + setDMPConfig1(0x03); + //write start address LSB into register + setDMPConfig2(0x00); + + DEBUG_PRINTLN(F("Clearing OTP Bank flag...")); + setOTPBankValid(false); + + DEBUG_PRINTLN(F("Setting X/Y/Z gyro offset TCs to previous values...")); + setXGyroOffsetTC(xgOffsetTC); + setYGyroOffsetTC(ygOffsetTC); + setZGyroOffsetTC(zgOffsetTC); + + //DEBUG_PRINTLN(F("Setting X/Y/Z gyro user offsets to zero...")); + //setXGyroOffset(0); + //setYGyroOffset(0); + //setZGyroOffset(0); + + DEBUG_PRINTLN(F("Writing final memory update 1/7 (function unknown)...")); + uint8_t dmpUpdate[16], j; + uint16_t pos = 0; + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Writing final memory update 2/7 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Resetting FIFO...")); + resetFIFO(); + + DEBUG_PRINTLN(F("Reading FIFO count...")); + uint16_t fifoCount = getFIFOCount(); + uint8_t fifoBuffer[128]; + + DEBUG_PRINT(F("Current FIFO count=")); + DEBUG_PRINTLN(fifoCount); + getFIFOBytes(fifoBuffer, fifoCount); + + DEBUG_PRINTLN(F("Setting motion detection threshold to 2...")); + setMotionDetectionThreshold(2); + + DEBUG_PRINTLN(F("Setting zero-motion detection threshold to 156...")); + setZeroMotionDetectionThreshold(156); + + DEBUG_PRINTLN(F("Setting motion detection duration to 80...")); + setMotionDetectionDuration(80); + + DEBUG_PRINTLN(F("Setting zero-motion detection duration to 0...")); + setZeroMotionDetectionDuration(0); + + DEBUG_PRINTLN(F("Resetting FIFO...")); + resetFIFO(); + + DEBUG_PRINTLN(F("Enabling FIFO...")); + setFIFOEnabled(true); + + DEBUG_PRINTLN(F("Enabling DMP...")); + setDMPEnabled(true); + + DEBUG_PRINTLN(F("Resetting DMP...")); + resetDMP(); + + DEBUG_PRINTLN(F("Writing final memory update 3/7 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Writing final memory update 4/7 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Writing final memory update 5/7 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Waiting for FIFO count > 2...")); + while ((fifoCount = getFIFOCount()) < 3); + + DEBUG_PRINT(F("Current FIFO count=")); + DEBUG_PRINTLN(fifoCount); + DEBUG_PRINTLN(F("Reading FIFO data...")); + getFIFOBytes(fifoBuffer, fifoCount); + + DEBUG_PRINTLN(F("Reading interrupt status...")); + + DEBUG_PRINT(F("Current interrupt status=")); + DEBUG_PRINTLNF(getIntStatus(), HEX); + + DEBUG_PRINTLN(F("Reading final memory update 6/7 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + readMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Waiting for FIFO count > 2...")); + while ((fifoCount = getFIFOCount()) < 3); + + DEBUG_PRINT(F("Current FIFO count=")); + DEBUG_PRINTLN(fifoCount); + + DEBUG_PRINTLN(F("Reading FIFO data...")); + getFIFOBytes(fifoBuffer, fifoCount); + + DEBUG_PRINTLN(F("Reading interrupt status...")); + + DEBUG_PRINT(F("Current interrupt status=")); + DEBUG_PRINTLNF(getIntStatus(), HEX); + + DEBUG_PRINTLN(F("Writing final memory update 7/7 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("DMP is good to go! Finally.")); + + DEBUG_PRINTLN(F("Disabling DMP (you turn it on later)...")); + setDMPEnabled(false); + + DEBUG_PRINTLN(F("Setting up internal 42-byte (default) DMP packet buffer...")); + dmpPacketSize = 42; + /*if ((dmpPacketBuffer = (uint8_t *)malloc(42)) == 0) { + return 3; // TODO: proper error code for no memory + }*/ + + DEBUG_PRINTLN(F("Resetting FIFO and clearing INT status one last time...")); + resetFIFO(); + getIntStatus(); + } else { + DEBUG_PRINTLN(F("ERROR! DMP configuration verification failed.")); + return 2; // configuration block loading failed + } + } else { + DEBUG_PRINTLN(F("ERROR! DMP code verification failed.")); + return 1; // main binary block loading failed + } + return 0; // success +} + +bool MPU6050::dmpPacketAvailable() { + return getFIFOCount() >= dmpGetFIFOPacketSize(); +} + +// uint8_t MPU6050::dmpSetFIFORate(uint8_t fifoRate); +// uint8_t MPU6050::dmpGetFIFORate(); +// uint8_t MPU6050::dmpGetSampleStepSizeMS(); +// uint8_t MPU6050::dmpGetSampleFrequency(); +// int32_t MPU6050::dmpDecodeTemperature(int8_t tempReg); + +//uint8_t MPU6050::dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority); +//uint8_t MPU6050::dmpUnregisterFIFORateProcess(inv_obj_func func); +//uint8_t MPU6050::dmpRunFIFORateProcesses(); + +// uint8_t MPU6050::dmpSendQuaternion(uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendPacketNumber(uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy); + +uint8_t MPU6050::dmpGetAccel(int32_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = (((uint32_t)packet[28] << 24) | ((uint32_t)packet[29] << 16) | ((uint32_t)packet[30] << 8) | packet[31]); + data[1] = (((uint32_t)packet[32] << 24) | ((uint32_t)packet[33] << 16) | ((uint32_t)packet[34] << 8) | packet[35]); + data[2] = (((uint32_t)packet[36] << 24) | ((uint32_t)packet[37] << 16) | ((uint32_t)packet[38] << 8) | packet[39]); + return 0; +} +uint8_t MPU6050::dmpGetAccel(int16_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = (packet[28] << 8) | packet[29]; + data[1] = (packet[32] << 8) | packet[33]; + data[2] = (packet[36] << 8) | packet[37]; + return 0; +} +uint8_t MPU6050::dmpGetAccel(VectorInt16 *v, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + v -> x = (packet[28] << 8) | packet[29]; + v -> y = (packet[32] << 8) | packet[33]; + v -> z = (packet[36] << 8) | packet[37]; + return 0; +} +uint8_t MPU6050::dmpGetQuaternion(int32_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = (((uint32_t)packet[0] << 24) | ((uint32_t)packet[1] << 16) | ((uint32_t)packet[2] << 8) | packet[3]); + data[1] = (((uint32_t)packet[4] << 24) | ((uint32_t)packet[5] << 16) | ((uint32_t)packet[6] << 8) | packet[7]); + data[2] = (((uint32_t)packet[8] << 24) | ((uint32_t)packet[9] << 16) | ((uint32_t)packet[10] << 8) | packet[11]); + data[3] = (((uint32_t)packet[12] << 24) | ((uint32_t)packet[13] << 16) | ((uint32_t)packet[14] << 8) | packet[15]); + return 0; +} +uint8_t MPU6050::dmpGetQuaternion(int16_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = ((packet[0] << 8) | packet[1]); + data[1] = ((packet[4] << 8) | packet[5]); + data[2] = ((packet[8] << 8) | packet[9]); + data[3] = ((packet[12] << 8) | packet[13]); + return 0; +} +uint8_t MPU6050::dmpGetQuaternion(Quaternion *q, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + int16_t qI[4]; + uint8_t status = dmpGetQuaternion(qI, packet); + if (status == 0) { + q -> w = (float)qI[0] / 16384.0f; + q -> x = (float)qI[1] / 16384.0f; + q -> y = (float)qI[2] / 16384.0f; + q -> z = (float)qI[3] / 16384.0f; + return 0; + } + return status; // int16 return value, indicates error if this line is reached +} + +// uint8_t MPU6050::dmpGet6AxisQuaternion(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetRelativeQuaternion(long *data, const uint8_t* packet); +uint8_t MPU6050::dmpGetGyro(int32_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = (((uint32_t)packet[16] << 24) | ((uint32_t)packet[17] << 16) | ((uint32_t)packet[18] << 8) | packet[19]); + data[1] = (((uint32_t)packet[20] << 24) | ((uint32_t)packet[21] << 16) | ((uint32_t)packet[22] << 8) | packet[23]); + data[2] = (((uint32_t)packet[24] << 24) | ((uint32_t)packet[25] << 16) | ((uint32_t)packet[26] << 8) | packet[27]); + return 0; +} +uint8_t MPU6050::dmpGetMag(int16_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = (packet[28] << 8) | packet[29]; + data[1] = (packet[30] << 8) | packet[31]; + data[2] = (packet[32] << 8) | packet[33]; + return 0; +} +uint8_t MPU6050::dmpGetGyro(int16_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = (packet[16] << 8) | packet[17]; + data[1] = (packet[20] << 8) | packet[21]; + data[2] = (packet[24] << 8) | packet[25]; + return 0; +} +uint8_t MPU6050::dmpGetGyro(VectorInt16 *v, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + v -> x = (packet[16] << 8) | packet[17]; + v -> y = (packet[20] << 8) | packet[21]; + v -> z = (packet[24] << 8) | packet[25]; + return 0; +} +// uint8_t MPU6050::dmpSetLinearAccelFilterCoefficient(float coef); +// uint8_t MPU6050::dmpGetLinearAccel(long *data, const uint8_t* packet); +uint8_t MPU6050::dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity) { + // get rid of the gravity component (+1g = +8192 in standard DMP FIFO packet, sensitivity is 2g) + v -> x = vRaw -> x - gravity -> x*8192; + v -> y = vRaw -> y - gravity -> y*8192; + v -> z = vRaw -> z - gravity -> z*8192; + return 0; +} +// uint8_t MPU6050::dmpGetLinearAccelInWorld(long *data, const uint8_t* packet); +uint8_t MPU6050::dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q) { + // rotate measured 3D acceleration vector into original state + // frame of reference based on orientation quaternion + memcpy(v, vReal, sizeof(VectorInt16)); + v -> rotate(q); + return 0; +} +// uint8_t MPU6050::dmpGetGyroAndAccelSensor(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetGyroSensor(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetControlData(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetTemperature(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetGravity(long *data, const uint8_t* packet); +uint8_t MPU6050::dmpGetGravity(VectorFloat *v, Quaternion *q) { + v -> x = 2 * (q -> x*q -> z - q -> w*q -> y); + v -> y = 2 * (q -> w*q -> x + q -> y*q -> z); + v -> z = q -> w*q -> w - q -> x*q -> x - q -> y*q -> y + q -> z*q -> z; + return 0; +} +// uint8_t MPU6050::dmpGetUnquantizedAccel(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetQuantizedAccel(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetExternalSensorData(long *data, int size, const uint8_t* packet); +// uint8_t MPU6050::dmpGetEIS(long *data, const uint8_t* packet); + +uint8_t MPU6050::dmpGetEuler(float *data, Quaternion *q) { + data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1); // psi + data[1] = -asin(2*q -> x*q -> z + 2*q -> w*q -> y); // theta + data[2] = atan2(2*q -> y*q -> z - 2*q -> w*q -> x, 2*q -> w*q -> w + 2*q -> z*q -> z - 1); // phi + return 0; +} +uint8_t MPU6050::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity) { + // yaw: (about Z axis) + data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1); + // pitch: (nose up/down, about Y axis) + data[1] = atan(gravity -> x / sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z)); + // roll: (tilt left/right, about X axis) + data[2] = atan(gravity -> y / sqrt(gravity -> x*gravity -> x + gravity -> z*gravity -> z)); + return 0; +} + +// uint8_t MPU6050::dmpGetAccelFloat(float *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetQuaternionFloat(float *data, const uint8_t* packet); + +uint8_t MPU6050::dmpProcessFIFOPacket(const unsigned char *dmpData) { + /*for (uint8_t k = 0; k < dmpPacketSize; k++) { + if (dmpData[k] < 0x10) Serial.print("0"); + Serial.print(dmpData[k], HEX); + Serial.print(" "); + } + Serial.print("\n");*/ + //Serial.println((uint16_t)dmpPacketBuffer); + return 0; +} +uint8_t MPU6050::dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed) { + uint8_t status; + uint8_t buf[dmpPacketSize]; + for (uint8_t i = 0; i < numPackets; i++) { + // read packet from FIFO + getFIFOBytes(buf, dmpPacketSize); + + // process packet + if ((status = dmpProcessFIFOPacket(buf)) > 0) return status; + + // increment external process count variable, if supplied + if (processed != 0) (*processed)++; + } + return 0; +} + +// uint8_t MPU6050::dmpSetFIFOProcessedCallback(void (*func) (void)); + +// uint8_t MPU6050::dmpInitFIFOParam(); +// uint8_t MPU6050::dmpCloseFIFO(); +// uint8_t MPU6050::dmpSetGyroDataSource(uint_fast8_t source); +// uint8_t MPU6050::dmpDecodeQuantizedAccel(); +// uint32_t MPU6050::dmpGetGyroSumOfSquare(); +// uint32_t MPU6050::dmpGetAccelSumOfSquare(); +// void MPU6050::dmpOverrideQuaternion(long *q); +uint16_t MPU6050::dmpGetFIFOPacketSize() { + return dmpPacketSize; +} + +#endif /* _MPU6050_6AXIS_MOTIONAPPS20_H_ */ diff --git a/libraries/MPU6050/MPU6050_9Axis_MotionApps41.h b/libraries/MPU6050/MPU6050_9Axis_MotionApps41.h new file mode 100644 index 0000000..016d0b0 --- /dev/null +++ b/libraries/MPU6050/MPU6050_9Axis_MotionApps41.h @@ -0,0 +1,852 @@ +// I2Cdev library collection - MPU6050 I2C device class, 9-axis MotionApps 4.1 implementation +// Based on InvenSense MPU-6050 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00) +// 6/18/2012 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// ... - ongoing debug 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. +=============================================== +*/ + +#ifndef _MPU6050_9AXIS_MOTIONAPPS41_H_ +#define _MPU6050_9AXIS_MOTIONAPPS41_H_ + +#include "I2Cdev.h" +#include "helper_3dmath.h" + +// MotionApps 4.1 DMP implementation, built using the MPU-9150 "MotionFit" board +#define MPU6050_INCLUDE_DMP_MOTIONAPPS41 + +#include "MPU6050.h" + +// Tom Carpenter's conditional PROGMEM code +// http://forum.arduino.cc/index.php?topic=129407.0 +#ifdef __AVR__ + #include +#else + // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen + #ifndef __PGMSPACE_H_ + #define __PGMSPACE_H_ 1 + #include + + #define PROGMEM + #define PGM_P const char * + #define PSTR(str) (str) + #define F(x) x + + typedef void prog_void; + typedef char prog_char; + //typedef unsigned char prog_uchar; + typedef int8_t prog_int8_t; + typedef uint8_t prog_uint8_t; + typedef int16_t prog_int16_t; + typedef uint16_t prog_uint16_t; + typedef int32_t prog_int32_t; + typedef uint32_t prog_uint32_t; + + #define strcpy_P(dest, src) strcpy((dest), (src)) + #define strcat_P(dest, src) strcat((dest), (src)) + #define strcmp_P(a, b) strcmp((a), (b)) + + #define pgm_read_byte(addr) (*(const unsigned char *)(addr)) + #define pgm_read_word(addr) (*(const unsigned short *)(addr)) + #define pgm_read_dword(addr) (*(const unsigned long *)(addr)) + #define pgm_read_float(addr) (*(const float *)(addr)) + + #define pgm_read_byte_near(addr) pgm_read_byte(addr) + #define pgm_read_word_near(addr) pgm_read_word(addr) + #define pgm_read_dword_near(addr) pgm_read_dword(addr) + #define pgm_read_float_near(addr) pgm_read_float(addr) + #define pgm_read_byte_far(addr) pgm_read_byte(addr) + #define pgm_read_word_far(addr) pgm_read_word(addr) + #define pgm_read_dword_far(addr) pgm_read_dword(addr) + #define pgm_read_float_far(addr) pgm_read_float(addr) + #endif +#endif + +// NOTE! Enabling DEBUG adds about 3.3kB to the flash program size. +// Debug output is now working even on ATMega328P MCUs (e.g. Arduino Uno) +// after moving string constants to flash memory storage using the F() +// compiler macro (Arduino IDE 1.0+ required). + +//#define DEBUG +#ifdef DEBUG + #define DEBUG_PRINT(x) Serial.print(x) + #define DEBUG_PRINTF(x, y) Serial.print(x, y) + #define DEBUG_PRINTLN(x) Serial.println(x) + #define DEBUG_PRINTLNF(x, y) Serial.println(x, y) +#else + #define DEBUG_PRINT(x) + #define DEBUG_PRINTF(x, y) + #define DEBUG_PRINTLN(x) + #define DEBUG_PRINTLNF(x, y) +#endif + +#define MPU6050_DMP_CODE_SIZE 1962 // dmpMemory[] +#define MPU6050_DMP_CONFIG_SIZE 232 // dmpConfig[] +#define MPU6050_DMP_UPDATES_SIZE 140 // dmpUpdates[] + +/* ================================================================================================ * + | Default MotionApps v4.1 48-byte FIFO packet structure: | + | | + | [QUAT W][ ][QUAT X][ ][QUAT Y][ ][QUAT Z][ ][GYRO X][ ][GYRO Y][ ] | + | 0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 | + | | + | [GYRO Z][ ][MAG X ][MAG Y ][MAG Z ][ACC X ][ ][ACC Y ][ ][ACC Z ][ ][ ] | + | 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 | + * ================================================================================================ */ + +// this block of memory gets written to the MPU on start-up, and it seems +// to be volatile memory, so it has to be done each time (it only takes ~1 +// second though) +const unsigned char dmpMemory[MPU6050_DMP_CODE_SIZE] PROGMEM = { + // bank 0, 256 bytes + 0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00, + 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01, + 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01, + 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00, + 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00, + 0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82, + 0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC, + 0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4, + 0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10, + + // bank 1, 256 bytes + 0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00, + 0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8, + 0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C, + 0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C, + 0x80, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0, + + // bank 2, 256 bytes + 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x01, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x78, 0xA2, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + + // bank 3, 256 bytes + 0xD8, 0xDC, 0xF4, 0xD8, 0xB9, 0xAB, 0xF3, 0xF8, 0xFA, 0xF1, 0xBA, 0xA2, 0xDE, 0xB2, 0xB8, 0xB4, + 0xA8, 0x81, 0x98, 0xF7, 0x4A, 0x90, 0x7F, 0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA, + 0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2, 0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80, + 0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF, 0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0, + 0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C, 0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1, + 0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1, 0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3, + 0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01, 0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88, + 0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80, 0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF, + 0xF2, 0xAA, 0xC5, 0xCD, 0xC7, 0xA9, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89, + 0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80, 0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9, + 0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E, 0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A, + 0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9, 0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11, + 0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55, + 0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xF0, 0x00, 0x28, 0x50, 0xF5, 0xBA, 0xAD, 0x8F, 0x9F, 0x28, 0x54, + 0x7C, 0xB9, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xDB, 0xB2, 0xB6, 0x8E, 0x9D, + 0xAE, 0xF5, 0x60, 0x68, 0x70, 0xB1, 0xB5, 0xF1, 0xDA, 0xA6, 0xDF, 0xD9, 0xA6, 0xFA, 0xA3, 0x86, + + // bank 4, 256 bytes + 0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1, + 0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86, + 0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA, + 0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C, + 0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8, + 0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3, + 0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84, + 0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5, + 0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3, + 0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1, + 0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5, + 0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D, + 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9, + 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D, + 0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9, + 0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A, + + // bank 5, 256 bytes + 0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8, + 0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87, + 0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8, + 0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68, + 0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D, + 0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94, + 0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA, + 0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56, + 0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9, + 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA, + 0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0x97, 0x86, + 0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97, 0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40, + 0xB9, 0xA3, 0x8A, 0xC3, 0xC5, 0xC7, 0x9A, 0xA3, 0x28, 0x50, 0x78, 0xF1, 0xB5, 0x93, 0x01, 0xD9, + 0xDF, 0xDF, 0xDF, 0xD8, 0xB8, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04, 0x28, 0x51, 0x79, 0x1D, 0x30, + 0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78, 0x78, 0x9B, 0xF1, 0x1A, 0xB0, + 0xF0, 0xB1, 0x83, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0xB0, 0x8B, 0x29, 0x51, 0x79, 0xB1, 0x83, 0x24, + + // bank 6, 256 bytes + 0x70, 0x59, 0xB0, 0x8B, 0x20, 0x58, 0x71, 0xB1, 0x83, 0x44, 0x69, 0x38, 0xB0, 0x8B, 0x39, 0x40, + 0x68, 0xB1, 0x83, 0x64, 0x48, 0x31, 0xB0, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71, + 0x58, 0x44, 0x68, 0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0, + 0x8C, 0xA8, 0x04, 0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02, + 0x26, 0x46, 0x66, 0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, + 0x64, 0x48, 0x31, 0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19, + 0x31, 0x48, 0x60, 0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86, + 0xA8, 0x6E, 0x76, 0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A, + 0x6E, 0x8A, 0x56, 0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E, + 0x9D, 0xB8, 0xAD, 0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55, + 0x7D, 0x81, 0x91, 0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, + 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51, + 0xD9, 0x04, 0xAE, 0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19, + 0x81, 0xAD, 0xD9, 0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9, + 0xAD, 0xAD, 0xAD, 0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76, + 0xF3, 0xAC, 0x2E, 0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC, + + // bank 7, 170 bytes (remainder) + 0x30, 0x18, 0xA8, 0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24, + 0xF2, 0xB0, 0x89, 0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9, + 0xD8, 0xD8, 0x79, 0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D, + 0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D, + 0x80, 0x25, 0xDA, 0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34, + 0x3C, 0xF3, 0xAB, 0x8B, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xB0, 0x87, 0x9C, 0xB9, + 0xA3, 0xDD, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x95, 0xF1, 0xA3, 0xA3, 0xA3, 0x9D, 0xF1, 0xA3, 0xA3, + 0xA3, 0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, + 0xA3, 0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0xA3, 0xA3, + 0xA3, 0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0xA3, + 0xDC, 0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xD8, 0xD8, 0xFF +}; + +const unsigned char dmpConfig[MPU6050_DMP_CONFIG_SIZE] PROGMEM = { +// BANK OFFSET LENGTH [DATA] + 0x02, 0xEC, 0x04, 0x00, 0x47, 0x7D, 0x1A, // ? + 0x03, 0x82, 0x03, 0x4C, 0xCD, 0x6C, // FCFG_1 inv_set_gyro_calibration + 0x03, 0xB2, 0x03, 0x36, 0x56, 0x76, // FCFG_3 inv_set_gyro_calibration + 0x00, 0x68, 0x04, 0x02, 0xCA, 0xE3, 0x09, // D_0_104 inv_set_gyro_calibration + 0x01, 0x0C, 0x04, 0x00, 0x00, 0x00, 0x00, // D_1_152 inv_set_accel_calibration + 0x03, 0x86, 0x03, 0x0C, 0xC9, 0x2C, // FCFG_2 inv_set_accel_calibration + 0x03, 0x90, 0x03, 0x26, 0x46, 0x66, // (continued)...FCFG_2 inv_set_accel_calibration + 0x00, 0x6C, 0x02, 0x40, 0x00, // D_0_108 inv_set_accel_calibration + + 0x02, 0x40, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_00 inv_set_compass_calibration + 0x02, 0x44, 0x04, 0x40, 0x00, 0x00, 0x00, // CPASS_MTX_01 + 0x02, 0x48, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_02 + 0x02, 0x4C, 0x04, 0x40, 0x00, 0x00, 0x00, // CPASS_MTX_10 + 0x02, 0x50, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_11 + 0x02, 0x54, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_12 + 0x02, 0x58, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_20 + 0x02, 0x5C, 0x04, 0x00, 0x00, 0x00, 0x00, // CPASS_MTX_21 + 0x02, 0xBC, 0x04, 0xC0, 0x00, 0x00, 0x00, // CPASS_MTX_22 + + 0x01, 0xEC, 0x04, 0x00, 0x00, 0x40, 0x00, // D_1_236 inv_apply_endian_accel + 0x03, 0x86, 0x06, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_mpu_sensors + 0x04, 0x22, 0x03, 0x0D, 0x35, 0x5D, // CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion + 0x00, 0xA3, 0x01, 0x00, // ? + 0x04, 0x29, 0x04, 0x87, 0x2D, 0x35, 0x3D, // FCFG_5 inv_set_bias_update + 0x07, 0x62, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38, // CFG_8 inv_send_quaternion + 0x07, 0x9F, 0x01, 0x30, // CFG_16 inv_set_footer + 0x07, 0x67, 0x01, 0x9A, // CFG_GYRO_SOURCE inv_send_gyro + 0x07, 0x68, 0x04, 0xF1, 0x28, 0x30, 0x38, // CFG_9 inv_send_gyro -> inv_construct3_fifo + 0x07, 0x62, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38, // ? + 0x02, 0x0C, 0x04, 0x00, 0x00, 0x00, 0x00, // ? + 0x07, 0x83, 0x06, 0xC2, 0xCA, 0xC4, 0xA3, 0xA3, 0xA3, // ? + // SPECIAL 0x01 = enable interrupts + 0x00, 0x00, 0x00, 0x01, // SET INT_ENABLE, SPECIAL INSTRUCTION + 0x07, 0xA7, 0x01, 0xFE, // ? + 0x07, 0x62, 0x05, 0xF1, 0x20, 0x28, 0x30, 0x38, // ? + 0x07, 0x67, 0x01, 0x9A, // ? + 0x07, 0x68, 0x04, 0xF1, 0x28, 0x30, 0x38, // CFG_12 inv_send_accel -> inv_construct3_fifo + 0x07, 0x8D, 0x04, 0xF1, 0x28, 0x30, 0x38, // ??? CFG_12 inv_send_mag -> inv_construct3_fifo + 0x02, 0x16, 0x02, 0x00, 0x03 // D_0_22 inv_set_fifo_rate + + // This very last 0x01 WAS a 0x09, which drops the FIFO rate down to 20 Hz. 0x07 is 25 Hz, + // 0x01 is 100Hz. Going faster than 100Hz (0x00=200Hz) tends to result in very noisy data. + // DMP output frequency is calculated easily using this equation: (200Hz / (1 + value)) + + // It is important to make sure the host processor can keep up with reading and processing + // the FIFO output at the desired rate. Handling FIFO overflow cleanly is also a good idea. +}; + +const unsigned char dmpUpdates[MPU6050_DMP_UPDATES_SIZE] PROGMEM = { + 0x01, 0xB2, 0x02, 0xFF, 0xF5, + 0x01, 0x90, 0x04, 0x0A, 0x0D, 0x97, 0xC0, + 0x00, 0xA3, 0x01, 0x00, + 0x04, 0x29, 0x04, 0x87, 0x2D, 0x35, 0x3D, + 0x01, 0x6A, 0x02, 0x06, 0x00, + 0x01, 0x60, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x60, 0x04, 0x40, 0x00, 0x00, 0x00, + 0x02, 0x60, 0x0C, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x01, 0x08, 0x02, 0x01, 0x20, + 0x01, 0x0A, 0x02, 0x00, 0x4E, + 0x01, 0x02, 0x02, 0xFE, 0xB3, + 0x02, 0x6C, 0x04, 0x00, 0x00, 0x00, 0x00, // READ + 0x02, 0x6C, 0x04, 0xFA, 0xFE, 0x00, 0x00, + 0x02, 0x60, 0x0C, 0xFF, 0xFF, 0xCB, 0x4D, 0x00, 0x01, 0x08, 0xC1, 0xFF, 0xFF, 0xBC, 0x2C, + 0x02, 0xF4, 0x04, 0x00, 0x00, 0x00, 0x00, + 0x02, 0xF8, 0x04, 0x00, 0x00, 0x00, 0x00, + 0x02, 0xFC, 0x04, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x60, 0x04, 0x40, 0x00, 0x00, 0x00, + 0x00, 0x60, 0x04, 0x00, 0x40, 0x00, 0x00 +}; + +uint8_t MPU6050::dmpInitialize() { + // reset device + DEBUG_PRINTLN(F("\n\nResetting MPU6050...")); + reset(); + delay(30); // wait after reset + + // disable sleep mode + DEBUG_PRINTLN(F("Disabling sleep mode...")); + setSleepEnabled(false); + + // get MPU product ID + DEBUG_PRINTLN(F("Getting product ID...")); + //uint8_t productID = 0; //getProductID(); + DEBUG_PRINT(F("Product ID = ")); + DEBUG_PRINT(productID); + + // get MPU hardware revision + DEBUG_PRINTLN(F("Selecting user bank 16...")); + setMemoryBank(0x10, true, true); + DEBUG_PRINTLN(F("Selecting memory byte 6...")); + setMemoryStartAddress(0x06); + DEBUG_PRINTLN(F("Checking hardware revision...")); + uint8_t hwRevision = readMemoryByte(); + DEBUG_PRINT(F("Revision @ user[16][6] = ")); + DEBUG_PRINTLNF(hwRevision, HEX); + DEBUG_PRINTLN(F("Resetting memory bank selection to 0...")); + setMemoryBank(0, false, false); + + // check OTP bank valid + DEBUG_PRINTLN(F("Reading OTP bank valid flag...")); + uint8_t otpValid = getOTPBankValid(); + DEBUG_PRINT(F("OTP bank is ")); + DEBUG_PRINTLN(otpValid ? F("valid!") : F("invalid!")); + + // get X/Y/Z gyro offsets + DEBUG_PRINTLN(F("Reading gyro offset values...")); + int8_t xgOffset = getXGyroOffset(); + int8_t ygOffset = getYGyroOffset(); + int8_t zgOffset = getZGyroOffset(); + DEBUG_PRINT(F("X gyro offset = ")); + DEBUG_PRINTLN(xgOffset); + DEBUG_PRINT(F("Y gyro offset = ")); + DEBUG_PRINTLN(ygOffset); + DEBUG_PRINT(F("Z gyro offset = ")); + DEBUG_PRINTLN(zgOffset); + + I2Cdev::readByte(devAddr, MPU6050_RA_USER_CTRL, buffer); // ? + + DEBUG_PRINTLN(F("Enabling interrupt latch, clear on any read, AUX bypass enabled")); + I2Cdev::writeByte(devAddr, MPU6050_RA_INT_PIN_CFG, 0x32); + + // enable MPU AUX I2C bypass mode + //DEBUG_PRINTLN(F("Enabling AUX I2C bypass mode...")); + //setI2CBypassEnabled(true); + + DEBUG_PRINTLN(F("Setting magnetometer mode to power-down...")); + //mag -> setMode(0); + I2Cdev::writeByte(0x0E, 0x0A, 0x00); + + DEBUG_PRINTLN(F("Setting magnetometer mode to fuse access...")); + //mag -> setMode(0x0F); + I2Cdev::writeByte(0x0E, 0x0A, 0x0F); + + DEBUG_PRINTLN(F("Reading mag magnetometer factory calibration...")); + int8_t asax, asay, asaz; + //mag -> getAdjustment(&asax, &asay, &asaz); + I2Cdev::readBytes(0x0E, 0x10, 3, buffer); + asax = (int8_t)buffer[0]; + asay = (int8_t)buffer[1]; + asaz = (int8_t)buffer[2]; + DEBUG_PRINT(F("Adjustment X/Y/Z = ")); + DEBUG_PRINT(asax); + DEBUG_PRINT(F(" / ")); + DEBUG_PRINT(asay); + DEBUG_PRINT(F(" / ")); + DEBUG_PRINTLN(asaz); + + DEBUG_PRINTLN(F("Setting magnetometer mode to power-down...")); + //mag -> setMode(0); + I2Cdev::writeByte(0x0E, 0x0A, 0x00); + + // load DMP code into memory banks + DEBUG_PRINT(F("Writing DMP code to MPU memory banks (")); + DEBUG_PRINT(MPU6050_DMP_CODE_SIZE); + DEBUG_PRINTLN(F(" bytes)")); + if (writeProgMemoryBlock(dmpMemory, MPU6050_DMP_CODE_SIZE)) { + DEBUG_PRINTLN(F("Success! DMP code written and verified.")); + + DEBUG_PRINTLN(F("Configuring DMP and related settings...")); + + // write DMP configuration + DEBUG_PRINT(F("Writing DMP configuration to MPU memory banks (")); + DEBUG_PRINT(MPU6050_DMP_CONFIG_SIZE); + DEBUG_PRINTLN(F(" bytes in config def)")); + if (writeProgDMPConfigurationSet(dmpConfig, MPU6050_DMP_CONFIG_SIZE)) { + DEBUG_PRINTLN(F("Success! DMP configuration written and verified.")); + + DEBUG_PRINTLN(F("Setting DMP and FIFO_OFLOW interrupts enabled...")); + setIntEnabled(0x12); + + DEBUG_PRINTLN(F("Setting sample rate to 200Hz...")); + setRate(4); // 1khz / (1 + 4) = 200 Hz + + DEBUG_PRINTLN(F("Setting clock source to Z Gyro...")); + setClockSource(MPU6050_CLOCK_PLL_ZGYRO); + + DEBUG_PRINTLN(F("Setting DLPF bandwidth to 42Hz...")); + setDLPFMode(MPU6050_DLPF_BW_42); + + DEBUG_PRINTLN(F("Setting external frame sync to TEMP_OUT_L[0]...")); + setExternalFrameSync(MPU6050_EXT_SYNC_TEMP_OUT_L); + + DEBUG_PRINTLN(F("Setting gyro sensitivity to +/- 2000 deg/sec...")); + setFullScaleGyroRange(MPU6050_GYRO_FS_2000); + + DEBUG_PRINTLN(F("Setting DMP configuration bytes (function unknown)...")); + setDMPConfig1(0x03); + setDMPConfig2(0x00); + + DEBUG_PRINTLN(F("Clearing OTP Bank flag...")); + setOTPBankValid(false); + + DEBUG_PRINTLN(F("Setting X/Y/Z gyro offsets to previous values...")); + setXGyroOffsetTC(xgOffset); + setYGyroOffsetTC(ygOffset); + setZGyroOffsetTC(zgOffset); + + //DEBUG_PRINTLN(F("Setting X/Y/Z gyro user offsets to zero...")); + //setXGyroOffset(0); + //setYGyroOffset(0); + //setZGyroOffset(0); + + DEBUG_PRINTLN(F("Writing final memory update 1/19 (function unknown)...")); + uint8_t dmpUpdate[16], j; + uint16_t pos = 0; + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Writing final memory update 2/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Resetting FIFO...")); + resetFIFO(); + + DEBUG_PRINTLN(F("Reading FIFO count...")); + uint8_t fifoCount = getFIFOCount(); + + DEBUG_PRINT(F("Current FIFO count=")); + DEBUG_PRINTLN(fifoCount); + uint8_t fifoBuffer[128]; + //getFIFOBytes(fifoBuffer, fifoCount); + + DEBUG_PRINTLN(F("Writing final memory update 3/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Writing final memory update 4/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Disabling all standby flags...")); + I2Cdev::writeByte(0x68, MPU6050_RA_PWR_MGMT_2, 0x00); + + DEBUG_PRINTLN(F("Setting accelerometer sensitivity to +/- 2g...")); + I2Cdev::writeByte(0x68, MPU6050_RA_ACCEL_CONFIG, 0x00); + + DEBUG_PRINTLN(F("Setting motion detection threshold to 2...")); + setMotionDetectionThreshold(2); + + DEBUG_PRINTLN(F("Setting zero-motion detection threshold to 156...")); + setZeroMotionDetectionThreshold(156); + + DEBUG_PRINTLN(F("Setting motion detection duration to 80...")); + setMotionDetectionDuration(80); + + DEBUG_PRINTLN(F("Setting zero-motion detection duration to 0...")); + setZeroMotionDetectionDuration(0); + + DEBUG_PRINTLN(F("Setting AK8975 to single measurement mode...")); + //mag -> setMode(1); + I2Cdev::writeByte(0x0E, 0x0A, 0x01); + + // setup AK8975 (0x0E) as Slave 0 in read mode + DEBUG_PRINTLN(F("Setting up AK8975 read slave 0...")); + I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV0_ADDR, 0x8E); + I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV0_REG, 0x01); + I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV0_CTRL, 0xDA); + + // setup AK8975 (0x0E) as Slave 2 in write mode + DEBUG_PRINTLN(F("Setting up AK8975 write slave 2...")); + I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV2_ADDR, 0x0E); + I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV2_REG, 0x0A); + I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV2_CTRL, 0x81); + I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV2_DO, 0x01); + + // setup I2C timing/delay control + DEBUG_PRINTLN(F("Setting up slave access delay...")); + I2Cdev::writeByte(0x68, MPU6050_RA_I2C_SLV4_CTRL, 0x18); + I2Cdev::writeByte(0x68, MPU6050_RA_I2C_MST_DELAY_CTRL, 0x05); + + // enable interrupts + DEBUG_PRINTLN(F("Enabling default interrupt behavior/no bypass...")); + I2Cdev::writeByte(0x68, MPU6050_RA_INT_PIN_CFG, 0x00); + + // enable I2C master mode and reset DMP/FIFO + DEBUG_PRINTLN(F("Enabling I2C master mode...")); + I2Cdev::writeByte(0x68, MPU6050_RA_USER_CTRL, 0x20); + DEBUG_PRINTLN(F("Resetting FIFO...")); + I2Cdev::writeByte(0x68, MPU6050_RA_USER_CTRL, 0x24); + DEBUG_PRINTLN(F("Rewriting I2C master mode enabled because...I don't know")); + I2Cdev::writeByte(0x68, MPU6050_RA_USER_CTRL, 0x20); + DEBUG_PRINTLN(F("Enabling and resetting DMP/FIFO...")); + I2Cdev::writeByte(0x68, MPU6050_RA_USER_CTRL, 0xE8); + + DEBUG_PRINTLN(F("Writing final memory update 5/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + DEBUG_PRINTLN(F("Writing final memory update 6/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + DEBUG_PRINTLN(F("Writing final memory update 7/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + DEBUG_PRINTLN(F("Writing final memory update 8/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + DEBUG_PRINTLN(F("Writing final memory update 9/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + DEBUG_PRINTLN(F("Writing final memory update 10/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + DEBUG_PRINTLN(F("Writing final memory update 11/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Reading final memory update 12/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + readMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + #ifdef DEBUG + DEBUG_PRINT(F("Read bytes: ")); + for (j = 0; j < 4; j++) { + DEBUG_PRINTF(dmpUpdate[3 + j], HEX); + DEBUG_PRINT(" "); + } + DEBUG_PRINTLN(""); + #endif + + DEBUG_PRINTLN(F("Writing final memory update 13/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + DEBUG_PRINTLN(F("Writing final memory update 14/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + DEBUG_PRINTLN(F("Writing final memory update 15/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + DEBUG_PRINTLN(F("Writing final memory update 16/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + DEBUG_PRINTLN(F("Writing final memory update 17/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Waiting for FIRO count >= 46...")); + while ((fifoCount = getFIFOCount()) < 46); + DEBUG_PRINTLN(F("Reading FIFO...")); + getFIFOBytes(fifoBuffer, min(fifoCount, 128)); // safeguard only 128 bytes + DEBUG_PRINTLN(F("Reading interrupt status...")); + getIntStatus(); + + DEBUG_PRINTLN(F("Writing final memory update 18/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Waiting for FIRO count >= 48...")); + while ((fifoCount = getFIFOCount()) < 48); + DEBUG_PRINTLN(F("Reading FIFO...")); + getFIFOBytes(fifoBuffer, min(fifoCount, 128)); // safeguard only 128 bytes + DEBUG_PRINTLN(F("Reading interrupt status...")); + getIntStatus(); + DEBUG_PRINTLN(F("Waiting for FIRO count >= 48...")); + while ((fifoCount = getFIFOCount()) < 48); + DEBUG_PRINTLN(F("Reading FIFO...")); + getFIFOBytes(fifoBuffer, min(fifoCount, 128)); // safeguard only 128 bytes + DEBUG_PRINTLN(F("Reading interrupt status...")); + getIntStatus(); + + DEBUG_PRINTLN(F("Writing final memory update 19/19 (function unknown)...")); + for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]); + writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]); + + DEBUG_PRINTLN(F("Disabling DMP (you turn it on later)...")); + setDMPEnabled(false); + + DEBUG_PRINTLN(F("Setting up internal 48-byte (default) DMP packet buffer...")); + dmpPacketSize = 48; + /*if ((dmpPacketBuffer = (uint8_t *)malloc(42)) == 0) { + return 3; // TODO: proper error code for no memory + }*/ + + DEBUG_PRINTLN(F("Resetting FIFO and clearing INT status one last time...")); + resetFIFO(); + getIntStatus(); + } else { + DEBUG_PRINTLN(F("ERROR! DMP configuration verification failed.")); + return 2; // configuration block loading failed + } + } else { + DEBUG_PRINTLN(F("ERROR! DMP code verification failed.")); + return 1; // main binary block loading failed + } + return 0; // success +} + +bool MPU6050::dmpPacketAvailable() { + return getFIFOCount() >= dmpGetFIFOPacketSize(); +} + +// uint8_t MPU6050::dmpSetFIFORate(uint8_t fifoRate); +// uint8_t MPU6050::dmpGetFIFORate(); +// uint8_t MPU6050::dmpGetSampleStepSizeMS(); +// uint8_t MPU6050::dmpGetSampleFrequency(); +// int32_t MPU6050::dmpDecodeTemperature(int8_t tempReg); + +//uint8_t MPU6050::dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority); +//uint8_t MPU6050::dmpUnregisterFIFORateProcess(inv_obj_func func); +//uint8_t MPU6050::dmpRunFIFORateProcesses(); + +// uint8_t MPU6050::dmpSendQuaternion(uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendPacketNumber(uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy); +// uint8_t MPU6050::dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy); + +uint8_t MPU6050::dmpGetAccel(int32_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = (((uint32_t)packet[34] << 24) | ((uint32_t)packet[35] << 16) | ((uint32_t)packet[36] << 8) | packet[37]); + data[1] = (((uint32_t)packet[38] << 24) | ((uint32_t)packet[39] << 16) | ((uint32_t)packet[40] << 8) | packet[41]); + data[2] = (((uint32_t)packet[42] << 24) | ((uint32_t)packet[43] << 16) | ((uint32_t)packet[44] << 8) | packet[45]); + return 0; +} +uint8_t MPU6050::dmpGetAccel(int16_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = (packet[34] << 8) | packet[35]; + data[1] = (packet[38] << 8) | packet[39]; + data[2] = (packet[42] << 8) | packet[43]; + return 0; +} +uint8_t MPU6050::dmpGetAccel(VectorInt16 *v, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + v -> x = (packet[34] << 8) | packet[35]; + v -> y = (packet[38] << 8) | packet[39]; + v -> z = (packet[42] << 8) | packet[43]; + return 0; +} +uint8_t MPU6050::dmpGetQuaternion(int32_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = (((uint32_t)packet[0] << 24) | ((uint32_t)packet[1] << 16) | ((uint32_t)packet[2] << 8) | packet[3]); + data[1] = (((uint32_t)packet[4] << 24) | ((uint32_t)packet[5] << 16) | ((uint32_t)packet[6] << 8) | packet[7]); + data[2] = (((uint32_t)packet[8] << 24) | ((uint32_t)packet[9] << 16) | ((uint32_t)packet[10] << 8) | packet[11]); + data[3] = (((uint32_t)packet[12] << 24) | ((uint32_t)packet[13] << 16) | ((uint32_t)packet[14] << 8) | packet[15]); + return 0; +} +uint8_t MPU6050::dmpGetQuaternion(int16_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = ((packet[0] << 8) | packet[1]); + data[1] = ((packet[4] << 8) | packet[5]); + data[2] = ((packet[8] << 8) | packet[9]); + data[3] = ((packet[12] << 8) | packet[13]); + return 0; +} +uint8_t MPU6050::dmpGetQuaternion(Quaternion *q, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + int16_t qI[4]; + uint8_t status = dmpGetQuaternion(qI, packet); + if (status == 0) { + q -> w = (float)qI[0] / 16384.0f; + q -> x = (float)qI[1] / 16384.0f; + q -> y = (float)qI[2] / 16384.0f; + q -> z = (float)qI[3] / 16384.0f; + return 0; + } + return status; // int16 return value, indicates error if this line is reached +} +// uint8_t MPU6050::dmpGet6AxisQuaternion(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetRelativeQuaternion(long *data, const uint8_t* packet); +uint8_t MPU6050::dmpGetGyro(int32_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = (((uint32_t)packet[16] << 24) | ((uint32_t)packet[17] << 16) | ((uint32_t)packet[18] << 8) | packet[19]); + data[1] = (((uint32_t)packet[20] << 24) | ((uint32_t)packet[21] << 16) | ((uint32_t)packet[22] << 8) | packet[23]); + data[2] = (((uint32_t)packet[24] << 24) | ((uint32_t)packet[25] << 16) | ((uint32_t)packet[26] << 8) | packet[27]); + return 0; +} +uint8_t MPU6050::dmpGetGyro(int16_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = (packet[16] << 8) | packet[17]; + data[1] = (packet[20] << 8) | packet[21]; + data[2] = (packet[24] << 8) | packet[25]; + return 0; +} +uint8_t MPU6050::dmpGetMag(int16_t *data, const uint8_t* packet) { + // TODO: accommodate different arrangements of sent data (ONLY default supported now) + if (packet == 0) packet = dmpPacketBuffer; + data[0] = (packet[28] << 8) | packet[29]; + data[1] = (packet[30] << 8) | packet[31]; + data[2] = (packet[32] << 8) | packet[33]; + return 0; +} +// uint8_t MPU6050::dmpSetLinearAccelFilterCoefficient(float coef); +// uint8_t MPU6050::dmpGetLinearAccel(long *data, const uint8_t* packet); +uint8_t MPU6050::dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity) { + // get rid of the gravity component (+1g = +4096 in standard DMP FIFO packet) + v -> x = vRaw -> x - gravity -> x*4096; + v -> y = vRaw -> y - gravity -> y*4096; + v -> z = vRaw -> z - gravity -> z*4096; + return 0; +} +// uint8_t MPU6050::dmpGetLinearAccelInWorld(long *data, const uint8_t* packet); +uint8_t MPU6050::dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q) { + // rotate measured 3D acceleration vector into original state + // frame of reference based on orientation quaternion + memcpy(v, vReal, sizeof(VectorInt16)); + v -> rotate(q); + return 0; +} +// uint8_t MPU6050::dmpGetGyroAndAccelSensor(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetGyroSensor(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetControlData(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetTemperature(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetGravity(long *data, const uint8_t* packet); +uint8_t MPU6050::dmpGetGravity(VectorFloat *v, Quaternion *q) { + v -> x = 2 * (q -> x*q -> z - q -> w*q -> y); + v -> y = 2 * (q -> w*q -> x + q -> y*q -> z); + v -> z = q -> w*q -> w - q -> x*q -> x - q -> y*q -> y + q -> z*q -> z; + return 0; +} +// uint8_t MPU6050::dmpGetUnquantizedAccel(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetQuantizedAccel(long *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetExternalSensorData(long *data, int size, const uint8_t* packet); +// uint8_t MPU6050::dmpGetEIS(long *data, const uint8_t* packet); + +uint8_t MPU6050::dmpGetEuler(float *data, Quaternion *q) { + data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1); // psi + data[1] = -asin(2*q -> x*q -> z + 2*q -> w*q -> y); // theta + data[2] = atan2(2*q -> y*q -> z - 2*q -> w*q -> x, 2*q -> w*q -> w + 2*q -> z*q -> z - 1); // phi + return 0; +} +uint8_t MPU6050::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity) { + // yaw: (about Z axis) + data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1); + // pitch: (nose up/down, about Y axis) + data[1] = atan(gravity -> x / sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z)); + // roll: (tilt left/right, about X axis) + data[2] = atan(gravity -> y / sqrt(gravity -> x*gravity -> x + gravity -> z*gravity -> z)); + return 0; +} + +// uint8_t MPU6050::dmpGetAccelFloat(float *data, const uint8_t* packet); +// uint8_t MPU6050::dmpGetQuaternionFloat(float *data, const uint8_t* packet); + +uint8_t MPU6050::dmpProcessFIFOPacket(const unsigned char *dmpData) { + /*for (uint8_t k = 0; k < dmpPacketSize; k++) { + if (dmpData[k] < 0x10) Serial.print("0"); + Serial.print(dmpData[k], HEX); + Serial.print(" "); + } + Serial.print("\n");*/ + //Serial.println((uint16_t)dmpPacketBuffer); + return 0; +} +uint8_t MPU6050::dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed) { + uint8_t status; + uint8_t buf[dmpPacketSize]; + for (uint8_t i = 0; i < numPackets; i++) { + // read packet from FIFO + getFIFOBytes(buf, dmpPacketSize); + + // process packet + if ((status = dmpProcessFIFOPacket(buf)) > 0) return status; + + // increment external process count variable, if supplied + if (processed != 0) *processed++; + } + return 0; +} + +// uint8_t MPU6050::dmpSetFIFOProcessedCallback(void (*func) (void)); + +// uint8_t MPU6050::dmpInitFIFOParam(); +// uint8_t MPU6050::dmpCloseFIFO(); +// uint8_t MPU6050::dmpSetGyroDataSource(uint_fast8_t source); +// uint8_t MPU6050::dmpDecodeQuantizedAccel(); +// uint32_t MPU6050::dmpGetGyroSumOfSquare(); +// uint32_t MPU6050::dmpGetAccelSumOfSquare(); +// void MPU6050::dmpOverrideQuaternion(long *q); +uint16_t MPU6050::dmpGetFIFOPacketSize() { + return dmpPacketSize; +} + +#endif /* _MPU6050_9AXIS_MOTIONAPPS41_H_ */ diff --git a/libraries/MPU6050/examples/IMU_Zero/IMU_Zero.ino b/libraries/MPU6050/examples/IMU_Zero/IMU_Zero.ino new file mode 100644 index 0000000..c1a5cf8 --- /dev/null +++ b/libraries/MPU6050/examples/IMU_Zero/IMU_Zero.ino @@ -0,0 +1,318 @@ +// MPU6050 offset-finder, based on Jeff Rowberg's MPU6050_RAW +// 2016-10-19 by Robert R. Fenichel (bob@fenichel.net) + +// I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class +// 10/7/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2016-11-25 - added delays to reduce sampling rate to ~200 Hz +// added temporizing printing during long computations +// 2016-10-25 - requires inequality (Low < Target, High > Target) during expansion +// dynamic speed change when closing in +// 2016-10-22 - cosmetic changes +// 2016-10-19 - initial release of IMU_Zero +// 2013-05-08 - added multiple output formats +// - added seamless Fastwire support +// 2011-10-07 - initial release of MPU6050_RAW + +/* ============================================ +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. + + If an MPU6050 + * is an ideal member of its tribe, + * is properly warmed up, + * is at rest in a neutral position, + * is in a location where the pull of gravity is exactly 1g, and + * has been loaded with the best possible offsets, +then it will report 0 for all accelerations and displacements, except for +Z acceleration, for which it will report 16384 (that is, 2^14). Your device +probably won't do quite this well, but good offsets will all get the baseline +outputs close to these target values. + + Put the MPU6050 in a flat and horizontal surface, and leave it operating for +5-10 minutes so its temperature gets stabilized. + + Run this program. A "----- done -----" line will indicate that it has done its best. +With the current accuracy-related constants (NFast = 1000, NSlow = 10000), it will take +a few minutes to get there. + + Along the way, it will generate a dozen or so lines of output, showing that for each +of the 6 desired offsets, it is + * first, trying to find two estimates, one too low and one too high, and + * then, closing in until the bracket can't be made smaller. + + The line just above the "done" line will look something like + [567,567] --> [-1,2] [-2223,-2223] --> [0,1] [1131,1132] --> [16374,16404] [155,156] --> [-1,1] [-25,-24] --> [0,3] [5,6] --> [0,4] +As will have been shown in interspersed header lines, the six groups making up this +line describe the optimum offsets for the X acceleration, Y acceleration, Z acceleration, +X gyro, Y gyro, and Z gyro, respectively. In the sample shown just above, the trial showed +that +567 was the best offset for the X acceleration, -2223 was best for Y acceleration, +and so on. + + The need for the delay between readings (usDelay) was brought to my attention by Nikolaus Doppelhammer. +=============================================== +*/ + +// 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" + +// 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 InvenSense evaluation board) +// AD0 high = 0x69 +MPU6050 accelgyro; +//MPU6050 accelgyro(0x69); // <-- use for AD0 high + + +const char LBRACKET = '['; +const char RBRACKET = ']'; +const char COMMA = ','; +const char BLANK = ' '; +const char PERIOD = '.'; + +const int iAx = 0; +const int iAy = 1; +const int iAz = 2; +const int iGx = 3; +const int iGy = 4; +const int iGz = 5; + +const int usDelay = 3150; // empirical, to hold sampling to 200 Hz +const int NFast = 1000; // the bigger, the better (but slower) +const int NSlow = 10000; // .. +const int LinesBetweenHeaders = 5; + int LowValue[6]; + int HighValue[6]; + int Smoothed[6]; + int LowOffset[6]; + int HighOffset[6]; + int Target[6]; + int LinesOut; + int N; + +void ForceHeader() + { LinesOut = 99; } + +void GetSmoothed() + { int RawValue[6]; + int i; + long Sums[6]; + for (i = iAx; i <= iGz; i++) + { Sums[i] = 0; } +// unsigned long Start = micros(); + + for (i = 1; i <= N; i++) + { // get sums + accelgyro.getMotion6(&RawValue[iAx], &RawValue[iAy], &RawValue[iAz], + &RawValue[iGx], &RawValue[iGy], &RawValue[iGz]); + if ((i % 500) == 0) + Serial.print(PERIOD); + delayMicroseconds(usDelay); + for (int j = iAx; j <= iGz; j++) + Sums[j] = Sums[j] + RawValue[j]; + } // get sums +// unsigned long usForN = micros() - Start; +// Serial.print(" reading at "); +// Serial.print(1000000/((usForN+N/2)/N)); +// Serial.println(" Hz"); + for (i = iAx; i <= iGz; i++) + { Smoothed[i] = (Sums[i] + N/2) / N ; } + } // GetSmoothed + +void Initialize() + { + // join I2C bus (I2Cdev library doesn't do this automatically) + #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE + Wire.begin(); + #elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE + Fastwire::setup(400, true); + #endif + + Serial.begin(9600); + + // initialize device + Serial.println("Initializing I2C devices..."); + accelgyro.initialize(); + + // verify connection + Serial.println("Testing device connections..."); + Serial.println(accelgyro.testConnection() ? "MPU6050 connection successful" : "MPU6050 connection failed"); + } // Initialize + +void SetOffsets(int TheOffsets[6]) + { accelgyro.setXAccelOffset(TheOffsets [iAx]); + accelgyro.setYAccelOffset(TheOffsets [iAy]); + accelgyro.setZAccelOffset(TheOffsets [iAz]); + accelgyro.setXGyroOffset (TheOffsets [iGx]); + accelgyro.setYGyroOffset (TheOffsets [iGy]); + accelgyro.setZGyroOffset (TheOffsets [iGz]); + } // SetOffsets + +void ShowProgress() + { if (LinesOut >= LinesBetweenHeaders) + { // show header + Serial.println("\tXAccel\t\t\tYAccel\t\t\t\tZAccel\t\t\tXGyro\t\t\tYGyro\t\t\tZGyro"); + LinesOut = 0; + } // show header + Serial.print(BLANK); + for (int i = iAx; i <= iGz; i++) + { Serial.print(LBRACKET); + Serial.print(LowOffset[i]), + Serial.print(COMMA); + Serial.print(HighOffset[i]); + Serial.print("] --> ["); + Serial.print(LowValue[i]); + Serial.print(COMMA); + Serial.print(HighValue[i]); + if (i == iGz) + { Serial.println(RBRACKET); } + else + { Serial.print("]\t"); } + } + LinesOut++; + } // ShowProgress + +void PullBracketsIn() + { boolean AllBracketsNarrow; + boolean StillWorking; + int NewOffset[6]; + + Serial.println("\nclosing in:"); + AllBracketsNarrow = false; + ForceHeader(); + StillWorking = true; + while (StillWorking) + { StillWorking = false; + if (AllBracketsNarrow && (N == NFast)) + { SetAveraging(NSlow); } + else + { AllBracketsNarrow = true; }// tentative + for (int i = iAx; i <= iGz; i++) + { if (HighOffset[i] <= (LowOffset[i]+1)) + { NewOffset[i] = LowOffset[i]; } + else + { // binary search + StillWorking = true; + NewOffset[i] = (LowOffset[i] + HighOffset[i]) / 2; + if (HighOffset[i] > (LowOffset[i] + 10)) + { AllBracketsNarrow = false; } + } // binary search + } + SetOffsets(NewOffset); + GetSmoothed(); + for (int i = iAx; i <= iGz; i++) + { // closing in + if (Smoothed[i] > Target[i]) + { // use lower half + HighOffset[i] = NewOffset[i]; + HighValue[i] = Smoothed[i]; + } // use lower half + else + { // use upper half + LowOffset[i] = NewOffset[i]; + LowValue[i] = Smoothed[i]; + } // use upper half + } // closing in + ShowProgress(); + } // still working + + } // PullBracketsIn + +void PullBracketsOut() + { boolean Done = false; + int NextLowOffset[6]; + int NextHighOffset[6]; + + Serial.println("expanding:"); + ForceHeader(); + + while (!Done) + { Done = true; + SetOffsets(LowOffset); + GetSmoothed(); + for (int i = iAx; i <= iGz; i++) + { // got low values + LowValue[i] = Smoothed[i]; + if (LowValue[i] >= Target[i]) + { Done = false; + NextLowOffset[i] = LowOffset[i] - 1000; + } + else + { NextLowOffset[i] = LowOffset[i]; } + } // got low values + + SetOffsets(HighOffset); + GetSmoothed(); + for (int i = iAx; i <= iGz; i++) + { // got high values + HighValue[i] = Smoothed[i]; + if (HighValue[i] <= Target[i]) + { Done = false; + NextHighOffset[i] = HighOffset[i] + 1000; + } + else + { NextHighOffset[i] = HighOffset[i]; } + } // got high values + ShowProgress(); + for (int i = iAx; i <= iGz; i++) + { LowOffset[i] = NextLowOffset[i]; // had to wait until ShowProgress done + HighOffset[i] = NextHighOffset[i]; // .. + } + } // keep going + } // PullBracketsOut + +void SetAveraging(int NewN) + { N = NewN; + Serial.print("averaging "); + Serial.print(N); + Serial.println(" readings each time"); + } // SetAveraging + +void setup() + { Initialize(); + for (int i = iAx; i <= iGz; i++) + { // set targets and initial guesses + Target[i] = 0; // must fix for ZAccel + HighOffset[i] = 0; + LowOffset[i] = 0; + } // set targets and initial guesses + Target[iAz] = 16384; + SetAveraging(NFast); + + PullBracketsOut(); + PullBracketsIn(); + + Serial.println("-------------- done --------------"); + } // setup + +void loop() + { + } // loop diff --git a/libraries/MPU6050/examples/MPU6050_DMP6/MPU6050_DMP6.ino b/libraries/MPU6050/examples/MPU6050_DMP6/MPU6050_DMP6.ino new file mode 100644 index 0000000..d755665 --- /dev/null +++ b/libraries/MPU6050/examples/MPU6050_DMP6/MPU6050_DMP6.ino @@ -0,0 +1,374 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class using DMP (MotionApps v2.0) +// 6/21/2012 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2013-05-08 - added seamless Fastwire support +// - added note about gyro calibration +// 2012-06-21 - added note about Arduino 1.0.1 + Leonardo compatibility error +// 2012-06-20 - improved FIFO overflow handling and simplified read process +// 2012-06-19 - completely rearranged DMP initialization code and simplification +// 2012-06-13 - pull gyro and accel data from FIFO packet instead of reading directly +// 2012-06-09 - fix broken FIFO read sequence and change interrupt detection to RISING +// 2012-06-05 - add gravity-compensated initial reference frame acceleration output +// - add 3D math helper file to DMP6 example sketch +// - add Euler output and Yaw/Pitch/Roll output formats +// 2012-06-04 - remove accel offset clearing for better results (thanks Sungon Lee) +// 2012-06-01 - fixed gyro sensitivity to be 2000 deg/sec instead of 250 +// 2012-05-30 - basic DMP initialization working + +/* ============================================ +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. +=============================================== +*/ + +// 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_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; +//MPU6050 mpu(0x69); // <-- use for AD0 high + +/* ========================================================================= + NOTE: In addition to connection 3.3v, GND, SDA, and SCL, this sketch + depends on the MPU-6050's INT pin being connected to the Arduino's + external interrupt #0 pin. On the Arduino Uno and Mega 2560, this is + digital I/O pin 2. + * ========================================================================= */ + +/* ========================================================================= + NOTE: Arduino v1.0.1 with the Leonardo board generates a compile error + when using Serial.write(buf, len). The Teapot output uses this method. + The solution requires a modification to the Arduino USBAPI.h file, which + is fortunately simple, but annoying. This will be fixed in the next IDE + release. For more info, see these links: + + http://arduino.cc/forum/index.php/topic,109987.0.html + http://code.google.com/p/arduino/issues/detail?id=958 + * ========================================================================= */ + + + +// uncomment "OUTPUT_READABLE_QUATERNION" if you want to see the actual +// quaternion components in a [w, x, y, z] format (not best for parsing +// on a remote host such as Processing or something though) +//#define OUTPUT_READABLE_QUATERNION + +// uncomment "OUTPUT_READABLE_EULER" if you want to see Euler angles +// (in degrees) calculated from the quaternions coming from the FIFO. +// Note that Euler angles suffer from gimbal lock (for more info, see +// http://en.wikipedia.org/wiki/Gimbal_lock) +//#define OUTPUT_READABLE_EULER + +// uncomment "OUTPUT_READABLE_YAWPITCHROLL" if you want to see the yaw/ +// pitch/roll angles (in degrees) calculated from the quaternions coming +// from the FIFO. Note this also requires gravity vector calculations. +// Also note that yaw/pitch/roll angles suffer from gimbal lock (for +// more info, see: http://en.wikipedia.org/wiki/Gimbal_lock) +#define OUTPUT_READABLE_YAWPITCHROLL + +// uncomment "OUTPUT_READABLE_REALACCEL" if you want to see acceleration +// components with gravity removed. This acceleration reference frame is +// not compensated for orientation, so +X is always +X according to the +// sensor, just without the effects of gravity. If you want acceleration +// compensated for orientation, us OUTPUT_READABLE_WORLDACCEL instead. +//#define OUTPUT_READABLE_REALACCEL + +// uncomment "OUTPUT_READABLE_WORLDACCEL" if you want to see acceleration +// components with gravity removed and adjusted for the world frame of +// reference (yaw is relative to initial orientation, since no magnetometer +// is present in this case). Could be quite handy in some cases. +//#define OUTPUT_READABLE_WORLDACCEL + +// uncomment "OUTPUT_TEAPOT" if you want output that matches the +// format used for the InvenSense teapot demo +//#define OUTPUT_TEAPOT + + + +#define INTERRUPT_PIN 2 // use pin 2 on Arduino Uno & most boards +#define LED_PIN 13 // (Arduino is 13, Teensy is 11, Teensy++ is 6) +bool blinkState = false; + +// 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 + +// orientation/motion vars +Quaternion q; // [w, x, y, z] quaternion container +VectorInt16 aa; // [x, y, z] accel sensor measurements +VectorInt16 aaReal; // [x, y, z] gravity-free accel sensor measurements +VectorInt16 aaWorld; // [x, y, z] world-frame accel sensor measurements +VectorFloat gravity; // [x, y, z] gravity vector +float euler[3]; // [psi, theta, phi] Euler angle container +float ypr[3]; // [yaw, pitch, roll] yaw/pitch/roll container and gravity vector + +// packet structure for InvenSense teapot demo +uint8_t teapotPacket[14] = { '$', 0x02, 0,0, 0,0, 0,0, 0,0, 0x00, 0x00, '\r', '\n' }; + + + +// ================================================================ +// === INTERRUPT DETECTION ROUTINE === +// ================================================================ + +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) + #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE + Wire.begin(); + Wire.setClock(400000); // 400kHz I2C clock. Comment this line if having compilation difficulties + #elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE + Fastwire::setup(400, true); + #endif + + // 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); + 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(); + pinMode(INTERRUPT_PIN, INPUT); + + // verify connection + Serial.println(F("Testing device connections...")); + Serial.println(mpu.testConnection() ? F("MPU6050 connection successful") : F("MPU6050 connection failed")); + + // 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(220); + mpu.setYGyroOffset(76); + mpu.setZGyroOffset(-85); + mpu.setZAccelOffset(1788); // 1688 factory default for my test chip + + // 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(digitalPinToInterrupt(INTERRUPT_PIN), 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 { + // 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(")")); + } + + // configure LED for output + pinMode(LED_PIN, OUTPUT); +} + + + +// ================================================================ +// === 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) { + // wait for correct available data length, should be a VERY short wait + while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount(); + + // read a packet from FIFO + mpu.getFIFOBytes(fifoBuffer, packetSize); + + // track FIFO count here in case there is > 1 packet available + // (this lets us immediately read more without waiting for an interrupt) + fifoCount -= packetSize; + + #ifdef OUTPUT_READABLE_QUATERNION + // display quaternion values in easy matrix form: w x y z + mpu.dmpGetQuaternion(&q, fifoBuffer); + Serial.print("quat\t"); + Serial.print(q.w); + Serial.print("\t"); + Serial.print(q.x); + Serial.print("\t"); + Serial.print(q.y); + Serial.print("\t"); + Serial.println(q.z); + #endif + + #ifdef OUTPUT_READABLE_EULER + // display Euler angles in degrees + mpu.dmpGetQuaternion(&q, fifoBuffer); + mpu.dmpGetEuler(euler, &q); + Serial.print("euler\t"); + Serial.print(euler[0] * 180/M_PI); + Serial.print("\t"); + Serial.print(euler[1] * 180/M_PI); + Serial.print("\t"); + Serial.println(euler[2] * 180/M_PI); + #endif + + #ifdef OUTPUT_READABLE_YAWPITCHROLL + // display Euler angles in degrees + mpu.dmpGetQuaternion(&q, fifoBuffer); + mpu.dmpGetGravity(&gravity, &q); + mpu.dmpGetYawPitchRoll(ypr, &q, &gravity); + Serial.print("ypr\t"); + Serial.print(ypr[0] * 180/M_PI); + Serial.print("\t"); + Serial.print(ypr[1] * 180/M_PI); + Serial.print("\t"); + Serial.println(ypr[2] * 180/M_PI); + #endif + + #ifdef OUTPUT_READABLE_REALACCEL + // display real acceleration, adjusted to remove gravity + mpu.dmpGetQuaternion(&q, fifoBuffer); + mpu.dmpGetAccel(&aa, fifoBuffer); + mpu.dmpGetGravity(&gravity, &q); + mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity); + Serial.print("areal\t"); + Serial.print(aaReal.x); + Serial.print("\t"); + Serial.print(aaReal.y); + Serial.print("\t"); + Serial.println(aaReal.z); + #endif + + #ifdef OUTPUT_READABLE_WORLDACCEL + // display initial world-frame acceleration, adjusted to remove gravity + // and rotated based on known orientation from quaternion + mpu.dmpGetQuaternion(&q, fifoBuffer); + mpu.dmpGetAccel(&aa, fifoBuffer); + mpu.dmpGetGravity(&gravity, &q); + mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity); + mpu.dmpGetLinearAccelInWorld(&aaWorld, &aaReal, &q); + Serial.print("aworld\t"); + Serial.print(aaWorld.x); + Serial.print("\t"); + Serial.print(aaWorld.y); + Serial.print("\t"); + Serial.println(aaWorld.z); + #endif + + #ifdef OUTPUT_TEAPOT + // display quaternion values in InvenSense Teapot demo format: + teapotPacket[2] = fifoBuffer[0]; + teapotPacket[3] = fifoBuffer[1]; + teapotPacket[4] = fifoBuffer[4]; + teapotPacket[5] = fifoBuffer[5]; + teapotPacket[6] = fifoBuffer[8]; + teapotPacket[7] = fifoBuffer[9]; + teapotPacket[8] = fifoBuffer[12]; + teapotPacket[9] = fifoBuffer[13]; + Serial.write(teapotPacket, 14); + teapotPacket[11]++; // packetCount, loops at 0xFF on purpose + #endif + + // blink LED to indicate activity + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); + } +} diff --git a/libraries/MPU6050/examples/MPU6050_DMP6/Processing/MPUTeapot/MPUTeapot.pde b/libraries/MPU6050/examples/MPU6050_DMP6/Processing/MPUTeapot/MPUTeapot.pde new file mode 100644 index 0000000..130fc4d --- /dev/null +++ b/libraries/MPU6050/examples/MPU6050_DMP6/Processing/MPUTeapot/MPUTeapot.pde @@ -0,0 +1,242 @@ +// I2C device class (I2Cdev) demonstration Processing sketch for MPU6050 DMP output +// 6/20/2012 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2012-06-20 - 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. +=============================================== +*/ + +import processing.serial.*; +import processing.opengl.*; +import toxi.geom.*; +import toxi.processing.*; + +// NOTE: requires ToxicLibs to be installed in order to run properly. +// 1. Download from http://toxiclibs.org/downloads +// 2. Extract into [userdir]/Processing/libraries +// (location may be different on Mac/Linux) +// 3. Run and bask in awesomeness + +ToxiclibsSupport gfx; + +Serial port; // The serial port +char[] teapotPacket = new char[14]; // InvenSense Teapot packet +int serialCount = 0; // current packet byte position +int synced = 0; +int interval = 0; + +float[] q = new float[4]; +Quaternion quat = new Quaternion(1, 0, 0, 0); + +float[] gravity = new float[3]; +float[] euler = new float[3]; +float[] ypr = new float[3]; + +void setup() { + // 300px square viewport using OpenGL rendering + size(300, 300, OPENGL); + gfx = new ToxiclibsSupport(this); + + // setup lights and antialiasing + lights(); + smooth(); + + // display serial port list for debugging/clarity + println(Serial.list()); + + // get the first available port (use EITHER this OR the specific port code below) + String portName = Serial.list()[0]; + + // get a specific serial port (use EITHER this OR the first-available code above) + //String portName = "COM4"; + + // open the serial port + port = new Serial(this, portName, 115200); + + // send single character to trigger DMP init/start + // (expected by MPU6050_DMP6 example Arduino sketch) + port.write('r'); +} + +void draw() { + if (millis() - interval > 1000) { + // resend single character to trigger DMP init/start + // in case the MPU is halted/reset while applet is running + port.write('r'); + interval = millis(); + } + + // black background + background(0); + + // translate everything to the middle of the viewport + pushMatrix(); + translate(width / 2, height / 2); + + // 3-step rotation from yaw/pitch/roll angles (gimbal lock!) + // ...and other weirdness I haven't figured out yet + //rotateY(-ypr[0]); + //rotateZ(-ypr[1]); + //rotateX(-ypr[2]); + + // toxiclibs direct angle/axis rotation from quaternion (NO gimbal lock!) + // (axis order [1, 3, 2] and inversion [-1, +1, +1] is a consequence of + // different coordinate system orientation assumptions between Processing + // and InvenSense DMP) + float[] axis = quat.toAxisAngle(); + rotate(axis[0], -axis[1], axis[3], axis[2]); + + // draw main body in red + fill(255, 0, 0, 200); + box(10, 10, 200); + + // draw front-facing tip in blue + fill(0, 0, 255, 200); + pushMatrix(); + translate(0, 0, -120); + rotateX(PI/2); + drawCylinder(0, 20, 20, 8); + popMatrix(); + + // draw wings and tail fin in green + fill(0, 255, 0, 200); + beginShape(TRIANGLES); + vertex(-100, 2, 30); vertex(0, 2, -80); vertex(100, 2, 30); // wing top layer + vertex(-100, -2, 30); vertex(0, -2, -80); vertex(100, -2, 30); // wing bottom layer + vertex(-2, 0, 98); vertex(-2, -30, 98); vertex(-2, 0, 70); // tail left layer + vertex( 2, 0, 98); vertex( 2, -30, 98); vertex( 2, 0, 70); // tail right layer + endShape(); + beginShape(QUADS); + vertex(-100, 2, 30); vertex(-100, -2, 30); vertex( 0, -2, -80); vertex( 0, 2, -80); + vertex( 100, 2, 30); vertex( 100, -2, 30); vertex( 0, -2, -80); vertex( 0, 2, -80); + vertex(-100, 2, 30); vertex(-100, -2, 30); vertex(100, -2, 30); vertex(100, 2, 30); + vertex(-2, 0, 98); vertex(2, 0, 98); vertex(2, -30, 98); vertex(-2, -30, 98); + vertex(-2, 0, 98); vertex(2, 0, 98); vertex(2, 0, 70); vertex(-2, 0, 70); + vertex(-2, -30, 98); vertex(2, -30, 98); vertex(2, 0, 70); vertex(-2, 0, 70); + endShape(); + + popMatrix(); +} + +void serialEvent(Serial port) { + interval = millis(); + while (port.available() > 0) { + int ch = port.read(); + + if (synced == 0 && ch != '$') return; // initial synchronization - also used to resync/realign if needed + synced = 1; + print ((char)ch); + + if ((serialCount == 1 && ch != 2) + || (serialCount == 12 && ch != '\r') + || (serialCount == 13 && ch != '\n')) { + serialCount = 0; + synced = 0; + return; + } + + if (serialCount > 0 || ch == '$') { + teapotPacket[serialCount++] = (char)ch; + if (serialCount == 14) { + serialCount = 0; // restart packet byte position + + // get quaternion from data packet + q[0] = ((teapotPacket[2] << 8) | teapotPacket[3]) / 16384.0f; + q[1] = ((teapotPacket[4] << 8) | teapotPacket[5]) / 16384.0f; + q[2] = ((teapotPacket[6] << 8) | teapotPacket[7]) / 16384.0f; + q[3] = ((teapotPacket[8] << 8) | teapotPacket[9]) / 16384.0f; + for (int i = 0; i < 4; i++) if (q[i] >= 2) q[i] = -4 + q[i]; + + // set our toxilibs quaternion to new data + quat.set(q[0], q[1], q[2], q[3]); + + /* + // below calculations unnecessary for orientation only using toxilibs + + // calculate gravity vector + gravity[0] = 2 * (q[1]*q[3] - q[0]*q[2]); + gravity[1] = 2 * (q[0]*q[1] + q[2]*q[3]); + gravity[2] = q[0]*q[0] - q[1]*q[1] - q[2]*q[2] + q[3]*q[3]; + + // calculate Euler angles + euler[0] = atan2(2*q[1]*q[2] - 2*q[0]*q[3], 2*q[0]*q[0] + 2*q[1]*q[1] - 1); + euler[1] = -asin(2*q[1]*q[3] + 2*q[0]*q[2]); + euler[2] = atan2(2*q[2]*q[3] - 2*q[0]*q[1], 2*q[0]*q[0] + 2*q[3]*q[3] - 1); + + // calculate yaw/pitch/roll angles + ypr[0] = atan2(2*q[1]*q[2] - 2*q[0]*q[3], 2*q[0]*q[0] + 2*q[1]*q[1] - 1); + ypr[1] = atan(gravity[0] / sqrt(gravity[1]*gravity[1] + gravity[2]*gravity[2])); + ypr[2] = atan(gravity[1] / sqrt(gravity[0]*gravity[0] + gravity[2]*gravity[2])); + + // output various components for debugging + //println("q:\t" + round(q[0]*100.0f)/100.0f + "\t" + round(q[1]*100.0f)/100.0f + "\t" + round(q[2]*100.0f)/100.0f + "\t" + round(q[3]*100.0f)/100.0f); + //println("euler:\t" + euler[0]*180.0f/PI + "\t" + euler[1]*180.0f/PI + "\t" + euler[2]*180.0f/PI); + //println("ypr:\t" + ypr[0]*180.0f/PI + "\t" + ypr[1]*180.0f/PI + "\t" + ypr[2]*180.0f/PI); + */ + } + } + } +} + +void drawCylinder(float topRadius, float bottomRadius, float tall, int sides) { + float angle = 0; + float angleIncrement = TWO_PI / sides; + beginShape(QUAD_STRIP); + for (int i = 0; i < sides + 1; ++i) { + vertex(topRadius*cos(angle), 0, topRadius*sin(angle)); + vertex(bottomRadius*cos(angle), tall, bottomRadius*sin(angle)); + angle += angleIncrement; + } + endShape(); + + // If it is not a cone, draw the circular top cap + if (topRadius != 0) { + angle = 0; + beginShape(TRIANGLE_FAN); + + // Center point + vertex(0, 0, 0); + for (int i = 0; i < sides + 1; i++) { + vertex(topRadius * cos(angle), 0, topRadius * sin(angle)); + angle += angleIncrement; + } + endShape(); + } + + // If it is not a cone, draw the circular bottom cap + if (bottomRadius != 0) { + angle = 0; + beginShape(TRIANGLE_FAN); + + // Center point + vertex(0, tall, 0); + for (int i = 0; i < sides + 1; i++) { + vertex(bottomRadius * cos(angle), tall, bottomRadius * sin(angle)); + angle += angleIncrement; + } + endShape(); + } +} diff --git a/libraries/MPU6050/examples/MPU6050_DMP6_Ethernet/MPU6050_DMP6_Ethernet.ino b/libraries/MPU6050/examples/MPU6050_DMP6_Ethernet/MPU6050_DMP6_Ethernet.ino new file mode 100644 index 0000000..d95badd --- /dev/null +++ b/libraries/MPU6050/examples/MPU6050_DMP6_Ethernet/MPU6050_DMP6_Ethernet.ino @@ -0,0 +1,537 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class using DMP (MotionApps v2.0) over Ethernet +// 2/27/2016 by hellphoenix +// Based on I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class using DMP (MotionApps v2.0) (6/21/2012 by Jeff Rowberg ) +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2016-02-28 - Cleaned up code to be in line with other example codes + // - Added Ethernet outputs for Quaternion, Euler, RealAccel, WorldAccel +// 2016-02-27 - Initial working code compiled +// Bugs: +// - There is still a hangup after some time, though it only occurs when you are reading data from the website. +// If you only read the data from the serial port, there are no hangups. +/* ============================================ +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. +=============================================== +*/ +#include +// 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_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 +#include "Wire.h" +#include "avr/wdt.h"// Watchdog library + +// 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; +//MPU6050 mpu(0x69); // <-- use for AD0 high + +// MAC address from Ethernet shield sticker under board +byte mac[] = { + 0x90, 0xA2, 0xDA, 0x10, 0x26, 0x82 +}; +// assign an IP address for the controller: +IPAddress ip(192,168,1,50); +// the router's gateway address: +byte gateway[] = { 192, 168, 1, 1 }; +// the subnet: +byte subnet[] = { 255, 255, 0, 0 }; + +// Initialize the Ethernet server library +// with the IP address and port you want to use +// (port 80 is default for HTTP): +EthernetServer server(80); + +String HTTP_req; // stores the HTTP request + +/* ========================================================================= + NOTE: In addition to connection 3.3v, GND, SDA, and SCL, this sketch + depends on the MPU-6050's INT pin being connected to the Arduino's + external interrupt #0 pin. On the Arduino Uno and Mega 2560, this is + digital I/O pin 2. + * ========================================================================= */ + +/* ========================================================================= + NOTE: Arduino v1.0.1 with the Leonardo board generates a compile error + when using Serial.write(buf, len). The Teapot output uses this method. + The solution requires a modification to the Arduino USBAPI.h file, which + is fortunately simple, but annoying. This will be fixed in the next IDE + release. For more info, see these links: + + http://arduino.cc/forum/index.php/topic,109987.0.html + http://code.google.com/p/arduino/issues/detail?id=958 + * ========================================================================= */ + + +// uncomment "OUTPUT_READABLE_QUATERNION" if you want to see the actual +// quaternion components in a [w, x, y, z] format (not best for parsing +// on a remote host such as Processing or something though) +//#define OUTPUT_READABLE_QUATERNION + +// uncomment "OUTPUT_READABLE_EULER" if you want to see Euler angles +// (in degrees) calculated from the quaternions coming from the FIFO. +// Note that Euler angles suffer from gimbal lock (for more info, see +// http://en.wikipedia.org/wiki/Gimbal_lock) +//#define OUTPUT_READABLE_EULER + +// uncomment "OUTPUT_READABLE_YAWPITCHROLL" if you want to see the yaw/ +// pitch/roll angles (in degrees) calculated from the quaternions coming +// from the FIFO. Note this also requires gravity vector calculations. +// Also note that yaw/pitch/roll angles suffer from gimbal lock (for +// more info, see: http://en.wikipedia.org/wiki/Gimbal_lock) +#define OUTPUT_READABLE_YAWPITCHROLL + +// uncomment "OUTPUT_READABLE_REALACCEL" if you want to see acceleration +// components with gravity removed. This acceleration reference frame is +// not compensated for orientation, so +X is always +X according to the +// sensor, just without the effects of gravity. If you want acceleration +// compensated for orientation, us OUTPUT_READABLE_WORLDACCEL instead. +//#define OUTPUT_READABLE_REALACCEL + +// uncomment "OUTPUT_READABLE_WORLDACCEL" if you want to see acceleration +// components with gravity removed and adjusted for the world frame of +// reference (yaw is relative to initial orientation, since no magnetometer +// is present in this case). Could be quite handy in some cases. +//#define OUTPUT_READABLE_WORLDACCEL + +// uncomment "OUTPUT_TEAPOT" if you want output that matches the +// format used for the InvenSense teapot demo +//#define OUTPUT_TEAPOT + +#define INTERRUPT_PIN 2 // use pin 2 on Arduino Uno & most boards +#define LED_PIN 13 // (Arduino is 13, Teensy is 11, Teensy++ is 6) +bool blinkState = false; + +// 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 + +// orientation/motion vars +Quaternion q; // [w, x, y, z] quaternion container +VectorInt16 aa; // [x, y, z] accel sensor measurements +VectorInt16 aaReal; // [x, y, z] gravity-free accel sensor measurements +VectorInt16 aaWorld; // [x, y, z] world-frame accel sensor measurements +VectorFloat gravity; // [x, y, z] gravity vector +float euler[3]; // [psi, theta, phi] Euler angle container +float ypr[3]; // [yaw, pitch, roll] yaw/pitch/roll container and gravity vector + +// packet structure for InvenSense teapot demo +uint8_t teapotPacket[14] = { '$', 0x02, 0,0, 0,0, 0,0, 0,0, 0x00, 0x00, '\r', '\n' }; + + + +// ================================================================ +// === INTERRUPT DETECTION ROUTINE === +// ================================================================ + +volatile bool mpuInterrupt = false; // indicates whether MPU interrupt pin has gone high +void dmpDataReady() { + mpuInterrupt = true; +} +// ================================================================ +// === INITIAL SETUP === +// ================================================================ + +void setup() { + wdt_enable(WDTO_1S); //Watchdog enable. + //WDTO_1S sets the watchdog timer to 1 second. The time set here is approximate. + // You can find more time settings at http://www.nongnu.org/avr-libc/user-manual/group__avr__watchdog.html . + + // join I2C bus (I2Cdev library doesn't do this automatically) + #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE + Wire.begin(); + Wire.setClock(400000); // 400kHz I2C clock (200kHz if CPU is 8MHz). Comment this line if having compilation difficulties + #elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE + Fastwire::setup(400, true); + #endif + + // 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); + // 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. + + Ethernet.begin(mac, ip, gateway, subnet); + server.begin(); + Serial.print("server is at "); + Serial.println(Ethernet.localIP()); + while (!Serial); // wait for Leonardo enumeration, others continue immediately + + // initialize device + Serial.println(F("Initializing I2C devices...")); + mpu.initialize(); + pinMode(INTERRUPT_PIN, INPUT); + + // verify connection + Serial.println(F("Testing device connections...")); + Serial.println(mpu.testConnection() ? F("MPU6050 connection successful") : F("MPU6050 connection failed")); + + // 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(220); + mpu.setYGyroOffset(76); + mpu.setZGyroOffset(-85); + mpu.setZAccelOffset(1788); // 1688 factory default for my test chip + + // 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(digitalPinToInterrupt(INTERRUPT_PIN), 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 { + // 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(")")); + return; + } + + // configure LED for output + pinMode(LED_PIN, OUTPUT); +} + + + +// ================================================================ +// === MAIN PROGRAM LOOP === +// ================================================================ + +void loop() { + // if programming failed, don't try to do anything + if (!dmpReady) return; + wdt_reset();//Resets the watchdog timer. If the timer is not reset, and the timer expires, a watchdog-initiated device reset will occur. + // 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) { + // wait for correct available data length, should be a VERY short wait + while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount(); + + // read a packet from FIFO, then clear the buffer + mpu.getFIFOBytes(fifoBuffer, packetSize); + //mpu.resetFIFO(); + + // track FIFO count here in case there is > 1 packet available + // (this lets us immediately read more without waiting for an interrupt) + fifoCount -= packetSize; + + #ifdef OUTPUT_READABLE_QUATERNION + // display quaternion values in easy matrix form: w x y z + mpu.dmpGetQuaternion(&q, fifoBuffer); + Serial.print("quat\t"); + Serial.print(q.w); + Serial.print("\t"); + Serial.print(q.x); + Serial.print("\t"); + Serial.print(q.y); + Serial.print("\t"); + Serial.println(q.z); + #endif + #ifdef OUTPUT_READABLE_EULER + // display Euler angles in degrees + mpu.dmpGetQuaternion(&q, fifoBuffer); + mpu.dmpGetEuler(euler, &q); + Serial.print("euler\t"); + Serial.print(euler[0] * 180/M_PI); + Serial.print("\t"); + Serial.print(euler[1] * 180/M_PI); + Serial.print("\t"); + Serial.println(euler[2] * 180/M_PI); + #endif + #ifdef OUTPUT_READABLE_YAWPITCHROLL + // display Euler angles in degrees + mpu.dmpGetQuaternion(&q, fifoBuffer); + mpu.dmpGetGravity(&gravity, &q); + mpu.dmpGetYawPitchRoll(ypr, &q, &gravity); + Serial.print("ypr\t"); + Serial.print(ypr[0] * 180/M_PI); + Serial.print("\t"); + Serial.print(ypr[1] * 180/M_PI); + Serial.print("\t"); + Serial.println(ypr[2] * 180/M_PI); + #endif + #ifdef OUTPUT_READABLE_REALACCEL + // display real acceleration, adjusted to remove gravity + mpu.dmpGetQuaternion(&q, fifoBuffer); + mpu.dmpGetAccel(&aa, fifoBuffer); + mpu.dmpGetGravity(&gravity, &q); + mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity); + Serial.print("areal\t"); + Serial.print(aaReal.x); + Serial.print("\t"); + Serial.print(aaReal.y); + Serial.print("\t"); + Serial.println(aaReal.z); + #endif + #ifdef OUTPUT_READABLE_WORLDACCEL + // display initial world-frame acceleration, adjusted to remove gravity + // and rotated based on known orientation from quaternion + mpu.dmpGetQuaternion(&q, fifoBuffer); + mpu.dmpGetAccel(&aa, fifoBuffer); + mpu.dmpGetGravity(&gravity, &q); + mpu.dmpGetLinearAccel(&aaReal, &aa, &gravity); + mpu.dmpGetLinearAccelInWorld(&aaWorld, &aaReal, &q); + Serial.print("aworld\t"); + Serial.print(aaWorld.x); + Serial.print("\t"); + Serial.print(aaWorld.y); + Serial.print("\t"); + Serial.println(aaWorld.z); + #endif + #ifdef OUTPUT_TEAPOT + // display quaternion values in InvenSense Teapot demo format: + teapotPacket[2] = fifoBuffer[0]; + teapotPacket[3] = fifoBuffer[1]; + teapotPacket[4] = fifoBuffer[4]; + teapotPacket[5] = fifoBuffer[5]; + teapotPacket[6] = fifoBuffer[8]; + teapotPacket[7] = fifoBuffer[9]; + teapotPacket[8] = fifoBuffer[12]; + teapotPacket[9] = fifoBuffer[13]; + Serial.write(teapotPacket, 14); + teapotPacket[11]++; // packetCount, loops at 0xFF on purpose + #endif + serversend(); + // blink LED to indicate activity + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); + } +} + +void serversend(){ + + EthernetClient client = server.available(); // try to get client + + if (client) { // got client? + //boolean currentLineIsBlank = true; + while (client.connected()) { + if (client.available()) { // client data available to read + char c = client.read(); // read 1 byte (character) from client + HTTP_req += c; // save the HTTP request 1 char at a time + // last line of client request is blank and ends with \n + // respond to client only after last line received + if (c == '\n') { + // send a standard http response header + client.println("HTTP/1.1 200 OK"); + client.println("Content-Type: text/html"); + //client.println("Connection: keep-alive"); + client.println(); + // AJAX request for switch state + if (HTTP_req.indexOf("ajax_switch") > -1) { + // read switch state and analog input + GetAjaxData(client); + } + else { // HTTP request for web page + // send web page - contains JavaScript with AJAX calls + client.println(""); + client.println(""); + client.println(""); + client.println("Arduino Web Page"); + client.println(""); + client.println(""); + client.println(""); + client.println("

MPU6050 Output

"); + client.println("
"); + client.println("
"); + client.println(""); + client.println(""); + } + // display received HTTP request on serial port + Serial.print(HTTP_req); + HTTP_req = ""; // finished with request, empty string + client.stop(); // close the connection + break; + } + } + } + } +} + +void GetAjaxData(EthernetClient cl) +{ + #ifdef OUTPUT_READABLE_QUATERNION + // display quaternion values in easy matrix form: w x y z + cl.print("Quaternion Values:\t"); + cl.print("

w:"); + cl.print(q.w); + cl.print("\t"); + cl.println("

"); + cl.print("

x:"); + cl.print(q.x); + cl.print("\t"); + cl.println("

"); + cl.print("

y:"); + cl.print(q.y); + cl.print("\t"); + cl.println("

"); + cl.print("

z:"); + cl.print(q.z); + cl.print("\t"); + cl.println("

"); + #endif + #ifdef OUTPUT_READABLE_EULER + // display Euler angles in degrees + cl.print("Euler Angles:\t"); + cl.print("

Yaw:"); + cl.print(euler[0] * 180/M_PI); + cl.print("\t"); + cl.println("

"); + cl.print("

Pitch:"); + cl.print(euler[2] * 180/M_PI); + cl.print("\t"); + cl.println("

"); + cl.print("

Roll:"); + cl.print(euler[1] * 180/M_PI); + cl.print("\t"); + cl.println("

"); + #endif + #ifdef OUTPUT_READABLE_YAWPITCHROLL + // display Yaw/Pitch/Roll values in degrees + cl.print("Yaw, Pitch, and Roll:\t"); + cl.print("

Yaw:"); + cl.print(ypr[0] * 180/M_PI); + cl.print("\t"); + cl.println("

"); + cl.print("

Pitch:"); + cl.print(ypr[2] * 180/M_PI); + cl.print("\t"); + cl.println("

"); + cl.print("

Roll:"); + cl.print(ypr[1] * 180/M_PI); + cl.print("\t"); + cl.println("

"); + #endif + #ifdef OUTPUT_READABLE_REALACCEL + // display real acceleration, adjusted to remove gravity + cl.print("Real Accel:\t"); + cl.print("

Yaw:"); + cl.print(aaReal.x); + cl.print("\t"); + cl.println("

"); + cl.print("

Pitch:"); + cl.print(aaReal.z); + cl.print("\t"); + cl.println("

"); + cl.print("

Roll:"); + cl.print(aaReal.y); + cl.print("\t"); + cl.println("

"); + #endif + #ifdef OUTPUT_READABLE_WORLDACCEL + // display initial world-frame acceleration, adjusted to remove gravity + // and rotated based on known orientation from quaternion + cl.print("World Accel:\t"); + cl.print("

Yaw:"); + cl.print(aaWorld.x); + cl.print("\t"); + cl.println("

"); + cl.print("

Pitch:"); + cl.print(aaWorld.z); + cl.print("\t"); + cl.println("

"); + cl.print("

Roll:"); + cl.print(aaWorld.y); + cl.print("\t"); + cl.println("

"); + #endif + #ifdef OUTPUT_TEAPOT + cl.print("

teapotpacket:"); + cl.write(teapotPacket, 14); + cl.print("\t"); + cl.println("

"); + #endif +} diff --git a/libraries/MPU6050/examples/MPU6050_raw/MPU6050_raw.ino b/libraries/MPU6050/examples/MPU6050_raw/MPU6050_raw.ino new file mode 100644 index 0000000..28418a9 --- /dev/null +++ b/libraries/MPU6050/examples/MPU6050_raw/MPU6050_raw.ino @@ -0,0 +1,151 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class +// 10/7/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2013-05-08 - added multiple output formats +// - added seamless Fastwire support +// 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. +=============================================== +*/ + +// 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" + +// 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 InvenSense evaluation board) +// AD0 high = 0x69 +MPU6050 accelgyro; +//MPU6050 accelgyro(0x69); // <-- use for AD0 high + +int16_t ax, ay, az; +int16_t gx, gy, gz; + + + +// uncomment "OUTPUT_READABLE_ACCELGYRO" if you want to see a tab-separated +// list of the accel X/Y/Z and then gyro X/Y/Z values in decimal. Easy to read, +// not so easy to parse, and slow(er) over UART. +#define OUTPUT_READABLE_ACCELGYRO + +// uncomment "OUTPUT_BINARY_ACCELGYRO" to send all 6 axes of data as 16-bit +// binary, one right after the other. This is very fast (as fast as possible +// without compression or data loss), and easy to parse, but impossible to read +// for a human. +//#define OUTPUT_BINARY_ACCELGYRO + + +#define LED_PIN 13 +bool blinkState = false; + +void setup() { + // join I2C bus (I2Cdev library doesn't do this automatically) + #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE + Wire.begin(); + #elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE + Fastwire::setup(400, true); + #endif + + // 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(); + + // verify connection + Serial.println("Testing device connections..."); + Serial.println(accelgyro.testConnection() ? "MPU6050 connection successful" : "MPU6050 connection failed"); + + // use the code below to change accel/gyro offset values + /* + Serial.println("Updating internal sensor offsets..."); + // -76 -2359 1688 0 0 0 + Serial.print(accelgyro.getXAccelOffset()); Serial.print("\t"); // -76 + Serial.print(accelgyro.getYAccelOffset()); Serial.print("\t"); // -2359 + Serial.print(accelgyro.getZAccelOffset()); Serial.print("\t"); // 1688 + Serial.print(accelgyro.getXGyroOffset()); Serial.print("\t"); // 0 + Serial.print(accelgyro.getYGyroOffset()); Serial.print("\t"); // 0 + Serial.print(accelgyro.getZGyroOffset()); Serial.print("\t"); // 0 + Serial.print("\n"); + accelgyro.setXGyroOffset(220); + accelgyro.setYGyroOffset(76); + accelgyro.setZGyroOffset(-85); + Serial.print(accelgyro.getXAccelOffset()); Serial.print("\t"); // -76 + Serial.print(accelgyro.getYAccelOffset()); Serial.print("\t"); // -2359 + Serial.print(accelgyro.getZAccelOffset()); Serial.print("\t"); // 1688 + Serial.print(accelgyro.getXGyroOffset()); Serial.print("\t"); // 0 + Serial.print(accelgyro.getYGyroOffset()); Serial.print("\t"); // 0 + Serial.print(accelgyro.getZGyroOffset()); Serial.print("\t"); // 0 + Serial.print("\n"); + */ + + // configure Arduino LED for + pinMode(LED_PIN, OUTPUT); +} + +void loop() { + // read raw accel/gyro measurements from device + accelgyro.getMotion6(&ax, &ay, &az, &gx, &gy, &gz); + + // these methods (and a few others) are also available + //accelgyro.getAcceleration(&ax, &ay, &az); + //accelgyro.getRotation(&gx, &gy, &gz); + + #ifdef OUTPUT_READABLE_ACCELGYRO + // display tab-separated accel/gyro x/y/z values + Serial.print("a/g:\t"); + Serial.print(ax); Serial.print("\t"); + Serial.print(ay); Serial.print("\t"); + Serial.print(az); Serial.print("\t"); + Serial.print(gx); Serial.print("\t"); + Serial.print(gy); Serial.print("\t"); + Serial.println(gz); + #endif + + #ifdef OUTPUT_BINARY_ACCELGYRO + Serial.write((uint8_t)(ax >> 8)); Serial.write((uint8_t)(ax & 0xFF)); + Serial.write((uint8_t)(ay >> 8)); Serial.write((uint8_t)(ay & 0xFF)); + Serial.write((uint8_t)(az >> 8)); Serial.write((uint8_t)(az & 0xFF)); + Serial.write((uint8_t)(gx >> 8)); Serial.write((uint8_t)(gx & 0xFF)); + Serial.write((uint8_t)(gy >> 8)); Serial.write((uint8_t)(gy & 0xFF)); + Serial.write((uint8_t)(gz >> 8)); Serial.write((uint8_t)(gz & 0xFF)); + #endif + + // blink LED to indicate activity + blinkState = !blinkState; + digitalWrite(LED_PIN, blinkState); +} diff --git a/libraries/MPU6050/helper_3dmath.h b/libraries/MPU6050/helper_3dmath.h new file mode 100644 index 0000000..9ed260e --- /dev/null +++ b/libraries/MPU6050/helper_3dmath.h @@ -0,0 +1,216 @@ +// I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class, 3D math helper +// 6/5/2012 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// 2012-06-05 - add 3D math helper file to DMP6 example sketch + +/* ============================================ +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. +=============================================== +*/ + +#ifndef _HELPER_3DMATH_H_ +#define _HELPER_3DMATH_H_ + +class Quaternion { + public: + float w; + float x; + float y; + float z; + + Quaternion() { + w = 1.0f; + x = 0.0f; + y = 0.0f; + z = 0.0f; + } + + Quaternion(float nw, float nx, float ny, float nz) { + w = nw; + x = nx; + y = ny; + z = nz; + } + + Quaternion getProduct(Quaternion q) { + // Quaternion multiplication is defined by: + // (Q1 * Q2).w = (w1w2 - x1x2 - y1y2 - z1z2) + // (Q1 * Q2).x = (w1x2 + x1w2 + y1z2 - z1y2) + // (Q1 * Q2).y = (w1y2 - x1z2 + y1w2 + z1x2) + // (Q1 * Q2).z = (w1z2 + x1y2 - y1x2 + z1w2 + return Quaternion( + w*q.w - x*q.x - y*q.y - z*q.z, // new w + w*q.x + x*q.w + y*q.z - z*q.y, // new x + w*q.y - x*q.z + y*q.w + z*q.x, // new y + w*q.z + x*q.y - y*q.x + z*q.w); // new z + } + + Quaternion getConjugate() { + return Quaternion(w, -x, -y, -z); + } + + float getMagnitude() { + return sqrt(w*w + x*x + y*y + z*z); + } + + void normalize() { + float m = getMagnitude(); + w /= m; + x /= m; + y /= m; + z /= m; + } + + Quaternion getNormalized() { + Quaternion r(w, x, y, z); + r.normalize(); + return r; + } +}; + +class VectorInt16 { + public: + int16_t x; + int16_t y; + int16_t z; + + VectorInt16() { + x = 0; + y = 0; + z = 0; + } + + VectorInt16(int16_t nx, int16_t ny, int16_t nz) { + x = nx; + y = ny; + z = nz; + } + + float getMagnitude() { + return sqrt(x*x + y*y + z*z); + } + + void normalize() { + float m = getMagnitude(); + x /= m; + y /= m; + z /= m; + } + + VectorInt16 getNormalized() { + VectorInt16 r(x, y, z); + r.normalize(); + return r; + } + + void rotate(Quaternion *q) { + // http://www.cprogramming.com/tutorial/3d/quaternions.html + // http://www.euclideanspace.com/maths/algebra/realNormedAlgebra/quaternions/transforms/index.htm + // http://content.gpwiki.org/index.php/OpenGL:Tutorials:Using_Quaternions_to_represent_rotation + // ^ or: http://webcache.googleusercontent.com/search?q=cache:xgJAp3bDNhQJ:content.gpwiki.org/index.php/OpenGL:Tutorials:Using_Quaternions_to_represent_rotation&hl=en&gl=us&strip=1 + + // P_out = q * P_in * conj(q) + // - P_out is the output vector + // - q is the orientation quaternion + // - P_in is the input vector (a*aReal) + // - conj(q) is the conjugate of the orientation quaternion (q=[w,x,y,z], q*=[w,-x,-y,-z]) + Quaternion p(0, x, y, z); + + // quaternion multiplication: q * p, stored back in p + p = q -> getProduct(p); + + // quaternion multiplication: p * conj(q), stored back in p + p = p.getProduct(q -> getConjugate()); + + // p quaternion is now [0, x', y', z'] + x = p.x; + y = p.y; + z = p.z; + } + + VectorInt16 getRotated(Quaternion *q) { + VectorInt16 r(x, y, z); + r.rotate(q); + return r; + } +}; + +class VectorFloat { + public: + float x; + float y; + float z; + + VectorFloat() { + x = 0; + y = 0; + z = 0; + } + + VectorFloat(float nx, float ny, float nz) { + x = nx; + y = ny; + z = nz; + } + + float getMagnitude() { + return sqrt(x*x + y*y + z*z); + } + + void normalize() { + float m = getMagnitude(); + x /= m; + y /= m; + z /= m; + } + + VectorFloat getNormalized() { + VectorFloat r(x, y, z); + r.normalize(); + return r; + } + + void rotate(Quaternion *q) { + Quaternion p(0, x, y, z); + + // quaternion multiplication: q * p, stored back in p + p = q -> getProduct(p); + + // quaternion multiplication: p * conj(q), stored back in p + p = p.getProduct(q -> getConjugate()); + + // p quaternion is now [0, x', y', z'] + x = p.x; + y = p.y; + z = p.z; + } + + VectorFloat getRotated(Quaternion *q) { + VectorFloat r(x, y, z); + r.rotate(q); + return r; + } +}; + +#endif /* _HELPER_3DMATH_H_ */ \ No newline at end of file diff --git a/libraries/MPU6050/library.json b/libraries/MPU6050/library.json new file mode 100644 index 0000000..174b452 --- /dev/null +++ b/libraries/MPU6050/library.json @@ -0,0 +1,18 @@ +{ + "name": "I2Cdevlib-MPU6050", + "keywords": "gyroscope, accelerometer, sensor, i2cdevlib, i2c", + "description": "The MPU6050 combines a 3-axis gyroscope and a 3-axis accelerometer on the same silicon die together with an onboard Digital Motion Processor(DMP) which processes complex 6-axis MotionFusion algorithms", + "include": "Arduino/MPU6050", + "repository": + { + "type": "git", + "url": "https://github.com/jrowberg/i2cdevlib.git" + }, + "dependencies": + { + "name": "I2Cdevlib-Core", + "frameworks": "arduino" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/MPU9150/MPU9150.cpp b/libraries/MPU9150/MPU9150.cpp new file mode 100644 index 0000000..cffcc09 --- /dev/null +++ b/libraries/MPU9150/MPU9150.cpp @@ -0,0 +1,3156 @@ +// I2Cdev library collection - MPU9150 I2C device class +// Based on InvenSense MPU-9150 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00) +// 8/24/2011 by Jeff Rowberg +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// ... - ongoing debug release + +// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE +// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF +// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING. + +/* ============================================ +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. +=============================================== +*/ + +#include "MPU9150.h" + +/** Default constructor, uses default I2C address. + * @see MPU9150_DEFAULT_ADDRESS + */ +MPU9150::MPU9150() { + devAddr = MPU9150_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see MPU9150_DEFAULT_ADDRESS + * @see MPU9150_ADDRESS_AD0_LOW + * @see MPU9150_ADDRESS_AD0_HIGH + */ +MPU9150::MPU9150(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + * This will activate the device and take it out of sleep mode (which must be done + * after start-up). This function also sets both the accelerometer and the gyroscope + * to their most sensitive settings, namely +/- 2g and +/- 250 degrees/sec, and sets + * the clock source to use the X Gyro for reference, which is slightly better than + * the default internal clock source. + */ +void MPU9150::initialize() { + setClockSource(MPU9150_CLOCK_PLL_XGYRO); + setFullScaleGyroRange(MPU9150_GYRO_FS_250); + setFullScaleAccelRange(MPU9150_ACCEL_FS_2); + setSleepEnabled(false); // thanks to Jack Elston for pointing this one out! +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool MPU9150::testConnection() { + return getDeviceID() == 0x34; +} + +// AUX_VDDIO register (InvenSense demo code calls this RA_*G_OFFS_TC) + +/** Get the auxiliary I2C supply voltage level. + * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to + * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to + * the MPU-6000, which does not have a VLOGIC pin. + * @return I2C supply voltage level (0=VLOGIC, 1=VDD) + */ +uint8_t MPU9150::getAuxVDDIOLevel() { + I2Cdev::readBit(devAddr, MPU9150_RA_YG_OFFS_TC, MPU9150_TC_PWR_MODE_BIT, buffer); + return buffer[0]; +} +/** Set the auxiliary I2C supply voltage level. + * When set to 1, the auxiliary I2C bus high logic level is VDD. When cleared to + * 0, the auxiliary I2C bus high logic level is VLOGIC. This does not apply to + * the MPU-6000, which does not have a VLOGIC pin. + * @param level I2C supply voltage level (0=VLOGIC, 1=VDD) + */ +void MPU9150::setAuxVDDIOLevel(uint8_t level) { + I2Cdev::writeBit(devAddr, MPU9150_RA_YG_OFFS_TC, MPU9150_TC_PWR_MODE_BIT, level); +} + +// SMPLRT_DIV register + +/** Get gyroscope output rate divider. + * The sensor register output, FIFO output, DMP sampling, Motion detection, Zero + * Motion detection, and Free Fall detection are all based on the Sample Rate. + * The Sample Rate is generated by dividing the gyroscope output rate by + * SMPLRT_DIV: + * + * Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV) + * + * where Gyroscope Output Rate = 8kHz when the DLPF is disabled (DLPF_CFG = 0 or + * 7), and 1kHz when the DLPF is enabled (see Register 26). + * + * Note: The accelerometer output rate is 1kHz. This means that for a Sample + * Rate greater than 1kHz, the same accelerometer sample may be output to the + * FIFO, DMP, and sensor registers more than once. + * + * For a diagram of the gyroscope and accelerometer signal paths, see Section 8 + * of the MPU-6000/MPU-9150 Product Specification document. + * + * @return Current sample rate + * @see MPU9150_RA_SMPLRT_DIV + */ +uint8_t MPU9150::getRate() { + I2Cdev::readByte(devAddr, MPU9150_RA_SMPLRT_DIV, buffer); + return buffer[0]; +} +/** Set gyroscope sample rate divider. + * @param rate New sample rate divider + * @see getRate() + * @see MPU9150_RA_SMPLRT_DIV + */ +void MPU9150::setRate(uint8_t rate) { + I2Cdev::writeByte(devAddr, MPU9150_RA_SMPLRT_DIV, rate); +} + +// CONFIG register + +/** Get external FSYNC configuration. + * Configures the external Frame Synchronization (FSYNC) pin sampling. An + * external signal connected to the FSYNC pin can be sampled by configuring + * EXT_SYNC_SET. Signal changes to the FSYNC pin are latched so that short + * strobes may be captured. The latched FSYNC signal will be sampled at the + * Sampling Rate, as defined in register 25. After sampling, the latch will + * reset to the current FSYNC signal state. + * + * The sampled value will be reported in place of the least significant bit in + * a sensor data register determined by the value of EXT_SYNC_SET according to + * the following table. + * + *
+ * EXT_SYNC_SET | FSYNC Bit Location
+ * -------------+-------------------
+ * 0            | Input disabled
+ * 1            | TEMP_OUT_L[0]
+ * 2            | GYRO_XOUT_L[0]
+ * 3            | GYRO_YOUT_L[0]
+ * 4            | GYRO_ZOUT_L[0]
+ * 5            | ACCEL_XOUT_L[0]
+ * 6            | ACCEL_YOUT_L[0]
+ * 7            | ACCEL_ZOUT_L[0]
+ * 
+ * + * @return FSYNC configuration value + */ +uint8_t MPU9150::getExternalFrameSync() { + I2Cdev::readBits(devAddr, MPU9150_RA_CONFIG, MPU9150_CFG_EXT_SYNC_SET_BIT, MPU9150_CFG_EXT_SYNC_SET_LENGTH, buffer); + return buffer[0]; +} +/** Set external FSYNC configuration. + * @see getExternalFrameSync() + * @see MPU9150_RA_CONFIG + * @param sync New FSYNC configuration value + */ +void MPU9150::setExternalFrameSync(uint8_t sync) { + I2Cdev::writeBits(devAddr, MPU9150_RA_CONFIG, MPU9150_CFG_EXT_SYNC_SET_BIT, MPU9150_CFG_EXT_SYNC_SET_LENGTH, sync); +} +/** Get digital low-pass filter configuration. + * The DLPF_CFG parameter sets the digital low pass filter configuration. It + * also determines the internal sampling rate used by the device as shown in + * the table below. + * + * Note: The accelerometer output rate is 1kHz. This means that for a Sample + * Rate greater than 1kHz, the same accelerometer sample may be output to the + * FIFO, DMP, and sensor registers more than once. + * + *
+ *          |   ACCELEROMETER    |           GYROSCOPE
+ * DLPF_CFG | Bandwidth | Delay  | Bandwidth | Delay  | Sample Rate
+ * ---------+-----------+--------+-----------+--------+-------------
+ * 0        | 260Hz     | 0ms    | 256Hz     | 0.98ms | 8kHz
+ * 1        | 184Hz     | 2.0ms  | 188Hz     | 1.9ms  | 1kHz
+ * 2        | 94Hz      | 3.0ms  | 98Hz      | 2.8ms  | 1kHz
+ * 3        | 44Hz      | 4.9ms  | 42Hz      | 4.8ms  | 1kHz
+ * 4        | 21Hz      | 8.5ms  | 20Hz      | 8.3ms  | 1kHz
+ * 5        | 10Hz      | 13.8ms | 10Hz      | 13.4ms | 1kHz
+ * 6        | 5Hz       | 19.0ms | 5Hz       | 18.6ms | 1kHz
+ * 7        |   -- Reserved --   |   -- Reserved --   | Reserved
+ * 
+ * + * @return DLFP configuration + * @see MPU9150_RA_CONFIG + * @see MPU9150_CFG_DLPF_CFG_BIT + * @see MPU9150_CFG_DLPF_CFG_LENGTH + */ +uint8_t MPU9150::getDLPFMode() { + I2Cdev::readBits(devAddr, MPU9150_RA_CONFIG, MPU9150_CFG_DLPF_CFG_BIT, MPU9150_CFG_DLPF_CFG_LENGTH, buffer); + return buffer[0]; +} +/** Set digital low-pass filter configuration. + * @param mode New DLFP configuration setting + * @see getDLPFBandwidth() + * @see MPU9150_DLPF_BW_256 + * @see MPU9150_RA_CONFIG + * @see MPU9150_CFG_DLPF_CFG_BIT + * @see MPU9150_CFG_DLPF_CFG_LENGTH + */ +void MPU9150::setDLPFMode(uint8_t mode) { + I2Cdev::writeBits(devAddr, MPU9150_RA_CONFIG, MPU9150_CFG_DLPF_CFG_BIT, MPU9150_CFG_DLPF_CFG_LENGTH, mode); +} + +// GYRO_CONFIG register + +/** Get full-scale gyroscope range. + * The FS_SEL parameter allows setting the full-scale range of the gyro sensors, + * as described in the table below. + * + *
+ * 0 = +/- 250 degrees/sec
+ * 1 = +/- 500 degrees/sec
+ * 2 = +/- 1000 degrees/sec
+ * 3 = +/- 2000 degrees/sec
+ * 
+ * + * @return Current full-scale gyroscope range setting + * @see MPU9150_GYRO_FS_250 + * @see MPU9150_RA_GYRO_CONFIG + * @see MPU9150_GCONFIG_FS_SEL_BIT + * @see MPU9150_GCONFIG_FS_SEL_LENGTH + */ +uint8_t MPU9150::getFullScaleGyroRange() { + I2Cdev::readBits(devAddr, MPU9150_RA_GYRO_CONFIG, MPU9150_GCONFIG_FS_SEL_BIT, MPU9150_GCONFIG_FS_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set full-scale gyroscope range. + * @param range New full-scale gyroscope range value + * @see getFullScaleRange() + * @see MPU9150_GYRO_FS_250 + * @see MPU9150_RA_GYRO_CONFIG + * @see MPU9150_GCONFIG_FS_SEL_BIT + * @see MPU9150_GCONFIG_FS_SEL_LENGTH + */ +void MPU9150::setFullScaleGyroRange(uint8_t range) { + I2Cdev::writeBits(devAddr, MPU9150_RA_GYRO_CONFIG, MPU9150_GCONFIG_FS_SEL_BIT, MPU9150_GCONFIG_FS_SEL_LENGTH, range); +} + +// ACCEL_CONFIG register + +/** Get self-test enabled setting for accelerometer X axis. + * @return Self-test enabled value + * @see MPU9150_RA_ACCEL_CONFIG + */ +bool MPU9150::getAccelXSelfTest() { + I2Cdev::readBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_XA_ST_BIT, buffer); + return buffer[0]; +} +/** Get self-test enabled setting for accelerometer X axis. + * @param enabled Self-test enabled value + * @see MPU9150_RA_ACCEL_CONFIG + */ +void MPU9150::setAccelXSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_XA_ST_BIT, enabled); +} +/** Get self-test enabled value for accelerometer Y axis. + * @return Self-test enabled value + * @see MPU9150_RA_ACCEL_CONFIG + */ +bool MPU9150::getAccelYSelfTest() { + I2Cdev::readBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_YA_ST_BIT, buffer); + return buffer[0]; +} +/** Get self-test enabled value for accelerometer Y axis. + * @param enabled Self-test enabled value + * @see MPU9150_RA_ACCEL_CONFIG + */ +void MPU9150::setAccelYSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_YA_ST_BIT, enabled); +} +/** Get self-test enabled value for accelerometer Z axis. + * @return Self-test enabled value + * @see MPU9150_RA_ACCEL_CONFIG + */ +bool MPU9150::getAccelZSelfTest() { + I2Cdev::readBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_ZA_ST_BIT, buffer); + return buffer[0]; +} +/** Set self-test enabled value for accelerometer Z axis. + * @param enabled Self-test enabled value + * @see MPU9150_RA_ACCEL_CONFIG + */ +void MPU9150::setAccelZSelfTest(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_ZA_ST_BIT, enabled); +} +/** Get full-scale accelerometer range. + * The FS_SEL parameter allows setting the full-scale range of the accelerometer + * sensors, as described in the table below. + * + *
+ * 0 = +/- 2g
+ * 1 = +/- 4g
+ * 2 = +/- 8g
+ * 3 = +/- 16g
+ * 
+ * + * @return Current full-scale accelerometer range setting + * @see MPU9150_ACCEL_FS_2 + * @see MPU9150_RA_ACCEL_CONFIG + * @see MPU9150_ACONFIG_AFS_SEL_BIT + * @see MPU9150_ACONFIG_AFS_SEL_LENGTH + */ +uint8_t MPU9150::getFullScaleAccelRange() { + I2Cdev::readBits(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_AFS_SEL_BIT, MPU9150_ACONFIG_AFS_SEL_LENGTH, buffer); + return buffer[0]; +} +/** Set full-scale accelerometer range. + * @param range New full-scale accelerometer range setting + * @see getFullScaleAccelRange() + */ +void MPU9150::setFullScaleAccelRange(uint8_t range) { + I2Cdev::writeBits(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_AFS_SEL_BIT, MPU9150_ACONFIG_AFS_SEL_LENGTH, range); +} +/** Get the high-pass filter configuration. + * The DHPF is a filter module in the path leading to motion detectors (Free + * Fall, Motion threshold, and Zero Motion). The high pass filter output is not + * available to the data registers (see Figure in Section 8 of the MPU-6000/ + * MPU-9150 Product Specification document). + * + * The high pass filter has three modes: + * + *
+ *    Reset: The filter output settles to zero within one sample. This
+ *           effectively disables the high pass filter. This mode may be toggled
+ *           to quickly settle the filter.
+ *
+ *    On:    The high pass filter will pass signals above the cut off frequency.
+ *
+ *    Hold:  When triggered, the filter holds the present sample. The filter
+ *           output will be the difference between the input sample and the held
+ *           sample.
+ * 
+ * + *
+ * ACCEL_HPF | Filter Mode | Cut-off Frequency
+ * ----------+-------------+------------------
+ * 0         | Reset       | None
+ * 1         | On          | 5Hz
+ * 2         | On          | 2.5Hz
+ * 3         | On          | 1.25Hz
+ * 4         | On          | 0.63Hz
+ * 7         | Hold        | None
+ * 
+ * + * @return Current high-pass filter configuration + * @see MPU9150_DHPF_RESET + * @see MPU9150_RA_ACCEL_CONFIG + */ +uint8_t MPU9150::getDHPFMode() { + I2Cdev::readBits(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_ACCEL_HPF_BIT, MPU9150_ACONFIG_ACCEL_HPF_LENGTH, buffer); + return buffer[0]; +} +/** Set the high-pass filter configuration. + * @param bandwidth New high-pass filter configuration + * @see setDHPFMode() + * @see MPU9150_DHPF_RESET + * @see MPU9150_RA_ACCEL_CONFIG + */ +void MPU9150::setDHPFMode(uint8_t bandwidth) { + I2Cdev::writeBits(devAddr, MPU9150_RA_ACCEL_CONFIG, MPU9150_ACONFIG_ACCEL_HPF_BIT, MPU9150_ACONFIG_ACCEL_HPF_LENGTH, bandwidth); +} + +// FF_THR register + +/** Get free-fall event acceleration threshold. + * This register configures the detection threshold for Free Fall event + * detection. The unit of FF_THR is 1LSB = 2mg. Free Fall is detected when the + * absolute value of the accelerometer measurements for the three axes are each + * less than the detection threshold. This condition increments the Free Fall + * duration counter (Register 30). The Free Fall interrupt is triggered when the + * Free Fall duration counter reaches the time specified in FF_DUR. + * + * For more details on the Free Fall detection interrupt, see Section 8.2 of the + * MPU-6000/MPU-9150 Product Specification document as well as Registers 56 and + * 58 of this document. + * + * @return Current free-fall acceleration threshold value (LSB = 2mg) + * @see MPU9150_RA_FF_THR + */ +uint8_t MPU9150::getFreefallDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU9150_RA_FF_THR, buffer); + return buffer[0]; +} +/** Get free-fall event acceleration threshold. + * @param threshold New free-fall acceleration threshold value (LSB = 2mg) + * @see getFreefallDetectionThreshold() + * @see MPU9150_RA_FF_THR + */ +void MPU9150::setFreefallDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU9150_RA_FF_THR, threshold); +} + +// FF_DUR register + +/** Get free-fall event duration threshold. + * This register configures the duration counter threshold for Free Fall event + * detection. The duration counter ticks at 1kHz, therefore FF_DUR has a unit + * of 1 LSB = 1 ms. + * + * The Free Fall duration counter increments while the absolute value of the + * accelerometer measurements are each less than the detection threshold + * (Register 29). The Free Fall interrupt is triggered when the Free Fall + * duration counter reaches the time specified in this register. + * + * For more details on the Free Fall detection interrupt, see Section 8.2 of + * the MPU-6000/MPU-9150 Product Specification document as well as Registers 56 + * and 58 of this document. + * + * @return Current free-fall duration threshold value (LSB = 1ms) + * @see MPU9150_RA_FF_DUR + */ +uint8_t MPU9150::getFreefallDetectionDuration() { + I2Cdev::readByte(devAddr, MPU9150_RA_FF_DUR, buffer); + return buffer[0]; +} +/** Get free-fall event duration threshold. + * @param duration New free-fall duration threshold value (LSB = 1ms) + * @see getFreefallDetectionDuration() + * @see MPU9150_RA_FF_DUR + */ +void MPU9150::setFreefallDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU9150_RA_FF_DUR, duration); +} + +// MOT_THR register + +/** Get motion detection event acceleration threshold. + * This register configures the detection threshold for Motion interrupt + * generation. The unit of MOT_THR is 1LSB = 2mg. Motion is detected when the + * absolute value of any of the accelerometer measurements exceeds this Motion + * detection threshold. This condition increments the Motion detection duration + * counter (Register 32). The Motion detection interrupt is triggered when the + * Motion Detection counter reaches the time count specified in MOT_DUR + * (Register 32). + * + * The Motion interrupt will indicate the axis and polarity of detected motion + * in MOT_DETECT_STATUS (Register 97). + * + * For more details on the Motion detection interrupt, see Section 8.3 of the + * MPU-6000/MPU-9150 Product Specification document as well as Registers 56 and + * 58 of this document. + * + * @return Current motion detection acceleration threshold value (LSB = 2mg) + * @see MPU9150_RA_MOT_THR + */ +uint8_t MPU9150::getMotionDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU9150_RA_MOT_THR, buffer); + return buffer[0]; +} +/** Set free-fall event acceleration threshold. + * @param threshold New motion detection acceleration threshold value (LSB = 2mg) + * @see getMotionDetectionThreshold() + * @see MPU9150_RA_MOT_THR + */ +void MPU9150::setMotionDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU9150_RA_MOT_THR, threshold); +} + +// MOT_DUR register + +/** Get motion detection event duration threshold. + * This register configures the duration counter threshold for Motion interrupt + * generation. The duration counter ticks at 1 kHz, therefore MOT_DUR has a unit + * of 1LSB = 1ms. The Motion detection duration counter increments when the + * absolute value of any of the accelerometer measurements exceeds the Motion + * detection threshold (Register 31). The Motion detection interrupt is + * triggered when the Motion detection counter reaches the time count specified + * in this register. + * + * For more details on the Motion detection interrupt, see Section 8.3 of the + * MPU-6000/MPU-9150 Product Specification document. + * + * @return Current motion detection duration threshold value (LSB = 1ms) + * @see MPU9150_RA_MOT_DUR + */ +uint8_t MPU9150::getMotionDetectionDuration() { + I2Cdev::readByte(devAddr, MPU9150_RA_MOT_DUR, buffer); + return buffer[0]; +} +/** Set motion detection event duration threshold. + * @param duration New motion detection duration threshold value (LSB = 1ms) + * @see getMotionDetectionDuration() + * @see MPU9150_RA_MOT_DUR + */ +void MPU9150::setMotionDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU9150_RA_MOT_DUR, duration); +} + +// ZRMOT_THR register + +/** Get zero motion detection event acceleration threshold. + * This register configures the detection threshold for Zero Motion interrupt + * generation. The unit of ZRMOT_THR is 1LSB = 2mg. Zero Motion is detected when + * the absolute value of the accelerometer measurements for the 3 axes are each + * less than the detection threshold. This condition increments the Zero Motion + * duration counter (Register 34). The Zero Motion interrupt is triggered when + * the Zero Motion duration counter reaches the time count specified in + * ZRMOT_DUR (Register 34). + * + * Unlike Free Fall or Motion detection, Zero Motion detection triggers an + * interrupt both when Zero Motion is first detected and when Zero Motion is no + * longer detected. + * + * When a zero motion event is detected, a Zero Motion Status will be indicated + * in the MOT_DETECT_STATUS register (Register 97). When a motion-to-zero-motion + * condition is detected, the status bit is set to 1. When a zero-motion-to- + * motion condition is detected, the status bit is set to 0. + * + * For more details on the Zero Motion detection interrupt, see Section 8.4 of + * the MPU-6000/MPU-9150 Product Specification document as well as Registers 56 + * and 58 of this document. + * + * @return Current zero motion detection acceleration threshold value (LSB = 2mg) + * @see MPU9150_RA_ZRMOT_THR + */ +uint8_t MPU9150::getZeroMotionDetectionThreshold() { + I2Cdev::readByte(devAddr, MPU9150_RA_ZRMOT_THR, buffer); + return buffer[0]; +} +/** Set zero motion detection event acceleration threshold. + * @param threshold New zero motion detection acceleration threshold value (LSB = 2mg) + * @see getZeroMotionDetectionThreshold() + * @see MPU9150_RA_ZRMOT_THR + */ +void MPU9150::setZeroMotionDetectionThreshold(uint8_t threshold) { + I2Cdev::writeByte(devAddr, MPU9150_RA_ZRMOT_THR, threshold); +} + +// ZRMOT_DUR register + +/** Get zero motion detection event duration threshold. + * This register configures the duration counter threshold for Zero Motion + * interrupt generation. The duration counter ticks at 16 Hz, therefore + * ZRMOT_DUR has a unit of 1 LSB = 64 ms. The Zero Motion duration counter + * increments while the absolute value of the accelerometer measurements are + * each less than the detection threshold (Register 33). The Zero Motion + * interrupt is triggered when the Zero Motion duration counter reaches the time + * count specified in this register. + * + * For more details on the Zero Motion detection interrupt, see Section 8.4 of + * the MPU-6000/MPU-9150 Product Specification document, as well as Registers 56 + * and 58 of this document. + * + * @return Current zero motion detection duration threshold value (LSB = 64ms) + * @see MPU9150_RA_ZRMOT_DUR + */ +uint8_t MPU9150::getZeroMotionDetectionDuration() { + I2Cdev::readByte(devAddr, MPU9150_RA_ZRMOT_DUR, buffer); + return buffer[0]; +} +/** Set zero motion detection event duration threshold. + * @param duration New zero motion detection duration threshold value (LSB = 1ms) + * @see getZeroMotionDetectionDuration() + * @see MPU9150_RA_ZRMOT_DUR + */ +void MPU9150::setZeroMotionDetectionDuration(uint8_t duration) { + I2Cdev::writeByte(devAddr, MPU9150_RA_ZRMOT_DUR, duration); +} + +// FIFO_EN register + +/** Get temperature FIFO enabled value. + * When set to 1, this bit enables TEMP_OUT_H and TEMP_OUT_L (Registers 65 and + * 66) to be written into the FIFO buffer. + * @return Current temperature FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getTempFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_TEMP_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set temperature FIFO enabled value. + * @param enabled New temperature FIFO enabled value + * @see getTempFIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setTempFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_TEMP_FIFO_EN_BIT, enabled); +} +/** Get gyroscope X-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_XOUT_H and GYRO_XOUT_L (Registers 67 and + * 68) to be written into the FIFO buffer. + * @return Current gyroscope X-axis FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getXGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_XG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope X-axis FIFO enabled value. + * @param enabled New gyroscope X-axis FIFO enabled value + * @see getXGyroFIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setXGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_XG_FIFO_EN_BIT, enabled); +} +/** Get gyroscope Y-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_YOUT_H and GYRO_YOUT_L (Registers 69 and + * 70) to be written into the FIFO buffer. + * @return Current gyroscope Y-axis FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getYGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_YG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope Y-axis FIFO enabled value. + * @param enabled New gyroscope Y-axis FIFO enabled value + * @see getYGyroFIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setYGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_YG_FIFO_EN_BIT, enabled); +} +/** Get gyroscope Z-axis FIFO enabled value. + * When set to 1, this bit enables GYRO_ZOUT_H and GYRO_ZOUT_L (Registers 71 and + * 72) to be written into the FIFO buffer. + * @return Current gyroscope Z-axis FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getZGyroFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_ZG_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set gyroscope Z-axis FIFO enabled value. + * @param enabled New gyroscope Z-axis FIFO enabled value + * @see getZGyroFIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setZGyroFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_ZG_FIFO_EN_BIT, enabled); +} +/** Get accelerometer FIFO enabled value. + * When set to 1, this bit enables ACCEL_XOUT_H, ACCEL_XOUT_L, ACCEL_YOUT_H, + * ACCEL_YOUT_L, ACCEL_ZOUT_H, and ACCEL_ZOUT_L (Registers 59 to 64) to be + * written into the FIFO buffer. + * @return Current accelerometer FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getAccelFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_ACCEL_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set accelerometer FIFO enabled value. + * @param enabled New accelerometer FIFO enabled value + * @see getAccelFIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setAccelFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_ACCEL_FIFO_EN_BIT, enabled); +} +/** Get Slave 2 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 2 to be written into the FIFO buffer. + * @return Current Slave 2 FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getSlave2FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV2_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 2 FIFO enabled value. + * @param enabled New Slave 2 FIFO enabled value + * @see getSlave2FIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setSlave2FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV2_FIFO_EN_BIT, enabled); +} +/** Get Slave 1 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 1 to be written into the FIFO buffer. + * @return Current Slave 1 FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getSlave1FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV1_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 1 FIFO enabled value. + * @param enabled New Slave 1 FIFO enabled value + * @see getSlave1FIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setSlave1FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV1_FIFO_EN_BIT, enabled); +} +/** Get Slave 0 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 0 to be written into the FIFO buffer. + * @return Current Slave 0 FIFO enabled value + * @see MPU9150_RA_FIFO_EN + */ +bool MPU9150::getSlave0FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV0_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 0 FIFO enabled value. + * @param enabled New Slave 0 FIFO enabled value + * @see getSlave0FIFOEnabled() + * @see MPU9150_RA_FIFO_EN + */ +void MPU9150::setSlave0FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_FIFO_EN, MPU9150_SLV0_FIFO_EN_BIT, enabled); +} + +// I2C_MST_CTRL register + +/** Get multi-master enabled value. + * Multi-master capability allows multiple I2C masters to operate on the same + * bus. In circuits where multi-master capability is required, set MULT_MST_EN + * to 1. This will increase current drawn by approximately 30uA. + * + * In circuits where multi-master capability is required, the state of the I2C + * bus must always be monitored by each separate I2C Master. Before an I2C + * Master can assume arbitration of the bus, it must first confirm that no other + * I2C Master has arbitration of the bus. When MULT_MST_EN is set to 1, the + * MPU-60X0's bus arbitration detection logic is turned on, enabling it to + * detect when the bus is available. + * + * @return Current multi-master enabled value + * @see MPU9150_RA_I2C_MST_CTRL + */ +bool MPU9150::getMultiMasterEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_MULT_MST_EN_BIT, buffer); + return buffer[0]; +} +/** Set multi-master enabled value. + * @param enabled New multi-master enabled value + * @see getMultiMasterEnabled() + * @see MPU9150_RA_I2C_MST_CTRL + */ +void MPU9150::setMultiMasterEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_MULT_MST_EN_BIT, enabled); +} +/** Get wait-for-external-sensor-data enabled value. + * When the WAIT_FOR_ES bit is set to 1, the Data Ready interrupt will be + * delayed until External Sensor data from the Slave Devices are loaded into the + * EXT_SENS_DATA registers. This is used to ensure that both the internal sensor + * data (i.e. from gyro and accel) and external sensor data have been loaded to + * their respective data registers (i.e. the data is synced) when the Data Ready + * interrupt is triggered. + * + * @return Current wait-for-external-sensor-data enabled value + * @see MPU9150_RA_I2C_MST_CTRL + */ +bool MPU9150::getWaitForExternalSensorEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_WAIT_FOR_ES_BIT, buffer); + return buffer[0]; +} +/** Set wait-for-external-sensor-data enabled value. + * @param enabled New wait-for-external-sensor-data enabled value + * @see getWaitForExternalSensorEnabled() + * @see MPU9150_RA_I2C_MST_CTRL + */ +void MPU9150::setWaitForExternalSensorEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_WAIT_FOR_ES_BIT, enabled); +} +/** Get Slave 3 FIFO enabled value. + * When set to 1, this bit enables EXT_SENS_DATA registers (Registers 73 to 96) + * associated with Slave 3 to be written into the FIFO buffer. + * @return Current Slave 3 FIFO enabled value + * @see MPU9150_RA_MST_CTRL + */ +bool MPU9150::getSlave3FIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_SLV_3_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set Slave 3 FIFO enabled value. + * @param enabled New Slave 3 FIFO enabled value + * @see getSlave3FIFOEnabled() + * @see MPU9150_RA_MST_CTRL + */ +void MPU9150::setSlave3FIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_SLV_3_FIFO_EN_BIT, enabled); +} +/** Get slave read/write transition enabled value. + * The I2C_MST_P_NSR bit configures the I2C Master's transition from one slave + * read to the next slave read. If the bit equals 0, there will be a restart + * between reads. If the bit equals 1, there will be a stop followed by a start + * of the following read. When a write transaction follows a read transaction, + * the stop followed by a start of the successive write will be always used. + * + * @return Current slave read/write transition enabled value + * @see MPU9150_RA_I2C_MST_CTRL + */ +bool MPU9150::getSlaveReadWriteTransitionEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_I2C_MST_P_NSR_BIT, buffer); + return buffer[0]; +} +/** Set slave read/write transition enabled value. + * @param enabled New slave read/write transition enabled value + * @see getSlaveReadWriteTransitionEnabled() + * @see MPU9150_RA_I2C_MST_CTRL + */ +void MPU9150::setSlaveReadWriteTransitionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_I2C_MST_P_NSR_BIT, enabled); +} +/** Get I2C master clock speed. + * I2C_MST_CLK is a 4 bit unsigned value which configures a divider on the + * MPU-60X0 internal 8MHz clock. It sets the I2C master clock speed according to + * the following table: + * + *
+ * I2C_MST_CLK | I2C Master Clock Speed | 8MHz Clock Divider
+ * ------------+------------------------+-------------------
+ * 0           | 348kHz                 | 23
+ * 1           | 333kHz                 | 24
+ * 2           | 320kHz                 | 25
+ * 3           | 308kHz                 | 26
+ * 4           | 296kHz                 | 27
+ * 5           | 286kHz                 | 28
+ * 6           | 276kHz                 | 29
+ * 7           | 267kHz                 | 30
+ * 8           | 258kHz                 | 31
+ * 9           | 500kHz                 | 16
+ * 10          | 471kHz                 | 17
+ * 11          | 444kHz                 | 18
+ * 12          | 421kHz                 | 19
+ * 13          | 400kHz                 | 20
+ * 14          | 381kHz                 | 21
+ * 15          | 364kHz                 | 22
+ * 
+ * + * @return Current I2C master clock speed + * @see MPU9150_RA_I2C_MST_CTRL + */ +uint8_t MPU9150::getMasterClockSpeed() { + I2Cdev::readBits(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_I2C_MST_CLK_BIT, MPU9150_I2C_MST_CLK_LENGTH, buffer); + return buffer[0]; +} +/** Set I2C master clock speed. + * @reparam speed Current I2C master clock speed + * @see MPU9150_RA_I2C_MST_CTRL + */ +void MPU9150::setMasterClockSpeed(uint8_t speed) { + I2Cdev::writeBits(devAddr, MPU9150_RA_I2C_MST_CTRL, MPU9150_I2C_MST_CLK_BIT, MPU9150_I2C_MST_CLK_LENGTH, speed); +} + +// I2C_SLV* registers (Slave 0-3) + +/** Get the I2C address of the specified slave (0-3). + * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read + * operation, and if it is cleared, then it's a write operation. The remaining + * bits (6-0) are the 7-bit device address of the slave device. + * + * In read mode, the result of the read is placed in the lowest available + * EXT_SENS_DATA register. For further information regarding the allocation of + * read results, please refer to the EXT_SENS_DATA register description + * (Registers 73 - 96). + * + * The MPU-9150 supports a total of five slaves, but Slave 4 has unique + * characteristics, and so it has its own functions (getSlave4* and setSlave4*). + * + * I2C data transactions are performed at the Sample Rate, as defined in + * Register 25. The user is responsible for ensuring that I2C data transactions + * to and from each enabled Slave can be completed within a single period of the + * Sample Rate. + * + * The I2C slave access rate can be reduced relative to the Sample Rate. This + * reduced access rate is determined by I2C_MST_DLY (Register 52). Whether a + * slave's access rate is reduced relative to the Sample Rate is determined by + * I2C_MST_DELAY_CTRL (Register 103). + * + * The processing order for the slaves is fixed. The sequence followed for + * processing the slaves is Slave 0, Slave 1, Slave 2, Slave 3 and Slave 4. If a + * particular Slave is disabled it will be skipped. + * + * Each slave can either be accessed at the sample rate or at a reduced sample + * rate. In a case where some slaves are accessed at the Sample Rate and some + * slaves are accessed at the reduced rate, the sequence of accessing the slaves + * (Slave 0 to Slave 4) is still followed. However, the reduced rate slaves will + * be skipped if their access rate dictates that they should not be accessed + * during that particular cycle. For further information regarding the reduced + * access rate, please refer to Register 52. Whether a slave is accessed at the + * Sample Rate or at the reduced rate is determined by the Delay Enable bits in + * Register 103. + * + * @param num Slave number (0-3) + * @return Current address for specified slave + * @see MPU9150_RA_I2C_SLV0_ADDR + */ +uint8_t MPU9150::getSlaveAddress(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV0_ADDR + num*3, buffer); + return buffer[0]; +} +/** Set the I2C address of the specified slave (0-3). + * @param num Slave number (0-3) + * @param address New address for specified slave + * @see getSlaveAddress() + * @see MPU9150_RA_I2C_SLV0_ADDR + */ +void MPU9150::setSlaveAddress(uint8_t num, uint8_t address) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU9150_RA_I2C_SLV0_ADDR + num*3, address); +} +/** Get the active internal register for the specified slave (0-3). + * Read/write operations for this slave will be done to whatever internal + * register address is stored in this MPU register. + * + * The MPU-9150 supports a total of five slaves, but Slave 4 has unique + * characteristics, and so it has its own functions. + * + * @param num Slave number (0-3) + * @return Current active register for specified slave + * @see MPU9150_RA_I2C_SLV0_REG + */ +uint8_t MPU9150::getSlaveRegister(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV0_REG + num*3, buffer); + return buffer[0]; +} +/** Set the active internal register for the specified slave (0-3). + * @param num Slave number (0-3) + * @param reg New active register for specified slave + * @see getSlaveRegister() + * @see MPU9150_RA_I2C_SLV0_REG + */ +void MPU9150::setSlaveRegister(uint8_t num, uint8_t reg) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU9150_RA_I2C_SLV0_REG + num*3, reg); +} +/** Get the enabled value for the specified slave (0-3). + * When set to 1, this bit enables Slave 0 for data transfer operations. When + * cleared to 0, this bit disables Slave 0 from data transfer operations. + * @param num Slave number (0-3) + * @return Current enabled value for specified slave + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +bool MPU9150::getSlaveEnabled(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New enabled value for specified slave + * @see getSlaveEnabled() + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +void MPU9150::setSlaveEnabled(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_EN_BIT, enabled); +} +/** Get word pair byte-swapping enabled for the specified slave (0-3). + * When set to 1, this bit enables byte swapping. When byte swapping is enabled, + * the high and low bytes of a word pair are swapped. Please refer to + * I2C_SLV0_GRP for the pairing convention of the word pairs. When cleared to 0, + * bytes transferred to and from Slave 0 will be written to EXT_SENS_DATA + * registers in the order they were transferred. + * + * @param num Slave number (0-3) + * @return Current word pair byte-swapping enabled value for specified slave + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +bool MPU9150::getSlaveWordByteSwap(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_BYTE_SW_BIT, buffer); + return buffer[0]; +} +/** Set word pair byte-swapping enabled for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New word pair byte-swapping enabled value for specified slave + * @see getSlaveWordByteSwap() + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +void MPU9150::setSlaveWordByteSwap(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_BYTE_SW_BIT, enabled); +} +/** Get write mode for the specified slave (0-3). + * When set to 1, the transaction will read or write data only. When cleared to + * 0, the transaction will write a register address prior to reading or writing + * data. This should equal 0 when specifying the register address within the + * Slave device to/from which the ensuing data transaction will take place. + * + * @param num Slave number (0-3) + * @return Current write mode for specified slave (0 = register address + data, 1 = data only) + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +bool MPU9150::getSlaveWriteMode(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_REG_DIS_BIT, buffer); + return buffer[0]; +} +/** Set write mode for the specified slave (0-3). + * @param num Slave number (0-3) + * @param mode New write mode for specified slave (0 = register address + data, 1 = data only) + * @see getSlaveWriteMode() + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +void MPU9150::setSlaveWriteMode(uint8_t num, bool mode) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_REG_DIS_BIT, mode); +} +/** Get word pair grouping order offset for the specified slave (0-3). + * This sets specifies the grouping order of word pairs received from registers. + * When cleared to 0, bytes from register addresses 0 and 1, 2 and 3, etc (even, + * then odd register addresses) are paired to form a word. When set to 1, bytes + * from register addresses are paired 1 and 2, 3 and 4, etc. (odd, then even + * register addresses) are paired to form a word. + * + * @param num Slave number (0-3) + * @return Current word pair grouping order offset for specified slave + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +bool MPU9150::getSlaveWordGroupOffset(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_GRP_BIT, buffer); + return buffer[0]; +} +/** Set word pair grouping order offset for the specified slave (0-3). + * @param num Slave number (0-3) + * @param enabled New word pair grouping order offset for specified slave + * @see getSlaveWordGroupOffset() + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +void MPU9150::setSlaveWordGroupOffset(uint8_t num, bool enabled) { + if (num > 3) return; + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_GRP_BIT, enabled); +} +/** Get number of bytes to read for the specified slave (0-3). + * Specifies the number of bytes transferred to and from Slave 0. Clearing this + * bit to 0 is equivalent to disabling the register by writing 0 to I2C_SLV0_EN. + * @param num Slave number (0-3) + * @return Number of bytes to read for specified slave + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +uint8_t MPU9150::getSlaveDataLength(uint8_t num) { + if (num > 3) return 0; + I2Cdev::readBits(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_LEN_BIT, MPU9150_I2C_SLV_LEN_LENGTH, buffer); + return buffer[0]; +} +/** Set number of bytes to read for the specified slave (0-3). + * @param num Slave number (0-3) + * @param length Number of bytes to read for specified slave + * @see getSlaveDataLength() + * @see MPU9150_RA_I2C_SLV0_CTRL + */ +void MPU9150::setSlaveDataLength(uint8_t num, uint8_t length) { + if (num > 3) return; + I2Cdev::writeBits(devAddr, MPU9150_RA_I2C_SLV0_CTRL + num*3, MPU9150_I2C_SLV_LEN_BIT, MPU9150_I2C_SLV_LEN_LENGTH, length); +} + +// I2C_SLV* registers (Slave 4) + +/** Get the I2C address of Slave 4. + * Note that Bit 7 (MSB) controls read/write mode. If Bit 7 is set, it's a read + * operation, and if it is cleared, then it's a write operation. The remaining + * bits (6-0) are the 7-bit device address of the slave device. + * + * @return Current address for Slave 4 + * @see getSlaveAddress() + * @see MPU9150_RA_I2C_SLV4_ADDR + */ +uint8_t MPU9150::getSlave4Address() { + I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV4_ADDR, buffer); + return buffer[0]; +} +/** Set the I2C address of Slave 4. + * @param address New address for Slave 4 + * @see getSlave4Address() + * @see MPU9150_RA_I2C_SLV4_ADDR + */ +void MPU9150::setSlave4Address(uint8_t address) { + I2Cdev::writeByte(devAddr, MPU9150_RA_I2C_SLV4_ADDR, address); +} +/** Get the active internal register for the Slave 4. + * Read/write operations for this slave will be done to whatever internal + * register address is stored in this MPU register. + * + * @return Current active register for Slave 4 + * @see MPU9150_RA_I2C_SLV4_REG + */ +uint8_t MPU9150::getSlave4Register() { + I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV4_REG, buffer); + return buffer[0]; +} +/** Set the active internal register for Slave 4. + * @param reg New active register for Slave 4 + * @see getSlave4Register() + * @see MPU9150_RA_I2C_SLV4_REG + */ +void MPU9150::setSlave4Register(uint8_t reg) { + I2Cdev::writeByte(devAddr, MPU9150_RA_I2C_SLV4_REG, reg); +} +/** Set new byte to write to Slave 4. + * This register stores the data to be written into the Slave 4. If I2C_SLV4_RW + * is set 1 (set to read), this register has no effect. + * @param data New byte to write to Slave 4 + * @see MPU9150_RA_I2C_SLV4_DO + */ +void MPU9150::setSlave4OutputByte(uint8_t data) { + I2Cdev::writeByte(devAddr, MPU9150_RA_I2C_SLV4_DO, data); +} +/** Get the enabled value for the Slave 4. + * When set to 1, this bit enables Slave 4 for data transfer operations. When + * cleared to 0, this bit disables Slave 4 from data transfer operations. + * @return Current enabled value for Slave 4 + * @see MPU9150_RA_I2C_SLV4_CTRL + */ +bool MPU9150::getSlave4Enabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for Slave 4. + * @param enabled New enabled value for Slave 4 + * @see getSlave4Enabled() + * @see MPU9150_RA_I2C_SLV4_CTRL + */ +void MPU9150::setSlave4Enabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_EN_BIT, enabled); +} +/** Get the enabled value for Slave 4 transaction interrupts. + * When set to 1, this bit enables the generation of an interrupt signal upon + * completion of a Slave 4 transaction. When cleared to 0, this bit disables the + * generation of an interrupt signal upon completion of a Slave 4 transaction. + * The interrupt status can be observed in Register 54. + * + * @return Current enabled value for Slave 4 transaction interrupts. + * @see MPU9150_RA_I2C_SLV4_CTRL + */ +bool MPU9150::getSlave4InterruptEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set the enabled value for Slave 4 transaction interrupts. + * @param enabled New enabled value for Slave 4 transaction interrupts. + * @see getSlave4InterruptEnabled() + * @see MPU9150_RA_I2C_SLV4_CTRL + */ +void MPU9150::setSlave4InterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_INT_EN_BIT, enabled); +} +/** Get write mode for Slave 4. + * When set to 1, the transaction will read or write data only. When cleared to + * 0, the transaction will write a register address prior to reading or writing + * data. This should equal 0 when specifying the register address within the + * Slave device to/from which the ensuing data transaction will take place. + * + * @return Current write mode for Slave 4 (0 = register address + data, 1 = data only) + * @see MPU9150_RA_I2C_SLV4_CTRL + */ +bool MPU9150::getSlave4WriteMode() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_REG_DIS_BIT, buffer); + return buffer[0]; +} +/** Set write mode for the Slave 4. + * @param mode New write mode for Slave 4 (0 = register address + data, 1 = data only) + * @see getSlave4WriteMode() + * @see MPU9150_RA_I2C_SLV4_CTRL + */ +void MPU9150::setSlave4WriteMode(bool mode) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_REG_DIS_BIT, mode); +} +/** Get Slave 4 master delay value. + * This configures the reduced access rate of I2C slaves relative to the Sample + * Rate. When a slave's access rate is decreased relative to the Sample Rate, + * the slave is accessed every: + * + * 1 / (1 + I2C_MST_DLY) samples + * + * This base Sample Rate in turn is determined by SMPLRT_DIV (register 25) and + * DLPF_CFG (register 26). Whether a slave's access rate is reduced relative to + * the Sample Rate is determined by I2C_MST_DELAY_CTRL (register 103). For + * further information regarding the Sample Rate, please refer to register 25. + * + * @return Current Slave 4 master delay value + * @see MPU9150_RA_I2C_SLV4_CTRL + */ +uint8_t MPU9150::getSlave4MasterDelay() { + I2Cdev::readBits(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_MST_DLY_BIT, MPU9150_I2C_SLV4_MST_DLY_LENGTH, buffer); + return buffer[0]; +} +/** Set Slave 4 master delay value. + * @param delay New Slave 4 master delay value + * @see getSlave4MasterDelay() + * @see MPU9150_RA_I2C_SLV4_CTRL + */ +void MPU9150::setSlave4MasterDelay(uint8_t delay) { + I2Cdev::writeBits(devAddr, MPU9150_RA_I2C_SLV4_CTRL, MPU9150_I2C_SLV4_MST_DLY_BIT, MPU9150_I2C_SLV4_MST_DLY_LENGTH, delay); +} +/** Get last available byte read from Slave 4. + * This register stores the data read from Slave 4. This field is populated + * after a read transaction. + * @return Last available byte read from to Slave 4 + * @see MPU9150_RA_I2C_SLV4_DI + */ +uint8_t MPU9150::getSlate4InputByte() { + I2Cdev::readByte(devAddr, MPU9150_RA_I2C_SLV4_DI, buffer); + return buffer[0]; +} + +// I2C_MST_STATUS register + +/** Get FSYNC interrupt status. + * This bit reflects the status of the FSYNC interrupt from an external device + * into the MPU-60X0. This is used as a way to pass an external interrupt + * through the MPU-60X0 to the host application processor. When set to 1, this + * bit will cause an interrupt if FSYNC_INT_EN is asserted in INT_PIN_CFG + * (Register 55). + * @return FSYNC interrupt status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getPassthroughStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_PASS_THROUGH_BIT, buffer); + return buffer[0]; +} +/** Get Slave 4 transaction done status. + * Automatically sets to 1 when a Slave 4 transaction has completed. This + * triggers an interrupt if the I2C_MST_INT_EN bit in the INT_ENABLE register + * (Register 56) is asserted and if the SLV_4_DONE_INT bit is asserted in the + * I2C_SLV4_CTRL register (Register 52). + * @return Slave 4 transaction done status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getSlave4IsDone() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV4_DONE_BIT, buffer); + return buffer[0]; +} +/** Get master arbitration lost status. + * This bit automatically sets to 1 when the I2C Master has lost arbitration of + * the auxiliary I2C bus (an error condition). This triggers an interrupt if the + * I2C_MST_INT_EN bit in the INT_ENABLE register (Register 56) is asserted. + * @return Master arbitration lost status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getLostArbitration() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_LOST_ARB_BIT, buffer); + return buffer[0]; +} +/** Get Slave 4 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 4. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 4 NACK interrupt status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getSlave4Nack() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV4_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 3 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 3. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 3 NACK interrupt status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getSlave3Nack() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV3_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 2 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 2. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 2 NACK interrupt status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getSlave2Nack() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV2_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 1 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 1. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 1 NACK interrupt status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getSlave1Nack() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV1_NACK_BIT, buffer); + return buffer[0]; +} +/** Get Slave 0 NACK status. + * This bit automatically sets to 1 when the I2C Master receives a NACK in a + * transaction with Slave 0. This triggers an interrupt if the I2C_MST_INT_EN + * bit in the INT_ENABLE register (Register 56) is asserted. + * @return Slave 0 NACK interrupt status + * @see MPU9150_RA_I2C_MST_STATUS + */ +bool MPU9150::getSlave0Nack() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_STATUS, MPU9150_MST_I2C_SLV0_NACK_BIT, buffer); + return buffer[0]; +} + +// INT_PIN_CFG register + +/** Get interrupt logic level mode. + * Will be set 0 for active-high, 1 for active-low. + * @return Current interrupt mode (0=active-high, 1=active-low) + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_INT_LEVEL_BIT + */ +bool MPU9150::getInterruptMode() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_LEVEL_BIT, buffer); + return buffer[0]; +} +/** Set interrupt logic level mode. + * @param mode New interrupt mode (0=active-high, 1=active-low) + * @see getInterruptMode() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_INT_LEVEL_BIT + */ +void MPU9150::setInterruptMode(bool mode) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_LEVEL_BIT, mode); +} +/** Get interrupt drive mode. + * Will be set 0 for push-pull, 1 for open-drain. + * @return Current interrupt drive mode (0=push-pull, 1=open-drain) + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_INT_OPEN_BIT + */ +bool MPU9150::getInterruptDrive() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_OPEN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt drive mode. + * @param drive New interrupt drive mode (0=push-pull, 1=open-drain) + * @see getInterruptDrive() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_INT_OPEN_BIT + */ +void MPU9150::setInterruptDrive(bool drive) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_OPEN_BIT, drive); +} +/** Get interrupt latch mode. + * Will be set 0 for 50us-pulse, 1 for latch-until-int-cleared. + * @return Current latch mode (0=50us-pulse, 1=latch-until-int-cleared) + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_LATCH_INT_EN_BIT + */ +bool MPU9150::getInterruptLatch() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_LATCH_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch mode. + * @param latch New latch mode (0=50us-pulse, 1=latch-until-int-cleared) + * @see getInterruptLatch() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_LATCH_INT_EN_BIT + */ +void MPU9150::setInterruptLatch(bool latch) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_LATCH_INT_EN_BIT, latch); +} +/** Get interrupt latch clear mode. + * Will be set 0 for status-read-only, 1 for any-register-read. + * @return Current latch clear mode (0=status-read-only, 1=any-register-read) + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_INT_RD_CLEAR_BIT + */ +bool MPU9150::getInterruptLatchClear() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_RD_CLEAR_BIT, buffer); + return buffer[0]; +} +/** Set interrupt latch clear mode. + * @param clear New latch clear mode (0=status-read-only, 1=any-register-read) + * @see getInterruptLatchClear() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_INT_RD_CLEAR_BIT + */ +void MPU9150::setInterruptLatchClear(bool clear) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_INT_RD_CLEAR_BIT, clear); +} +/** Get FSYNC interrupt logic level mode. + * @return Current FSYNC interrupt mode (0=active-high, 1=active-low) + * @see getFSyncInterruptMode() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT + */ +bool MPU9150::getFSyncInterruptLevel() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT, buffer); + return buffer[0]; +} +/** Set FSYNC interrupt logic level mode. + * @param mode New FSYNC interrupt mode (0=active-high, 1=active-low) + * @see getFSyncInterruptMode() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT + */ +void MPU9150::setFSyncInterruptLevel(bool level) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT, level); +} +/** Get FSYNC pin interrupt enabled setting. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled setting + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_FSYNC_INT_EN_BIT + */ +bool MPU9150::getFSyncInterruptEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_FSYNC_INT_EN_BIT, buffer); + return buffer[0]; +} +/** Set FSYNC pin interrupt enabled setting. + * @param enabled New FSYNC pin interrupt enabled setting + * @see getFSyncInterruptEnabled() + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_FSYNC_INT_EN_BIT + */ +void MPU9150::setFSyncInterruptEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_FSYNC_INT_EN_BIT, enabled); +} +/** Get I2C bypass enabled status. + * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to + * 0, the host application processor will be able to directly access the + * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host + * application processor will not be able to directly access the auxiliary I2C + * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106 + * bit[5]). + * @return Current I2C bypass enabled status + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_I2C_BYPASS_EN_BIT + */ +bool MPU9150::getI2CBypassEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_I2C_BYPASS_EN_BIT, buffer); + return buffer[0]; +} +/** Set I2C bypass enabled status. + * When this bit is equal to 1 and I2C_MST_EN (Register 106 bit[5]) is equal to + * 0, the host application processor will be able to directly access the + * auxiliary I2C bus of the MPU-60X0. When this bit is equal to 0, the host + * application processor will not be able to directly access the auxiliary I2C + * bus of the MPU-60X0 regardless of the state of I2C_MST_EN (Register 106 + * bit[5]). + * @param enabled New I2C bypass enabled status + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_I2C_BYPASS_EN_BIT + */ +void MPU9150::setI2CBypassEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_I2C_BYPASS_EN_BIT, enabled); +} +/** Get reference clock output enabled status. + * When this bit is equal to 1, a reference clock output is provided at the + * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For + * further information regarding CLKOUT, please refer to the MPU-60X0 Product + * Specification document. + * @return Current reference clock output enabled status + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_CLKOUT_EN_BIT + */ +bool MPU9150::getClockOutputEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_CLKOUT_EN_BIT, buffer); + return buffer[0]; +} +/** Set reference clock output enabled status. + * When this bit is equal to 1, a reference clock output is provided at the + * CLKOUT pin. When this bit is equal to 0, the clock output is disabled. For + * further information regarding CLKOUT, please refer to the MPU-60X0 Product + * Specification document. + * @param enabled New reference clock output enabled status + * @see MPU9150_RA_INT_PIN_CFG + * @see MPU9150_INTCFG_CLKOUT_EN_BIT + */ +void MPU9150::setClockOutputEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_PIN_CFG, MPU9150_INTCFG_CLKOUT_EN_BIT, enabled); +} + +// INT_ENABLE register + +/** Get full interrupt enabled status. + * Full register byte for all interrupts, for quick reading. Each bit will be + * set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_FF_BIT + **/ +uint8_t MPU9150::getIntEnabled() { + I2Cdev::readByte(devAddr, MPU9150_RA_INT_ENABLE, buffer); + return buffer[0]; +} +/** Set full interrupt enabled status. + * Full register byte for all interrupts, for quick reading. Each bit should be + * set 0 for disabled, 1 for enabled. + * @param enabled New interrupt enabled status + * @see getIntFreefallEnabled() + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_FF_BIT + **/ +void MPU9150::setIntEnabled(uint8_t enabled) { + I2Cdev::writeByte(devAddr, MPU9150_RA_INT_ENABLE, enabled); +} +/** Get Free Fall interrupt enabled status. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_FF_BIT + **/ +bool MPU9150::getIntFreefallEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_FF_BIT, buffer); + return buffer[0]; +} +/** Set Free Fall interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntFreefallEnabled() + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_FF_BIT + **/ +void MPU9150::setIntFreefallEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_FF_BIT, enabled); +} +/** Get Motion Detection interrupt enabled status. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_MOT_BIT + **/ +bool MPU9150::getIntMotionEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_MOT_BIT, buffer); + return buffer[0]; +} +/** Set Motion Detection interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntMotionEnabled() + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_MOT_BIT + **/ +void MPU9150::setIntMotionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_MOT_BIT, enabled); +} +/** Get Zero Motion Detection interrupt enabled status. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_ZMOT_BIT + **/ +bool MPU9150::getIntZeroMotionEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_ZMOT_BIT, buffer); + return buffer[0]; +} +/** Set Zero Motion Detection interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntZeroMotionEnabled() + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_ZMOT_BIT + **/ +void MPU9150::setIntZeroMotionEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_ZMOT_BIT, enabled); +} +/** Get FIFO Buffer Overflow interrupt enabled status. + * Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_FIFO_OFLOW_BIT + **/ +bool MPU9150::getIntFIFOBufferOverflowEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_FIFO_OFLOW_BIT, buffer); + return buffer[0]; +} +/** Set FIFO Buffer Overflow interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntFIFOBufferOverflowEnabled() + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_FIFO_OFLOW_BIT + **/ +void MPU9150::setIntFIFOBufferOverflowEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_FIFO_OFLOW_BIT, enabled); +} +/** Get I2C Master interrupt enabled status. + * This enables any of the I2C Master interrupt sources to generate an + * interrupt. Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_I2C_MST_INT_BIT + **/ +bool MPU9150::getIntI2CMasterEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_I2C_MST_INT_BIT, buffer); + return buffer[0]; +} +/** Set I2C Master interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntI2CMasterEnabled() + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_I2C_MST_INT_BIT + **/ +void MPU9150::setIntI2CMasterEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_I2C_MST_INT_BIT, enabled); +} +/** Get Data Ready interrupt enabled setting. + * This event occurs each time a write operation to all of the sensor registers + * has been completed. Will be set 0 for disabled, 1 for enabled. + * @return Current interrupt enabled status + * @see MPU9150_RA_INT_ENABLE + * @see MPU9150_INTERRUPT_DATA_RDY_BIT + */ +bool MPU9150::getIntDataReadyEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_DATA_RDY_BIT, buffer); + return buffer[0]; +} +/** Set Data Ready interrupt enabled status. + * @param enabled New interrupt enabled status + * @see getIntDataReadyEnabled() + * @see MPU9150_RA_INT_CFG + * @see MPU9150_INTERRUPT_DATA_RDY_BIT + */ +void MPU9150::setIntDataReadyEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_DATA_RDY_BIT, enabled); +} + +// INT_STATUS register + +/** Get full set of interrupt status bits. + * These bits clear to 0 after the register has been read. Very useful + * for getting multiple INT statuses, since each single bit read clears + * all of them because it has to read the whole byte. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + */ +uint8_t MPU9150::getIntStatus() { + I2Cdev::readByte(devAddr, MPU9150_RA_INT_STATUS, buffer); + return buffer[0]; +} +/** Get Free Fall interrupt status. + * This bit automatically sets to 1 when a Free Fall interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + * @see MPU9150_INTERRUPT_FF_BIT + */ +bool MPU9150::getIntFreefallStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_FF_BIT, buffer); + return buffer[0]; +} +/** Get Motion Detection interrupt status. + * This bit automatically sets to 1 when a Motion Detection interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + * @see MPU9150_INTERRUPT_MOT_BIT + */ +bool MPU9150::getIntMotionStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_MOT_BIT, buffer); + return buffer[0]; +} +/** Get Zero Motion Detection interrupt status. + * This bit automatically sets to 1 when a Zero Motion Detection interrupt has + * been generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + * @see MPU9150_INTERRUPT_ZMOT_BIT + */ +bool MPU9150::getIntZeroMotionStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_ZMOT_BIT, buffer); + return buffer[0]; +} +/** Get FIFO Buffer Overflow interrupt status. + * This bit automatically sets to 1 when a Free Fall interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + * @see MPU9150_INTERRUPT_FIFO_OFLOW_BIT + */ +bool MPU9150::getIntFIFOBufferOverflowStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_FIFO_OFLOW_BIT, buffer); + return buffer[0]; +} +/** Get I2C Master interrupt status. + * This bit automatically sets to 1 when an I2C Master interrupt has been + * generated. For a list of I2C Master interrupts, please refer to Register 54. + * The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + * @see MPU9150_INTERRUPT_I2C_MST_INT_BIT + */ +bool MPU9150::getIntI2CMasterStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_I2C_MST_INT_BIT, buffer); + return buffer[0]; +} +/** Get Data Ready interrupt status. + * This bit automatically sets to 1 when a Data Ready interrupt has been + * generated. The bit clears to 0 after the register has been read. + * @return Current interrupt status + * @see MPU9150_RA_INT_STATUS + * @see MPU9150_INTERRUPT_DATA_RDY_BIT + */ +bool MPU9150::getIntDataReadyStatus() { + I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_DATA_RDY_BIT, buffer); + return buffer[0]; +} + +// ACCEL_*OUT_* registers + +/** Get raw 9-axis motion sensor readings (accel/gyro/compass). + * FUNCTION NOT FULLY IMPLEMENTED YET. + * @param ax 16-bit signed integer container for accelerometer X-axis value + * @param ay 16-bit signed integer container for accelerometer Y-axis value + * @param az 16-bit signed integer container for accelerometer Z-axis value + * @param gx 16-bit signed integer container for gyroscope X-axis value + * @param gy 16-bit signed integer container for gyroscope Y-axis value + * @param gz 16-bit signed integer container for gyroscope Z-axis value + * @param mx 16-bit signed integer container for magnetometer X-axis value + * @param my 16-bit signed integer container for magnetometer Y-axis value + * @param mz 16-bit signed integer container for magnetometer Z-axis value + * @see getMotion6() + * @see getAcceleration() + * @see getRotation() + * @see MPU9150_RA_ACCEL_XOUT_H + */ +void MPU9150::getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz) { + + //get accel and gyro + getMotion6(ax, ay, az, gx, gy, gz); + + //read mag + I2Cdev::writeByte(devAddr, MPU9150_RA_INT_PIN_CFG, 0x02); //set i2c bypass enable pin to true to access magnetometer + delay(10); + I2Cdev::writeByte(MPU9150_RA_MAG_ADDRESS, 0x0A, 0x01); //enable the magnetometer + delay(10); + I2Cdev::readBytes(MPU9150_RA_MAG_ADDRESS, MPU9150_RA_MAG_XOUT_L, 6, buffer); + *mx = (((int16_t)buffer[0]) << 8) | buffer[1]; + *my = (((int16_t)buffer[2]) << 8) | buffer[3]; + *mz = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get raw 6-axis motion sensor readings (accel/gyro). + * Retrieves all currently available motion sensor values. + * @param ax 16-bit signed integer container for accelerometer X-axis value + * @param ay 16-bit signed integer container for accelerometer Y-axis value + * @param az 16-bit signed integer container for accelerometer Z-axis value + * @param gx 16-bit signed integer container for gyroscope X-axis value + * @param gy 16-bit signed integer container for gyroscope Y-axis value + * @param gz 16-bit signed integer container for gyroscope Z-axis value + * @see getAcceleration() + * @see getRotation() + * @see MPU9150_RA_ACCEL_XOUT_H + */ +void MPU9150::getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz) { + I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_XOUT_H, 14, buffer); + *ax = (((int16_t)buffer[0]) << 8) | buffer[1]; + *ay = (((int16_t)buffer[2]) << 8) | buffer[3]; + *az = (((int16_t)buffer[4]) << 8) | buffer[5]; + *gx = (((int16_t)buffer[8]) << 8) | buffer[9]; + *gy = (((int16_t)buffer[10]) << 8) | buffer[11]; + *gz = (((int16_t)buffer[12]) << 8) | buffer[13]; +} +/** Get 3-axis accelerometer readings. + * These registers store the most recent accelerometer measurements. + * Accelerometer measurements are written to these registers at the Sample Rate + * as defined in Register 25. + * + * The accelerometer measurement registers, along with the temperature + * measurement registers, gyroscope measurement registers, and external sensor + * data registers, are composed of two sets of registers: an internal register + * set and a user-facing read register set. + * + * The data within the accelerometer sensors' internal register set is always + * updated at the Sample Rate. Meanwhile, the user-facing read register set + * duplicates the internal register set's data values whenever the serial + * interface is idle. This guarantees that a burst read of sensor registers will + * read measurements from the same sampling instant. Note that if burst reads + * are not used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Each 16-bit accelerometer measurement has a full scale defined in ACCEL_FS + * (Register 28). For each full scale setting, the accelerometers' sensitivity + * per LSB in ACCEL_xOUT is shown in the table below: + * + *
+ * AFS_SEL | Full Scale Range | LSB Sensitivity
+ * --------+------------------+----------------
+ * 0       | +/- 2g           | 8192 LSB/mg
+ * 1       | +/- 4g           | 4096 LSB/mg
+ * 2       | +/- 8g           | 2048 LSB/mg
+ * 3       | +/- 16g          | 1024 LSB/mg
+ * 
+ * + * @param x 16-bit signed integer container for X-axis acceleration + * @param y 16-bit signed integer container for Y-axis acceleration + * @param z 16-bit signed integer container for Z-axis acceleration + * @see MPU9150_RA_GYRO_XOUT_H + */ +void MPU9150::getAcceleration(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_XOUT_H, 6, buffer); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis accelerometer reading. + * @return X-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9150_RA_ACCEL_XOUT_H + */ +int16_t MPU9150::getAccelerationX() { + I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_XOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis accelerometer reading. + * @return Y-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9150_RA_ACCEL_YOUT_H + */ +int16_t MPU9150::getAccelerationY() { + I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_YOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Z-axis accelerometer reading. + * @return Z-axis acceleration measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9150_RA_ACCEL_ZOUT_H + */ +int16_t MPU9150::getAccelerationZ() { + I2Cdev::readBytes(devAddr, MPU9150_RA_ACCEL_ZOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// TEMP_OUT_* registers + +/** Get current internal temperature. + * @return Temperature reading in 16-bit 2's complement format + * @see MPU9150_RA_TEMP_OUT_H + */ +int16_t MPU9150::getTemperature() { + I2Cdev::readBytes(devAddr, MPU9150_RA_TEMP_OUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// GYRO_*OUT_* registers + +/** Get 3-axis gyroscope readings. + * These gyroscope measurement registers, along with the accelerometer + * measurement registers, temperature measurement registers, and external sensor + * data registers, are composed of two sets of registers: an internal register + * set and a user-facing read register set. + * The data within the gyroscope sensors' internal register set is always + * updated at the Sample Rate. Meanwhile, the user-facing read register set + * duplicates the internal register set's data values whenever the serial + * interface is idle. This guarantees that a burst read of sensor registers will + * read measurements from the same sampling instant. Note that if burst reads + * are not used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Each 16-bit gyroscope measurement has a full scale defined in FS_SEL + * (Register 27). For each full scale setting, the gyroscopes' sensitivity per + * LSB in GYRO_xOUT is shown in the table below: + * + *
+ * FS_SEL | Full Scale Range   | LSB Sensitivity
+ * -------+--------------------+----------------
+ * 0      | +/- 250 degrees/s  | 131 LSB/deg/s
+ * 1      | +/- 500 degrees/s  | 65.5 LSB/deg/s
+ * 2      | +/- 1000 degrees/s | 32.8 LSB/deg/s
+ * 3      | +/- 2000 degrees/s | 16.4 LSB/deg/s
+ * 
+ * + * @param x 16-bit signed integer container for X-axis rotation + * @param y 16-bit signed integer container for Y-axis rotation + * @param z 16-bit signed integer container for Z-axis rotation + * @see getMotion6() + * @see MPU9150_RA_GYRO_XOUT_H + */ +void MPU9150::getRotation(int16_t* x, int16_t* y, int16_t* z) { + I2Cdev::readBytes(devAddr, MPU9150_RA_GYRO_XOUT_H, 6, buffer); + *x = (((int16_t)buffer[0]) << 8) | buffer[1]; + *y = (((int16_t)buffer[2]) << 8) | buffer[3]; + *z = (((int16_t)buffer[4]) << 8) | buffer[5]; +} +/** Get X-axis gyroscope reading. + * @return X-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9150_RA_GYRO_XOUT_H + */ +int16_t MPU9150::getRotationX() { + I2Cdev::readBytes(devAddr, MPU9150_RA_GYRO_XOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Y-axis gyroscope reading. + * @return Y-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9150_RA_GYRO_YOUT_H + */ +int16_t MPU9150::getRotationY() { + I2Cdev::readBytes(devAddr, MPU9150_RA_GYRO_YOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} +/** Get Z-axis gyroscope reading. + * @return Z-axis rotation measurement in 16-bit 2's complement format + * @see getMotion6() + * @see MPU9150_RA_GYRO_ZOUT_H + */ +int16_t MPU9150::getRotationZ() { + I2Cdev::readBytes(devAddr, MPU9150_RA_GYRO_ZOUT_H, 2, buffer); + return (((int16_t)buffer[0]) << 8) | buffer[1]; +} + +// EXT_SENS_DATA_* registers + +/** Read single byte from external sensor data register. + * These registers store data read from external sensors by the Slave 0, 1, 2, + * and 3 on the auxiliary I2C interface. Data read by Slave 4 is stored in + * I2C_SLV4_DI (Register 53). + * + * External sensor data is written to these registers at the Sample Rate as + * defined in Register 25. This access rate can be reduced by using the Slave + * Delay Enable registers (Register 103). + * + * External sensor data registers, along with the gyroscope measurement + * registers, accelerometer measurement registers, and temperature measurement + * registers, are composed of two sets of registers: an internal register set + * and a user-facing read register set. + * + * The data within the external sensors' internal register set is always updated + * at the Sample Rate (or the reduced access rate) whenever the serial interface + * is idle. This guarantees that a burst read of sensor registers will read + * measurements from the same sampling instant. Note that if burst reads are not + * used, the user is responsible for ensuring a set of single byte reads + * correspond to a single sampling instant by checking the Data Ready interrupt. + * + * Data is placed in these external sensor data registers according to + * I2C_SLV0_CTRL, I2C_SLV1_CTRL, I2C_SLV2_CTRL, and I2C_SLV3_CTRL (Registers 39, + * 42, 45, and 48). When more than zero bytes are read (I2C_SLVx_LEN > 0) from + * an enabled slave (I2C_SLVx_EN = 1), the slave is read at the Sample Rate (as + * defined in Register 25) or delayed rate (if specified in Register 52 and + * 103). During each Sample cycle, slave reads are performed in order of Slave + * number. If all slaves are enabled with more than zero bytes to be read, the + * order will be Slave 0, followed by Slave 1, Slave 2, and Slave 3. + * + * Each enabled slave will have EXT_SENS_DATA registers associated with it by + * number of bytes read (I2C_SLVx_LEN) in order of slave number, starting from + * EXT_SENS_DATA_00. Note that this means enabling or disabling a slave may + * change the higher numbered slaves' associated registers. Furthermore, if + * fewer total bytes are being read from the external sensors as a result of + * such a change, then the data remaining in the registers which no longer have + * an associated slave device (i.e. high numbered registers) will remain in + * these previously allocated registers unless reset. + * + * If the sum of the read lengths of all SLVx transactions exceed the number of + * available EXT_SENS_DATA registers, the excess bytes will be dropped. There + * are 24 EXT_SENS_DATA registers and hence the total read lengths between all + * the slaves cannot be greater than 24 or some bytes will be lost. + * + * Note: Slave 4's behavior is distinct from that of Slaves 0-3. For further + * information regarding the characteristics of Slave 4, please refer to + * Registers 49 to 53. + * + * EXAMPLE: + * Suppose that Slave 0 is enabled with 4 bytes to be read (I2C_SLV0_EN = 1 and + * I2C_SLV0_LEN = 4) while Slave 1 is enabled with 2 bytes to be read so that + * I2C_SLV1_EN = 1 and I2C_SLV1_LEN = 2. In such a situation, EXT_SENS_DATA _00 + * through _03 will be associated with Slave 0, while EXT_SENS_DATA _04 and 05 + * will be associated with Slave 1. If Slave 2 is enabled as well, registers + * starting from EXT_SENS_DATA_06 will be allocated to Slave 2. + * + * If Slave 2 is disabled while Slave 3 is enabled in this same situation, then + * registers starting from EXT_SENS_DATA_06 will be allocated to Slave 3 + * instead. + * + * REGISTER ALLOCATION FOR DYNAMIC DISABLE VS. NORMAL DISABLE: + * If a slave is disabled at any time, the space initially allocated to the + * slave in the EXT_SENS_DATA register, will remain associated with that slave. + * This is to avoid dynamic adjustment of the register allocation. + * + * The allocation of the EXT_SENS_DATA registers is recomputed only when (1) all + * slaves are disabled, or (2) the I2C_MST_RST bit is set (Register 106). + * + * This above is also true if one of the slaves gets NACKed and stops + * functioning. + * + * @param position Starting position (0-23) + * @return Byte read from register + */ +uint8_t MPU9150::getExternalSensorByte(int position) { + I2Cdev::readByte(devAddr, MPU9150_RA_EXT_SENS_DATA_00 + position, buffer); + return buffer[0]; +} +/** Read word (2 bytes) from external sensor data registers. + * @param position Starting position (0-21) + * @return Word read from register + * @see getExternalSensorByte() + */ +uint16_t MPU9150::getExternalSensorWord(int position) { + I2Cdev::readBytes(devAddr, MPU9150_RA_EXT_SENS_DATA_00 + position, 2, buffer); + return (((uint16_t)buffer[0]) << 8) | buffer[1]; +} +/** Read double word (4 bytes) from external sensor data registers. + * @param position Starting position (0-20) + * @return Double word read from registers + * @see getExternalSensorByte() + */ +uint32_t MPU9150::getExternalSensorDWord(int position) { + I2Cdev::readBytes(devAddr, MPU9150_RA_EXT_SENS_DATA_00 + position, 4, buffer); + return (((uint32_t)buffer[0]) << 24) | (((uint32_t)buffer[1]) << 16) | (((uint16_t)buffer[2]) << 8) | buffer[3]; +} + +// MOT_DETECT_STATUS register + +/** Get X-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_XNEG_BIT + */ +bool MPU9150::getXNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_XNEG_BIT, buffer); + return buffer[0]; +} +/** Get X-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_XPOS_BIT + */ +bool MPU9150::getXPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_XPOS_BIT, buffer); + return buffer[0]; +} +/** Get Y-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_YNEG_BIT + */ +bool MPU9150::getYNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_YNEG_BIT, buffer); + return buffer[0]; +} +/** Get Y-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_YPOS_BIT + */ +bool MPU9150::getYPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_YPOS_BIT, buffer); + return buffer[0]; +} +/** Get Z-axis negative motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_ZNEG_BIT + */ +bool MPU9150::getZNegMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_ZNEG_BIT, buffer); + return buffer[0]; +} +/** Get Z-axis positive motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_ZPOS_BIT + */ +bool MPU9150::getZPosMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_ZPOS_BIT, buffer); + return buffer[0]; +} +/** Get zero motion detection interrupt status. + * @return Motion detection status + * @see MPU9150_RA_MOT_DETECT_STATUS + * @see MPU9150_MOTION_MOT_ZRMOT_BIT + */ +bool MPU9150::getZeroMotionDetected() { + I2Cdev::readBit(devAddr, MPU9150_RA_MOT_DETECT_STATUS, MPU9150_MOTION_MOT_ZRMOT_BIT, buffer); + return buffer[0]; +} + +// I2C_SLV*_DO register + +/** Write byte to Data Output container for specified slave. + * This register holds the output data written into Slave when Slave is set to + * write mode. For further information regarding Slave control, please + * refer to Registers 37 to 39 and immediately following. + * @param num Slave number (0-3) + * @param data Byte to write + * @see MPU9150_RA_I2C_SLV0_DO + */ +void MPU9150::setSlaveOutputByte(uint8_t num, uint8_t data) { + if (num > 3) return; + I2Cdev::writeByte(devAddr, MPU9150_RA_I2C_SLV0_DO + num, data); +} + +// I2C_MST_DELAY_CTRL register + +/** Get external data shadow delay enabled status. + * This register is used to specify the timing of external sensor data + * shadowing. When DELAY_ES_SHADOW is set to 1, shadowing of external + * sensor data is delayed until all data has been received. + * @return Current external data shadow delay enabled status. + * @see MPU9150_RA_I2C_MST_DELAY_CTRL + * @see MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT + */ +bool MPU9150::getExternalShadowDelayEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_DELAY_CTRL, MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT, buffer); + return buffer[0]; +} +/** Set external data shadow delay enabled status. + * @param enabled New external data shadow delay enabled status. + * @see getExternalShadowDelayEnabled() + * @see MPU9150_RA_I2C_MST_DELAY_CTRL + * @see MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT + */ +void MPU9150::setExternalShadowDelayEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_DELAY_CTRL, MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT, enabled); +} +/** Get slave delay enabled status. + * When a particular slave delay is enabled, the rate of access for the that + * slave device is reduced. When a slave's access rate is decreased relative to + * the Sample Rate, the slave is accessed every: + * + * 1 / (1 + I2C_MST_DLY) Samples + * + * This base Sample Rate in turn is determined by SMPLRT_DIV (register * 25) + * and DLPF_CFG (register 26). + * + * For further information regarding I2C_MST_DLY, please refer to register 52. + * For further information regarding the Sample Rate, please refer to register 25. + * + * @param num Slave number (0-4) + * @return Current slave delay enabled status. + * @see MPU9150_RA_I2C_MST_DELAY_CTRL + * @see MPU9150_DELAYCTRL_I2C_SLV0_DLY_EN_BIT + */ +bool MPU9150::getSlaveDelayEnabled(uint8_t num) { + // MPU9150_DELAYCTRL_I2C_SLV4_DLY_EN_BIT is 4, SLV3 is 3, etc. + if (num > 4) return 0; + I2Cdev::readBit(devAddr, MPU9150_RA_I2C_MST_DELAY_CTRL, num, buffer); + return buffer[0]; +} +/** Set slave delay enabled status. + * @param num Slave number (0-4) + * @param enabled New slave delay enabled status. + * @see MPU9150_RA_I2C_MST_DELAY_CTRL + * @see MPU9150_DELAYCTRL_I2C_SLV0_DLY_EN_BIT + */ +void MPU9150::setSlaveDelayEnabled(uint8_t num, bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_I2C_MST_DELAY_CTRL, num, enabled); +} + +// SIGNAL_PATH_RESET register + +/** Reset gyroscope signal path. + * The reset will revert the signal path analog to digital converters and + * filters to their power up configurations. + * @see MPU9150_RA_SIGNAL_PATH_RESET + * @see MPU9150_PATHRESET_GYRO_RESET_BIT + */ +void MPU9150::resetGyroscopePath() { + I2Cdev::writeBit(devAddr, MPU9150_RA_SIGNAL_PATH_RESET, MPU9150_PATHRESET_GYRO_RESET_BIT, true); +} +/** Reset accelerometer signal path. + * The reset will revert the signal path analog to digital converters and + * filters to their power up configurations. + * @see MPU9150_RA_SIGNAL_PATH_RESET + * @see MPU9150_PATHRESET_ACCEL_RESET_BIT + */ +void MPU9150::resetAccelerometerPath() { + I2Cdev::writeBit(devAddr, MPU9150_RA_SIGNAL_PATH_RESET, MPU9150_PATHRESET_ACCEL_RESET_BIT, true); +} +/** Reset temperature sensor signal path. + * The reset will revert the signal path analog to digital converters and + * filters to their power up configurations. + * @see MPU9150_RA_SIGNAL_PATH_RESET + * @see MPU9150_PATHRESET_TEMP_RESET_BIT + */ +void MPU9150::resetTemperaturePath() { + I2Cdev::writeBit(devAddr, MPU9150_RA_SIGNAL_PATH_RESET, MPU9150_PATHRESET_TEMP_RESET_BIT, true); +} + +// MOT_DETECT_CTRL register + +/** Get accelerometer power-on delay. + * The accelerometer data path provides samples to the sensor registers, Motion + * detection, Zero Motion detection, and Free Fall detection modules. The + * signal path contains filters which must be flushed on wake-up with new + * samples before the detection modules begin operations. The default wake-up + * delay, of 4ms can be lengthened by up to 3ms. This additional delay is + * specified in ACCEL_ON_DELAY in units of 1 LSB = 1 ms. The user may select + * any value above zero unless instructed otherwise by InvenSense. Please refer + * to Section 8 of the MPU-6000/MPU-9150 Product Specification document for + * further information regarding the detection modules. + * @return Current accelerometer power-on delay + * @see MPU9150_RA_MOT_DETECT_CTRL + * @see MPU9150_DETECT_ACCEL_ON_DELAY_BIT + */ +uint8_t MPU9150::getAccelerometerPowerOnDelay() { + I2Cdev::readBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_ACCEL_ON_DELAY_BIT, MPU9150_DETECT_ACCEL_ON_DELAY_LENGTH, buffer); + return buffer[0]; +} +/** Set accelerometer power-on delay. + * @param delay New accelerometer power-on delay (0-3) + * @see getAccelerometerPowerOnDelay() + * @see MPU9150_RA_MOT_DETECT_CTRL + * @see MPU9150_DETECT_ACCEL_ON_DELAY_BIT + */ +void MPU9150::setAccelerometerPowerOnDelay(uint8_t delay) { + I2Cdev::writeBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_ACCEL_ON_DELAY_BIT, MPU9150_DETECT_ACCEL_ON_DELAY_LENGTH, delay); +} +/** Get Free Fall detection counter decrement configuration. + * Detection is registered by the Free Fall detection module after accelerometer + * measurements meet their respective threshold conditions over a specified + * number of samples. When the threshold conditions are met, the corresponding + * detection counter increments by 1. The user may control the rate at which the + * detection counter decrements when the threshold condition is not met by + * configuring FF_COUNT. The decrement rate can be set according to the + * following table: + * + *
+ * FF_COUNT | Counter Decrement
+ * ---------+------------------
+ * 0        | Reset
+ * 1        | 1
+ * 2        | 2
+ * 3        | 4
+ * 
+ * + * When FF_COUNT is configured to 0 (reset), any non-qualifying sample will + * reset the counter to 0. For further information on Free Fall detection, + * please refer to Registers 29 to 32. + * + * @return Current decrement configuration + * @see MPU9150_RA_MOT_DETECT_CTRL + * @see MPU9150_DETECT_FF_COUNT_BIT + */ +uint8_t MPU9150::getFreefallDetectionCounterDecrement() { + I2Cdev::readBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_FF_COUNT_BIT, MPU9150_DETECT_FF_COUNT_LENGTH, buffer); + return buffer[0]; +} +/** Set Free Fall detection counter decrement configuration. + * @param decrement New decrement configuration value + * @see getFreefallDetectionCounterDecrement() + * @see MPU9150_RA_MOT_DETECT_CTRL + * @see MPU9150_DETECT_FF_COUNT_BIT + */ +void MPU9150::setFreefallDetectionCounterDecrement(uint8_t decrement) { + I2Cdev::writeBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_FF_COUNT_BIT, MPU9150_DETECT_FF_COUNT_LENGTH, decrement); +} +/** Get Motion detection counter decrement configuration. + * Detection is registered by the Motion detection module after accelerometer + * measurements meet their respective threshold conditions over a specified + * number of samples. When the threshold conditions are met, the corresponding + * detection counter increments by 1. The user may control the rate at which the + * detection counter decrements when the threshold condition is not met by + * configuring MOT_COUNT. The decrement rate can be set according to the + * following table: + * + *
+ * MOT_COUNT | Counter Decrement
+ * ----------+------------------
+ * 0         | Reset
+ * 1         | 1
+ * 2         | 2
+ * 3         | 4
+ * 
+ * + * When MOT_COUNT is configured to 0 (reset), any non-qualifying sample will + * reset the counter to 0. For further information on Motion detection, + * please refer to Registers 29 to 32. + * + */ +uint8_t MPU9150::getMotionDetectionCounterDecrement() { + I2Cdev::readBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_MOT_COUNT_BIT, MPU9150_DETECT_MOT_COUNT_LENGTH, buffer); + return buffer[0]; +} +/** Set Motion detection counter decrement configuration. + * @param decrement New decrement configuration value + * @see getMotionDetectionCounterDecrement() + * @see MPU9150_RA_MOT_DETECT_CTRL + * @see MPU9150_DETECT_MOT_COUNT_BIT + */ +void MPU9150::setMotionDetectionCounterDecrement(uint8_t decrement) { + I2Cdev::writeBits(devAddr, MPU9150_RA_MOT_DETECT_CTRL, MPU9150_DETECT_MOT_COUNT_BIT, MPU9150_DETECT_MOT_COUNT_LENGTH, decrement); +} + +// USER_CTRL register + +/** Get FIFO enabled status. + * When this bit is set to 0, the FIFO buffer is disabled. The FIFO buffer + * cannot be written to or read from while disabled. The FIFO buffer's state + * does not change unless the MPU-60X0 is power cycled. + * @return Current FIFO enabled status + * @see MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_FIFO_EN_BIT + */ +bool MPU9150::getFIFOEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_FIFO_EN_BIT, buffer); + return buffer[0]; +} +/** Set FIFO enabled status. + * @param enabled New FIFO enabled status + * @see getFIFOEnabled() + * @see MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_FIFO_EN_BIT + */ +void MPU9150::setFIFOEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_FIFO_EN_BIT, enabled); +} +/** Get I2C Master Mode enabled status. + * When this mode is enabled, the MPU-60X0 acts as the I2C Master to the + * external sensor slave devices on the auxiliary I2C bus. When this bit is + * cleared to 0, the auxiliary I2C bus lines (AUX_DA and AUX_CL) are logically + * driven by the primary I2C bus (SDA and SCL). This is a precondition to + * enabling Bypass Mode. For further information regarding Bypass Mode, please + * refer to Register 55. + * @return Current I2C Master Mode enabled status + * @see MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_I2C_MST_EN_BIT + */ +bool MPU9150::getI2CMasterModeEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_I2C_MST_EN_BIT, buffer); + return buffer[0]; +} +/** Set I2C Master Mode enabled status. + * @param enabled New I2C Master Mode enabled status + * @see getI2CMasterModeEnabled() + * @see MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_I2C_MST_EN_BIT + */ +void MPU9150::setI2CMasterModeEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_I2C_MST_EN_BIT, enabled); +} +/** Switch from I2C to SPI mode (MPU-6000 only) + * If this is set, the primary SPI interface will be enabled in place of the + * disabled primary I2C interface. + */ +void MPU9150::switchSPIEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_I2C_IF_DIS_BIT, enabled); +} +/** Reset the FIFO. + * This bit resets the FIFO buffer when set to 1 while FIFO_EN equals 0. This + * bit automatically clears to 0 after the reset has been triggered. + * @see MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_FIFO_RESET_BIT + */ +void MPU9150::resetFIFO() { + I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_FIFO_RESET_BIT, true); +} +/** Reset the I2C Master. + * This bit resets the I2C Master when set to 1 while I2C_MST_EN equals 0. + * This bit automatically clears to 0 after the reset has been triggered. + * @see MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_I2C_MST_RESET_BIT + */ +void MPU9150::resetI2CMaster() { + I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_I2C_MST_RESET_BIT, true); +} +/** Reset all sensor registers and signal paths. + * When set to 1, this bit resets the signal paths for all sensors (gyroscopes, + * accelerometers, and temperature sensor). This operation will also clear the + * sensor registers. This bit automatically clears to 0 after the reset has been + * triggered. + * + * When resetting only the signal path (and not the sensor registers), please + * use Register 104, SIGNAL_PATH_RESET. + * + * @see MPU9150_RA_USER_CTRL + * @see MPU9150_USERCTRL_SIG_COND_RESET_BIT + */ +void MPU9150::resetSensors() { + I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_SIG_COND_RESET_BIT, true); +} + +// PWR_MGMT_1 register + +/** Trigger a full device reset. + * A small delay of ~50ms may be desirable after triggering a reset. + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_DEVICE_RESET_BIT + */ +void MPU9150::reset() { + I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_DEVICE_RESET_BIT, true); +} +/** Get sleep mode status. + * Setting the SLEEP bit in the register puts the device into very low power + * sleep mode. In this mode, only the serial interface and internal registers + * remain active, allowing for a very low standby current. Clearing this bit + * puts the device back into normal mode. To save power, the individual standby + * selections for each of the gyros should be used if any gyro axis is not used + * by the application. + * @return Current sleep mode enabled status + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_SLEEP_BIT + */ +bool MPU9150::getSleepEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_SLEEP_BIT, buffer); + return buffer[0]; +} +/** Set sleep mode status. + * @param enabled New sleep mode enabled status + * @see getSleepEnabled() + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_SLEEP_BIT + */ +void MPU9150::setSleepEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_SLEEP_BIT, enabled); +} +/** Get wake cycle enabled status. + * When this bit is set to 1 and SLEEP is disabled, the MPU-60X0 will cycle + * between sleep mode and waking up to take a single sample of data from active + * sensors at a rate determined by LP_WAKE_CTRL (register 108). + * @return Current sleep mode enabled status + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_CYCLE_BIT + */ +bool MPU9150::getWakeCycleEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_CYCLE_BIT, buffer); + return buffer[0]; +} +/** Set wake cycle enabled status. + * @param enabled New sleep mode enabled status + * @see getWakeCycleEnabled() + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_CYCLE_BIT + */ +void MPU9150::setWakeCycleEnabled(bool enabled) { + I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_CYCLE_BIT, enabled); +} +/** Get temperature sensor enabled status. + * Control the usage of the internal temperature sensor. + * + * Note: this register stores the *disabled* value, but for consistency with the + * rest of the code, the function is named and used with standard true/false + * values to indicate whether the sensor is enabled or disabled, respectively. + * + * @return Current temperature sensor enabled status + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_TEMP_DIS_BIT + */ +bool MPU9150::getTempSensorEnabled() { + I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_TEMP_DIS_BIT, buffer); + return buffer[0] == 0; // 1 is actually disabled here +} +/** Set temperature sensor enabled status. + * Note: this register stores the *disabled* value, but for consistency with the + * rest of the code, the function is named and used with standard true/false + * values to indicate whether the sensor is enabled or disabled, respectively. + * + * @param enabled New temperature sensor enabled status + * @see getTempSensorEnabled() + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_TEMP_DIS_BIT + */ +void MPU9150::setTempSensorEnabled(bool enabled) { + // 1 is actually disabled here + I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_TEMP_DIS_BIT, !enabled); +} +/** Get clock source setting. + * @return Current clock source setting + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_CLKSEL_BIT + * @see MPU9150_PWR1_CLKSEL_LENGTH + */ +uint8_t MPU9150::getClockSource() { + I2Cdev::readBits(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_CLKSEL_BIT, MPU9150_PWR1_CLKSEL_LENGTH, buffer); + return buffer[0]; +} +/** Set clock source setting. + * An internal 8MHz oscillator, gyroscope based clock, or external sources can + * be selected as the MPU-60X0 clock source. When the internal 8 MHz oscillator + * or an external source is chosen as the clock source, the MPU-60X0 can operate + * in low power modes with the gyroscopes disabled. + * + * Upon power up, the MPU-60X0 clock source defaults to the internal oscillator. + * However, it is highly recommended that the device be configured to use one of + * the gyroscopes (or an external clock source) as the clock reference for + * improved stability. The clock source can be selected according to the following table: + * + *
+ * CLK_SEL | Clock Source
+ * --------+--------------------------------------
+ * 0       | Internal oscillator
+ * 1       | PLL with X Gyro reference
+ * 2       | PLL with Y Gyro reference
+ * 3       | PLL with Z Gyro reference
+ * 4       | PLL with external 32.768kHz reference
+ * 5       | PLL with external 19.2MHz reference
+ * 6       | Reserved
+ * 7       | Stops the clock and keeps the timing generator in reset
+ * 
+ * + * @param source New clock source setting + * @see getClockSource() + * @see MPU9150_RA_PWR_MGMT_1 + * @see MPU9150_PWR1_CLKSEL_BIT + * @see MPU9150_PWR1_CLKSEL_LENGTH + */ +void MPU9150::setClockSource(uint8_t source) { + I2Cdev::writeBits(devAddr, MPU9150_RA_PWR_MGMT_1, MPU9150_PWR1_CLKSEL_BIT, MPU9150_PWR1_CLKSEL_LENGTH, source); +} + +// PWR_MGMT_2 register + +/** Get wake frequency in Accel-Only Low Power Mode. + * The MPU-60X0 can be put into Accerlerometer Only Low Power Mode by setting + * PWRSEL to 1 in the Power Management 1 register (Register 107). In this mode, + * the device will power off all devices except for the primary I2C interface, + * waking only the accelerometer at fixed intervals to take a single + * measurement. The frequency of wake-ups can be configured with LP_WAKE_CTRL + * as shown below: + * + *
+ * LP_WAKE_CTRL | Wake-up Frequency
+ * -------------+------------------
+ * 0            | 1.25 Hz
+ * 1            | 2.5 Hz
+ * 2            | 5 Hz
+ * 3            | 10 Hz
+ * 
+ *
+ * For further information regarding the MPU-60X0's power modes, please refer to
+ * Register 107.
+ *
+ * @return Current wake frequency
+ * @see MPU9150_RA_PWR_MGMT_2
+ */
+uint8_t MPU9150::getWakeFrequency() {
+    I2Cdev::readBits(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_LP_WAKE_CTRL_BIT, MPU9150_PWR2_LP_WAKE_CTRL_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set wake frequency in Accel-Only Low Power Mode.
+ * @param frequency New wake frequency
+ * @see MPU9150_RA_PWR_MGMT_2
+ */
+void MPU9150::setWakeFrequency(uint8_t frequency) {
+    I2Cdev::writeBits(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_LP_WAKE_CTRL_BIT, MPU9150_PWR2_LP_WAKE_CTRL_LENGTH, frequency);
+}
+
+/** Get X-axis accelerometer standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_XA_BIT
+ */
+bool MPU9150::getStandbyXAccelEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_XA_BIT, buffer);
+    return buffer[0];
+}
+/** Set X-axis accelerometer standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXAccelEnabled()
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_XA_BIT
+ */
+void MPU9150::setStandbyXAccelEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_XA_BIT, enabled);
+}
+/** Get Y-axis accelerometer standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_YA_BIT
+ */
+bool MPU9150::getStandbyYAccelEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_YA_BIT, buffer);
+    return buffer[0];
+}
+/** Set Y-axis accelerometer standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYAccelEnabled()
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_YA_BIT
+ */
+void MPU9150::setStandbyYAccelEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_YA_BIT, enabled);
+}
+/** Get Z-axis accelerometer standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_ZA_BIT
+ */
+bool MPU9150::getStandbyZAccelEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_ZA_BIT, buffer);
+    return buffer[0];
+}
+/** Set Z-axis accelerometer standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZAccelEnabled()
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_ZA_BIT
+ */
+void MPU9150::setStandbyZAccelEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_ZA_BIT, enabled);
+}
+/** Get X-axis gyroscope standby enabled status.
+ * If enabled, the X-axis will not gather or report data (or use power).
+ * @return Current X-axis standby enabled status
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_XG_BIT
+ */
+bool MPU9150::getStandbyXGyroEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_XG_BIT, buffer);
+    return buffer[0];
+}
+/** Set X-axis gyroscope standby enabled status.
+ * @param New X-axis standby enabled status
+ * @see getStandbyXGyroEnabled()
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_XG_BIT
+ */
+void MPU9150::setStandbyXGyroEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_XG_BIT, enabled);
+}
+/** Get Y-axis gyroscope standby enabled status.
+ * If enabled, the Y-axis will not gather or report data (or use power).
+ * @return Current Y-axis standby enabled status
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_YG_BIT
+ */
+bool MPU9150::getStandbyYGyroEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_YG_BIT, buffer);
+    return buffer[0];
+}
+/** Set Y-axis gyroscope standby enabled status.
+ * @param New Y-axis standby enabled status
+ * @see getStandbyYGyroEnabled()
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_YG_BIT
+ */
+void MPU9150::setStandbyYGyroEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_YG_BIT, enabled);
+}
+/** Get Z-axis gyroscope standby enabled status.
+ * If enabled, the Z-axis will not gather or report data (or use power).
+ * @return Current Z-axis standby enabled status
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_ZG_BIT
+ */
+bool MPU9150::getStandbyZGyroEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_ZG_BIT, buffer);
+    return buffer[0];
+}
+/** Set Z-axis gyroscope standby enabled status.
+ * @param New Z-axis standby enabled status
+ * @see getStandbyZGyroEnabled()
+ * @see MPU9150_RA_PWR_MGMT_2
+ * @see MPU9150_PWR2_STBY_ZG_BIT
+ */
+void MPU9150::setStandbyZGyroEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_PWR_MGMT_2, MPU9150_PWR2_STBY_ZG_BIT, enabled);
+}
+
+// FIFO_COUNT* registers
+
+/** Get current FIFO buffer size.
+ * This value indicates the number of bytes stored in the FIFO buffer. This
+ * number is in turn the number of bytes that can be read from the FIFO buffer
+ * and it is directly proportional to the number of samples available given the
+ * set of sensor data bound to be stored in the FIFO (register 35 and 36).
+ * @return Current FIFO buffer size
+ */
+uint16_t MPU9150::getFIFOCount() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_FIFO_COUNTH, 2, buffer);
+    return (((uint16_t)buffer[0]) << 8) | buffer[1];
+}
+
+// FIFO_R_W register
+
+/** Get byte from FIFO buffer.
+ * This register is used to read and write data from the FIFO buffer. Data is
+ * written to the FIFO in order of register number (from lowest to highest). If
+ * all the FIFO enable flags (see below) are enabled and all External Sensor
+ * Data registers (Registers 73 to 96) are associated with a Slave device, the
+ * contents of registers 59 through 96 will be written in order at the Sample
+ * Rate.
+ *
+ * The contents of the sensor data registers (Registers 59 to 96) are written
+ * into the FIFO buffer when their corresponding FIFO enable flags are set to 1
+ * in FIFO_EN (Register 35). An additional flag for the sensor data registers
+ * associated with I2C Slave 3 can be found in I2C_MST_CTRL (Register 36).
+ *
+ * If the FIFO buffer has overflowed, the status bit FIFO_OFLOW_INT is
+ * automatically set to 1. This bit is located in INT_STATUS (Register 58).
+ * When the FIFO buffer has overflowed, the oldest data will be lost and new
+ * data will be written to the FIFO.
+ *
+ * If the FIFO buffer is empty, reading this register will return the last byte
+ * that was previously read from the FIFO until new data is available. The user
+ * should check FIFO_COUNT to ensure that the FIFO buffer is not read when
+ * empty.
+ *
+ * @return Byte from FIFO buffer
+ */
+uint8_t MPU9150::getFIFOByte() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_FIFO_R_W, buffer);
+    return buffer[0];
+}
+void MPU9150::getFIFOBytes(uint8_t *data, uint8_t length) {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_FIFO_R_W, length, data);
+}
+/** Write byte to FIFO buffer.
+ * @see getFIFOByte()
+ * @see MPU9150_RA_FIFO_R_W
+ */
+void MPU9150::setFIFOByte(uint8_t data) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_FIFO_R_W, data);
+}
+
+// WHO_AM_I register
+
+/** Get Device ID.
+ * This register is used to verify the identity of the device (0b110100, 0x34).
+ * @return Device ID (6 bits only! should be 0x34)
+ * @see MPU9150_RA_WHO_AM_I
+ * @see MPU9150_WHO_AM_I_BIT
+ * @see MPU9150_WHO_AM_I_LENGTH
+ */
+uint8_t MPU9150::getDeviceID() {
+    I2Cdev::readBits(devAddr, MPU9150_RA_WHO_AM_I, MPU9150_WHO_AM_I_BIT, MPU9150_WHO_AM_I_LENGTH, buffer);
+    return buffer[0];
+}
+/** Set Device ID.
+ * Write a new ID into the WHO_AM_I register (no idea why this should ever be
+ * necessary though).
+ * @param id New device ID to set.
+ * @see getDeviceID()
+ * @see MPU9150_RA_WHO_AM_I
+ * @see MPU9150_WHO_AM_I_BIT
+ * @see MPU9150_WHO_AM_I_LENGTH
+ */
+void MPU9150::setDeviceID(uint8_t id) {
+    I2Cdev::writeBits(devAddr, MPU9150_RA_WHO_AM_I, MPU9150_WHO_AM_I_BIT, MPU9150_WHO_AM_I_LENGTH, id);
+}
+
+// ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+
+// XG_OFFS_TC register
+
+uint8_t MPU9150::getOTPBankValid() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_XG_OFFS_TC, MPU9150_TC_OTP_BNK_VLD_BIT, buffer);
+    return buffer[0];
+}
+void MPU9150::setOTPBankValid(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_XG_OFFS_TC, MPU9150_TC_OTP_BNK_VLD_BIT, enabled);
+}
+int8_t MPU9150::getXGyroOffsetTC() {
+    I2Cdev::readBits(devAddr, MPU9150_RA_XG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU9150::setXGyroOffsetTC(int8_t offset) {
+    I2Cdev::writeBits(devAddr, MPU9150_RA_XG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, offset);
+}
+
+// YG_OFFS_TC register
+
+int8_t MPU9150::getYGyroOffsetTC() {
+    I2Cdev::readBits(devAddr, MPU9150_RA_YG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU9150::setYGyroOffsetTC(int8_t offset) {
+    I2Cdev::writeBits(devAddr, MPU9150_RA_YG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, offset);
+}
+
+// ZG_OFFS_TC register
+
+int8_t MPU9150::getZGyroOffsetTC() {
+    I2Cdev::readBits(devAddr, MPU9150_RA_ZG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, buffer);
+    return buffer[0];
+}
+void MPU9150::setZGyroOffsetTC(int8_t offset) {
+    I2Cdev::writeBits(devAddr, MPU9150_RA_ZG_OFFS_TC, MPU9150_TC_OFFSET_BIT, MPU9150_TC_OFFSET_LENGTH, offset);
+}
+
+// X_FINE_GAIN register
+
+int8_t MPU9150::getXFineGain() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_X_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU9150::setXFineGain(int8_t gain) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_X_FINE_GAIN, gain);
+}
+
+// Y_FINE_GAIN register
+
+int8_t MPU9150::getYFineGain() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_Y_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU9150::setYFineGain(int8_t gain) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_Y_FINE_GAIN, gain);
+}
+
+// Z_FINE_GAIN register
+
+int8_t MPU9150::getZFineGain() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_Z_FINE_GAIN, buffer);
+    return buffer[0];
+}
+void MPU9150::setZFineGain(int8_t gain) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_Z_FINE_GAIN, gain);
+}
+
+// XA_OFFS_* registers
+
+int16_t MPU9150::getXAccelOffset() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_XA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9150::setXAccelOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9150_RA_XA_OFFS_H, offset);
+}
+
+// YA_OFFS_* register
+
+int16_t MPU9150::getYAccelOffset() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_YA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9150::setYAccelOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9150_RA_YA_OFFS_H, offset);
+}
+
+// ZA_OFFS_* register
+
+int16_t MPU9150::getZAccelOffset() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_ZA_OFFS_H, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9150::setZAccelOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9150_RA_ZA_OFFS_H, offset);
+}
+
+// XG_OFFS_USR* registers
+
+int16_t MPU9150::getXGyroOffset() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_XG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9150::setXGyroOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9150_RA_XG_OFFS_USRH, offset);
+}
+
+// YG_OFFS_USR* register
+
+int16_t MPU9150::getYGyroOffset() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_YG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9150::setYGyroOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9150_RA_YG_OFFS_USRH, offset);
+}
+
+// ZG_OFFS_USR* register
+
+int16_t MPU9150::getZGyroOffset() {
+    I2Cdev::readBytes(devAddr, MPU9150_RA_ZG_OFFS_USRH, 2, buffer);
+    return (((int16_t)buffer[0]) << 8) | buffer[1];
+}
+void MPU9150::setZGyroOffset(int16_t offset) {
+    I2Cdev::writeWord(devAddr, MPU9150_RA_ZG_OFFS_USRH, offset);
+}
+
+// INT_ENABLE register (DMP functions)
+
+bool MPU9150::getIntPLLReadyEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+    return buffer[0];
+}
+void MPU9150::setIntPLLReadyEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_PLL_RDY_INT_BIT, enabled);
+}
+bool MPU9150::getIntDMPEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_DMP_INT_BIT, buffer);
+    return buffer[0];
+}
+void MPU9150::setIntDMPEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_INT_ENABLE, MPU9150_INTERRUPT_DMP_INT_BIT, enabled);
+}
+
+// DMP_INT_STATUS
+
+bool MPU9150::getDMPInt5Status() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_5_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9150::getDMPInt4Status() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_4_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9150::getDMPInt3Status() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_3_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9150::getDMPInt2Status() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_2_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9150::getDMPInt1Status() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_1_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9150::getDMPInt0Status() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_DMP_INT_STATUS, MPU9150_DMPINT_0_BIT, buffer);
+    return buffer[0];
+}
+
+// INT_STATUS register (DMP functions)
+
+bool MPU9150::getIntPLLReadyStatus() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_PLL_RDY_INT_BIT, buffer);
+    return buffer[0];
+}
+bool MPU9150::getIntDMPStatus() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_INT_STATUS, MPU9150_INTERRUPT_DMP_INT_BIT, buffer);
+    return buffer[0];
+}
+
+// USER_CTRL register (DMP functions)
+
+bool MPU9150::getDMPEnabled() {
+    I2Cdev::readBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_DMP_EN_BIT, buffer);
+    return buffer[0];
+}
+void MPU9150::setDMPEnabled(bool enabled) {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_DMP_EN_BIT, enabled);
+}
+void MPU9150::resetDMP() {
+    I2Cdev::writeBit(devAddr, MPU9150_RA_USER_CTRL, MPU9150_USERCTRL_DMP_RESET_BIT, true);
+}
+
+// BANK_SEL register
+
+void MPU9150::setMemoryBank(uint8_t bank, bool prefetchEnabled, bool userBank) {
+    bank &= 0x1F;
+    if (userBank) bank |= 0x20;
+    if (prefetchEnabled) bank |= 0x40;
+    I2Cdev::writeByte(devAddr, MPU9150_RA_BANK_SEL, bank);
+}
+
+// MEM_START_ADDR register
+
+void MPU9150::setMemoryStartAddress(uint8_t address) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_MEM_START_ADDR, address);
+}
+
+// MEM_R_W register
+
+uint8_t MPU9150::readMemoryByte() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_MEM_R_W, buffer);
+    return buffer[0];
+}
+void MPU9150::writeMemoryByte(uint8_t data) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_MEM_R_W, data);
+}
+void MPU9150::readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address) {
+    setMemoryBank(bank);
+    setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    for (uint16_t i = 0; i < dataSize;) {
+        // determine correct chunk size according to bank position and data size
+        chunkSize = MPU9150_DMP_MEMORY_CHUNK_SIZE;
+
+        // make sure we don't go past the data size
+        if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+        // make sure this chunk doesn't go past the bank boundary (256 bytes)
+        if (chunkSize > 256 - address) chunkSize = 256 - address;
+
+        // read the chunk of data as specified
+        I2Cdev::readBytes(devAddr, MPU9150_RA_MEM_R_W, chunkSize, data + i);
+        
+        // increase byte index by [chunkSize]
+        i += chunkSize;
+
+        // uint8_t automatically wraps to 0 at 256
+        address += chunkSize;
+
+        // if we aren't done, update bank (if necessary) and address
+        if (i < dataSize) {
+            if (address == 0) bank++;
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+        }
+    }
+}
+bool MPU9150::writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify, bool useProgMem) {
+    setMemoryBank(bank);
+    setMemoryStartAddress(address);
+    uint8_t chunkSize;
+    uint8_t *verifyBuffer;
+    uint8_t *progBuffer;
+    uint16_t i;
+    uint8_t j;
+    if (verify) verifyBuffer = (uint8_t *)malloc(MPU9150_DMP_MEMORY_CHUNK_SIZE);
+    if (useProgMem) progBuffer = (uint8_t *)malloc(MPU9150_DMP_MEMORY_CHUNK_SIZE);
+    else progBuffer = NULL;
+    for (i = 0; i < dataSize;) {
+        // determine correct chunk size according to bank position and data size
+        chunkSize = MPU9150_DMP_MEMORY_CHUNK_SIZE;
+
+        // make sure we don't go past the data size
+        if (i + chunkSize > dataSize) chunkSize = dataSize - i;
+
+        // make sure this chunk doesn't go past the bank boundary (256 bytes)
+        if (chunkSize > 256 - address) chunkSize = 256 - address;
+        
+        if (useProgMem) {
+            // write the chunk of data as specified
+            for (j = 0; j < chunkSize; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+        } else {
+            // write the chunk of data as specified
+            progBuffer = (uint8_t *)data + i;
+        }
+
+        I2Cdev::writeBytes(devAddr, MPU9150_RA_MEM_R_W, chunkSize, progBuffer);
+
+        // verify data if needed
+        if (verify && verifyBuffer) {
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+            I2Cdev::readBytes(devAddr, MPU9150_RA_MEM_R_W, chunkSize, verifyBuffer);
+            if (memcmp(progBuffer, verifyBuffer, chunkSize) != 0) {
+                /*Serial.print("Block write verification error, bank ");
+                Serial.print(bank, DEC);
+                Serial.print(", address ");
+                Serial.print(address, DEC);
+                Serial.print("!\nExpected:");
+                for (j = 0; j < chunkSize; j++) {
+                    Serial.print(" 0x");
+                    if (progBuffer[j] < 16) Serial.print("0");
+                    Serial.print(progBuffer[j], HEX);
+                }
+                Serial.print("\nReceived:");
+                for (uint8_t j = 0; j < chunkSize; j++) {
+                    Serial.print(" 0x");
+                    if (verifyBuffer[i + j] < 16) Serial.print("0");
+                    Serial.print(verifyBuffer[i + j], HEX);
+                }
+                Serial.print("\n");*/
+                free(verifyBuffer);
+                if (useProgMem) free(progBuffer);
+                return false; // uh oh.
+            }
+        }
+
+        // increase byte index by [chunkSize]
+        i += chunkSize;
+
+        // uint8_t automatically wraps to 0 at 256
+        address += chunkSize;
+
+        // if we aren't done, update bank (if necessary) and address
+        if (i < dataSize) {
+            if (address == 0) bank++;
+            setMemoryBank(bank);
+            setMemoryStartAddress(address);
+        }
+    }
+    if (verify) free(verifyBuffer);
+    if (useProgMem) free(progBuffer);
+    return true;
+}
+bool MPU9150::writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank, uint8_t address, bool verify) {
+    return writeMemoryBlock(data, dataSize, bank, address, verify, true);
+}
+bool MPU9150::writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem) {
+    uint8_t *progBuffer, success, special;
+    uint16_t i, j;
+    if (useProgMem) {
+        progBuffer = (uint8_t *)malloc(8); // assume 8-byte blocks, realloc later if necessary
+    } else {
+        progBuffer = NULL;
+    }
+
+    // config set data is a long string of blocks with the following structure:
+    // [bank] [offset] [length] [byte[0], byte[1], ..., byte[length]]
+    uint8_t bank, offset, length;
+    for (i = 0; i < dataSize;) {
+        if (useProgMem) {
+            bank = pgm_read_byte(data + i++);
+            offset = pgm_read_byte(data + i++);
+            length = pgm_read_byte(data + i++);
+        } else {
+            bank = data[i++];
+            offset = data[i++];
+            length = data[i++];
+        }
+
+        // write data or perform special action
+        if (length > 0) {
+            // regular block of data to write
+            /*Serial.print("Writing config block to bank ");
+            Serial.print(bank);
+            Serial.print(", offset ");
+            Serial.print(offset);
+            Serial.print(", length=");
+            Serial.println(length);*/
+            if (useProgMem) {
+                if (sizeof(progBuffer) < length) progBuffer = (uint8_t *)realloc(progBuffer, length);
+                for (j = 0; j < length; j++) progBuffer[j] = pgm_read_byte(data + i + j);
+            } else {
+                progBuffer = (uint8_t *)data + i;
+            }
+            success = writeMemoryBlock(progBuffer, length, bank, offset, true);
+            i += length;
+        } else {
+            // special instruction
+            // NOTE: this kind of behavior (what and when to do certain things)
+            // is totally undocumented. This code is in here based on observed
+            // behavior only, and exactly why (or even whether) it has to be here
+            // is anybody's guess for now.
+            if (useProgMem) {
+                special = pgm_read_byte(data + i++);
+            } else {
+                special = data[i++];
+            }
+            /*Serial.print("Special command code ");
+            Serial.print(special, HEX);
+            Serial.println(" found...");*/
+            if (special == 0x01) {
+                // enable DMP-related interrupts
+                
+                //setIntZeroMotionEnabled(true);
+                //setIntFIFOBufferOverflowEnabled(true);
+                //setIntDMPEnabled(true);
+                I2Cdev::writeByte(devAddr, MPU9150_RA_INT_ENABLE, 0x32);  // single operation
+
+                success = true;
+            } else {
+                // unknown special command
+                success = false;
+            }
+        }
+        
+        if (!success) {
+            if (useProgMem) free(progBuffer);
+            return false; // uh oh
+        }
+    }
+    if (useProgMem) free(progBuffer);
+    return true;
+}
+bool MPU9150::writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize) {
+    return writeDMPConfigurationSet(data, dataSize, true);
+}
+
+// DMP_CFG_1 register
+
+uint8_t MPU9150::getDMPConfig1() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_DMP_CFG_1, buffer);
+    return buffer[0];
+}
+void MPU9150::setDMPConfig1(uint8_t config) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_DMP_CFG_1, config);
+}
+
+// DMP_CFG_2 register
+
+uint8_t MPU9150::getDMPConfig2() {
+    I2Cdev::readByte(devAddr, MPU9150_RA_DMP_CFG_2, buffer);
+    return buffer[0];
+}
+void MPU9150::setDMPConfig2(uint8_t config) {
+    I2Cdev::writeByte(devAddr, MPU9150_RA_DMP_CFG_2, config);
+}
diff --git a/libraries/MPU9150/MPU9150.h b/libraries/MPU9150/MPU9150.h
new file mode 100644
index 0000000..90ee1cc
--- /dev/null
+++ b/libraries/MPU9150/MPU9150.h
@@ -0,0 +1,1038 @@
+// I2Cdev library collection - MPU9150 I2C device class
+// Based on InvenSense MPU-9150 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 10/3/2011 by Jeff Rowberg 
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+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.
+===============================================
+*/
+
+#ifndef _MPU9150_H_
+#define _MPU9150_H_
+
+#include "I2Cdev.h"
+
+// Tom Carpenter's conditional PROGMEM code
+// http://forum.arduino.cc/index.php?topic=129407.0
+#ifdef __AVR__
+    #include 
+#else
+    // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen
+    #ifndef __PGMSPACE_H_
+        #define __PGMSPACE_H_ 1
+        #include 
+
+        #define PROGMEM
+        #define PGM_P  const char *
+        #define PSTR(str) (str)
+        #define F(x) x
+
+        typedef void prog_void;
+        typedef char prog_char;
+        typedef unsigned char prog_uchar;
+        typedef int8_t prog_int8_t;
+        typedef uint8_t prog_uint8_t;
+        typedef int16_t prog_int16_t;
+        typedef uint16_t prog_uint16_t;
+        typedef int32_t prog_int32_t;
+        typedef uint32_t prog_uint32_t;
+
+        #define strcpy_P(dest, src) strcpy((dest), (src))
+        #define strcat_P(dest, src) strcat((dest), (src))
+        #define strcmp_P(a, b) strcmp((a), (b))
+
+        #define pgm_read_byte(addr) (*(const unsigned char *)(addr))
+        #define pgm_read_word(addr) (*(const unsigned short *)(addr))
+        #define pgm_read_dword(addr) (*(const unsigned long *)(addr))
+        #define pgm_read_float(addr) (*(const float *)(addr))
+
+        #define pgm_read_byte_near(addr) pgm_read_byte(addr)
+        #define pgm_read_word_near(addr) pgm_read_word(addr)
+        #define pgm_read_dword_near(addr) pgm_read_dword(addr)
+        #define pgm_read_float_near(addr) pgm_read_float(addr)
+        #define pgm_read_byte_far(addr) pgm_read_byte(addr)
+        #define pgm_read_word_far(addr) pgm_read_word(addr)
+        #define pgm_read_dword_far(addr) pgm_read_dword(addr)
+        #define pgm_read_float_far(addr) pgm_read_float(addr)
+    #endif
+#endif
+
+//Magnetometer Registers
+#define MPU9150_RA_MAG_ADDRESS		0x0C
+#define MPU9150_RA_MAG_XOUT_L		0x03
+#define MPU9150_RA_MAG_XOUT_H		0x04
+#define MPU9150_RA_MAG_YOUT_L		0x05
+#define MPU9150_RA_MAG_YOUT_H		0x06
+#define MPU9150_RA_MAG_ZOUT_L		0x07
+#define MPU9150_RA_MAG_ZOUT_H		0x08
+
+#define MPU9150_ADDRESS_AD0_LOW     0x68 // address pin low (GND), default for InvenSense evaluation board
+#define MPU9150_ADDRESS_AD0_HIGH    0x69 // address pin high (VCC)
+#define MPU9150_DEFAULT_ADDRESS     MPU9150_ADDRESS_AD0_LOW
+
+#define MPU9150_RA_XG_OFFS_TC       0x00 //[7] PWR_MODE, [6:1] XG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU9150_RA_YG_OFFS_TC       0x01 //[7] PWR_MODE, [6:1] YG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU9150_RA_ZG_OFFS_TC       0x02 //[7] PWR_MODE, [6:1] ZG_OFFS_TC, [0] OTP_BNK_VLD
+#define MPU9150_RA_X_FINE_GAIN      0x03 //[7:0] X_FINE_GAIN
+#define MPU9150_RA_Y_FINE_GAIN      0x04 //[7:0] Y_FINE_GAIN
+#define MPU9150_RA_Z_FINE_GAIN      0x05 //[7:0] Z_FINE_GAIN
+#define MPU9150_RA_XA_OFFS_H        0x06 //[15:0] XA_OFFS
+#define MPU9150_RA_XA_OFFS_L_TC     0x07
+#define MPU9150_RA_YA_OFFS_H        0x08 //[15:0] YA_OFFS
+#define MPU9150_RA_YA_OFFS_L_TC     0x09
+#define MPU9150_RA_ZA_OFFS_H        0x0A //[15:0] ZA_OFFS
+#define MPU9150_RA_ZA_OFFS_L_TC     0x0B
+#define MPU9150_RA_XG_OFFS_USRH     0x13 //[15:0] XG_OFFS_USR
+#define MPU9150_RA_XG_OFFS_USRL     0x14
+#define MPU9150_RA_YG_OFFS_USRH     0x15 //[15:0] YG_OFFS_USR
+#define MPU9150_RA_YG_OFFS_USRL     0x16
+#define MPU9150_RA_ZG_OFFS_USRH     0x17 //[15:0] ZG_OFFS_USR
+#define MPU9150_RA_ZG_OFFS_USRL     0x18
+#define MPU9150_RA_SMPLRT_DIV       0x19
+#define MPU9150_RA_CONFIG           0x1A
+#define MPU9150_RA_GYRO_CONFIG      0x1B
+#define MPU9150_RA_ACCEL_CONFIG     0x1C
+#define MPU9150_RA_FF_THR           0x1D
+#define MPU9150_RA_FF_DUR           0x1E
+#define MPU9150_RA_MOT_THR          0x1F
+#define MPU9150_RA_MOT_DUR          0x20
+#define MPU9150_RA_ZRMOT_THR        0x21
+#define MPU9150_RA_ZRMOT_DUR        0x22
+#define MPU9150_RA_FIFO_EN          0x23
+#define MPU9150_RA_I2C_MST_CTRL     0x24
+#define MPU9150_RA_I2C_SLV0_ADDR    0x25
+#define MPU9150_RA_I2C_SLV0_REG     0x26
+#define MPU9150_RA_I2C_SLV0_CTRL    0x27
+#define MPU9150_RA_I2C_SLV1_ADDR    0x28
+#define MPU9150_RA_I2C_SLV1_REG     0x29
+#define MPU9150_RA_I2C_SLV1_CTRL    0x2A
+#define MPU9150_RA_I2C_SLV2_ADDR    0x2B
+#define MPU9150_RA_I2C_SLV2_REG     0x2C
+#define MPU9150_RA_I2C_SLV2_CTRL    0x2D
+#define MPU9150_RA_I2C_SLV3_ADDR    0x2E
+#define MPU9150_RA_I2C_SLV3_REG     0x2F
+#define MPU9150_RA_I2C_SLV3_CTRL    0x30
+#define MPU9150_RA_I2C_SLV4_ADDR    0x31
+#define MPU9150_RA_I2C_SLV4_REG     0x32
+#define MPU9150_RA_I2C_SLV4_DO      0x33
+#define MPU9150_RA_I2C_SLV4_CTRL    0x34
+#define MPU9150_RA_I2C_SLV4_DI      0x35
+#define MPU9150_RA_I2C_MST_STATUS   0x36
+#define MPU9150_RA_INT_PIN_CFG      0x37
+#define MPU9150_RA_INT_ENABLE       0x38
+#define MPU9150_RA_DMP_INT_STATUS   0x39
+#define MPU9150_RA_INT_STATUS       0x3A
+#define MPU9150_RA_ACCEL_XOUT_H     0x3B
+#define MPU9150_RA_ACCEL_XOUT_L     0x3C
+#define MPU9150_RA_ACCEL_YOUT_H     0x3D
+#define MPU9150_RA_ACCEL_YOUT_L     0x3E
+#define MPU9150_RA_ACCEL_ZOUT_H     0x3F
+#define MPU9150_RA_ACCEL_ZOUT_L     0x40
+#define MPU9150_RA_TEMP_OUT_H       0x41
+#define MPU9150_RA_TEMP_OUT_L       0x42
+#define MPU9150_RA_GYRO_XOUT_H      0x43
+#define MPU9150_RA_GYRO_XOUT_L      0x44
+#define MPU9150_RA_GYRO_YOUT_H      0x45
+#define MPU9150_RA_GYRO_YOUT_L      0x46
+#define MPU9150_RA_GYRO_ZOUT_H      0x47
+#define MPU9150_RA_GYRO_ZOUT_L      0x48
+#define MPU9150_RA_EXT_SENS_DATA_00 0x49
+#define MPU9150_RA_EXT_SENS_DATA_01 0x4A
+#define MPU9150_RA_EXT_SENS_DATA_02 0x4B
+#define MPU9150_RA_EXT_SENS_DATA_03 0x4C
+#define MPU9150_RA_EXT_SENS_DATA_04 0x4D
+#define MPU9150_RA_EXT_SENS_DATA_05 0x4E
+#define MPU9150_RA_EXT_SENS_DATA_06 0x4F
+#define MPU9150_RA_EXT_SENS_DATA_07 0x50
+#define MPU9150_RA_EXT_SENS_DATA_08 0x51
+#define MPU9150_RA_EXT_SENS_DATA_09 0x52
+#define MPU9150_RA_EXT_SENS_DATA_10 0x53
+#define MPU9150_RA_EXT_SENS_DATA_11 0x54
+#define MPU9150_RA_EXT_SENS_DATA_12 0x55
+#define MPU9150_RA_EXT_SENS_DATA_13 0x56
+#define MPU9150_RA_EXT_SENS_DATA_14 0x57
+#define MPU9150_RA_EXT_SENS_DATA_15 0x58
+#define MPU9150_RA_EXT_SENS_DATA_16 0x59
+#define MPU9150_RA_EXT_SENS_DATA_17 0x5A
+#define MPU9150_RA_EXT_SENS_DATA_18 0x5B
+#define MPU9150_RA_EXT_SENS_DATA_19 0x5C
+#define MPU9150_RA_EXT_SENS_DATA_20 0x5D
+#define MPU9150_RA_EXT_SENS_DATA_21 0x5E
+#define MPU9150_RA_EXT_SENS_DATA_22 0x5F
+#define MPU9150_RA_EXT_SENS_DATA_23 0x60
+#define MPU9150_RA_MOT_DETECT_STATUS    0x61
+#define MPU9150_RA_I2C_SLV0_DO      0x63
+#define MPU9150_RA_I2C_SLV1_DO      0x64
+#define MPU9150_RA_I2C_SLV2_DO      0x65
+#define MPU9150_RA_I2C_SLV3_DO      0x66
+#define MPU9150_RA_I2C_MST_DELAY_CTRL   0x67
+#define MPU9150_RA_SIGNAL_PATH_RESET    0x68
+#define MPU9150_RA_MOT_DETECT_CTRL      0x69
+#define MPU9150_RA_USER_CTRL        0x6A
+#define MPU9150_RA_PWR_MGMT_1       0x6B
+#define MPU9150_RA_PWR_MGMT_2       0x6C
+#define MPU9150_RA_BANK_SEL         0x6D
+#define MPU9150_RA_MEM_START_ADDR   0x6E
+#define MPU9150_RA_MEM_R_W          0x6F
+#define MPU9150_RA_DMP_CFG_1        0x70
+#define MPU9150_RA_DMP_CFG_2        0x71
+#define MPU9150_RA_FIFO_COUNTH      0x72
+#define MPU9150_RA_FIFO_COUNTL      0x73
+#define MPU9150_RA_FIFO_R_W         0x74
+#define MPU9150_RA_WHO_AM_I         0x75
+
+#define MPU9150_TC_PWR_MODE_BIT     7
+#define MPU9150_TC_OFFSET_BIT       6
+#define MPU9150_TC_OFFSET_LENGTH    6
+#define MPU9150_TC_OTP_BNK_VLD_BIT  0
+
+#define MPU9150_VDDIO_LEVEL_VLOGIC  0
+#define MPU9150_VDDIO_LEVEL_VDD     1
+
+#define MPU9150_CFG_EXT_SYNC_SET_BIT    5
+#define MPU9150_CFG_EXT_SYNC_SET_LENGTH 3
+#define MPU9150_CFG_DLPF_CFG_BIT    2
+#define MPU9150_CFG_DLPF_CFG_LENGTH 3
+
+#define MPU9150_EXT_SYNC_DISABLED       0x0
+#define MPU9150_EXT_SYNC_TEMP_OUT_L     0x1
+#define MPU9150_EXT_SYNC_GYRO_XOUT_L    0x2
+#define MPU9150_EXT_SYNC_GYRO_YOUT_L    0x3
+#define MPU9150_EXT_SYNC_GYRO_ZOUT_L    0x4
+#define MPU9150_EXT_SYNC_ACCEL_XOUT_L   0x5
+#define MPU9150_EXT_SYNC_ACCEL_YOUT_L   0x6
+#define MPU9150_EXT_SYNC_ACCEL_ZOUT_L   0x7
+
+#define MPU9150_DLPF_BW_256         0x00
+#define MPU9150_DLPF_BW_188         0x01
+#define MPU9150_DLPF_BW_98          0x02
+#define MPU9150_DLPF_BW_42          0x03
+#define MPU9150_DLPF_BW_20          0x04
+#define MPU9150_DLPF_BW_10          0x05
+#define MPU9150_DLPF_BW_5           0x06
+
+#define MPU9150_GCONFIG_FS_SEL_BIT      4
+#define MPU9150_GCONFIG_FS_SEL_LENGTH   2
+
+#define MPU9150_GYRO_FS_250         0x00
+#define MPU9150_GYRO_FS_500         0x01
+#define MPU9150_GYRO_FS_1000        0x02
+#define MPU9150_GYRO_FS_2000        0x03
+
+#define MPU9150_ACONFIG_XA_ST_BIT           7
+#define MPU9150_ACONFIG_YA_ST_BIT           6
+#define MPU9150_ACONFIG_ZA_ST_BIT           5
+#define MPU9150_ACONFIG_AFS_SEL_BIT         4
+#define MPU9150_ACONFIG_AFS_SEL_LENGTH      2
+#define MPU9150_ACONFIG_ACCEL_HPF_BIT       2
+#define MPU9150_ACONFIG_ACCEL_HPF_LENGTH    3
+
+#define MPU9150_ACCEL_FS_2          0x00
+#define MPU9150_ACCEL_FS_4          0x01
+#define MPU9150_ACCEL_FS_8          0x02
+#define MPU9150_ACCEL_FS_16         0x03
+
+#define MPU9150_DHPF_RESET          0x00
+#define MPU9150_DHPF_5              0x01
+#define MPU9150_DHPF_2P5            0x02
+#define MPU9150_DHPF_1P25           0x03
+#define MPU9150_DHPF_0P63           0x04
+#define MPU9150_DHPF_HOLD           0x07
+
+#define MPU9150_TEMP_FIFO_EN_BIT    7
+#define MPU9150_XG_FIFO_EN_BIT      6
+#define MPU9150_YG_FIFO_EN_BIT      5
+#define MPU9150_ZG_FIFO_EN_BIT      4
+#define MPU9150_ACCEL_FIFO_EN_BIT   3
+#define MPU9150_SLV2_FIFO_EN_BIT    2
+#define MPU9150_SLV1_FIFO_EN_BIT    1
+#define MPU9150_SLV0_FIFO_EN_BIT    0
+
+#define MPU9150_MULT_MST_EN_BIT     7
+#define MPU9150_WAIT_FOR_ES_BIT     6
+#define MPU9150_SLV_3_FIFO_EN_BIT   5
+#define MPU9150_I2C_MST_P_NSR_BIT   4
+#define MPU9150_I2C_MST_CLK_BIT     3
+#define MPU9150_I2C_MST_CLK_LENGTH  4
+
+#define MPU9150_CLOCK_DIV_348       0x0
+#define MPU9150_CLOCK_DIV_333       0x1
+#define MPU9150_CLOCK_DIV_320       0x2
+#define MPU9150_CLOCK_DIV_308       0x3
+#define MPU9150_CLOCK_DIV_296       0x4
+#define MPU9150_CLOCK_DIV_286       0x5
+#define MPU9150_CLOCK_DIV_276       0x6
+#define MPU9150_CLOCK_DIV_267       0x7
+#define MPU9150_CLOCK_DIV_258       0x8
+#define MPU9150_CLOCK_DIV_500       0x9
+#define MPU9150_CLOCK_DIV_471       0xA
+#define MPU9150_CLOCK_DIV_444       0xB
+#define MPU9150_CLOCK_DIV_421       0xC
+#define MPU9150_CLOCK_DIV_400       0xD
+#define MPU9150_CLOCK_DIV_381       0xE
+#define MPU9150_CLOCK_DIV_364       0xF
+
+#define MPU9150_I2C_SLV_RW_BIT      7
+#define MPU9150_I2C_SLV_ADDR_BIT    6
+#define MPU9150_I2C_SLV_ADDR_LENGTH 7
+#define MPU9150_I2C_SLV_EN_BIT      7
+#define MPU9150_I2C_SLV_BYTE_SW_BIT 6
+#define MPU9150_I2C_SLV_REG_DIS_BIT 5
+#define MPU9150_I2C_SLV_GRP_BIT     4
+#define MPU9150_I2C_SLV_LEN_BIT     3
+#define MPU9150_I2C_SLV_LEN_LENGTH  4
+
+#define MPU9150_I2C_SLV4_RW_BIT         7
+#define MPU9150_I2C_SLV4_ADDR_BIT       6
+#define MPU9150_I2C_SLV4_ADDR_LENGTH    7
+#define MPU9150_I2C_SLV4_EN_BIT         7
+#define MPU9150_I2C_SLV4_INT_EN_BIT     6
+#define MPU9150_I2C_SLV4_REG_DIS_BIT    5
+#define MPU9150_I2C_SLV4_MST_DLY_BIT    4
+#define MPU9150_I2C_SLV4_MST_DLY_LENGTH 5
+
+#define MPU9150_MST_PASS_THROUGH_BIT    7
+#define MPU9150_MST_I2C_SLV4_DONE_BIT   6
+#define MPU9150_MST_I2C_LOST_ARB_BIT    5
+#define MPU9150_MST_I2C_SLV4_NACK_BIT   4
+#define MPU9150_MST_I2C_SLV3_NACK_BIT   3
+#define MPU9150_MST_I2C_SLV2_NACK_BIT   2
+#define MPU9150_MST_I2C_SLV1_NACK_BIT   1
+#define MPU9150_MST_I2C_SLV0_NACK_BIT   0
+
+#define MPU9150_INTCFG_INT_LEVEL_BIT        7
+#define MPU9150_INTCFG_INT_OPEN_BIT         6
+#define MPU9150_INTCFG_LATCH_INT_EN_BIT     5
+#define MPU9150_INTCFG_INT_RD_CLEAR_BIT     4
+#define MPU9150_INTCFG_FSYNC_INT_LEVEL_BIT  3
+#define MPU9150_INTCFG_FSYNC_INT_EN_BIT     2
+#define MPU9150_INTCFG_I2C_BYPASS_EN_BIT    1
+#define MPU9150_INTCFG_CLKOUT_EN_BIT        0
+
+#define MPU9150_INTMODE_ACTIVEHIGH  0x00
+#define MPU9150_INTMODE_ACTIVELOW   0x01
+
+#define MPU9150_INTDRV_PUSHPULL     0x00
+#define MPU9150_INTDRV_OPENDRAIN    0x01
+
+#define MPU9150_INTLATCH_50USPULSE  0x00
+#define MPU9150_INTLATCH_WAITCLEAR  0x01
+
+#define MPU9150_INTCLEAR_STATUSREAD 0x00
+#define MPU9150_INTCLEAR_ANYREAD    0x01
+
+#define MPU9150_INTERRUPT_FF_BIT            7
+#define MPU9150_INTERRUPT_MOT_BIT           6
+#define MPU9150_INTERRUPT_ZMOT_BIT          5
+#define MPU9150_INTERRUPT_FIFO_OFLOW_BIT    4
+#define MPU9150_INTERRUPT_I2C_MST_INT_BIT   3
+#define MPU9150_INTERRUPT_PLL_RDY_INT_BIT   2
+#define MPU9150_INTERRUPT_DMP_INT_BIT       1
+#define MPU9150_INTERRUPT_DATA_RDY_BIT      0
+
+// TODO: figure out what these actually do
+// UMPL source code is not very obivous
+#define MPU9150_DMPINT_5_BIT            5
+#define MPU9150_DMPINT_4_BIT            4
+#define MPU9150_DMPINT_3_BIT            3
+#define MPU9150_DMPINT_2_BIT            2
+#define MPU9150_DMPINT_1_BIT            1
+#define MPU9150_DMPINT_0_BIT            0
+
+#define MPU9150_MOTION_MOT_XNEG_BIT     7
+#define MPU9150_MOTION_MOT_XPOS_BIT     6
+#define MPU9150_MOTION_MOT_YNEG_BIT     5
+#define MPU9150_MOTION_MOT_YPOS_BIT     4
+#define MPU9150_MOTION_MOT_ZNEG_BIT     3
+#define MPU9150_MOTION_MOT_ZPOS_BIT     2
+#define MPU9150_MOTION_MOT_ZRMOT_BIT    0
+
+#define MPU9150_DELAYCTRL_DELAY_ES_SHADOW_BIT   7
+#define MPU9150_DELAYCTRL_I2C_SLV4_DLY_EN_BIT   4
+#define MPU9150_DELAYCTRL_I2C_SLV3_DLY_EN_BIT   3
+#define MPU9150_DELAYCTRL_I2C_SLV2_DLY_EN_BIT   2
+#define MPU9150_DELAYCTRL_I2C_SLV1_DLY_EN_BIT   1
+#define MPU9150_DELAYCTRL_I2C_SLV0_DLY_EN_BIT   0
+
+#define MPU9150_PATHRESET_GYRO_RESET_BIT    2
+#define MPU9150_PATHRESET_ACCEL_RESET_BIT   1
+#define MPU9150_PATHRESET_TEMP_RESET_BIT    0
+
+#define MPU9150_DETECT_ACCEL_ON_DELAY_BIT       5
+#define MPU9150_DETECT_ACCEL_ON_DELAY_LENGTH    2
+#define MPU9150_DETECT_FF_COUNT_BIT             3
+#define MPU9150_DETECT_FF_COUNT_LENGTH          2
+#define MPU9150_DETECT_MOT_COUNT_BIT            1
+#define MPU9150_DETECT_MOT_COUNT_LENGTH         2
+
+#define MPU9150_DETECT_DECREMENT_RESET  0x0
+#define MPU9150_DETECT_DECREMENT_1      0x1
+#define MPU9150_DETECT_DECREMENT_2      0x2
+#define MPU9150_DETECT_DECREMENT_4      0x3
+
+#define MPU9150_USERCTRL_DMP_EN_BIT             7
+#define MPU9150_USERCTRL_FIFO_EN_BIT            6
+#define MPU9150_USERCTRL_I2C_MST_EN_BIT         5
+#define MPU9150_USERCTRL_I2C_IF_DIS_BIT         4
+#define MPU9150_USERCTRL_DMP_RESET_BIT          3
+#define MPU9150_USERCTRL_FIFO_RESET_BIT         2
+#define MPU9150_USERCTRL_I2C_MST_RESET_BIT      1
+#define MPU9150_USERCTRL_SIG_COND_RESET_BIT     0
+
+#define MPU9150_PWR1_DEVICE_RESET_BIT   7
+#define MPU9150_PWR1_SLEEP_BIT          6
+#define MPU9150_PWR1_CYCLE_BIT          5
+#define MPU9150_PWR1_TEMP_DIS_BIT       3
+#define MPU9150_PWR1_CLKSEL_BIT         2
+#define MPU9150_PWR1_CLKSEL_LENGTH      3
+
+#define MPU9150_CLOCK_INTERNAL          0x00
+#define MPU9150_CLOCK_PLL_XGYRO         0x01
+#define MPU9150_CLOCK_PLL_YGYRO         0x02
+#define MPU9150_CLOCK_PLL_ZGYRO         0x03
+#define MPU9150_CLOCK_PLL_EXT32K        0x04
+#define MPU9150_CLOCK_PLL_EXT19M        0x05
+#define MPU9150_CLOCK_KEEP_RESET        0x07
+
+#define MPU9150_PWR2_LP_WAKE_CTRL_BIT       7
+#define MPU9150_PWR2_LP_WAKE_CTRL_LENGTH    2
+#define MPU9150_PWR2_STBY_XA_BIT            5
+#define MPU9150_PWR2_STBY_YA_BIT            4
+#define MPU9150_PWR2_STBY_ZA_BIT            3
+#define MPU9150_PWR2_STBY_XG_BIT            2
+#define MPU9150_PWR2_STBY_YG_BIT            1
+#define MPU9150_PWR2_STBY_ZG_BIT            0
+
+#define MPU9150_WAKE_FREQ_1P25      0x0
+#define MPU9150_WAKE_FREQ_2P5       0x1
+#define MPU9150_WAKE_FREQ_5         0x2
+#define MPU9150_WAKE_FREQ_10        0x3
+
+#define MPU9150_BANKSEL_PRFTCH_EN_BIT       6
+#define MPU9150_BANKSEL_CFG_USER_BANK_BIT   5
+#define MPU9150_BANKSEL_MEM_SEL_BIT         4
+#define MPU9150_BANKSEL_MEM_SEL_LENGTH      5
+
+#define MPU9150_WHO_AM_I_BIT        6
+#define MPU9150_WHO_AM_I_LENGTH     6
+
+#define MPU9150_DMP_MEMORY_BANKS        8
+#define MPU9150_DMP_MEMORY_BANK_SIZE    256
+#define MPU9150_DMP_MEMORY_CHUNK_SIZE   16
+
+// note: DMP code memory blocks defined at end of header file
+
+class MPU9150 {
+    public:
+        MPU9150();
+        MPU9150(uint8_t address);
+
+        void initialize();
+        bool testConnection();
+
+        // AUX_VDDIO register
+        uint8_t getAuxVDDIOLevel();
+        void setAuxVDDIOLevel(uint8_t level);
+
+        // SMPLRT_DIV register
+        uint8_t getRate();
+        void setRate(uint8_t rate);
+
+        // CONFIG register
+        uint8_t getExternalFrameSync();
+        void setExternalFrameSync(uint8_t sync);
+        uint8_t getDLPFMode();
+        void setDLPFMode(uint8_t bandwidth);
+
+        // GYRO_CONFIG register
+        uint8_t getFullScaleGyroRange();
+        void setFullScaleGyroRange(uint8_t range);
+
+        // ACCEL_CONFIG register
+        bool getAccelXSelfTest();
+        void setAccelXSelfTest(bool enabled);
+        bool getAccelYSelfTest();
+        void setAccelYSelfTest(bool enabled);
+        bool getAccelZSelfTest();
+        void setAccelZSelfTest(bool enabled);
+        uint8_t getFullScaleAccelRange();
+        void setFullScaleAccelRange(uint8_t range);
+        uint8_t getDHPFMode();
+        void setDHPFMode(uint8_t mode);
+
+        // FF_THR register
+        uint8_t getFreefallDetectionThreshold();
+        void setFreefallDetectionThreshold(uint8_t threshold);
+
+        // FF_DUR register
+        uint8_t getFreefallDetectionDuration();
+        void setFreefallDetectionDuration(uint8_t duration);
+
+        // MOT_THR register
+        uint8_t getMotionDetectionThreshold();
+        void setMotionDetectionThreshold(uint8_t threshold);
+
+        // MOT_DUR register
+        uint8_t getMotionDetectionDuration();
+        void setMotionDetectionDuration(uint8_t duration);
+
+        // ZRMOT_THR register
+        uint8_t getZeroMotionDetectionThreshold();
+        void setZeroMotionDetectionThreshold(uint8_t threshold);
+
+        // ZRMOT_DUR register
+        uint8_t getZeroMotionDetectionDuration();
+        void setZeroMotionDetectionDuration(uint8_t duration);
+
+        // FIFO_EN register
+        bool getTempFIFOEnabled();
+        void setTempFIFOEnabled(bool enabled);
+        bool getXGyroFIFOEnabled();
+        void setXGyroFIFOEnabled(bool enabled);
+        bool getYGyroFIFOEnabled();
+        void setYGyroFIFOEnabled(bool enabled);
+        bool getZGyroFIFOEnabled();
+        void setZGyroFIFOEnabled(bool enabled);
+        bool getAccelFIFOEnabled();
+        void setAccelFIFOEnabled(bool enabled);
+        bool getSlave2FIFOEnabled();
+        void setSlave2FIFOEnabled(bool enabled);
+        bool getSlave1FIFOEnabled();
+        void setSlave1FIFOEnabled(bool enabled);
+        bool getSlave0FIFOEnabled();
+        void setSlave0FIFOEnabled(bool enabled);
+
+        // I2C_MST_CTRL register
+        bool getMultiMasterEnabled();
+        void setMultiMasterEnabled(bool enabled);
+        bool getWaitForExternalSensorEnabled();
+        void setWaitForExternalSensorEnabled(bool enabled);
+        bool getSlave3FIFOEnabled();
+        void setSlave3FIFOEnabled(bool enabled);
+        bool getSlaveReadWriteTransitionEnabled();
+        void setSlaveReadWriteTransitionEnabled(bool enabled);
+        uint8_t getMasterClockSpeed();
+        void setMasterClockSpeed(uint8_t speed);
+
+        // I2C_SLV* registers (Slave 0-3)
+        uint8_t getSlaveAddress(uint8_t num);
+        void setSlaveAddress(uint8_t num, uint8_t address);
+        uint8_t getSlaveRegister(uint8_t num);
+        void setSlaveRegister(uint8_t num, uint8_t reg);
+        bool getSlaveEnabled(uint8_t num);
+        void setSlaveEnabled(uint8_t num, bool enabled);
+        bool getSlaveWordByteSwap(uint8_t num);
+        void setSlaveWordByteSwap(uint8_t num, bool enabled);
+        bool getSlaveWriteMode(uint8_t num);
+        void setSlaveWriteMode(uint8_t num, bool mode);
+        bool getSlaveWordGroupOffset(uint8_t num);
+        void setSlaveWordGroupOffset(uint8_t num, bool enabled);
+        uint8_t getSlaveDataLength(uint8_t num);
+        void setSlaveDataLength(uint8_t num, uint8_t length);
+
+        // I2C_SLV* registers (Slave 4)
+        uint8_t getSlave4Address();
+        void setSlave4Address(uint8_t address);
+        uint8_t getSlave4Register();
+        void setSlave4Register(uint8_t reg);
+        void setSlave4OutputByte(uint8_t data);
+        bool getSlave4Enabled();
+        void setSlave4Enabled(bool enabled);
+        bool getSlave4InterruptEnabled();
+        void setSlave4InterruptEnabled(bool enabled);
+        bool getSlave4WriteMode();
+        void setSlave4WriteMode(bool mode);
+        uint8_t getSlave4MasterDelay();
+        void setSlave4MasterDelay(uint8_t delay);
+        uint8_t getSlate4InputByte();
+
+        // I2C_MST_STATUS register
+        bool getPassthroughStatus();
+        bool getSlave4IsDone();
+        bool getLostArbitration();
+        bool getSlave4Nack();
+        bool getSlave3Nack();
+        bool getSlave2Nack();
+        bool getSlave1Nack();
+        bool getSlave0Nack();
+
+        // INT_PIN_CFG register
+        bool getInterruptMode();
+        void setInterruptMode(bool mode);
+        bool getInterruptDrive();
+        void setInterruptDrive(bool drive);
+        bool getInterruptLatch();
+        void setInterruptLatch(bool latch);
+        bool getInterruptLatchClear();
+        void setInterruptLatchClear(bool clear);
+        bool getFSyncInterruptLevel();
+        void setFSyncInterruptLevel(bool level);
+        bool getFSyncInterruptEnabled();
+        void setFSyncInterruptEnabled(bool enabled);
+        bool getI2CBypassEnabled();
+        void setI2CBypassEnabled(bool enabled);
+        bool getClockOutputEnabled();
+        void setClockOutputEnabled(bool enabled);
+
+        // INT_ENABLE register
+        uint8_t getIntEnabled();
+        void setIntEnabled(uint8_t enabled);
+        bool getIntFreefallEnabled();
+        void setIntFreefallEnabled(bool enabled);
+        bool getIntMotionEnabled();
+        void setIntMotionEnabled(bool enabled);
+        bool getIntZeroMotionEnabled();
+        void setIntZeroMotionEnabled(bool enabled);
+        bool getIntFIFOBufferOverflowEnabled();
+        void setIntFIFOBufferOverflowEnabled(bool enabled);
+        bool getIntI2CMasterEnabled();
+        void setIntI2CMasterEnabled(bool enabled);
+        bool getIntDataReadyEnabled();
+        void setIntDataReadyEnabled(bool enabled);
+
+        // INT_STATUS register
+        uint8_t getIntStatus();
+        bool getIntFreefallStatus();
+        bool getIntMotionStatus();
+        bool getIntZeroMotionStatus();
+        bool getIntFIFOBufferOverflowStatus();
+        bool getIntI2CMasterStatus();
+        bool getIntDataReadyStatus();
+
+        // ACCEL_*OUT_* registers
+        void getMotion9(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz, int16_t* mx, int16_t* my, int16_t* mz);
+        void getMotion6(int16_t* ax, int16_t* ay, int16_t* az, int16_t* gx, int16_t* gy, int16_t* gz);
+        void getAcceleration(int16_t* x, int16_t* y, int16_t* z);
+        int16_t getAccelerationX();
+        int16_t getAccelerationY();
+        int16_t getAccelerationZ();
+
+        // TEMP_OUT_* registers
+        int16_t getTemperature();
+
+        // GYRO_*OUT_* registers
+        void getRotation(int16_t* x, int16_t* y, int16_t* z);
+        int16_t getRotationX();
+        int16_t getRotationY();
+        int16_t getRotationZ();
+
+        // EXT_SENS_DATA_* registers
+        uint8_t getExternalSensorByte(int position);
+        uint16_t getExternalSensorWord(int position);
+        uint32_t getExternalSensorDWord(int position);
+
+        // MOT_DETECT_STATUS register
+        bool getXNegMotionDetected();
+        bool getXPosMotionDetected();
+        bool getYNegMotionDetected();
+        bool getYPosMotionDetected();
+        bool getZNegMotionDetected();
+        bool getZPosMotionDetected();
+        bool getZeroMotionDetected();
+
+        // I2C_SLV*_DO register
+        void setSlaveOutputByte(uint8_t num, uint8_t data);
+
+        // I2C_MST_DELAY_CTRL register
+        bool getExternalShadowDelayEnabled();
+        void setExternalShadowDelayEnabled(bool enabled);
+        bool getSlaveDelayEnabled(uint8_t num);
+        void setSlaveDelayEnabled(uint8_t num, bool enabled);
+
+        // SIGNAL_PATH_RESET register
+        void resetGyroscopePath();
+        void resetAccelerometerPath();
+        void resetTemperaturePath();
+
+        // MOT_DETECT_CTRL register
+        uint8_t getAccelerometerPowerOnDelay();
+        void setAccelerometerPowerOnDelay(uint8_t delay);
+        uint8_t getFreefallDetectionCounterDecrement();
+        void setFreefallDetectionCounterDecrement(uint8_t decrement);
+        uint8_t getMotionDetectionCounterDecrement();
+        void setMotionDetectionCounterDecrement(uint8_t decrement);
+
+        // USER_CTRL register
+        bool getFIFOEnabled();
+        void setFIFOEnabled(bool enabled);
+        bool getI2CMasterModeEnabled();
+        void setI2CMasterModeEnabled(bool enabled);
+        void switchSPIEnabled(bool enabled);
+        void resetFIFO();
+        void resetI2CMaster();
+        void resetSensors();
+
+        // PWR_MGMT_1 register
+        void reset();
+        bool getSleepEnabled();
+        void setSleepEnabled(bool enabled);
+        bool getWakeCycleEnabled();
+        void setWakeCycleEnabled(bool enabled);
+        bool getTempSensorEnabled();
+        void setTempSensorEnabled(bool enabled);
+        uint8_t getClockSource();
+        void setClockSource(uint8_t source);
+
+        // PWR_MGMT_2 register
+        uint8_t getWakeFrequency();
+        void setWakeFrequency(uint8_t frequency);
+        bool getStandbyXAccelEnabled();
+        void setStandbyXAccelEnabled(bool enabled);
+        bool getStandbyYAccelEnabled();
+        void setStandbyYAccelEnabled(bool enabled);
+        bool getStandbyZAccelEnabled();
+        void setStandbyZAccelEnabled(bool enabled);
+        bool getStandbyXGyroEnabled();
+        void setStandbyXGyroEnabled(bool enabled);
+        bool getStandbyYGyroEnabled();
+        void setStandbyYGyroEnabled(bool enabled);
+        bool getStandbyZGyroEnabled();
+        void setStandbyZGyroEnabled(bool enabled);
+
+        // FIFO_COUNT_* registers
+        uint16_t getFIFOCount();
+
+        // FIFO_R_W register
+        uint8_t getFIFOByte();
+        void setFIFOByte(uint8_t data);
+        void getFIFOBytes(uint8_t *data, uint8_t length);
+
+        // WHO_AM_I register
+        uint8_t getDeviceID();
+        void setDeviceID(uint8_t id);
+        
+        // ======== UNDOCUMENTED/DMP REGISTERS/METHODS ========
+        
+        // XG_OFFS_TC register
+        uint8_t getOTPBankValid();
+        void setOTPBankValid(bool enabled);
+        int8_t getXGyroOffsetTC();
+        void setXGyroOffsetTC(int8_t offset);
+
+        // YG_OFFS_TC register
+        int8_t getYGyroOffsetTC();
+        void setYGyroOffsetTC(int8_t offset);
+
+        // ZG_OFFS_TC register
+        int8_t getZGyroOffsetTC();
+        void setZGyroOffsetTC(int8_t offset);
+
+        // X_FINE_GAIN register
+        int8_t getXFineGain();
+        void setXFineGain(int8_t gain);
+
+        // Y_FINE_GAIN register
+        int8_t getYFineGain();
+        void setYFineGain(int8_t gain);
+
+        // Z_FINE_GAIN register
+        int8_t getZFineGain();
+        void setZFineGain(int8_t gain);
+
+        // XA_OFFS_* registers
+        int16_t getXAccelOffset();
+        void setXAccelOffset(int16_t offset);
+
+        // YA_OFFS_* register
+        int16_t getYAccelOffset();
+        void setYAccelOffset(int16_t offset);
+
+        // ZA_OFFS_* register
+        int16_t getZAccelOffset();
+        void setZAccelOffset(int16_t offset);
+
+        // XG_OFFS_USR* registers
+        int16_t getXGyroOffset();
+        void setXGyroOffset(int16_t offset);
+
+        // YG_OFFS_USR* register
+        int16_t getYGyroOffset();
+        void setYGyroOffset(int16_t offset);
+
+        // ZG_OFFS_USR* register
+        int16_t getZGyroOffset();
+        void setZGyroOffset(int16_t offset);
+        
+        // INT_ENABLE register (DMP functions)
+        bool getIntPLLReadyEnabled();
+        void setIntPLLReadyEnabled(bool enabled);
+        bool getIntDMPEnabled();
+        void setIntDMPEnabled(bool enabled);
+        
+        // DMP_INT_STATUS
+        bool getDMPInt5Status();
+        bool getDMPInt4Status();
+        bool getDMPInt3Status();
+        bool getDMPInt2Status();
+        bool getDMPInt1Status();
+        bool getDMPInt0Status();
+
+        // INT_STATUS register (DMP functions)
+        bool getIntPLLReadyStatus();
+        bool getIntDMPStatus();
+        
+        // USER_CTRL register (DMP functions)
+        bool getDMPEnabled();
+        void setDMPEnabled(bool enabled);
+        void resetDMP();
+        
+        // BANK_SEL register
+        void setMemoryBank(uint8_t bank, bool prefetchEnabled=false, bool userBank=false);
+        
+        // MEM_START_ADDR register
+        void setMemoryStartAddress(uint8_t address);
+        
+        // MEM_R_W register
+        uint8_t readMemoryByte();
+        void writeMemoryByte(uint8_t data);
+        void readMemoryBlock(uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0);
+        bool writeMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true, bool useProgMem=false);
+        bool writeProgMemoryBlock(const uint8_t *data, uint16_t dataSize, uint8_t bank=0, uint8_t address=0, bool verify=true);
+
+        bool writeDMPConfigurationSet(const uint8_t *data, uint16_t dataSize, bool useProgMem=false);
+        bool writeProgDMPConfigurationSet(const uint8_t *data, uint16_t dataSize);
+
+        // DMP_CFG_1 register
+        uint8_t getDMPConfig1();
+        void setDMPConfig1(uint8_t config);
+
+        // DMP_CFG_2 register
+        uint8_t getDMPConfig2();
+        void setDMPConfig2(uint8_t config);
+
+        // special methods for MotionApps 2.0 implementation
+        #ifdef MPU9150_INCLUDE_DMP_MOTIONAPPS20
+            uint8_t *dmpPacketBuffer;
+            uint16_t dmpPacketSize;
+
+            uint8_t dmpInitialize();
+            bool dmpPacketAvailable();
+
+            uint8_t dmpSetFIFORate(uint8_t fifoRate);
+            uint8_t dmpGetFIFORate();
+            uint8_t dmpGetSampleStepSizeMS();
+            uint8_t dmpGetSampleFrequency();
+            int32_t dmpDecodeTemperature(int8_t tempReg);
+            
+            // Register callbacks after a packet of FIFO data is processed
+            //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+            //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+            uint8_t dmpRunFIFORateProcesses();
+            
+            // Setup FIFO for various output
+            uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+            uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+            uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+            // Get Fixed Point data from FIFO
+            uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+            uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+            uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+            uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+            uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+            uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+            
+            uint8_t dmpGetEuler(float *data, Quaternion *q);
+            uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+            // Get Floating Point data from FIFO
+            uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+            uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+            uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+            uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+            uint8_t dmpInitFIFOParam();
+            uint8_t dmpCloseFIFO();
+            uint8_t dmpSetGyroDataSource(uint8_t source);
+            uint8_t dmpDecodeQuantizedAccel();
+            uint32_t dmpGetGyroSumOfSquare();
+            uint32_t dmpGetAccelSumOfSquare();
+            void dmpOverrideQuaternion(long *q);
+            uint16_t dmpGetFIFOPacketSize();
+        #endif
+
+        // special methods for MotionApps 4.1 implementation
+        #ifdef MPU9150_INCLUDE_DMP_MOTIONAPPS41
+            uint8_t *dmpPacketBuffer;
+            uint16_t dmpPacketSize;
+
+            uint8_t dmpInitialize();
+            bool dmpPacketAvailable();
+
+            uint8_t dmpSetFIFORate(uint8_t fifoRate);
+            uint8_t dmpGetFIFORate();
+            uint8_t dmpGetSampleStepSizeMS();
+            uint8_t dmpGetSampleFrequency();
+            int32_t dmpDecodeTemperature(int8_t tempReg);
+            
+            // Register callbacks after a packet of FIFO data is processed
+            //uint8_t dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+            //uint8_t dmpUnregisterFIFORateProcess(inv_obj_func func);
+            uint8_t dmpRunFIFORateProcesses();
+            
+            // Setup FIFO for various output
+            uint8_t dmpSendQuaternion(uint_fast16_t accuracy);
+            uint8_t dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendPacketNumber(uint_fast16_t accuracy);
+            uint8_t dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+            uint8_t dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+            // Get Fixed Point data from FIFO
+            uint8_t dmpGetAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGet6AxisQuaternion(Quaternion *q, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetRelativeQuaternion(Quaternion *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyro(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetMag(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpSetLinearAccelFilterCoefficient(float coef);
+            uint8_t dmpGetLinearAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity);
+            uint8_t dmpGetLinearAccelInWorld(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q);
+            uint8_t dmpGetGyroAndAccelSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroAndAccelSensor(VectorInt16 *g, VectorInt16 *a, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGyroSensor(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetControlData(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetTemperature(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetGravity(VectorFloat *v, Quaternion *q);
+            uint8_t dmpGetUnquantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetUnquantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int32_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(int16_t *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuantizedAccel(VectorInt16 *v, const uint8_t* packet=0);
+            uint8_t dmpGetExternalSensorData(int32_t *data, uint16_t size, const uint8_t* packet=0);
+            uint8_t dmpGetEIS(int32_t *data, const uint8_t* packet=0);
+            
+            uint8_t dmpGetEuler(float *data, Quaternion *q);
+            uint8_t dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity);
+
+            // Get Floating Point data from FIFO
+            uint8_t dmpGetAccelFloat(float *data, const uint8_t* packet=0);
+            uint8_t dmpGetQuaternionFloat(float *data, const uint8_t* packet=0);
+
+            uint8_t dmpProcessFIFOPacket(const unsigned char *dmpData);
+            uint8_t dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed=NULL);
+
+            uint8_t dmpSetFIFOProcessedCallback(void (*func) (void));
+
+            uint8_t dmpInitFIFOParam();
+            uint8_t dmpCloseFIFO();
+            uint8_t dmpSetGyroDataSource(uint8_t source);
+            uint8_t dmpDecodeQuantizedAccel();
+            uint32_t dmpGetGyroSumOfSquare();
+            uint32_t dmpGetAccelSumOfSquare();
+            void dmpOverrideQuaternion(long *q);
+            uint16_t dmpGetFIFOPacketSize();
+        #endif
+
+    private:
+        uint8_t devAddr;
+        uint8_t buffer[14];
+};
+
+#endif /* _MPU9150_H_ */
diff --git a/libraries/MPU9150/MPU9150_9Axis_MotionApps41.h b/libraries/MPU9150/MPU9150_9Axis_MotionApps41.h
new file mode 100644
index 0000000..21b44ed
--- /dev/null
+++ b/libraries/MPU9150/MPU9150_9Axis_MotionApps41.h
@@ -0,0 +1,852 @@
+// I2Cdev library collection - MPU9150 I2C device class, 9-axis MotionApps 4.1 implementation
+// Based on InvenSense MPU-9150 register map document rev. 2.0, 5/19/2011 (RM-MPU-6000A-00)
+// 6/18/2012 by Jeff Rowberg 
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug 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.
+===============================================
+*/
+
+#ifndef _MPU9150_9AXIS_MOTIONAPPS41_H_
+#define _MPU9150_9AXIS_MOTIONAPPS41_H_
+
+#include "I2Cdev.h"
+#include "helper_3dmath.h"
+
+// MotionApps 4.1 DMP implementation, built using the MPU-9150 "MotionFit" board
+#define MPU9150_INCLUDE_DMP_MOTIONAPPS41
+
+#include "MPU9150.h"
+
+// Tom Carpenter's conditional PROGMEM code
+// http://forum.arduino.cc/index.php?topic=129407.0
+#ifdef __AVR__
+    #include 
+#else
+    // Teensy 3.0 library conditional PROGMEM code from Paul Stoffregen
+    #ifndef __PGMSPACE_H_
+        #define __PGMSPACE_H_ 1
+        #include 
+
+        #define PROGMEM
+        #define PGM_P  const char *
+        #define PSTR(str) (str)
+        #define F(x) x
+
+        typedef void prog_void;
+        typedef char prog_char;
+        typedef unsigned char prog_uchar;
+        typedef int8_t prog_int8_t;
+        typedef uint8_t prog_uint8_t;
+        typedef int16_t prog_int16_t;
+        typedef uint16_t prog_uint16_t;
+        typedef int32_t prog_int32_t;
+        typedef uint32_t prog_uint32_t;
+        
+        #define strcpy_P(dest, src) strcpy((dest), (src))
+        #define strcat_P(dest, src) strcat((dest), (src))
+        #define strcmp_P(a, b) strcmp((a), (b))
+        
+        #define pgm_read_byte(addr) (*(const unsigned char *)(addr))
+        #define pgm_read_word(addr) (*(const unsigned short *)(addr))
+        #define pgm_read_dword(addr) (*(const unsigned long *)(addr))
+        #define pgm_read_float(addr) (*(const float *)(addr))
+        
+        #define pgm_read_byte_near(addr) pgm_read_byte(addr)
+        #define pgm_read_word_near(addr) pgm_read_word(addr)
+        #define pgm_read_dword_near(addr) pgm_read_dword(addr)
+        #define pgm_read_float_near(addr) pgm_read_float(addr)
+        #define pgm_read_byte_far(addr) pgm_read_byte(addr)
+        #define pgm_read_word_far(addr) pgm_read_word(addr)
+        #define pgm_read_dword_far(addr) pgm_read_dword(addr)
+        #define pgm_read_float_far(addr) pgm_read_float(addr)
+    #endif
+#endif
+
+// NOTE! Enabling DEBUG adds about 3.3kB to the flash program size.
+// Debug output is now working even on ATMega328P MCUs (e.g. Arduino Uno)
+// after moving string constants to flash memory storage using the F()
+// compiler macro (Arduino IDE 1.0+ required).
+
+//#define DEBUG
+#ifdef DEBUG
+    #define DEBUG_PRINT(x) Serial.print(x)
+    #define DEBUG_PRINTF(x, y) Serial.print(x, y)
+    #define DEBUG_PRINTLN(x) Serial.println(x)
+    #define DEBUG_PRINTLNF(x, y) Serial.println(x, y)
+#else
+    #define DEBUG_PRINT(x)
+    #define DEBUG_PRINTF(x, y)
+    #define DEBUG_PRINTLN(x)
+    #define DEBUG_PRINTLNF(x, y)
+#endif
+
+#define MPU9150_DMP_CODE_SIZE       1962    // dmpMemory[]
+#define MPU9150_DMP_CONFIG_SIZE     232     // dmpConfig[]
+#define MPU9150_DMP_UPDATES_SIZE    140     // dmpUpdates[]
+
+/* ================================================================================================ *
+ | Default MotionApps v4.1 48-byte FIFO packet structure:                                           |
+ |                                                                                                  |
+ | [QUAT W][      ][QUAT X][      ][QUAT Y][      ][QUAT Z][      ][GYRO X][      ][GYRO Y][      ] |
+ |   0   1   2   3   4   5   6   7   8   9  10  11  12  13  14  15  16  17  18  19  20  21  22  23  |
+ |                                                                                                  |
+ | [GYRO Z][      ][MAG X ][MAG Y ][MAG Z ][ACC X ][      ][ACC Y ][      ][ACC Z ][      ][      ] |
+ |  24  25  26  27  28  29  30  31  32  33  34  35  36  37  38  39  40  41  42  43  44  45  46  47  |
+ * ================================================================================================ */
+
+// this block of memory gets written to the MPU on start-up, and it seems
+// to be volatile memory, so it has to be done each time (it only takes ~1
+// second though)
+const prog_uchar dmpMemory[MPU9150_DMP_CODE_SIZE] PROGMEM = {
+    // bank 0, 256 bytes
+    0xFB, 0x00, 0x00, 0x3E, 0x00, 0x0B, 0x00, 0x36, 0x00, 0x01, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00,
+    0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0xFA, 0x80, 0x00, 0x0B, 0x12, 0x82, 0x00, 0x01,
+    0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x28, 0x00, 0x00, 0xFF, 0xFF, 0x45, 0x81, 0xFF, 0xFF, 0xFA, 0x72, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x03, 0xE8, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x7F, 0xFF, 0xFF, 0xFE, 0x80, 0x01,
+    0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x3E, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xCA, 0xE3, 0x09, 0x3E, 0x80, 0x00, 0x00,
+    0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00,
+    0x41, 0xFF, 0x00, 0x00, 0x00, 0x00, 0x0B, 0x2A, 0x00, 0x00, 0x16, 0x55, 0x00, 0x00, 0x21, 0x82,
+    0xFD, 0x87, 0x26, 0x50, 0xFD, 0x80, 0x00, 0x00, 0x00, 0x1F, 0x00, 0x00, 0x00, 0x05, 0x80, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x04, 0x6F, 0x00, 0x02, 0x65, 0x32, 0x00, 0x00, 0x5E, 0xC0,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0xFB, 0x8C, 0x6F, 0x5D, 0xFD, 0x5D, 0x08, 0xD9, 0x00, 0x7C, 0x73, 0x3B, 0x00, 0x6C, 0x12, 0xCC,
+    0x32, 0x00, 0x13, 0x9D, 0x32, 0x00, 0xD0, 0xD6, 0x32, 0x00, 0x08, 0x00, 0x40, 0x00, 0x01, 0xF4,
+    0xFF, 0xE6, 0x80, 0x79, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0xD0, 0xD6, 0x00, 0x00, 0x27, 0x10,
+
+    // bank 1, 256 bytes
+    0xFB, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0xFA, 0x36, 0xFF, 0xBC, 0x30, 0x8E, 0x00, 0x05, 0xFB, 0xF0, 0xFF, 0xD9, 0x5B, 0xC8,
+    0xFF, 0xD0, 0x9A, 0xBE, 0x00, 0x00, 0x10, 0xA9, 0xFF, 0xF4, 0x1E, 0xB2, 0x00, 0xCE, 0xBB, 0xF7,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x04, 0x00, 0x02, 0x00, 0x02, 0x02, 0x00, 0x00, 0x0C,
+    0xFF, 0xC2, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0xCF, 0x80, 0x00, 0x40, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x03, 0x3F, 0x68, 0xB6, 0x79, 0x35, 0x28, 0xBC, 0xC6, 0x7E, 0xD1, 0x6C,
+    0x80, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0xB2, 0x6A, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x3F, 0xF0, 0x00, 0x00, 0x00, 0x30,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x25, 0x4D, 0x00, 0x2F, 0x70, 0x6D, 0x00, 0x00, 0x05, 0xAE, 0x00, 0x0C, 0x02, 0xD0,
+    
+    // bank 2, 256 bytes
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x54, 0xFF, 0xEF, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x01, 0x00, 0x00, 0x44, 0x00, 0x00, 0x00, 0x00, 0x0C, 0x00, 0x00, 0x00, 0x01, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x54, 0x00, 0x00, 0xFF, 0xEF, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00,
+    0x00, 0x1B, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x47, 0x78, 0xA2,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    
+    // bank 3, 256 bytes
+    0xD8, 0xDC, 0xF4, 0xD8, 0xB9, 0xAB, 0xF3, 0xF8, 0xFA, 0xF1, 0xBA, 0xA2, 0xDE, 0xB2, 0xB8, 0xB4,
+    0xA8, 0x81, 0x98, 0xF7, 0x4A, 0x90, 0x7F, 0x91, 0x6A, 0xF3, 0xF9, 0xDB, 0xA8, 0xF9, 0xB0, 0xBA,
+    0xA0, 0x80, 0xF2, 0xCE, 0x81, 0xF3, 0xC2, 0xF1, 0xC1, 0xF2, 0xC3, 0xF3, 0xCC, 0xA2, 0xB2, 0x80,
+    0xF1, 0xC6, 0xD8, 0x80, 0xBA, 0xA7, 0xDF, 0xDF, 0xDF, 0xF2, 0xA7, 0xC3, 0xCB, 0xC5, 0xB6, 0xF0,
+    0x87, 0xA2, 0x94, 0x24, 0x48, 0x70, 0x3C, 0x95, 0x40, 0x68, 0x34, 0x58, 0x9B, 0x78, 0xA2, 0xF1,
+    0x83, 0x92, 0x2D, 0x55, 0x7D, 0xD8, 0xB1, 0xB4, 0xB8, 0xA1, 0xD0, 0x91, 0x80, 0xF2, 0x70, 0xF3,
+    0x70, 0xF2, 0x7C, 0x80, 0xA8, 0xF1, 0x01, 0xB0, 0x98, 0x87, 0xD9, 0x43, 0xD8, 0x86, 0xC9, 0x88,
+    0xBA, 0xA1, 0xF2, 0x0E, 0xB8, 0x97, 0x80, 0xF1, 0xA9, 0xDF, 0xDF, 0xDF, 0xAA, 0xDF, 0xDF, 0xDF,
+    0xF2, 0xAA, 0xC5, 0xCD, 0xC7, 0xA9, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, 0x97, 0xF1, 0xA9, 0x89,
+    0x26, 0x46, 0x66, 0xB0, 0xB4, 0xBA, 0x80, 0xAC, 0xDE, 0xF2, 0xCA, 0xF1, 0xB2, 0x8C, 0x02, 0xA9,
+    0xB6, 0x98, 0x00, 0x89, 0x0E, 0x16, 0x1E, 0xB8, 0xA9, 0xB4, 0x99, 0x2C, 0x54, 0x7C, 0xB0, 0x8A,
+    0xA8, 0x96, 0x36, 0x56, 0x76, 0xF1, 0xB9, 0xAF, 0xB4, 0xB0, 0x83, 0xC0, 0xB8, 0xA8, 0x97, 0x11,
+    0xB1, 0x8F, 0x98, 0xB9, 0xAF, 0xF0, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xF1, 0xA3, 0x29, 0x55,
+    0x7D, 0xAF, 0x83, 0xB5, 0x93, 0xF0, 0x00, 0x28, 0x50, 0xF5, 0xBA, 0xAD, 0x8F, 0x9F, 0x28, 0x54,
+    0x7C, 0xB9, 0xF1, 0xA3, 0x86, 0x9F, 0x61, 0xA6, 0xDA, 0xDE, 0xDF, 0xDB, 0xB2, 0xB6, 0x8E, 0x9D,
+    0xAE, 0xF5, 0x60, 0x68, 0x70, 0xB1, 0xB5, 0xF1, 0xDA, 0xA6, 0xDF, 0xD9, 0xA6, 0xFA, 0xA3, 0x86,
+    
+    // bank 4, 256 bytes
+    0x96, 0xDB, 0x31, 0xA6, 0xD9, 0xF8, 0xDF, 0xBA, 0xA6, 0x8F, 0xC2, 0xC5, 0xC7, 0xB2, 0x8C, 0xC1,
+    0xB8, 0xA2, 0xDF, 0xDF, 0xDF, 0xA3, 0xDF, 0xDF, 0xDF, 0xD8, 0xD8, 0xF1, 0xB8, 0xA8, 0xB2, 0x86,
+    0xB4, 0x98, 0x0D, 0x35, 0x5D, 0xB8, 0xAA, 0x98, 0xB0, 0x87, 0x2D, 0x35, 0x3D, 0xB2, 0xB6, 0xBA,
+    0xAF, 0x8C, 0x96, 0x19, 0x8F, 0x9F, 0xA7, 0x0E, 0x16, 0x1E, 0xB4, 0x9A, 0xB8, 0xAA, 0x87, 0x2C,
+    0x54, 0x7C, 0xB9, 0xA3, 0xDE, 0xDF, 0xDF, 0xA3, 0xB1, 0x80, 0xF2, 0xC4, 0xCD, 0xC9, 0xF1, 0xB8,
+    0xA9, 0xB4, 0x99, 0x83, 0x0D, 0x35, 0x5D, 0x89, 0xB9, 0xA3, 0x2D, 0x55, 0x7D, 0xB5, 0x93, 0xA3,
+    0x0E, 0x16, 0x1E, 0xA9, 0x2C, 0x54, 0x7C, 0xB8, 0xB4, 0xB0, 0xF1, 0x97, 0x83, 0xA8, 0x11, 0x84,
+    0xA5, 0x09, 0x98, 0xA3, 0x83, 0xF0, 0xDA, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xD8, 0xF1, 0xA5,
+    0x29, 0x55, 0x7D, 0xA5, 0x85, 0x95, 0x02, 0x1A, 0x2E, 0x3A, 0x56, 0x5A, 0x40, 0x48, 0xF9, 0xF3,
+    0xA3, 0xD9, 0xF8, 0xF0, 0x98, 0x83, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0x97, 0x82, 0xA8, 0xF1,
+    0x11, 0xF0, 0x98, 0xA2, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xDA, 0xF3, 0xDE, 0xD8, 0x83, 0xA5,
+    0x94, 0x01, 0xD9, 0xA3, 0x02, 0xF1, 0xA2, 0xC3, 0xC5, 0xC7, 0xD8, 0xF1, 0x84, 0x92, 0xA2, 0x4D,
+    0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+    0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0x93, 0xA3, 0x4D,
+    0xDA, 0x2A, 0xD8, 0x48, 0x69, 0xD9, 0x2A, 0xD8, 0x68, 0x55, 0xDA, 0x32, 0xD8, 0x50, 0x71, 0xD9,
+    0x32, 0xD8, 0x70, 0x5D, 0xDA, 0x3A, 0xD8, 0x58, 0x79, 0xD9, 0x3A, 0xD8, 0x78, 0xA8, 0x8A, 0x9A,
+    
+    // bank 5, 256 bytes
+    0xF0, 0x28, 0x50, 0x78, 0x9E, 0xF3, 0x88, 0x18, 0xF1, 0x9F, 0x1D, 0x98, 0xA8, 0xD9, 0x08, 0xD8,
+    0xC8, 0x9F, 0x12, 0x9E, 0xF3, 0x15, 0xA8, 0xDA, 0x12, 0x10, 0xD8, 0xF1, 0xAF, 0xC8, 0x97, 0x87,
+    0x34, 0xB5, 0xB9, 0x94, 0xA4, 0x21, 0xF3, 0xD9, 0x22, 0xD8, 0xF2, 0x2D, 0xF3, 0xD9, 0x2A, 0xD8,
+    0xF2, 0x35, 0xF3, 0xD9, 0x32, 0xD8, 0x81, 0xA4, 0x60, 0x60, 0x61, 0xD9, 0x61, 0xD8, 0x6C, 0x68,
+    0x69, 0xD9, 0x69, 0xD8, 0x74, 0x70, 0x71, 0xD9, 0x71, 0xD8, 0xB1, 0xA3, 0x84, 0x19, 0x3D, 0x5D,
+    0xA3, 0x83, 0x1A, 0x3E, 0x5E, 0x93, 0x10, 0x30, 0x81, 0x10, 0x11, 0xB8, 0xB0, 0xAF, 0x8F, 0x94,
+    0xF2, 0xDA, 0x3E, 0xD8, 0xB4, 0x9A, 0xA8, 0x87, 0x29, 0xDA, 0xF8, 0xD8, 0x87, 0x9A, 0x35, 0xDA,
+    0xF8, 0xD8, 0x87, 0x9A, 0x3D, 0xDA, 0xF8, 0xD8, 0xB1, 0xB9, 0xA4, 0x98, 0x85, 0x02, 0x2E, 0x56,
+    0xA5, 0x81, 0x00, 0x0C, 0x14, 0xA3, 0x97, 0xB0, 0x8A, 0xF1, 0x2D, 0xD9, 0x28, 0xD8, 0x4D, 0xD9,
+    0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x84, 0x0D, 0xDA, 0x0E, 0xD8, 0xA3, 0x29, 0x83, 0xDA,
+    0x2C, 0x0E, 0xD8, 0xA3, 0x84, 0x49, 0x83, 0xDA, 0x2C, 0x4C, 0x0E, 0xD8, 0xB8, 0xB0, 0x97, 0x86,
+    0xA8, 0x31, 0x9B, 0x06, 0x99, 0x07, 0xAB, 0x97, 0x28, 0x88, 0x9B, 0xF0, 0x0C, 0x20, 0x14, 0x40,
+    0xB9, 0xA3, 0x8A, 0xC3, 0xC5, 0xC7, 0x9A, 0xA3, 0x28, 0x50, 0x78, 0xF1, 0xB5, 0x93, 0x01, 0xD9,
+    0xDF, 0xDF, 0xDF, 0xD8, 0xB8, 0xB4, 0xA8, 0x8C, 0x9C, 0xF0, 0x04, 0x28, 0x51, 0x79, 0x1D, 0x30,
+    0x14, 0x38, 0xB2, 0x82, 0xAB, 0xD0, 0x98, 0x2C, 0x50, 0x50, 0x78, 0x78, 0x9B, 0xF1, 0x1A, 0xB0,
+    0xF0, 0xB1, 0x83, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0xB0, 0x8B, 0x29, 0x51, 0x79, 0xB1, 0x83, 0x24,
+
+    // bank 6, 256 bytes
+    0x70, 0x59, 0xB0, 0x8B, 0x20, 0x58, 0x71, 0xB1, 0x83, 0x44, 0x69, 0x38, 0xB0, 0x8B, 0x39, 0x40,
+    0x68, 0xB1, 0x83, 0x64, 0x48, 0x31, 0xB0, 0x8B, 0x30, 0x49, 0x60, 0xA5, 0x88, 0x20, 0x09, 0x71,
+    0x58, 0x44, 0x68, 0x11, 0x39, 0x64, 0x49, 0x30, 0x19, 0xF1, 0xAC, 0x00, 0x2C, 0x54, 0x7C, 0xF0,
+    0x8C, 0xA8, 0x04, 0x28, 0x50, 0x78, 0xF1, 0x88, 0x97, 0x26, 0xA8, 0x59, 0x98, 0xAC, 0x8C, 0x02,
+    0x26, 0x46, 0x66, 0xF0, 0x89, 0x9C, 0xA8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38,
+    0x64, 0x48, 0x31, 0xA9, 0x88, 0x09, 0x20, 0x59, 0x70, 0xAB, 0x11, 0x38, 0x40, 0x69, 0xA8, 0x19,
+    0x31, 0x48, 0x60, 0x8C, 0xA8, 0x3C, 0x41, 0x5C, 0x20, 0x7C, 0x00, 0xF1, 0x87, 0x98, 0x19, 0x86,
+    0xA8, 0x6E, 0x76, 0x7E, 0xA9, 0x99, 0x88, 0x2D, 0x55, 0x7D, 0x9E, 0xB9, 0xA3, 0x8A, 0x22, 0x8A,
+    0x6E, 0x8A, 0x56, 0x8A, 0x5E, 0x9F, 0xB1, 0x83, 0x06, 0x26, 0x46, 0x66, 0x0E, 0x2E, 0x4E, 0x6E,
+    0x9D, 0xB8, 0xAD, 0x00, 0x2C, 0x54, 0x7C, 0xF2, 0xB1, 0x8C, 0xB4, 0x99, 0xB9, 0xA3, 0x2D, 0x55,
+    0x7D, 0x81, 0x91, 0xAC, 0x38, 0xAD, 0x3A, 0xB5, 0x83, 0x91, 0xAC, 0x2D, 0xD9, 0x28, 0xD8, 0x4D,
+    0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0x8C, 0x9D, 0xAE, 0x29, 0xD9, 0x04, 0xAE, 0xD8, 0x51,
+    0xD9, 0x04, 0xAE, 0xD8, 0x79, 0xD9, 0x04, 0xD8, 0x81, 0xF3, 0x9D, 0xAD, 0x00, 0x8D, 0xAE, 0x19,
+    0x81, 0xAD, 0xD9, 0x01, 0xD8, 0xF2, 0xAE, 0xDA, 0x26, 0xD8, 0x8E, 0x91, 0x29, 0x83, 0xA7, 0xD9,
+    0xAD, 0xAD, 0xAD, 0xAD, 0xF3, 0x2A, 0xD8, 0xD8, 0xF1, 0xB0, 0xAC, 0x89, 0x91, 0x3E, 0x5E, 0x76,
+    0xF3, 0xAC, 0x2E, 0x2E, 0xF1, 0xB1, 0x8C, 0x5A, 0x9C, 0xAC, 0x2C, 0x28, 0x28, 0x28, 0x9C, 0xAC,
+    
+    // bank 7, 170 bytes (remainder)
+    0x30, 0x18, 0xA8, 0x98, 0x81, 0x28, 0x34, 0x3C, 0x97, 0x24, 0xA7, 0x28, 0x34, 0x3C, 0x9C, 0x24,
+    0xF2, 0xB0, 0x89, 0xAC, 0x91, 0x2C, 0x4C, 0x6C, 0x8A, 0x9B, 0x2D, 0xD9, 0xD8, 0xD8, 0x51, 0xD9,
+    0xD8, 0xD8, 0x79, 0xD9, 0xD8, 0xD8, 0xF1, 0x9E, 0x88, 0xA3, 0x31, 0xDA, 0xD8, 0xD8, 0x91, 0x2D,
+    0xD9, 0x28, 0xD8, 0x4D, 0xD9, 0x48, 0xD8, 0x6D, 0xD9, 0x68, 0xD8, 0xB1, 0x83, 0x93, 0x35, 0x3D,
+    0x80, 0x25, 0xDA, 0xD8, 0xD8, 0x85, 0x69, 0xDA, 0xD8, 0xD8, 0xB4, 0x93, 0x81, 0xA3, 0x28, 0x34,
+    0x3C, 0xF3, 0xAB, 0x8B, 0xA3, 0x91, 0xB6, 0x09, 0xB4, 0xD9, 0xAB, 0xDE, 0xB0, 0x87, 0x9C, 0xB9,
+    0xA3, 0xDD, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x95, 0xF1, 0xA3, 0xA3, 0xA3, 0x9D, 0xF1, 0xA3, 0xA3,
+    0xA3, 0xA3, 0xF2, 0xA3, 0xB4, 0x90, 0x80, 0xF2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3,
+    0xA3, 0xA3, 0xB2, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xA3, 0xB0, 0x87, 0xB5, 0x99, 0xF1, 0xA3, 0xA3,
+    0xA3, 0x98, 0xF1, 0xA3, 0xA3, 0xA3, 0xA3, 0x97, 0xA3, 0xA3, 0xA3, 0xA3, 0xF3, 0x9B, 0xA3, 0xA3,
+    0xDC, 0xB9, 0xA7, 0xF1, 0x26, 0x26, 0x26, 0xD8, 0xD8, 0xFF
+};
+
+const prog_uchar dmpConfig[MPU9150_DMP_CONFIG_SIZE] PROGMEM = {
+//  BANK    OFFSET  LENGTH  [DATA]
+    0x02,   0xEC,   0x04,   0x00, 0x47, 0x7D, 0x1A,   // ?
+    0x03,   0x82,   0x03,   0x4C, 0xCD, 0x6C,         // FCFG_1 inv_set_gyro_calibration
+    0x03,   0xB2,   0x03,   0x36, 0x56, 0x76,         // FCFG_3 inv_set_gyro_calibration
+    0x00,   0x68,   0x04,   0x02, 0xCA, 0xE3, 0x09,   // D_0_104 inv_set_gyro_calibration
+    0x01,   0x0C,   0x04,   0x00, 0x00, 0x00, 0x00,   // D_1_152 inv_set_accel_calibration
+    0x03,   0x86,   0x03,   0x0C, 0xC9, 0x2C,         // FCFG_2 inv_set_accel_calibration
+    0x03,   0x90,   0x03,   0x26, 0x46, 0x66,         //   (continued)...FCFG_2 inv_set_accel_calibration
+    0x00,   0x6C,   0x02,   0x40, 0x00,               // D_0_108 inv_set_accel_calibration
+
+    0x02,   0x40,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_00 inv_set_compass_calibration
+    0x02,   0x44,   0x04,   0x40, 0x00, 0x00, 0x00,   // CPASS_MTX_01
+    0x02,   0x48,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_02
+    0x02,   0x4C,   0x04,   0x40, 0x00, 0x00, 0x00,   // CPASS_MTX_10
+    0x02,   0x50,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_11
+    0x02,   0x54,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_12
+    0x02,   0x58,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_20
+    0x02,   0x5C,   0x04,   0x00, 0x00, 0x00, 0x00,   // CPASS_MTX_21
+    0x02,   0xBC,   0x04,   0xC0, 0x00, 0x00, 0x00,   // CPASS_MTX_22
+
+    0x01,   0xEC,   0x04,   0x00, 0x00, 0x40, 0x00,   // D_1_236 inv_apply_endian_accel
+    0x03,   0x86,   0x06,   0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97, // FCFG_2 inv_set_mpu_sensors
+    0x04,   0x22,   0x03,   0x0D, 0x35, 0x5D,         // CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion
+    0x00,   0xA3,   0x01,   0x00,                     // ?
+    0x04,   0x29,   0x04,   0x87, 0x2D, 0x35, 0x3D,   // FCFG_5 inv_set_bias_update
+    0x07,   0x62,   0x05,   0xF1, 0x20, 0x28, 0x30, 0x38, // CFG_8 inv_send_quaternion
+    0x07,   0x9F,   0x01,   0x30,                     // CFG_16 inv_set_footer
+    0x07,   0x67,   0x01,   0x9A,                     // CFG_GYRO_SOURCE inv_send_gyro
+    0x07,   0x68,   0x04,   0xF1, 0x28, 0x30, 0x38,   // CFG_9 inv_send_gyro -> inv_construct3_fifo
+    0x07,   0x62,   0x05,   0xF1, 0x20, 0x28, 0x30, 0x38, // ?
+    0x02,   0x0C,   0x04,   0x00, 0x00, 0x00, 0x00,   // ?
+    0x07,   0x83,   0x06,   0xC2, 0xCA, 0xC4, 0xA3, 0xA3, 0xA3, // ?
+                 // SPECIAL 0x01 = enable interrupts
+    0x00,   0x00,   0x00,   0x01, // SET INT_ENABLE, SPECIAL INSTRUCTION
+    0x07,   0xA7,   0x01,   0xFE,                     // ?
+    0x07,   0x62,   0x05,   0xF1, 0x20, 0x28, 0x30, 0x38, // ?
+    0x07,   0x67,   0x01,   0x9A,                     // ?
+    0x07,   0x68,   0x04,   0xF1, 0x28, 0x30, 0x38,   // CFG_12 inv_send_accel -> inv_construct3_fifo
+    0x07,   0x8D,   0x04,   0xF1, 0x28, 0x30, 0x38,   // ??? CFG_12 inv_send_mag -> inv_construct3_fifo
+    0x02,   0x16,   0x02,   0x00, 0x03                // D_0_22 inv_set_fifo_rate
+
+    // This very last 0x01 WAS a 0x09, which drops the FIFO rate down to 20 Hz. 0x07 is 25 Hz,
+    // 0x01 is 100Hz. Going faster than 100Hz (0x00=200Hz) tends to result in very noisy data.
+    // DMP output frequency is calculated easily using this equation: (200Hz / (1 + value))
+
+    // It is important to make sure the host processor can keep up with reading and processing
+    // the FIFO output at the desired rate. Handling FIFO overflow cleanly is also a good idea.
+};
+
+const prog_uchar dmpUpdates[MPU9150_DMP_UPDATES_SIZE] PROGMEM = {
+    0x01,   0xB2,   0x02,   0xFF, 0xF5,
+    0x01,   0x90,   0x04,   0x0A, 0x0D, 0x97, 0xC0,
+    0x00,   0xA3,   0x01,   0x00,
+    0x04,   0x29,   0x04,   0x87, 0x2D, 0x35, 0x3D,
+    0x01,   0x6A,   0x02,   0x06, 0x00,
+    0x01,   0x60,   0x08,   0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00,   0x60,   0x04,   0x40, 0x00, 0x00, 0x00,
+    0x02,   0x60,   0x0C,   0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x01,   0x08,   0x02,   0x01, 0x20,
+    0x01,   0x0A,   0x02,   0x00, 0x4E,
+    0x01,   0x02,   0x02,   0xFE, 0xB3,
+    0x02,   0x6C,   0x04,   0x00, 0x00, 0x00, 0x00, // READ
+    0x02,   0x6C,   0x04,   0xFA, 0xFE, 0x00, 0x00,
+    0x02,   0x60,   0x0C,   0xFF, 0xFF, 0xCB, 0x4D, 0x00, 0x01, 0x08, 0xC1, 0xFF, 0xFF, 0xBC, 0x2C,
+    0x02,   0xF4,   0x04,   0x00, 0x00, 0x00, 0x00,
+    0x02,   0xF8,   0x04,   0x00, 0x00, 0x00, 0x00,
+    0x02,   0xFC,   0x04,   0x00, 0x00, 0x00, 0x00,
+    0x00,   0x60,   0x04,   0x40, 0x00, 0x00, 0x00,
+    0x00,   0x60,   0x04,   0x00, 0x40, 0x00, 0x00
+};
+
+uint8_t MPU9150::dmpInitialize() {
+    // reset device
+    DEBUG_PRINTLN(F("\n\nResetting MPU9150..."));
+    reset();
+    delay(30); // wait after reset
+
+    // disable sleep mode
+    DEBUG_PRINTLN(F("Disabling sleep mode..."));
+    setSleepEnabled(false);
+
+    // get MPU product ID
+    DEBUG_PRINTLN(F("Getting product ID..."));
+    //uint8_t productID = 0; //getProductID();
+    DEBUG_PRINT(F("Product ID = "));
+    DEBUG_PRINT(productID);
+
+    // get MPU hardware revision
+    DEBUG_PRINTLN(F("Selecting user bank 16..."));
+    setMemoryBank(0x10, true, true);
+    DEBUG_PRINTLN(F("Selecting memory byte 6..."));
+    setMemoryStartAddress(0x06);
+    DEBUG_PRINTLN(F("Checking hardware revision..."));
+    uint8_t hwRevision = readMemoryByte();
+    DEBUG_PRINT(F("Revision @ user[16][6] = "));
+    DEBUG_PRINTLNF(hwRevision, HEX);
+    DEBUG_PRINTLN(F("Resetting memory bank selection to 0..."));
+    setMemoryBank(0, false, false);
+
+    // check OTP bank valid
+    DEBUG_PRINTLN(F("Reading OTP bank valid flag..."));
+    uint8_t otpValid = getOTPBankValid();
+    DEBUG_PRINT(F("OTP bank is "));
+    DEBUG_PRINTLN(otpValid ? F("valid!") : F("invalid!"));
+
+    // get X/Y/Z gyro offsets
+    DEBUG_PRINTLN(F("Reading gyro offset values..."));
+    int8_t xgOffset = getXGyroOffset();
+    int8_t ygOffset = getYGyroOffset();
+    int8_t zgOffset = getZGyroOffset();
+    DEBUG_PRINT(F("X gyro offset = "));
+    DEBUG_PRINTLN(xgOffset);
+    DEBUG_PRINT(F("Y gyro offset = "));
+    DEBUG_PRINTLN(ygOffset);
+    DEBUG_PRINT(F("Z gyro offset = "));
+    DEBUG_PRINTLN(zgOffset);
+    
+    I2Cdev::readByte(devAddr, MPU9150_RA_USER_CTRL, buffer); // ?
+    
+    DEBUG_PRINTLN(F("Enabling interrupt latch, clear on any read, AUX bypass enabled"));
+    I2Cdev::writeByte(devAddr, MPU9150_RA_INT_PIN_CFG, 0x32);
+
+    // enable MPU AUX I2C bypass mode
+    //DEBUG_PRINTLN(F("Enabling AUX I2C bypass mode..."));
+    //setI2CBypassEnabled(true);
+
+    DEBUG_PRINTLN(F("Setting magnetometer mode to power-down..."));
+    //mag -> setMode(0);
+    I2Cdev::writeByte(0x0E, 0x0A, 0x00);
+
+    DEBUG_PRINTLN(F("Setting magnetometer mode to fuse access..."));
+    //mag -> setMode(0x0F);
+    I2Cdev::writeByte(0x0E, 0x0A, 0x0F);
+
+    DEBUG_PRINTLN(F("Reading mag magnetometer factory calibration..."));
+    int8_t asax, asay, asaz;
+    //mag -> getAdjustment(&asax, &asay, &asaz);
+    I2Cdev::readBytes(0x0E, 0x10, 3, buffer);
+    asax = (int8_t)buffer[0];
+    asay = (int8_t)buffer[1];
+    asaz = (int8_t)buffer[2];
+    DEBUG_PRINT(F("Adjustment X/Y/Z = "));
+    DEBUG_PRINT(asax);
+    DEBUG_PRINT(F(" / "));
+    DEBUG_PRINT(asay);
+    DEBUG_PRINT(F(" / "));
+    DEBUG_PRINTLN(asaz);
+
+    DEBUG_PRINTLN(F("Setting magnetometer mode to power-down..."));
+    //mag -> setMode(0);
+    I2Cdev::writeByte(0x0E, 0x0A, 0x00);
+
+    // load DMP code into memory banks
+    DEBUG_PRINT(F("Writing DMP code to MPU memory banks ("));
+    DEBUG_PRINT(MPU9150_DMP_CODE_SIZE);
+    DEBUG_PRINTLN(F(" bytes)"));
+    if (writeProgMemoryBlock(dmpMemory, MPU9150_DMP_CODE_SIZE)) {
+        DEBUG_PRINTLN(F("Success! DMP code written and verified."));
+
+        DEBUG_PRINTLN(F("Configuring DMP and related settings..."));
+
+        // write DMP configuration
+        DEBUG_PRINT(F("Writing DMP configuration to MPU memory banks ("));
+        DEBUG_PRINT(MPU9150_DMP_CONFIG_SIZE);
+        DEBUG_PRINTLN(F(" bytes in config def)"));
+        if (writeProgDMPConfigurationSet(dmpConfig, MPU9150_DMP_CONFIG_SIZE)) {
+            DEBUG_PRINTLN(F("Success! DMP configuration written and verified."));
+
+            DEBUG_PRINTLN(F("Setting DMP and FIFO_OFLOW interrupts enabled..."));
+            setIntEnabled(0x12);
+
+            DEBUG_PRINTLN(F("Setting sample rate to 200Hz..."));
+            setRate(4); // 1khz / (1 + 4) = 200 Hz
+
+            DEBUG_PRINTLN(F("Setting clock source to Z Gyro..."));
+            setClockSource(MPU9150_CLOCK_PLL_ZGYRO);
+
+            DEBUG_PRINTLN(F("Setting DLPF bandwidth to 42Hz..."));
+            setDLPFMode(MPU9150_DLPF_BW_42);
+
+            DEBUG_PRINTLN(F("Setting external frame sync to TEMP_OUT_L[0]..."));
+            setExternalFrameSync(MPU9150_EXT_SYNC_TEMP_OUT_L);
+
+            DEBUG_PRINTLN(F("Setting gyro sensitivity to +/- 2000 deg/sec..."));
+            setFullScaleGyroRange(MPU9150_GYRO_FS_2000);
+
+            DEBUG_PRINTLN(F("Setting DMP configuration bytes (function unknown)..."));
+            setDMPConfig1(0x03);
+            setDMPConfig2(0x00);
+
+            DEBUG_PRINTLN(F("Clearing OTP Bank flag..."));
+            setOTPBankValid(false);
+
+            DEBUG_PRINTLN(F("Setting X/Y/Z gyro offsets to previous values..."));
+            setXGyroOffsetTC(xgOffset);
+            setYGyroOffsetTC(ygOffset);
+            setZGyroOffsetTC(zgOffset);
+
+            DEBUG_PRINTLN(F("Setting X/Y/Z gyro user offsets to zero..."));
+            setXGyroOffset(0);
+            setYGyroOffset(0);
+            setZGyroOffset(0);
+
+            DEBUG_PRINTLN(F("Writing final memory update 1/19 (function unknown)..."));
+            uint8_t dmpUpdate[16], j;
+            uint16_t pos = 0;
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            DEBUG_PRINTLN(F("Writing final memory update 2/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            DEBUG_PRINTLN(F("Resetting FIFO..."));
+            resetFIFO();
+
+            DEBUG_PRINTLN(F("Reading FIFO count..."));
+            uint8_t fifoCount = getFIFOCount();
+
+            DEBUG_PRINT(F("Current FIFO count="));
+            DEBUG_PRINTLN(fifoCount);
+            uint8_t fifoBuffer[128];
+            //getFIFOBytes(fifoBuffer, fifoCount);
+
+            DEBUG_PRINTLN(F("Writing final memory update 3/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            DEBUG_PRINTLN(F("Writing final memory update 4/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            DEBUG_PRINTLN(F("Disabling all standby flags..."));
+            I2Cdev::writeByte(0x68, MPU9150_RA_PWR_MGMT_2, 0x00);
+
+            DEBUG_PRINTLN(F("Setting accelerometer sensitivity to +/- 2g..."));
+            I2Cdev::writeByte(0x68, MPU9150_RA_ACCEL_CONFIG, 0x00);
+
+            DEBUG_PRINTLN(F("Setting motion detection threshold to 2..."));
+            setMotionDetectionThreshold(2);
+
+            DEBUG_PRINTLN(F("Setting zero-motion detection threshold to 156..."));
+            setZeroMotionDetectionThreshold(156);
+
+            DEBUG_PRINTLN(F("Setting motion detection duration to 80..."));
+            setMotionDetectionDuration(80);
+
+            DEBUG_PRINTLN(F("Setting zero-motion detection duration to 0..."));
+            setZeroMotionDetectionDuration(0);
+
+            DEBUG_PRINTLN(F("Setting AK8975 to single measurement mode..."));
+            //mag -> setMode(1);
+            I2Cdev::writeByte(0x0E, 0x0A, 0x01);
+
+            // setup AK8975 (0x0E) as Slave 0 in read mode
+            DEBUG_PRINTLN(F("Setting up AK8975 read slave 0..."));
+            I2Cdev::writeByte(0x68, MPU9150_RA_I2C_SLV0_ADDR, 0x8E);
+            I2Cdev::writeByte(0x68, MPU9150_RA_I2C_SLV0_REG,  0x01);
+            I2Cdev::writeByte(0x68, MPU9150_RA_I2C_SLV0_CTRL, 0xDA);
+
+            // setup AK8975 (0x0E) as Slave 2 in write mode
+            DEBUG_PRINTLN(F("Setting up AK8975 write slave 2..."));
+            I2Cdev::writeByte(0x68, MPU9150_RA_I2C_SLV2_ADDR, 0x0E);
+            I2Cdev::writeByte(0x68, MPU9150_RA_I2C_SLV2_REG,  0x0A);
+            I2Cdev::writeByte(0x68, MPU9150_RA_I2C_SLV2_CTRL, 0x81);
+            I2Cdev::writeByte(0x68, MPU9150_RA_I2C_SLV2_DO,   0x01);
+
+            // setup I2C timing/delay control
+            DEBUG_PRINTLN(F("Setting up slave access delay..."));
+            I2Cdev::writeByte(0x68, MPU9150_RA_I2C_SLV4_CTRL, 0x18);
+            I2Cdev::writeByte(0x68, MPU9150_RA_I2C_MST_DELAY_CTRL, 0x05);
+
+            // enable interrupts
+            DEBUG_PRINTLN(F("Enabling default interrupt behavior/no bypass..."));
+            I2Cdev::writeByte(0x68, MPU9150_RA_INT_PIN_CFG, 0x00);
+
+            // enable I2C master mode and reset DMP/FIFO
+            DEBUG_PRINTLN(F("Enabling I2C master mode..."));
+            I2Cdev::writeByte(0x68, MPU9150_RA_USER_CTRL, 0x20);
+            DEBUG_PRINTLN(F("Resetting FIFO..."));
+            I2Cdev::writeByte(0x68, MPU9150_RA_USER_CTRL, 0x24);
+            DEBUG_PRINTLN(F("Rewriting I2C master mode enabled because...I don't know"));
+            I2Cdev::writeByte(0x68, MPU9150_RA_USER_CTRL, 0x20);
+            DEBUG_PRINTLN(F("Enabling and resetting DMP/FIFO..."));
+            I2Cdev::writeByte(0x68, MPU9150_RA_USER_CTRL, 0xE8);
+
+            DEBUG_PRINTLN(F("Writing final memory update 5/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+            DEBUG_PRINTLN(F("Writing final memory update 6/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+            DEBUG_PRINTLN(F("Writing final memory update 7/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+            DEBUG_PRINTLN(F("Writing final memory update 8/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+            DEBUG_PRINTLN(F("Writing final memory update 9/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+            DEBUG_PRINTLN(F("Writing final memory update 10/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+            DEBUG_PRINTLN(F("Writing final memory update 11/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+            
+            DEBUG_PRINTLN(F("Reading final memory update 12/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            readMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+            #ifdef DEBUG
+                DEBUG_PRINT(F("Read bytes: "));
+                for (j = 0; j < 4; j++) {
+                    DEBUG_PRINTF(dmpUpdate[3 + j], HEX);
+                    DEBUG_PRINT(" ");
+                }
+                DEBUG_PRINTLN("");
+            #endif
+
+            DEBUG_PRINTLN(F("Writing final memory update 13/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+            DEBUG_PRINTLN(F("Writing final memory update 14/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+            DEBUG_PRINTLN(F("Writing final memory update 15/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+            DEBUG_PRINTLN(F("Writing final memory update 16/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+            DEBUG_PRINTLN(F("Writing final memory update 17/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            DEBUG_PRINTLN(F("Waiting for FIRO count >= 46..."));
+            while ((fifoCount = getFIFOCount()) < 46);
+            DEBUG_PRINTLN(F("Reading FIFO..."));
+            getFIFOBytes(fifoBuffer, min(fifoCount, 128)); // safeguard only 128 bytes
+            DEBUG_PRINTLN(F("Reading interrupt status..."));
+            getIntStatus();
+
+            DEBUG_PRINTLN(F("Writing final memory update 18/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            DEBUG_PRINTLN(F("Waiting for FIRO count >= 48..."));
+            while ((fifoCount = getFIFOCount()) < 48);
+            DEBUG_PRINTLN(F("Reading FIFO..."));
+            getFIFOBytes(fifoBuffer, min(fifoCount, 128)); // safeguard only 128 bytes
+            DEBUG_PRINTLN(F("Reading interrupt status..."));
+            getIntStatus();
+            DEBUG_PRINTLN(F("Waiting for FIRO count >= 48..."));
+            while ((fifoCount = getFIFOCount()) < 48);
+            DEBUG_PRINTLN(F("Reading FIFO..."));
+            getFIFOBytes(fifoBuffer, min(fifoCount, 128)); // safeguard only 128 bytes
+            DEBUG_PRINTLN(F("Reading interrupt status..."));
+            getIntStatus();
+
+            DEBUG_PRINTLN(F("Writing final memory update 19/19 (function unknown)..."));
+            for (j = 0; j < 4 || j < dmpUpdate[2] + 3; j++, pos++) dmpUpdate[j] = pgm_read_byte(&dmpUpdates[pos]);
+            writeMemoryBlock(dmpUpdate + 3, dmpUpdate[2], dmpUpdate[0], dmpUpdate[1]);
+
+            DEBUG_PRINTLN(F("Disabling DMP (you turn it on later)..."));
+            setDMPEnabled(false);
+
+            DEBUG_PRINTLN(F("Setting up internal 48-byte (default) DMP packet buffer..."));
+            dmpPacketSize = 48;
+            /*if ((dmpPacketBuffer = (uint8_t *)malloc(42)) == 0) {
+                return 3; // TODO: proper error code for no memory
+            }*/
+
+            DEBUG_PRINTLN(F("Resetting FIFO and clearing INT status one last time..."));
+            resetFIFO();
+            getIntStatus();
+        } else {
+            DEBUG_PRINTLN(F("ERROR! DMP configuration verification failed."));
+            return 2; // configuration block loading failed
+        }
+    } else {
+        DEBUG_PRINTLN(F("ERROR! DMP code verification failed."));
+        return 1; // main binary block loading failed
+    }
+    return 0; // success
+}
+
+bool MPU9150::dmpPacketAvailable() {
+    return getFIFOCount() >= dmpGetFIFOPacketSize();
+}
+
+// uint8_t MPU9150::dmpSetFIFORate(uint8_t fifoRate);
+// uint8_t MPU9150::dmpGetFIFORate();
+// uint8_t MPU9150::dmpGetSampleStepSizeMS();
+// uint8_t MPU9150::dmpGetSampleFrequency();
+// int32_t MPU9150::dmpDecodeTemperature(int8_t tempReg);
+
+//uint8_t MPU9150::dmpRegisterFIFORateProcess(inv_obj_func func, int16_t priority);
+//uint8_t MPU9150::dmpUnregisterFIFORateProcess(inv_obj_func func);
+//uint8_t MPU9150::dmpRunFIFORateProcesses();
+
+// uint8_t MPU9150::dmpSendQuaternion(uint_fast16_t accuracy);
+// uint8_t MPU9150::dmpSendGyro(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU9150::dmpSendAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU9150::dmpSendLinearAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU9150::dmpSendLinearAccelInWorld(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU9150::dmpSendControlData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU9150::dmpSendSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU9150::dmpSendExternalSensorData(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU9150::dmpSendGravity(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU9150::dmpSendPacketNumber(uint_fast16_t accuracy);
+// uint8_t MPU9150::dmpSendQuantizedAccel(uint_fast16_t elements, uint_fast16_t accuracy);
+// uint8_t MPU9150::dmpSendEIS(uint_fast16_t elements, uint_fast16_t accuracy);
+
+uint8_t MPU9150::dmpGetAccel(int32_t *data, const uint8_t* packet) {
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = ((packet[34] << 24) + (packet[35] << 16) + (packet[36] << 8) + packet[37]);
+    data[1] = ((packet[38] << 24) + (packet[39] << 16) + (packet[40] << 8) + packet[41]);
+    data[2] = ((packet[42] << 24) + (packet[43] << 16) + (packet[44] << 8) + packet[45]);
+    return 0;
+}
+uint8_t MPU9150::dmpGetAccel(int16_t *data, const uint8_t* packet) {
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = (packet[34] << 8) + packet[35];
+    data[1] = (packet[38] << 8) + packet[39];
+    data[2] = (packet[42] << 8) + packet[43];
+    return 0;
+}
+uint8_t MPU9150::dmpGetAccel(VectorInt16 *v, const uint8_t* packet) {
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    v -> x = (packet[34] << 8) + packet[35];
+    v -> y = (packet[38] << 8) + packet[39];
+    v -> z = (packet[42] << 8) + packet[43];
+    return 0;
+}
+uint8_t MPU9150::dmpGetQuaternion(int32_t *data, const uint8_t* packet) {
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = ((packet[0] << 24) + (packet[1] << 16) + (packet[2] << 8) + packet[3]);
+    data[1] = ((packet[4] << 24) + (packet[5] << 16) + (packet[6] << 8) + packet[7]);
+    data[2] = ((packet[8] << 24) + (packet[9] << 16) + (packet[10] << 8) + packet[11]);
+    data[3] = ((packet[12] << 24) + (packet[13] << 16) + (packet[14] << 8) + packet[15]);
+    return 0;
+}
+uint8_t MPU9150::dmpGetQuaternion(int16_t *data, const uint8_t* packet) {
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = ((packet[0] << 8) + packet[1]);
+    data[1] = ((packet[4] << 8) + packet[5]);
+    data[2] = ((packet[8] << 8) + packet[9]);
+    data[3] = ((packet[12] << 8) + packet[13]);
+    return 0;
+}
+uint8_t MPU9150::dmpGetQuaternion(Quaternion *q, const uint8_t* packet) {
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    int16_t qI[4];
+    uint8_t status = dmpGetQuaternion(qI, packet);
+    if (status == 0) {
+        q -> w = (float)qI[0] / 16384.0f;
+        q -> x = (float)qI[1] / 16384.0f;
+        q -> y = (float)qI[2] / 16384.0f;
+        q -> z = (float)qI[3] / 16384.0f;
+        return 0;
+    }
+    return status; // int16 return value, indicates error if this line is reached
+}
+// uint8_t MPU9150::dmpGet6AxisQuaternion(long *data, const uint8_t* packet);
+// uint8_t MPU9150::dmpGetRelativeQuaternion(long *data, const uint8_t* packet);
+uint8_t MPU9150::dmpGetGyro(int32_t *data, const uint8_t* packet) {
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = ((packet[16] << 24) + (packet[17] << 16) + (packet[18] << 8) + packet[19]);
+    data[1] = ((packet[20] << 24) + (packet[21] << 16) + (packet[22] << 8) + packet[23]);
+    data[2] = ((packet[24] << 24) + (packet[25] << 16) + (packet[26] << 8) + packet[27]);
+    return 0;
+}
+uint8_t MPU9150::dmpGetGyro(int16_t *data, const uint8_t* packet) {
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = (packet[16] << 8) + packet[17];
+    data[1] = (packet[20] << 8) + packet[21];
+    data[2] = (packet[24] << 8) + packet[25];
+    return 0;
+}
+uint8_t MPU9150::dmpGetMag(int16_t *data, const uint8_t* packet) {
+    // TODO: accommodate different arrangements of sent data (ONLY default supported now)
+    if (packet == 0) packet = dmpPacketBuffer;
+    data[0] = (packet[28] << 8) + packet[29];
+    data[1] = (packet[30] << 8) + packet[31];
+    data[2] = (packet[32] << 8) + packet[33];
+    return 0;
+}
+// uint8_t MPU9150::dmpSetLinearAccelFilterCoefficient(float coef);
+// uint8_t MPU9150::dmpGetLinearAccel(long *data, const uint8_t* packet);
+uint8_t MPU9150::dmpGetLinearAccel(VectorInt16 *v, VectorInt16 *vRaw, VectorFloat *gravity) {
+    // get rid of the gravity component (+1g = +4096 in standard DMP FIFO packet)
+    v -> x = vRaw -> x - gravity -> x*4096;
+    v -> y = vRaw -> y - gravity -> y*4096;
+    v -> z = vRaw -> z - gravity -> z*4096;
+    return 0;
+}
+// uint8_t MPU9150::dmpGetLinearAccelInWorld(long *data, const uint8_t* packet);
+uint8_t MPU9150::dmpGetLinearAccelInWorld(VectorInt16 *v, VectorInt16 *vReal, Quaternion *q) {
+    // rotate measured 3D acceleration vector into original state
+    // frame of reference based on orientation quaternion
+    memcpy(v, vReal, sizeof(VectorInt16));
+    v -> rotate(q);
+    return 0;
+}
+// uint8_t MPU9150::dmpGetGyroAndAccelSensor(long *data, const uint8_t* packet);
+// uint8_t MPU9150::dmpGetGyroSensor(long *data, const uint8_t* packet);
+// uint8_t MPU9150::dmpGetControlData(long *data, const uint8_t* packet);
+// uint8_t MPU9150::dmpGetTemperature(long *data, const uint8_t* packet);
+// uint8_t MPU9150::dmpGetGravity(long *data, const uint8_t* packet);
+uint8_t MPU9150::dmpGetGravity(VectorFloat *v, Quaternion *q) {
+    v -> x = 2 * (q -> x*q -> z - q -> w*q -> y);
+    v -> y = 2 * (q -> w*q -> x + q -> y*q -> z);
+    v -> z = q -> w*q -> w - q -> x*q -> x - q -> y*q -> y + q -> z*q -> z;
+    return 0;
+}
+// uint8_t MPU9150::dmpGetUnquantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU9150::dmpGetQuantizedAccel(long *data, const uint8_t* packet);
+// uint8_t MPU9150::dmpGetExternalSensorData(long *data, int size, const uint8_t* packet);
+// uint8_t MPU9150::dmpGetEIS(long *data, const uint8_t* packet);
+
+uint8_t MPU9150::dmpGetEuler(float *data, Quaternion *q) {
+    data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);   // psi
+    data[1] = -asin(2*q -> x*q -> z + 2*q -> w*q -> y);                              // theta
+    data[2] = atan2(2*q -> y*q -> z - 2*q -> w*q -> x, 2*q -> w*q -> w + 2*q -> z*q -> z - 1);   // phi
+    return 0;
+}
+uint8_t MPU9150::dmpGetYawPitchRoll(float *data, Quaternion *q, VectorFloat *gravity) {
+    // yaw: (about Z axis)
+    data[0] = atan2(2*q -> x*q -> y - 2*q -> w*q -> z, 2*q -> w*q -> w + 2*q -> x*q -> x - 1);
+    // pitch: (nose up/down, about Y axis)
+    data[1] = atan(gravity -> x / sqrt(gravity -> y*gravity -> y + gravity -> z*gravity -> z));
+    // roll: (tilt left/right, about X axis)
+    data[2] = atan(gravity -> y / sqrt(gravity -> x*gravity -> x + gravity -> z*gravity -> z));
+    return 0;
+}
+
+// uint8_t MPU9150::dmpGetAccelFloat(float *data, const uint8_t* packet);
+// uint8_t MPU9150::dmpGetQuaternionFloat(float *data, const uint8_t* packet);
+
+uint8_t MPU9150::dmpProcessFIFOPacket(const unsigned char *dmpData) {
+    /*for (uint8_t k = 0; k < dmpPacketSize; k++) {
+        if (dmpData[k] < 0x10) Serial.print("0");
+        Serial.print(dmpData[k], HEX);
+        Serial.print(" ");
+    }
+    Serial.print("\n");*/
+    //Serial.println((uint16_t)dmpPacketBuffer);
+    return 0;
+}
+uint8_t MPU9150::dmpReadAndProcessFIFOPacket(uint8_t numPackets, uint8_t *processed) {
+    uint8_t status;
+    uint8_t buf[dmpPacketSize];
+    for (uint8_t i = 0; i < numPackets; i++) {
+        // read packet from FIFO
+        getFIFOBytes(buf, dmpPacketSize);
+
+        // process packet
+        if ((status = dmpProcessFIFOPacket(buf)) > 0) return status;
+        
+        // increment external process count variable, if supplied
+        if (processed != 0) *processed++;
+    }
+    return 0;
+}
+
+// uint8_t MPU9150::dmpSetFIFOProcessedCallback(void (*func) (void));
+
+// uint8_t MPU9150::dmpInitFIFOParam();
+// uint8_t MPU9150::dmpCloseFIFO();
+// uint8_t MPU9150::dmpSetGyroDataSource(uint_fast8_t source);
+// uint8_t MPU9150::dmpDecodeQuantizedAccel();
+// uint32_t MPU9150::dmpGetGyroSumOfSquare();
+// uint32_t MPU9150::dmpGetAccelSumOfSquare();
+// void MPU9150::dmpOverrideQuaternion(long *q);
+uint16_t MPU9150::dmpGetFIFOPacketSize() {
+    return dmpPacketSize;
+}
+
+#endif /* _MPU9150_9AXIS_MOTIONAPPS41_H_ */
diff --git a/libraries/MPU9150/examples/MPU9150_raw/MPU9150_raw.ino b/libraries/MPU9150/examples/MPU9150_raw/MPU9150_raw.ino
new file mode 100644
index 0000000..e2c9224
--- /dev/null
+++ b/libraries/MPU9150/examples/MPU9150_raw/MPU9150_raw.ino
@@ -0,0 +1,108 @@
+// I2C device class (I2Cdev) demonstration Arduino sketch for MPU9150
+// 1/4/2013 original by Jeff Rowberg  at https://github.com/jrowberg/i2cdevlib
+//          modified by Aaron Weiss 
+//
+// Changelog:
+//     2011-10-07 - initial release
+//     2013-1-4 - added raw magnetometer output
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+
+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 MPU9150 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 "MPU9150.h"
+#include "helper_3dmath.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
+MPU9150 accelGyroMag;
+
+int16_t ax, ay, az;
+int16_t gx, gy, gz;
+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(115200);
+
+    // initialize device
+    Serial.println("Initializing I2C devices...");
+    accelGyroMag.initialize();
+
+    // verify connection
+    Serial.println("Testing device connections...");
+    Serial.println(accelGyroMag.testConnection() ? "MPU9150 connection successful" : "MPU9150 connection failed");
+
+    // configure Arduino LED for
+    pinMode(LED_PIN, OUTPUT);
+}
+
+void loop() {
+    // read raw accel/gyro/mag measurements from device
+    accelGyroMag.getMotion9(&ax, &ay, &az, &gx, &gy, &gz, &mx, &my, &mz);
+
+    // these methods (and a few others) are also available
+    //accelGyroMag.getAcceleration(&ax, &ay, &az);
+    //accelGyroMag.getRotation(&gx, &gy, &gz);
+
+    // display tab-separated accel/gyro/mag x/y/z values
+//  Serial.print("a/g/m:\t");
+//  Serial.print(ax); Serial.print("\t");
+//  Serial.print(ay); Serial.print("\t");
+//  Serial.print(az); Serial.print("\t");
+//  Serial.print(gx); Serial.print("\t");
+//  Serial.print(gy); Serial.print("\t");
+//  Serial.print(gz); Serial.print("\t");
+    Serial.print(int(mx)*int(mx)); Serial.print("\t");
+    Serial.print(int(my)*int(my)); Serial.print("\t");
+    Serial.print(int(mz)*int(mz)); Serial.print("\t | ");
+
+    const float N = 256;
+    float mag = mx*mx/N + my*my/N + mz*mz/N;
+
+    Serial.print(mag); Serial.print("\t");
+    for (int i=0; i
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     2012-06-05 - add 3D math helper file to DMP6 example sketch
+
+/* ============================================
+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.
+===============================================
+*/
+
+#ifndef _HELPER_3DMATH_H_
+#define _HELPER_3DMATH_H_
+
+class Quaternion {
+    public:
+        float w;
+        float x;
+        float y;
+        float z;
+        
+        Quaternion() {
+            w = 1.0f;
+            x = 0.0f;
+            y = 0.0f;
+            z = 0.0f;
+        }
+        
+        Quaternion(float nw, float nx, float ny, float nz) {
+            w = nw;
+            x = nx;
+            y = ny;
+            z = nz;
+        }
+
+        Quaternion getProduct(Quaternion q) {
+            // Quaternion multiplication is defined by:
+            //     (Q1 * Q2).w = (w1w2 - x1x2 - y1y2 - z1z2)
+            //     (Q1 * Q2).x = (w1x2 + x1w2 + y1z2 - z1y2)
+            //     (Q1 * Q2).y = (w1y2 - x1z2 + y1w2 + z1x2)
+            //     (Q1 * Q2).z = (w1z2 + x1y2 - y1x2 + z1w2
+            return Quaternion(
+                w*q.w - x*q.x - y*q.y - z*q.z,  // new w
+                w*q.x + x*q.w + y*q.z - z*q.y,  // new x
+                w*q.y - x*q.z + y*q.w + z*q.x,  // new y
+                w*q.z + x*q.y - y*q.x + z*q.w); // new z
+        }
+
+        Quaternion getConjugate() {
+            return Quaternion(w, -x, -y, -z);
+        }
+        
+        float getMagnitude() {
+            return sqrt(w*w + x*x + y*y + z*z);
+        }
+        
+        void normalize() {
+            float m = getMagnitude();
+            w /= m;
+            x /= m;
+            y /= m;
+            z /= m;
+        }
+        
+        Quaternion getNormalized() {
+            Quaternion r(w, x, y, z);
+            r.normalize();
+            return r;
+        }
+};
+
+class VectorInt16 {
+    public:
+        int16_t x;
+        int16_t y;
+        int16_t z;
+
+        VectorInt16() {
+            x = 0;
+            y = 0;
+            z = 0;
+        }
+        
+        VectorInt16(int16_t nx, int16_t ny, int16_t nz) {
+            x = nx;
+            y = ny;
+            z = nz;
+        }
+
+        float getMagnitude() {
+            return sqrt(x*x + y*y + z*z);
+        }
+
+        void normalize() {
+            float m = getMagnitude();
+            x /= m;
+            y /= m;
+            z /= m;
+        }
+        
+        VectorInt16 getNormalized() {
+            VectorInt16 r(x, y, z);
+            r.normalize();
+            return r;
+        }
+        
+        void rotate(Quaternion *q) {
+            // http://www.cprogramming.com/tutorial/3d/quaternions.html
+            // http://www.euclideanspace.com/maths/algebra/realNormedAlgebra/quaternions/transforms/index.htm
+            // http://content.gpwiki.org/index.php/OpenGL:Tutorials:Using_Quaternions_to_represent_rotation
+            // ^ or: http://webcache.googleusercontent.com/search?q=cache:xgJAp3bDNhQJ:content.gpwiki.org/index.php/OpenGL:Tutorials:Using_Quaternions_to_represent_rotation&hl=en&gl=us&strip=1
+        
+            // P_out = q * P_in * conj(q)
+            // - P_out is the output vector
+            // - q is the orientation quaternion
+            // - P_in is the input vector (a*aReal)
+            // - conj(q) is the conjugate of the orientation quaternion (q=[w,x,y,z], q*=[w,-x,-y,-z])
+            Quaternion p(0, x, y, z);
+
+            // quaternion multiplication: q * p, stored back in p
+            p = q -> getProduct(p);
+
+            // quaternion multiplication: p * conj(q), stored back in p
+            p = p.getProduct(q -> getConjugate());
+
+            // p quaternion is now [0, x', y', z']
+            x = p.x;
+            y = p.y;
+            z = p.z;
+        }
+
+        VectorInt16 getRotated(Quaternion *q) {
+            VectorInt16 r(x, y, z);
+            r.rotate(q);
+            return r;
+        }
+};
+
+class VectorFloat {
+    public:
+        float x;
+        float y;
+        float z;
+
+        VectorFloat() {
+            x = 0;
+            y = 0;
+            z = 0;
+        }
+        
+        VectorFloat(float nx, float ny, float nz) {
+            x = nx;
+            y = ny;
+            z = nz;
+        }
+
+        float getMagnitude() {
+            return sqrt(x*x + y*y + z*z);
+        }
+
+        void normalize() {
+            float m = getMagnitude();
+            x /= m;
+            y /= m;
+            z /= m;
+        }
+        
+        VectorFloat getNormalized() {
+            VectorFloat r(x, y, z);
+            r.normalize();
+            return r;
+        }
+        
+        void rotate(Quaternion *q) {
+            Quaternion p(0, x, y, z);
+
+            // quaternion multiplication: q * p, stored back in p
+            p = q -> getProduct(p);
+
+            // quaternion multiplication: p * conj(q), stored back in p
+            p = p.getProduct(q -> getConjugate());
+
+            // p quaternion is now [0, x', y', z']
+            x = p.x;
+            y = p.y;
+            z = p.z;
+        }
+
+        VectorFloat getRotated(Quaternion *q) {
+            VectorFloat r(x, y, z);
+            r.rotate(q);
+            return r;
+        }
+};
+
+#endif /* _HELPER_3DMATH_H_ */
\ No newline at end of file
diff --git a/libraries/MPU9150/library.json b/libraries/MPU9150/library.json
new file mode 100644
index 0000000..38cde7e
--- /dev/null
+++ b/libraries/MPU9150/library.json
@@ -0,0 +1,18 @@
+{
+  "name": "I2Cdevlib-MPU9150",
+  "keywords": "gyroscope, accelerometer, compass, sensor, i2cdevlib, i2c",
+  "description": "The MPU-9150 combines two chips: the MPU-6050, which contains a 3-axis gyroscope, 3-axis accelerometer and the AK8975, a 3-axis digital compass",
+  "include": "Arduino/MPU9150",
+  "repository":
+  {
+    "type": "git",
+    "url": "https://github.com/jrowberg/i2cdevlib.git"
+  },
+  "dependencies":
+  {
+    "name": "I2Cdevlib-Core",
+    "frameworks": "arduino"
+  },
+  "frameworks": "arduino",
+  "platforms": "atmelavr"
+}
diff --git a/libraries/MPU9150Lib/MPU9150Lib.cpp b/libraries/MPU9150Lib/MPU9150Lib.cpp
new file mode 100644
index 0000000..b106ccd
--- /dev/null
+++ b/libraries/MPU9150Lib/MPU9150Lib.cpp
@@ -0,0 +1,455 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of MPU9150Lib
+//
+//  Copyright (c) 2013 Pansenti, LLC
+//
+//  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 "MPU9150Lib.h"
+#include "inv_mpu.h"
+#include "inv_mpu_dmp_motion_driver.h"
+#include "MPUQuaternion.h"
+
+////////////////////////////////////////////////////////////////////////////
+//
+//  The functions below are from the InvenSense SDK example code.
+//
+//  Original copyright notice below:
+
+/*
+ $License:
+    Copyright (C) 2011-2012 InvenSense Corporation, All Rights Reserved.
+    See included License.txt for License information.
+ $
+ */
+
+/* These next two functions converts the orientation matrix (see
+ * gyro_orientation) to a scalar representation for use by the DMP.
+ * NOTE: These functions are borrowed from InvenSense's MPL.
+ */
+
+static inline unsigned short inv_row_2_scale(const signed char *row)
+{
+    unsigned short b;
+
+    if (row[0] > 0)
+        b = 0;
+    else if (row[0] < 0)
+        b = 4;
+    else if (row[1] > 0)
+        b = 1;
+    else if (row[1] < 0)
+        b = 5;
+    else if (row[2] > 0)
+        b = 2;
+    else if (row[2] < 0)
+        b = 6;
+    else
+        b = 7;      // error
+    return b;
+}
+
+/* The sensors can be mounted onto the board in any orientation. The mounting
+ * matrix seen below tells the MPL how to rotate the raw data from thei
+ * driver(s).
+ * TODO: The following matrices refer to the configuration on an internal test
+ * board at Invensense. If needed, please modify the matrices to match the
+ * chip-to-body matrix for your particular set up.
+ */
+
+static signed char gyro_orientation[9] = { 1, 0, 0,
+                                           0, 1, 0,
+                                           0, 0, 1};
+
+static inline unsigned short inv_orientation_matrix_to_scalar(const signed char *mtx)
+{
+    unsigned short scalar;
+    /*
+
+       XYZ  010_001_000 Identity Matrix
+       XZY  001_010_000
+       YXZ  010_000_001
+       YZX  000_010_001
+       ZXY  001_000_010
+       ZYX  000_001_010
+     */
+    scalar = inv_row_2_scale(mtx);
+    scalar |= inv_row_2_scale(mtx + 3) << 3;
+    scalar |= inv_row_2_scale(mtx + 6) << 6;
+    return scalar;
+}
+
+//
+////////////////////////////////////////////////////////////////////////////
+
+
+MPU9150Lib::MPU9150Lib()
+{
+  //  use calibration if available
+
+  m_useAccelCalibration = true;
+  m_useMagCalibration = true;
+  m_device = 0;
+ }
+
+void MPU9150Lib::selectDevice(int device)
+{
+  m_device = device;
+}
+
+void MPU9150Lib::useAccelCal(boolean useCal)
+{
+  m_useAccelCalibration = useCal;
+}
+
+void MPU9150Lib::disableAccelCal()
+{
+    if (!m_useAccelCalibration)
+        return;
+    m_useAccelCalibration = false;
+
+    m_accelOffset[0] = 0;
+    m_accelOffset[1] = 0;
+    m_accelOffset[2] = 0;
+
+    mpu_set_accel_bias(m_accelOffset);
+}
+
+void MPU9150Lib::useMagCal(boolean useCal)
+{
+  m_useMagCalibration = useCal;
+}
+
+boolean MPU9150Lib::init(int mpuRate, int magMix, int magRate, int lpf)
+{
+  struct int_param_s int_param;
+  int result;
+
+  mpu_select_device(m_device);
+  dmp_select_device(m_device);
+  if (magRate > 100)
+    return false;                                         // rate must be less than or equal to 100Hz
+  if (magRate < 1)
+    return false;
+  m_magInterval = (unsigned long)(1000 / magRate);        // record mag interval
+  m_lastMagSample = millis();
+
+  if (mpuRate > 1000)
+    return false;
+  if (mpuRate < 1)
+    return false;
+  m_magMix = magMix;
+  m_lastDMPYaw = 0;
+  m_lastYaw = 0;
+
+  // get calibration data if it's there
+
+  if (calLibRead(m_device, &m_calData)) {                 // use calibration data if it's there and wanted
+    m_useMagCalibration &= m_calData.magValid == 1;
+    m_useAccelCalibration &= m_calData.accelValid == 1;
+
+    //  Process calibration data for runtime
+
+    if (m_useMagCalibration) {
+       m_magXOffset = (short)(((long)m_calData.magMaxX + (long)m_calData.magMinX) / 2);
+       m_magXRange = m_calData.magMaxX - m_magXOffset;
+       m_magYOffset = (short)(((long)m_calData.magMaxY + (long)m_calData.magMinY) / 2);
+       m_magYRange = m_calData.magMaxY - m_magYOffset;
+       m_magZOffset = (short)(((long)m_calData.magMaxZ + (long)m_calData.magMinZ) / 2);
+       m_magZRange = m_calData.magMaxZ - m_magZOffset;
+    }
+
+     if (m_useAccelCalibration) {
+       m_accelOffset[0] = -((long)m_calData.accelMaxX + (long)m_calData.accelMinX) / 2;
+       m_accelOffset[1] = -((long)m_calData.accelMaxY + (long)m_calData.accelMinY) / 2;
+       m_accelOffset[2] = -((long)m_calData.accelMaxZ + (long)m_calData.accelMinZ) / 2;
+
+       mpu_set_accel_bias(m_accelOffset);
+
+       m_accelXRange = m_calData.accelMaxX + (short)m_accelOffset[0];
+       m_accelYRange = m_calData.accelMaxY + (short)m_accelOffset[1];
+       m_accelZRange = m_calData.accelMaxZ + (short)m_accelOffset[2];
+     }
+  } else {
+      m_useMagCalibration = false;
+      m_useAccelCalibration = false;
+  }
+
+#ifdef MPULIB_DEBUG
+  if (m_useMagCalibration)
+	  Serial.println("Using mag cal");
+  if (m_useAccelCalibration)
+	  Serial.println("Using accel cal");
+#endif
+
+  mpu_init_structures();
+    
+  // Not using interrupts so set up this structure to keep the driver happy
+        
+  int_param.cb = NULL;
+  int_param.pin = 0;
+  int_param.lp_exit = 0;
+  int_param.active_low = 1;
+  result = mpu_init(&int_param);
+  if (result != 0) {
+#ifdef MPULIB_DEBUG
+     Serial.print("mpu_init failed with code: "); Serial.println(result);
+#endif
+     return false; 
+  }
+  mpu_set_sensors(INV_XYZ_GYRO | INV_XYZ_ACCEL | INV_XYZ_COMPASS);   // enable all of the sensors
+  mpu_configure_fifo(INV_XYZ_GYRO | INV_XYZ_ACCEL);                  // get accel and gyro data in the FIFO also
+
+#ifdef MPULIB_DEBUG
+  Serial.println("Loading firmware");
+#endif
+
+  if ((result = dmp_load_motion_driver_firmware()) != 0) {           // try to load the DMP firmware
+#ifdef MPULIB_DEBUG
+    Serial.print("Failed to load dmp firmware: ");
+    Serial.println(result);
+#endif
+    return false;
+  }
+  dmp_set_orientation(inv_orientation_matrix_to_scalar(gyro_orientation)); // set up the correct orientation
+
+  dmp_enable_feature(DMP_FEATURE_6X_LP_QUAT | DMP_FEATURE_SEND_RAW_ACCEL | DMP_FEATURE_SEND_CAL_GYRO |
+        DMP_FEATURE_GYRO_CAL);
+  dmp_set_fifo_rate(mpuRate);
+  if (mpu_set_dmp_state(1) != 0) {
+#ifdef MPULIB_DEBUG
+    Serial.println("mpu_set_dmp_state failed");
+#endif
+    return false;
+  }
+  mpu_set_sample_rate(mpuRate);                                      // set the update rate
+  mpu_set_compass_sample_rate(magRate);                              // set the compass update rate to match
+  if (lpf != 0)
+    mpu_set_lpf(lpf);                                                // set the low pass filter
+  return true;
+}
+
+boolean MPU9150Lib::read()
+{
+    short intStatus;
+    int result;
+    short sensors;
+    unsigned char more;
+    unsigned long timestamp;
+   
+    mpu_select_device(m_device);
+    dmp_select_device(m_device);
+    mpu_get_int_status(&intStatus);                       // get the current MPU state
+    if ((intStatus & (MPU_INT_STATUS_DMP | MPU_INT_STATUS_DMP_0))
+            != (MPU_INT_STATUS_DMP | MPU_INT_STATUS_DMP_0))
+        return false;
+        
+    //  get the data from the fifo
+        
+    if ((result = dmp_read_fifo(m_rawGyro, m_rawAccel, m_rawQuaternion, ×tamp, &sensors, &more)) != 0) {
+      return false;
+    }      
+    
+    //  got the fifo data so now get the mag data if it's time
+    
+    if ((millis() - m_lastMagSample) >= m_magInterval) {
+      if ((result = mpu_get_compass_reg(m_rawMag, ×tamp)) != 0) {
+#ifdef MPULIB_DEBUG
+        Serial.print("Failed to read compass: ");
+        Serial.println(result);
+#endif
+        return false;
+      }
+      //	*** Note mag axes are changed here to align with gyros: Y = -X, X = Y
+
+      m_lastMagSample = millis();
+
+      if (m_useMagCalibration) {
+        m_calMag[VEC3_Y] = -(short)(((long)(m_rawMag[VEC3_X] - m_magXOffset) * (long)SENSOR_RANGE) / (long)m_magXRange);
+        m_calMag[VEC3_X] = (short)(((long)(m_rawMag[VEC3_Y] - m_magYOffset) * (long)SENSOR_RANGE) / (long)m_magYRange);
+        m_calMag[VEC3_Z] = (short)(((long)(m_rawMag[VEC3_Z] - m_magZOffset) * (long)SENSOR_RANGE) / (long)m_magZRange);
+      } else {
+        m_calMag[VEC3_Y] = -m_rawMag[VEC3_X];
+        m_calMag[VEC3_X] = m_rawMag[VEC3_Y];
+        m_calMag[VEC3_Z] = m_rawMag[VEC3_Z];
+      }
+    }
+    
+    // got the raw data - now process
+    
+    m_dmpQuaternion[QUAT_W] = (float)m_rawQuaternion[QUAT_W];  // get float version of quaternion
+    m_dmpQuaternion[QUAT_X] = (float)m_rawQuaternion[QUAT_X];
+    m_dmpQuaternion[QUAT_Y] = (float)m_rawQuaternion[QUAT_Y];
+    m_dmpQuaternion[QUAT_Z] = (float)m_rawQuaternion[QUAT_Z];
+    MPUQuaternionNormalize(m_dmpQuaternion);                 // and normalize
+    
+    MPUQuaternionQuaternionToEuler(m_dmpQuaternion, m_dmpEulerPose);
+
+
+    // Scale accel data 
+
+    if (m_useAccelCalibration) {
+/*        m_calAccel[VEC3_X] = -(short)((((long)m_rawAccel[VEC3_X] + m_accelOffset[0])
+                                        * (long)SENSOR_RANGE) / (long)m_accelXRange);
+        m_calAccel[VEC3_Y] = (short)((((long)m_rawAccel[VEC3_Y] + m_accelOffset[1])
+                                        * (long)SENSOR_RANGE) / (long)m_accelYRange);
+        m_calAccel[VEC3_Z] = (short)((((long)m_rawAccel[VEC3_Z] + m_accelOffset[2])
+                                        * (long)SENSOR_RANGE) / (long)m_accelZRange);
+*/        if (m_rawAccel[VEC3_X] >= 0)
+            m_calAccel[VEC3_X] = -(short)((((long)m_rawAccel[VEC3_X])
+                                        * (long)SENSOR_RANGE) / (long)m_calData.accelMaxX);
+        else
+            m_calAccel[VEC3_X] = -(short)((((long)m_rawAccel[VEC3_X])
+                                        * (long)SENSOR_RANGE) / -(long)m_calData.accelMinX);
+
+        if (m_rawAccel[VEC3_Y] >= 0)
+            m_calAccel[VEC3_Y] = (short)((((long)m_rawAccel[VEC3_Y])
+                                        * (long)SENSOR_RANGE) / (long)m_calData.accelMaxY);
+        else
+            m_calAccel[VEC3_Y] = (short)((((long)m_rawAccel[VEC3_Y])
+                                        * (long)SENSOR_RANGE) / -(long)m_calData.accelMinY);
+
+        if (m_rawAccel[VEC3_Z] >= 0)
+            m_calAccel[VEC3_Z] = (short)((((long)m_rawAccel[VEC3_Z])
+                                        * (long)SENSOR_RANGE) / (long)m_calData.accelMaxZ);
+        else
+            m_calAccel[VEC3_Z] = (short)((((long)m_rawAccel[VEC3_Z])
+                                        * (long)SENSOR_RANGE) / -(long)m_calData.accelMinZ);
+
+    } else {
+      m_calAccel[VEC3_X] = -m_rawAccel[VEC3_X];
+      m_calAccel[VEC3_Y] = m_rawAccel[VEC3_Y];
+      m_calAccel[VEC3_Z] = m_rawAccel[VEC3_Z];
+    }
+    dataFusion();
+    return true;
+}
+
+void MPU9150Lib::dataFusion()
+{
+  float qMag[4];
+  float deltaDMPYaw, deltaMagYaw;
+  float newMagYaw, newYaw;
+  float temp1[4], unFused[4];
+  float unFusedConjugate[4];
+
+  // *** NOTE *** pitch direction swapped here
+
+  m_fusedEulerPose[VEC3_X] = m_dmpEulerPose[VEC3_X];
+  m_fusedEulerPose[VEC3_Y] = -m_dmpEulerPose[VEC3_Y];
+  m_fusedEulerPose[VEC3_Z] = 0;	
+  MPUQuaternionEulerToQuaternion(m_fusedEulerPose, unFused);    // create a new quaternion
+
+  deltaDMPYaw = -m_dmpEulerPose[VEC3_Z] + m_lastDMPYaw;         // calculate change in yaw from dmp
+  m_lastDMPYaw = m_dmpEulerPose[VEC3_Z];                        // update that
+ 
+  qMag[QUAT_W] = 0;
+  qMag[QUAT_X] = m_calMag[VEC3_X];
+  qMag[QUAT_Y] = m_calMag[VEC3_Y];
+  qMag[QUAT_Z] = m_calMag[VEC3_Z];
+	
+  // Tilt compensate mag with the unfused data (i.e. just roll and pitch with yaw 0)
+	
+  MPUQuaternionConjugate(unFused, unFusedConjugate);
+  MPUQuaternionMultiply(qMag, unFusedConjugate, temp1);
+  MPUQuaternionMultiply(unFused, temp1, qMag);
+
+  // Now fuse this with the dmp yaw gyro information
+
+  newMagYaw = -atan2(qMag[QUAT_Y], qMag[QUAT_X]);
+
+  if (newMagYaw != newMagYaw) {                                 // check for nAn
+#ifdef MPULIB_DEBUG
+    Serial.println("***nAn\n");
+#endif
+    return;                                                     // just ignore in this case
+  }
+  if (newMagYaw < 0)
+    newMagYaw = 2.0f * (float)M_PI + newMagYaw;                 // need 0 <= newMagYaw <= 2*PI
+
+  newYaw = m_lastYaw + deltaDMPYaw;                             // compute new yaw from change
+
+  if (newYaw > (2.0f * (float)M_PI))                            // need 0 <= newYaw <= 2*PI
+    newYaw -= 2.0f * (float)M_PI;
+  if (newYaw < 0)
+    newYaw += 2.0f * (float)M_PI;
+
+  deltaMagYaw = newMagYaw - newYaw;                             // compute difference
+
+  if (deltaMagYaw >= (float)M_PI)
+    deltaMagYaw = deltaMagYaw - 2.0f * (float)M_PI;
+  if (deltaMagYaw <= -(float)M_PI)
+    deltaMagYaw = (2.0f * (float)M_PI + deltaMagYaw);
+
+  if (m_magMix > 0) {
+    newYaw += deltaMagYaw / m_magMix;                           // apply some of the correction
+
+    if (newYaw > (2.0f * (float)M_PI))				            // need 0 <= newYaw <= 2*PI
+      newYaw -= 2.0f * (float)M_PI;
+    if (newYaw < 0)
+      newYaw += 2.0f * (float)M_PI;
+  }
+
+  m_lastYaw = newYaw;
+
+  if (newYaw > (float)M_PI)
+    newYaw -= 2.0f * (float)M_PI;
+
+  m_fusedEulerPose[VEC3_Z] = newYaw;                            // fill in output yaw value
+	
+  MPUQuaternionEulerToQuaternion(m_fusedEulerPose, m_fusedQuaternion);
+}
+
+void MPU9150Lib::printQuaternion(long *quat)
+{
+  Serial.print("w: "); Serial.print(quat[QUAT_W]);  
+  Serial.print(" x: "); Serial.print(quat[QUAT_X]);  
+  Serial.print(" y: "); Serial.print(quat[QUAT_Y]);  
+  Serial.print(" z: "); Serial.print(quat[QUAT_Z]);  
+}
+
+void MPU9150Lib::printQuaternion(float *quat)
+{
+  Serial.print("w: "); Serial.print(quat[QUAT_W]);  
+  Serial.print(" x: "); Serial.print(quat[QUAT_X]);  
+  Serial.print(" y: "); Serial.print(quat[QUAT_Y]);  
+  Serial.print(" z: "); Serial.print(quat[QUAT_Z]);  
+}
+
+void MPU9150Lib::printVector(short *vec)
+{
+  Serial.print("x: "); Serial.print(vec[VEC3_X]);  
+  Serial.print(" y: "); Serial.print(vec[VEC3_Y]);  
+  Serial.print(" z: "); Serial.print(vec[VEC3_Z]);    
+}
+
+void MPU9150Lib::printVector(float *vec)
+{
+  Serial.print("x: "); Serial.print(vec[VEC3_X]);  
+  Serial.print(" y: "); Serial.print(vec[VEC3_Y]);  
+  Serial.print(" z: "); Serial.print(vec[VEC3_Z]);    
+}
+
+void MPU9150Lib::printAngles(float *vec)
+{
+  Serial.print("x: "); Serial.print(vec[VEC3_X] * RAD_TO_DEGREE);  
+  Serial.print(" y: "); Serial.print(vec[VEC3_Y] * RAD_TO_DEGREE);  
+  Serial.print(" z: "); Serial.print(vec[VEC3_Z] * RAD_TO_DEGREE);    
+}
+
diff --git a/libraries/MPU9150Lib/MPU9150Lib.h b/libraries/MPU9150Lib/MPU9150Lib.h
new file mode 100644
index 0000000..d571825
--- /dev/null
+++ b/libraries/MPU9150Lib/MPU9150Lib.h
@@ -0,0 +1,148 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of MPU9150Lib
+//
+//  Copyright (c) 2013 Pansenti, LLC
+//
+//  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 _MPU9150LIB_H_
+#define _MPU9150LIB_H_
+
+#include 
+#include "MPUQuaternion.h"
+#include "CalLib.h"
+
+//  Define this symbol to get debug info
+
+#define MPULIB_DEBUG
+
+//  This symbol defines the scaled range for mag and accel values
+
+#define SENSOR_RANGE   4096
+
+class MPU9150Lib
+{
+public: 
+
+  // Constructor
+
+  MPU9150Lib();
+
+  // selectDevice() can be called to select a device:
+  //
+  //   0 = device at address 0x68 (default)
+  //   1 = device at address 0x69
+  //
+  // selectDevice() must be called before init()
+
+  void selectDevice(int device);
+
+  // these two functions control if calibration data is used. Must be called before init()
+  // if defaults (use mag and accel cal) aren't required.
+
+  void useAccelCal(boolean useCal);
+  void useMagCal(boolean useCal);
+
+  // init must be called to setup the MPU chip.
+  // mpuRate is the update rate in Hz.
+  // magMix controls the amoutn of influence that the magnetometer has on yaw:
+  //   0 = just use MPU gyros (will not be referenced to north)
+  //   1 = just use magnetometer with no input from gyros
+  //   2-n = mix the two. Higher numbers decrease correction from magnetometer
+  // It returns false if something went wrong with the initialization.
+  // magRate is the magnetometer update rate in Hz. magRate <= mpuRate.
+  //   Also, magRate must be <= 100Hz.
+  // lpf is the low pass filter setting - can be between 5Hz and 188Hz.
+  //   0 means let the MotionDriver library decide.
+    
+  boolean init(int mpuRate, int magMix = 5, int magRate = 10, int lpf = 0);
+  
+  //  read checks to see if there's been a new update.
+  //  returns true if yes, false if not.
+  
+  boolean read();
+
+  // disableAccelCal can be called while running to disable
+  // accel bias offsets while performing accel calibration
+
+  void disableAccelCal();
+
+  //  check if calibration in use
+  
+  boolean isMagCal();
+  boolean isAccelCal();
+
+  //  these functions can be used to display quaternions and vectors
+  
+  void printQuaternion(long *quaternion);
+  void printQuaternion(float *quaternion);
+  void printVector(short *vec);
+  void printVector(float *vec);
+  void printAngles(float *vec);
+  
+  //  these variables are the values from the MPU
+  
+  long m_rawQuaternion[4];                                  // the quaternion output from the DMP
+  short m_rawGyro[3];                                       // calibrated gyro output from the sensor
+  short m_rawAccel[3];                                      // raw accel data
+  short m_rawMag[3];                                        // raw mag data 
+  
+  //  these variables are processed results
+  
+  float m_dmpQuaternion[4];                                 // float and normalized version of the dmp quaternion
+  float m_dmpEulerPose[3];                                  // Euler angles from the DMP quaternion
+  short m_calAccel[3];                                      // calibrated and scaled accel data
+  short m_calMag[3];                                        // calibrated mag data
+
+  // these variables are the fused results
+
+  float m_fusedEulerPose[3];                                // the fused Euler angles
+  float m_fusedQuaternion[4];								// the fused quaternion
+
+public:
+  CALLIB_DATA m_calData;                                    // calibration data
+  boolean m_useMagCalibration;                              // true if use mag calibration
+  boolean m_useAccelCalibration;                            // true if use mag calibration
+  byte m_device;                                            // IMU device index
+  int m_magMix;                                             // controls gyro and magnetometer mixing for yaw
+  unsigned long m_magInterval;                              // interval between mag reads in mS
+  unsigned long m_lastMagSample;                            // last time mag was read
+
+  void dataFusion();                                        // fuse mag data with the dmp quaternion
+
+  float m_lastDMPYaw;                                       // the last yaw from the DMP gyros
+  float m_lastYaw;                                          // last calculated output yaw
+
+  //  calibration data in processed form
+
+  short m_magXOffset;										// offset to be structed for mag X
+  short m_magXRange;										// range of mag X
+  short m_magYOffset;										// offset to be structed for mag Y
+  short m_magYRange;										// range of mag Y
+  short m_magZOffset;										// offset to be structed for mag Z
+  short m_magZRange;										// range of mag Z
+
+  short m_accelXRange;										// range of accel X
+  short m_accelYRange;										// range of accel Y
+  short m_accelZRange;										// range of accel Z
+  long m_accelOffset[3];                                    // offsets for accel
+
+};
+
+#endif // _MPU9150LIB_H_
diff --git a/libraries/MPU9150Lib/MPUQuaternion.cpp b/libraries/MPU9150Lib/MPUQuaternion.cpp
new file mode 100644
index 0000000..ea95591
--- /dev/null
+++ b/libraries/MPU9150Lib/MPUQuaternion.cpp
@@ -0,0 +1,98 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of MPU9150Lib
+//
+//  Copyright (c) 2013 Pansenti, LLC
+//
+//  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 "MPUQuaternion.h"
+
+void MPUQuaternionNormalize(MPUQuaternion q)
+{
+  float length = MPUQuaternionNorm(q);
+  
+  if (length == 0)
+    return;
+  q[QUAT_W] /= length;
+  q[QUAT_X] /= length;
+  q[QUAT_Y] /= length;
+  q[QUAT_Z] /= length;
+}
+
+void MPUQuaternionQuaternionToEuler(const MPUQuaternion q, MPUVector3 v)
+{
+  float pole = M_PI/2.0f - 0.05f;                           // fix roll near poles with this tolerance
+
+  v[VEC3_Y] = asin(2.0f * (q[QUAT_W] * q[QUAT_Y] - q[QUAT_X] * q[QUAT_Z]));
+
+  if ((v[VEC3_Y] < pole) && (v[VEC3_Y] > -pole))
+	  v[VEC3_X] = atan2(2.0f * (q[QUAT_Y] * q[QUAT_Z] + q[QUAT_W] * q[QUAT_X]),
+                    1.0f - 2.0f * (q[QUAT_X] * q[QUAT_X] + q[QUAT_Y] * q[QUAT_Y]));
+	
+  v[VEC3_Z] = atan2(2.0f * (q[QUAT_X] * q[QUAT_Y] + q[QUAT_W] * q[QUAT_Z]),
+                    1.0f - 2.0f * (q[QUAT_Y] * q[QUAT_Y] + q[QUAT_Z] * q[QUAT_Z]));
+}
+
+void MPUQuaternionEulerToQuaternion(const MPUVector3 v, MPUQuaternion q)
+{
+  float cosX2 = cos(v[VEC3_X] / 2.0f);
+  float sinX2 = sin(v[VEC3_X] / 2.0f);
+  float cosY2 = cos(v[VEC3_Y] / 2.0f);
+  float sinY2 = sin(v[VEC3_Y] / 2.0f);
+  float cosZ2 = cos(v[VEC3_Z] / 2.0f);
+  float sinZ2 = sin(v[VEC3_Z] / 2.0f);
+
+  q[QUAT_W] = cosX2 * cosY2 * cosZ2 + sinX2 * sinY2 * sinZ2;
+  q[QUAT_X] = sinX2 * cosY2 * cosZ2 - cosX2 * sinY2 * sinZ2;
+  q[QUAT_Y] = cosX2 * sinY2 * cosZ2 + sinX2 * cosY2 * sinZ2;
+  q[QUAT_Z] = cosX2 * cosY2 * sinZ2 - sinX2 * sinY2 * cosZ2;
+  MPUQuaternionNormalize(q);
+}
+
+void MPUQuaternionConjugate(const MPUQuaternion s, MPUQuaternion d) 
+{
+  d[QUAT_W] = s[QUAT_W];
+  d[QUAT_X] = -s[QUAT_X];
+  d[QUAT_Y] = -s[QUAT_Y];
+  d[QUAT_Z] = -s[QUAT_Z];
+}
+	
+void MPUQuaternionMultiply(const MPUQuaternion qa, const MPUQuaternion qb, MPUQuaternion qd) 
+{
+  MPUVector3 va;
+  MPUVector3 vb;
+  float dotAB;
+  MPUVector3 crossAB;
+		
+  va[VEC3_X] = qa[QUAT_X];
+  va[VEC3_Y] = qa[QUAT_Y];
+  va[VEC3_Z] = qa[QUAT_Z];
+	
+  vb[VEC3_X] = qb[QUAT_X];
+  vb[VEC3_Y] = qb[QUAT_Y];
+  vb[VEC3_Z] = qb[QUAT_Z];
+	
+  MPUVector3DotProduct(va, vb, &dotAB);
+  MPUVector3CrossProduct(va, vb, crossAB);
+		
+  qd[QUAT_W] = qa[QUAT_W] * qb[QUAT_W] - dotAB;
+  qd[QUAT_X] = qa[QUAT_W] * vb[VEC3_X] + qb[QUAT_W] * va[VEC3_X] + crossAB[VEC3_X];
+  qd[QUAT_Y] = qa[QUAT_W] * vb[VEC3_Y] + qb[QUAT_W] * va[VEC3_Y] + crossAB[VEC3_Y];
+  qd[QUAT_Z] = qa[QUAT_W] * vb[VEC3_Z] + qb[QUAT_W] * va[VEC3_Z] + crossAB[VEC3_Z];
+}
diff --git a/libraries/MPU9150Lib/MPUQuaternion.h b/libraries/MPU9150Lib/MPUQuaternion.h
new file mode 100644
index 0000000..530a8fd
--- /dev/null
+++ b/libraries/MPU9150Lib/MPUQuaternion.h
@@ -0,0 +1,50 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of MPU9150Lib
+//
+//  Copyright (c) 2013 Pansenti, LLC
+//
+//  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 MPUQUATERNION_H_
+#define MPUQUATERNION_H_
+
+#include 
+#include "MPUVector3.h"
+
+#define QUAT_W		0										// scalar offset
+#define QUAT_X		1										// x offset
+#define QUAT_Y		2										// y offset
+#define QUAT_Z		3										// z offset
+
+typedef float MPUQuaternion[4]; 
+
+void MPUQuaternionNormalize(MPUQuaternion q);
+void MPUQuaternionQuaternionToEuler(const MPUQuaternion q, MPUVector3 v);
+void MPUQuaternionEulerToQuaternion(const MPUVector3 v, MPUQuaternion q);
+void MPUQuaternionConjugate(const MPUQuaternion s, MPUQuaternion d);
+void MPUQuaternionMultiply(const MPUQuaternion qa, const MPUQuaternion qb, MPUQuaternion qd);
+
+inline float MPUQuaternionNorm(MPUQuaternion q)
+{
+  return sqrt(q[QUAT_W] * q[QUAT_W] + q[QUAT_X] * q[QUAT_X] +  
+    q[QUAT_Y] * q[QUAT_Y] + q[QUAT_Z] * q[QUAT_Z]);
+}
+
+
+#endif /* MPUQUATERNION_H_ */
diff --git a/libraries/MPU9150Lib/MPUVector3.cpp b/libraries/MPU9150Lib/MPUVector3.cpp
new file mode 100644
index 0000000..0b2b7bf
--- /dev/null
+++ b/libraries/MPU9150Lib/MPUVector3.cpp
@@ -0,0 +1,36 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of MPU9150Lib
+//
+//  Copyright (c) 2013 Pansenti, LLC
+//
+//  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 "MPUVector3.h"
+
+void MPUVector3DotProduct(MPUVector3 a, MPUVector3 b, float *d)
+{
+  *d = a[VEC3_X] * b[VEC3_X] + a[VEC3_Y] * b[VEC3_Y] + a[VEC3_Z] * b[VEC3_Z];  
+}
+
+void MPUVector3CrossProduct(MPUVector3 a, MPUVector3 b, MPUVector3 d) 
+{
+  d[VEC3_X] = a[VEC3_Y] * b[VEC3_Z] - a[VEC3_Z] * b[VEC3_Y];
+  d[VEC3_Y] = a[VEC3_Z] * b[VEC3_X] - a[VEC3_X] * b[VEC3_Z];
+  d[VEC3_Z] = a[VEC3_X] * b[VEC3_Y] - a[VEC3_Y] * b[VEC3_X];
+}
diff --git a/libraries/MPU9150Lib/MPUVector3.h b/libraries/MPU9150Lib/MPUVector3.h
new file mode 100644
index 0000000..8b7a380
--- /dev/null
+++ b/libraries/MPU9150Lib/MPUVector3.h
@@ -0,0 +1,44 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of MPU9150Lib
+//
+//  Copyright (c) 2013 Pansenti, LLC
+//
+//  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 MPUVECTOR3_H_
+#define MPUVECTOR3_H_
+
+#include 
+#include 
+
+
+#define	DEGREE_TO_RAD		(float)M_PI / 180.0f)
+#define	RAD_TO_DEGREE		(180.0f / (float)M_PI)
+
+#define VEC3_X		0										// x offset
+#define VEC3_Y		1										// y offset
+#define VEC3_Z		2										// z offset
+
+typedef float MPUVector3[3];
+
+void MPUVector3DotProduct(MPUVector3 a, MPUVector3 b, float *d);
+void MPUVector3CrossProduct(MPUVector3 a, MPUVector3 b, MPUVector3 d);
+
+
+#endif /* MPUVECTOR3_H_ */
diff --git a/libraries/MS5803/MS5803.cpp b/libraries/MS5803/MS5803.cpp
new file mode 100644
index 0000000..0f9d68c
--- /dev/null
+++ b/libraries/MS5803/MS5803.cpp
@@ -0,0 +1,346 @@
+// I2Cdev library collection - MS5803 I2C device class
+// Based on Measurement Specialties MS5803 document, 3/25/2013 (DA5803-01BA_010)
+// 3/29/2016 by Ryan Neve 
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2014 Ryan Neve
+
+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 "MS5803_I2C.h"
+
+const static uint8_t INIT_TRIES = 3;
+const static uint16_t PRESS_ATM_MBAR_DEFAULT = 1015;
+
+	
+const char* CALIBRATION_CONSTANTS[] = {
+	"_c1_SENSt1",
+	"_c2_OFFt1",
+	"_c3_TCS",
+	"_c4_TCO",
+	"_c5_Tref",
+	"_c6_TEMPSENS"
+};
+
+/** Default constructor, uses default I2C address.
+* @see MPU6050_DEFAULT_ADDRESS
+*/
+MS5803::MS5803() { MS5803(MS5803_DEFAULT_ADDRESS);}
+
+/** Specific address constructor.
+* @param address I2C address
+* @see MS5803_DEFAULT_ADDRESS
+* @see MS5803_ADDRESS_AD0_LOW
+* @see MS5803_ADDRESS_AD0_HIGH
+*/
+MS5803::MS5803(uint8_t address) {
+	setAddress(address);
+	_initialized = false;
+	_c1_SENSt1		= 0;
+	_c2_OFFt1		= 0;
+	_c3_TCS			= 0;
+	_c4_TCO			= 0;
+	_c5_Tref		= 0;
+	_c6_TEMPSENS	= 0;
+	_press_atm_mBar = (float)PRESS_ATM_MBAR_DEFAULT/1000.0; //default, can be changed with setAtmospheric() 
+}
+// Because sometimes you want to set the address later.
+void MS5803::setAddress(uint8_t address) {
+	_dev_address = address;
+}
+
+/** Power on and prepare for general usage.
+* This will reset the device to make sure that the calibration PROM gets loaded into
+* the internal register. It will then read the calibration constants from the PROM
+*/
+bool MS5803::initialize(uint8_t model) {
+	_initialized = false;
+	// Make sure model is valid.
+	switch (model) {
+		case ( 1): _model = BA01; break;
+		case ( 2): _model = BA02; break;
+		case ( 5): _model = BA05; break;
+		case (14): _model = BA14; break;
+		case (30): _model = BA30; break;
+		default:
+			Serial.print(F("MS5803 Model entered (")); Serial.print(model); Serial.println(F(") is not valid/supported."));
+			_model = INVALID; 
+			return 0;
+	}
+	if (_debug) Serial.println(reset());
+	uint8_t tries = 0;
+	do {
+		_getCalConstants(); // Seems to partially fail the first try sometimes.
+		if (_c1_SENSt1 && _c2_OFFt1 && _c3_TCS && _c4_TCO && _c5_Tref && _c6_TEMPSENS ) _initialized = true; // They must all be non-0
+		tries++;
+	} while (!_initialized && ( tries < INIT_TRIES) );
+	if (_debug) {
+		for ( uint8_t i = 1 ; i <= 6; i++){
+			Serial.print(i);
+			Serial.print(": ");
+			Serial.print(CALIBRATION_CONSTANTS[i-1]);
+			Serial.print(" = ");
+			Serial.println(_getCalConstant(i));
+		}
+	}
+	return _initialized;
+}
+
+// See if we can communicate
+bool MS5803::testConnection(){
+	uint8_t reg_address = CMD_ADC_CONV + TEMPERATURE + ADC_256;
+	return I2Cdev::writeBytes(_dev_address,reg_address,0,_buffer);
+}
+
+uint16_t MS5803::reset(){
+	// Not sure how to send no buffer to an address.
+	return I2Cdev::writeBytes(_dev_address, MS5803_RESET,0,_buffer);
+}
+
+void MS5803::_getCalConstants(){
+	/* Query and parse calibration constants */
+	I2Cdev::readBytes(_dev_address,MS5803_PROM_C1,2,_buffer);
+	_c1_SENSt1 =   (((uint16_t)_buffer[0] << 8) + _buffer[1]);
+	I2Cdev::readBytes(_dev_address,MS5803_PROM_C2,2,_buffer);
+	_c2_OFFt1 =    (((uint16_t)_buffer[0] << 8) + _buffer[1]);
+	I2Cdev::readBytes(_dev_address,MS5803_PROM_C3,2,_buffer);
+	_c3_TCS =      (((uint16_t)_buffer[0] << 8) + _buffer[1]);
+	I2Cdev::readBytes(_dev_address,MS5803_PROM_C4,2,_buffer);
+	_c4_TCO =      (((uint16_t)_buffer[0] << 8) + _buffer[1]);
+	I2Cdev::readBytes(_dev_address,MS5803_PROM_C5,2,_buffer);
+	_c5_Tref =     (((uint16_t)_buffer[0] << 8) + _buffer[1]);
+	I2Cdev::readBytes(_dev_address,MS5803_PROM_C6,2,_buffer);
+	_c6_TEMPSENS = (((uint16_t)_buffer[0] << 8) + _buffer[1]);
+}
+
+int32_t MS5803::_getCalConstant(uint8_t constant_no){
+	switch ( constant_no ) {
+		case 1: return _c1_SENSt1;
+		case 2: return _c2_OFFt1;
+		case 3: return _c3_TCS;
+		case 4: return _c4_TCO;
+		case 5: return _c5_Tref;
+		case 6: return _c6_TEMPSENS;
+		default: return 0;
+	}
+}
+
+/*	This function communicates with the sensor and does all the math to convert 
+	raw values to good data. Data can be accessed with various getters.
+*/
+void MS5803::calcMeasurements(precision _precision){
+	// Get raw temperature and pressure values
+	_d2_temperature = _getADCconversion(TEMPERATURE, _precision);
+	_d1_pressure = _getADCconversion(PRESSURE, _precision);
+	//Now that we have a raw temperature, let's compute our actual.
+	_dT = _d2_temperature - ((int32_t)_c5_Tref << 8);
+	double temp_dT = _dT / (double)pow(2,23);
+	_TEMP = 2000 +  (int32_t)(temp_dT * _c6_TEMPSENS);
+	if ( _debug ) {
+		Serial.println("Raw values:");
+		Serial.print("    _d2_temperature = "); Serial.println(_d2_temperature);
+		Serial.print("    _d1_pressure = "); Serial.println(_d1_pressure);
+		Serial.println("First order values:");
+		Serial.print("    _dT = "); Serial.println(_dT);
+		Serial.print("    _TEMP = "); Serial.println(_TEMP);
+	}
+	// Second order variables
+	int64_t T2 = 0;
+	int64_t off2 = 0;
+	int64_t sens2 = 0;
+	// Every variant does the calculations differently, so...
+	switch (_model) {
+		case (BA01):  //MS5803-01-----------------------------------------------------------
+			_OFF  = ((int64_t)_c2_OFFt1  << 16 ) + ((((int64_t)_c4_TCO * (int64_t)_dT)) >> 7 );
+			_SENS = ((int64_t)_c1_SENSt1 << 15 ) + ((((int64_t)_c3_TCS * (int64_t)_dT)) >> 8 );
+			// 2nd Order calculations
+			if ( _TEMP < 2000.0) {  // Is temperature below or above 20.00 deg C ?
+				T2 = 3 * pow(_dT,2)/(int64_t)pow(2,31);
+				off2  = 3 * pow((_TEMP - 2000.0),2);
+				sens2 = 7 * pow((_TEMP - 2000.0),2) / 8;
+				if ( _TEMP < 1500.0 ) sens2 += 2 * pow((_TEMP + 1500.0),2);// below 15C
+			}
+			else {
+				T2 = 0;
+				off2 = 0;
+				sens2 = 0;
+				if ( _TEMP >= 4500.0 ) {
+					sens2 -= ((int64_t)pow((_TEMP - 4500.0),2) >> 3);
+				}
+			}
+			break;
+		case (BA02):  //MS5803-02-----------------------------------------------------------
+			_OFF  = ((int64_t)_c2_OFFt1  << 17 ) + ((((int64_t)_c4_TCO * (int64_t)_dT)) >> 6 );
+			_SENS = ((int64_t)_c1_SENSt1 << 16 ) + ((((int64_t)_c3_TCS * (int64_t)_dT)) >> 7 );
+			// 2nd Order calculations
+			if ( _TEMP < 2000.0) {  // Is temperature below or above 20.00 deg C ?
+				T2 = 3 * pow(_dT,2)/(int64_t)pow(2,31);
+				off2 = 61 * pow((_TEMP - 2000.0),2) / 16;
+				sens2 = 2 * pow(((int64_t)_TEMP - 2000.0),2);
+				if ( _TEMP < 1500.0 ) { // below 15C
+					off2  += 20 * pow((_TEMP + 1500.0),2);
+					sens2 += 12 * pow((_TEMP + 1500.0),2);
+				}
+			}
+			else {
+				T2 = 0;
+				off2 = 0;
+				sens2 = 0;
+			}
+			break;
+		case (BA05):  //MS5803-05-----------------------------------------------------------
+			_OFF  = ((int64_t)_c2_OFFt1  << 18 ) + ((((int64_t)_c4_TCO * (int64_t)_dT)) >> 5 );
+			_SENS = ((int64_t)_c1_SENSt1 << 17 ) + ((((int64_t)_c3_TCS * (int64_t)_dT)) >> 7 );
+			// 2nd Order calculations
+			if ( _TEMP < 2000.0) {  // Is temperature below or above 20.00 deg C ?
+				T2 = 3 * pow(_dT,2)/(int64_t)pow(2,33);
+				off2 =  3 * pow((_TEMP - 2000.0),2) / 8;
+				sens2 = 7 * pow((_TEMP - 2000.0),2) / 8;
+				if ( _TEMP < -1500.0 ) { // below -15C
+					sens2 += 3 * pow((_TEMP + 1500.0),2);
+				}
+			}
+			else {
+				T2 = 0;
+				off2 = 0;
+				sens2 = 0;
+			}
+			break;
+		case (BA14):  //MS5803-14-----------------------------------------------------------
+			// 14 and 30 are the same calculations...
+		case (BA30):  //MS5803-30-----------------------------------------------------------
+			_OFF  = ((int64_t)_c2_OFFt1  << 16 ) + ((((int64_t)_c4_TCO * (int64_t)_dT)) >> 7 );
+			_SENS = ((int64_t)_c1_SENSt1 << 15 ) + ((((int64_t)_c3_TCS * (int64_t)_dT)) >> 8 );
+			// 2nd Order calculations
+			if ( _TEMP < 2000.0) {  // Is temperature below or above 20.00 deg C ?
+				T2 = 3 * pow(_dT,2)/(int64_t)pow(2,33);
+				off2 =  3 * pow((_TEMP - 2000.0),2) / 2;
+				sens2 = 5 * pow((_TEMP - 2000.0),2) / 8;
+				if ( _TEMP < 1500.0 ) { // below 15C
+					off2  += 7 * pow((_TEMP + 1500.0),2);
+					sens2 += 4 * pow((_TEMP + 1500.0),2);
+				}
+			}
+			else {
+				T2 =    7 * ((int64_t)_dT * _dT) >> 37;
+				off2 =  1 * (pow((_TEMP - 2000.0),2)) / 16;
+				sens2 = 0;
+			}
+			break;
+		default:
+			_OFF = 0;
+			_SENS = 0;
+			T2 = 0;
+			sens2 = 0;
+			off2 = 0;
+	}
+	if ( _debug ) {
+		Serial.print("    _OFF = "); serialPrintln64(_OFF);
+		Serial.print("    _SENS = "); serialPrintln64(_SENS);
+	}
+	 // Second Order
+	_TEMP  -= T2;
+	_SENS  -= sens2;
+	_OFF   -= off2;
+	// Now pressure
+	switch (_model) {
+		case (BA05):  //MS5803-05-----------------------------------------------------------
+			_P = ((((int32_t)_d1_pressure * _SENS) >> 21 ) - _OFF) >> 15;
+			_P /= 10; // NO IDEA WHY THIS NEEDS TO BE DONE. PERHAPS AN ERROR IN THE DATASHEET?
+			break;
+		case (BA01):  //MS5803-01--passthrough----------------------------------------------
+		case (BA02):  //MS5803-02--passthrough----------------------------------------------
+		case (BA14):  //MS5803-14--passthrough----------------------------------------------
+			_P = ((((int32_t)_d1_pressure * _SENS) >> 21 ) - _OFF) >> 15;
+			break;
+		case (BA30):  //MS5803-30-----------------------------------------------------------
+			_P = ((((int32_t)_d1_pressure * _SENS) >> 21 ) - _OFF) >> 13;
+			break;
+		default:
+			_P = 0;
+	}
+	if ( _debug ) {
+		Serial.println("Second order values:");
+		Serial.print("    T2 = "); serialPrintln64(T2);
+		Serial.print("    sens2 = "); serialPrintln64(sens2);
+		Serial.print("    off2 = "); serialPrintln64(off2);
+		Serial.print("    _TEMP = "); Serial.println(_TEMP);
+		Serial.print("    _SENS = "); serialPrintln64(_SENS);
+		Serial.print("    _OFF = "); serialPrintln64(_OFF);
+		Serial.println("Pressure:");
+		Serial.print("    _P = "); Serial.println(_P);
+	}
+}
+
+int32_t MS5803::_getADCconversion(measurement _measurement, precision _precision){
+	// Retrieve ADC measurement from the device.
+	// Select measurement type and precision
+	uint32_t result;
+	uint8_t reg_address = CMD_ADC_CONV + _measurement + _precision;
+	uint8_t write_length = 0;
+	uint8_t read_length = 3;
+	uint16_t read_timeout = 2000;
+	//sendCommand(CMD_ADC_CONV + _measurement + _precision);
+	I2Cdev::writeBytes(_dev_address,reg_address,write_length,_buffer); // buffer is ignored when write_length is 0
+		
+	// Wait for conversion to complete
+	delay(1); //general delay
+	switch( _precision )
+	{
+		case ADC_256 : delay(1); break;
+		case ADC_512 : delay(3 >> CLKPR); break;
+		case ADC_1024: delay(4 >> CLKPR); break;
+		case ADC_2048: delay(6 >> CLKPR); break;
+		case ADC_4096: delay(10 >> CLKPR); break;
+	}
+	I2Cdev::readBytes(_dev_address,MS5803_ADC_READ,read_length,_buffer,read_timeout);
+	result = ((uint32_t)_buffer[0] << 16) + ((uint32_t)_buffer[1] << 8) + _buffer[2];
+	if (_debug) {
+		Serial.print("Reading MS5803 ADC");
+		switch (_measurement) {
+			case PRESSURE:    Serial.println(" Pressure: "   ); break;
+			case TEMPERATURE: Serial.println(" Temperature: "); break;
+		}
+		Serial.print("    buffer[0] = "); Serial.println(_buffer[0]);
+		Serial.print("    buffer[1] = "); Serial.println(_buffer[1]);
+		Serial.print("    buffer[2] = "); Serial.println(_buffer[2]);
+	}
+	return result;
+}
+
+void serialPrintln64(int64_t val64){
+	serialPrint64(val64);
+	Serial.println();
+}
+void serialPrint64(int64_t val64){
+	int32_t result_high = val64 / 10000000L;
+	int32_t result_low = val64 - (10000000LL * result_high);
+	Serial.print(result_high);
+	Serial.print(result_low);
+}
\ No newline at end of file
diff --git a/libraries/MS5803/MS5803.h b/libraries/MS5803/MS5803.h
new file mode 100644
index 0000000..c6b6de2
--- /dev/null
+++ b/libraries/MS5803/MS5803.h
@@ -0,0 +1,159 @@
+// I2Cdev library collection - MS5803 I2C device class
+// Based on Measurement Specialties MS5803 document, 3/25/2013 (DA5803-01BA_010)
+// 4/12/2014 by Ryan Neve 
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+//
+// Changelog:
+//     ... - ongoing debug release
+
+// NOTE: THIS IS ONLY A PARIAL RELEASE. THIS DEVICE CLASS IS CURRENTLY UNDERGOING ACTIVE
+// DEVELOPMENT AND IS STILL MISSING SOME IMPORTANT FEATURES. PLEASE KEEP THIS IN MIND IF
+// YOU DECIDE TO USE THIS PARTICULAR CODE FOR ANYTHING.
+
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2014 Ryan Neve
+
+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 _MS5803_H_
+#define _MS5803_H_
+
+#define I2CDEV_SERIAL_DEBUG
+
+#include "I2Cdev.h"
+#include 
+
+#define MS5803_ADDRESS
+// Should convert these to enum
+#define MS5803_ADDRESS_AD0_LOW     0x77 // address pin low (GND), default for InvenSense evaluation board
+#define MS5803_ADDRESS_AD0_HIGH    0x76 // address pin high (VCC)
+
+#define MS5803_DEFAULT_ADDRESS     MS5803_ADDRESS_AD0_LOW
+
+#define MS5803_RESET     0x1E
+
+#define MS5803_PROM_BASE 0xA0
+#define MS5803_PROM_C1   0xA2
+#define MS5803_PROM_C2   0xA4
+#define MS5803_PROM_C3   0xA6
+#define MS5803_PROM_C4   0xA8
+#define MS5803_PROM_C5   0xAA
+#define MS5803_PROM_C6   0xAC
+#define MS5803_PROM_CRC  0xAE
+
+
+
+#define MS5803_ADC_READ  0x00
+#define CMD_ADC_CONV 0x40 // ADC conversion command
+
+// Define measurement type.
+enum measurement {
+	PRESSURE    = 0x00,
+	TEMPERATURE = 0x10
+};
+
+// Define constants for Conversion precision
+enum precision {
+	ADC_256  = 0x00,
+	ADC_512  = 0x02,
+	ADC_1024 = 0x04,
+	ADC_2048 = 0x06,
+	ADC_4096 = 0x08
+};
+
+enum ms5803_model {
+	INVALID =  0,
+	BA01    =  1,
+	BA02    =  2,
+	BA05    =  5,
+	BA14    = 14,
+	BA30    = 30
+};
+
+
+const static float FRESH_WATER_CONSTANT = 1.019716; // kg/m^3
+const static float BAR_IN_PSI = 14.50377;
+
+class MS5803 {
+	public:
+		MS5803();
+		MS5803(uint8_t address);
+	
+		void		setAddress(uint8_t address);
+		uint8_t		getAddress() {return _dev_address;}
+		bool		initialize(uint8_t model);
+		bool		initialized() {return _initialized;}
+		bool		testConnection();
+		void		calcMeasurements(precision _precision);	// Here's where the heavy lifting occurs.
+		uint16_t	reset();
+
+		// Setters
+		void		setAtmospheric(float pressure) {_press_atm_mBar = pressure;}
+		void		setDebug(bool debug) { _debug = debug; }
+
+		// Getters
+		bool		getDebug() { return _debug; }
+		float		getTemp_C() {return (float)_TEMP / 100.0;}
+		float		getPress_mBar() {return (float)_P / 10.0;}
+		float		getPress_kPa() {return (float)_P / 100.0;}
+		float		getPress_gauge() {return ((float)_P / 10.0) - _press_atm_mBar;}
+		float		getPress_psi() {return (((float)_P / 10.0) - _press_atm_mBar) * BAR_IN_PSI;}
+		float		getDepthFresh_m() {return ((float)_P/1000.0) * FRESH_WATER_CONSTANT;}
+
+
+	protected:
+	private:
+		void		_getCalConstants();
+		int32_t		_getCalConstant(uint8_t constant_no);
+		int32_t		_getADCconversion(measurement _measurement, precision _precision);
+		uint8_t		_buffer[14];
+		uint8_t		_dev_address;
+		ms5803_model	_model;	// the suffix after ms5803. E.g 2 for MS5803-02 indicates range.
+		bool		_initialized;
+		bool		_debug;
+		// Calibration Constants
+		int32_t		_c1_SENSt1;		// Pressure Sensitivity
+		int32_t		_c2_OFFt1;		// Pressure Offset
+		int32_t		_c3_TCS;		// Temperature coefficient of pressure sensitivity
+		int32_t		_c4_TCO;		// Temperature coefficient of pressure offset
+		int32_t		_c5_Tref;		// Reference Temperature
+		int32_t		_c6_TEMPSENS;	// Temperature coefficient of the temperature
+		// intermediate pressure and temperature data
+		int32_t		_d1_pressure;	// AdcPressure
+		int32_t		_d2_temperature;// AdcTemperature
+		// Calculated values
+		int32_t		_dT;		//TempDifference
+		int32_t		_TEMP;		// Actual temperature -40 to 85C with .01 resolution (divide by 100) - Temperature float
+		// Temperature compensated pressure
+		int64_t		_OFF;		// First Order Offset at actual temperature // Offset - float
+		int64_t		_SENS;		// Sensitivity at actual temperature // Sensitivity - float
+		int32_t		_P;			// Temperature compensated pressure 10...1300 mbar (divide by 100 to get mBar)
+		float		_press_atm_mBar;	// Atmospheric pressure
+
+};
+
+// Function prototype:
+void serialPrintln64(int64_t val64);
+void serialPrint64(int64_t val64);
+
+
+#endif
\ No newline at end of file
diff --git a/libraries/MS5803/examples/test_MS5803/test_MS5803.ino b/libraries/MS5803/examples/test_MS5803/test_MS5803.ino
new file mode 100644
index 0000000..15bb2f9
--- /dev/null
+++ b/libraries/MS5803/examples/test_MS5803/test_MS5803.ino
@@ -0,0 +1,32 @@
+
+
+#include 
+#include 
+#include 
+
+//const uint8_t MS_MODEL = 1; // MS5803-01BA
+//const uint8_t MS_MODEL = 2; // MS5803-02BA
+const uint8_t MS_MODEL = 5; // MS5803-05BA
+//const uint8_t MS_MODEL = 14; // MS5803-14BA
+//const uint8_t MS_MODEL = 30; // MS5803-30BA
+
+MS5803 presstemp(0x76);
+const uint8_t loop_delay = 10; // Seconds between readings
+uint32_t wake_time = millis();
+
+
+void setup() {
+  Serial.begin(57600);
+  Wire.begin();
+  // Start up and get Calubration constants.
+  presstemp.initialize(MS_MODEL);
+  if ( presstemp.testConnection() ) Serial.println("We are communicating with MS5803 via I2C.");
+  else Serial.println("I2C Communications with MS5803 failed.");
+}
+void loop(){
+    Serial.print("Getting temperature");
+    presstemp.calcMeasurements(ADC_4096);
+    Serial.print("The temperature is "); Serial.print(presstemp.getTemp_C()); Serial.println(" C");
+    Serial.print("The pressure is "); Serial.print(presstemp.getPress_mBar()); Serial.println(" mBar");
+  delay(2000);
+}
\ No newline at end of file
diff --git a/libraries/MS5803/keywords.txt b/libraries/MS5803/keywords.txt
new file mode 100644
index 0000000..3753408
--- /dev/null
+++ b/libraries/MS5803/keywords.txt
@@ -0,0 +1,42 @@
+###########################################
+# Datatypes (KEYWORD1)
+###########################################
+
+MS5803	KEYWORD1
+
+###########################################
+# Methods and Functions (KEYWORD2)
+###########################################
+setAddress	KEYWORD2
+getAddress	KEYWORD2
+initialize	KEYWORD2
+testConnection	KEYWORD2
+setAtmospheric	KEYWORD2
+calcMeasurements	KEYWORD2
+getD1Pressure	KEYWORD2
+getD2Temperature	KEYWORD2
+getTemp_C	KEYWORD2
+getPress_mBar	KEYWORD2
+getPress_kPa	KEYWORD2
+initialized	KEYWORD2
+getDebug	KEYWORD2
+setDebug	KEYWORD2
+
+###########################################
+# Constants (LITERAL1)
+###########################################
+MS5803_ADDRESS				LITERAL1
+MS5803_ADDRESS_AD0_LOW		LITERAL1
+MS5803_ADDRESS_AD0_HIGH		LITERAL1
+MS5803_DEFAULT_ADDRESS		LITERAL1
+MS5803_RESET     			LITERAL1
+MS5803_PROM_BASE 			LITERAL1
+MS5803_PROM_C1   			LITERAL1
+MS5803_PROM_C2   			LITERAL1
+MS5803_PROM_C3   			LITERAL1
+MS5803_PROM_C4   			LITERAL1
+MS5803_PROM_C5   			LITERAL1
+MS5803_PROM_C6   			LITERAL1
+MS5803_PROM_CRC  			LITERAL1
+MS5803_ADC_READ  			LITERAL1
+CMD_ADC_CONV 				LITERAL1
\ No newline at end of file
diff --git a/libraries/MadgwickAHRS/MadgwickAHRS.cpp b/libraries/MadgwickAHRS/MadgwickAHRS.cpp
new file mode 100644
index 0000000..c56d031
--- /dev/null
+++ b/libraries/MadgwickAHRS/MadgwickAHRS.cpp
@@ -0,0 +1,164 @@
+//=============================================================================================
+// MadgwickAHRS.c
+//=============================================================================================
+//
+// Implementation of Madgwick's IMU and AHRS algorithms.
+// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/
+//
+// From the x-io website "Open-source resources available on this website are
+// provided under the GNU General Public Licence unless an alternative licence
+// is provided in source."
+//
+// Date			Author          Notes
+// 29/09/2011	SOH Madgwick    Initial release
+// 02/10/2011	SOH Madgwick	Optimised for reduced CPU load
+// 19/02/2012	SOH Madgwick	Magnetometer measurement is normalised
+//
+//=============================================================================================
+
+//-------------------------------------------------------------------------------------------
+// Header files
+
+#include "MadgwickAHRS.h"
+#include 
+
+//-------------------------------------------------------------------------------------------
+// Definitions
+
+#define sampleFreqDef   100.0f          // sample frequency in Hz
+#define betaDef         0.1f            // 2 * proportional gain
+
+
+//============================================================================================
+// Functions
+
+//-------------------------------------------------------------------------------------------
+// AHRS algorithm update
+
+Madgwick::Madgwick() {
+	beta = betaDef;
+	q0 = 1.0f;
+	q1 = 0.0f;
+	q2 = 0.0f;
+	q3 = 0.0f;
+	invSampleFreq = 1.0f / sampleFreqDef;
+	anglesComputed = 0;
+}
+
+void Madgwick::update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz) {
+	float recipNorm;
+	float s0, s1, s2, s3;
+	float qDot1, qDot2, qDot3, qDot4;
+	float hx, hy;
+	float _2q0mx, _2q0my, _2q0mz, _2q1mx, _2bx, _2bz, _4bx, _4bz, _2q0, _2q1, _2q2, _2q3, _2q0q2, _2q2q3, q0q0, q0q1, q0q2, q0q3, q1q1, q1q2, q1q3, q2q2, q2q3, q3q3;
+
+	gx *= 0.0174533f;
+	gy *= 0.0174533f;
+	gz *= 0.0174533f;
+
+	// Rate of change of quaternion from gyroscope
+	qDot1 = 0.5f * (-q1 * gx - q2 * gy - q3 * gz);
+	qDot2 = 0.5f * (q0 * gx + q2 * gz - q3 * gy);
+	qDot3 = 0.5f * (q0 * gy - q1 * gz + q3 * gx);
+	qDot4 = 0.5f * (q0 * gz + q1 * gy - q2 * gx);
+
+		// Normalise accelerometer measurement
+		recipNorm = invSqrt(ax * ax + ay * ay + az * az);
+		ax *= recipNorm;
+		ay *= recipNorm;
+		az *= recipNorm;
+
+		// Normalise magnetometer measurement
+		recipNorm = invSqrt(mx * mx + my * my + mz * mz);
+		mx *= recipNorm;
+		my *= recipNorm;
+		mz *= recipNorm;
+
+		// Auxiliary variables to avoid repeated arithmetic
+		_2q0mx = 2.0f * q0 * mx;
+		_2q0my = 2.0f * q0 * my;
+		_2q0mz = 2.0f * q0 * mz;
+		_2q1mx = 2.0f * q1 * mx;
+		_2q0 = 2.0f * q0;
+		_2q1 = 2.0f * q1;
+		_2q2 = 2.0f * q2;
+		_2q3 = 2.0f * q3;
+		_2q0q2 = 2.0f * q0 * q2;
+		_2q2q3 = 2.0f * q2 * q3;
+		q0q0 = q0 * q0;
+		q0q1 = q0 * q1;
+		q0q2 = q0 * q2;
+		q0q3 = q0 * q3;
+		q1q1 = q1 * q1;
+		q1q2 = q1 * q2;
+		q1q3 = q1 * q3;
+		q2q2 = q2 * q2;
+		q2q3 = q2 * q3;
+		q3q3 = q3 * q3;
+
+		// Reference direction of Earth's magnetic field
+		hx = mx * q0q0 - _2q0my * q3 + _2q0mz * q2 + mx * q1q1 + _2q1 * my * q2 + _2q1 * mz * q3 - mx * q2q2 - mx * q3q3;
+		hy = _2q0mx * q3 + my * q0q0 - _2q0mz * q1 + _2q1mx * q2 - my * q1q1 + my * q2q2 + _2q2 * mz * q3 - my * q3q3;
+		_2bx = sqrtf(hx * hx + hy * hy);
+		_2bz = -_2q0mx * q2 + _2q0my * q1 + mz * q0q0 + _2q1mx * q3 - mz * q1q1 + _2q2 * my * q3 - mz * q2q2 + mz * q3q3;
+		_4bx = 2.0f * _2bx;
+		_4bz = 2.0f * _2bz;
+
+		// Gradient decent algorithm corrective step
+		s0 = -_2q2 * (2.0f * q1q3 - _2q0q2 - ax) + _2q1 * (2.0f * q0q1 + _2q2q3 - ay) - _2bz * q2 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (-_2bx * q3 + _2bz * q1) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + _2bx * q2 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz);
+		s1 = _2q3 * (2.0f * q1q3 - _2q0q2 - ax) + _2q0 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q1 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + _2bz * q3 * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (_2bx * q2 + _2bz * q0) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + (_2bx * q3 - _4bz * q1) * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz);
+		s2 = -_2q0 * (2.0f * q1q3 - _2q0q2 - ax) + _2q3 * (2.0f * q0q1 + _2q2q3 - ay) - 4.0f * q2 * (1 - 2.0f * q1q1 - 2.0f * q2q2 - az) + (-_4bx * q2 - _2bz * q0) * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (_2bx * q1 + _2bz * q3) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + (_2bx * q0 - _4bz * q2) * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz);
+		s3 = _2q1 * (2.0f * q1q3 - _2q0q2 - ax) + _2q2 * (2.0f * q0q1 + _2q2q3 - ay) + (-_4bx * q3 + _2bz * q1) * (_2bx * (0.5f - q2q2 - q3q3) + _2bz * (q1q3 - q0q2) - mx) + (-_2bx * q0 + _2bz * q2) * (_2bx * (q1q2 - q0q3) + _2bz * (q0q1 + q2q3) - my) + _2bx * q1 * (_2bx * (q0q2 + q1q3) + _2bz * (0.5f - q1q1 - q2q2) - mz);
+		recipNorm = invSqrt(s0 * s0 + s1 * s1 + s2 * s2 + s3 * s3); // normalise step magnitude
+		s0 *= recipNorm;
+		s1 *= recipNorm;
+		s2 *= recipNorm;
+		s3 *= recipNorm;
+
+		// Apply feedback step
+		qDot1 -= beta * s0;
+		qDot2 -= beta * s1;
+		qDot3 -= beta * s2;
+		qDot4 -= beta * s3;
+
+	// Integrate rate of change of quaternion to yield quaternion
+	q0 += qDot1 * invSampleFreq;
+	q1 += qDot2 * invSampleFreq;
+	q2 += qDot3 * invSampleFreq;
+	q3 += qDot4 * invSampleFreq;
+
+	// Normalise quaternion
+	recipNorm = invSqrt(q0 * q0 + q1 * q1 + q2 * q2 + q3 * q3);
+	q0 *= recipNorm;
+	q1 *= recipNorm;
+	q2 *= recipNorm;
+	q3 *= recipNorm;
+	anglesComputed = 0;
+}
+
+
+//-------------------------------------------------------------------------------------------
+// Fast inverse square-root
+// See: http://en.wikipedia.org/wiki/Fast_inverse_square_root
+
+float Madgwick::invSqrt(float x) {
+	float halfx = 0.5f * x;
+	float y = x;
+	long i = *(long*)&y;
+	i = 0x5f3759df - (i>>1);
+	y = *(float*)&i;
+	y = y * (1.5f - (halfx * y * y));
+	y = y * (1.5f - (halfx * y * y));
+	return y;
+}
+
+//-------------------------------------------------------------------------------------------
+
+void Madgwick::computeAngles()
+{
+	roll = atan2f(q0*q1 + q2*q3, 0.5f - q1*q1 - q2*q2);
+	pitch = asinf(-2.0f * (q1*q3 - q0*q2));
+	yaw = atan2f(q1*q2 + q0*q3, 0.5f - q2*q2 - q3*q3);
+	anglesComputed = 1;
+}
+
diff --git a/libraries/MadgwickAHRS/MadgwickAHRS.h b/libraries/MadgwickAHRS/MadgwickAHRS.h
new file mode 100644
index 0000000..b238f44
--- /dev/null
+++ b/libraries/MadgwickAHRS/MadgwickAHRS.h
@@ -0,0 +1,74 @@
+//=============================================================================================
+// MadgwickAHRS.h
+//=============================================================================================
+//
+// Implementation of Madgwick's IMU and AHRS algorithms.
+// See: http://www.x-io.co.uk/open-source-imu-and-ahrs-algorithms/
+//
+// From the x-io website "Open-source resources available on this website are
+// provided under the GNU General Public Licence unless an alternative licence
+// is provided in source."
+//
+// Date			Author          Notes
+// 29/09/2011	SOH Madgwick    Initial release
+// 02/10/2011	SOH Madgwick	Optimised for reduced CPU load
+//
+//=============================================================================================
+#ifndef MadgwickAHRS_h
+#define MadgwickAHRS_h
+#include 
+
+//--------------------------------------------------------------------------------------------
+// Variable declaration
+class Madgwick{
+public:
+    static float invSqrt(float x);
+    float beta;				// algorithm gain
+    float q0;
+    float q1;
+    float q2;
+    float q3;	// quaternion of sensor frame relative to auxiliary frame
+    float invSampleFreq;
+    float roll;
+    float pitch;
+    float yaw;
+    char anglesComputed;
+    void computeAngles();
+
+//-------------------------------------------------------------------------------------------
+// Function declarations
+public:
+    Madgwick(void);
+    void begin(float sampleFrequency) { invSampleFreq = 1.0f / sampleFrequency; }
+    void update(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz);
+    void updateIMU(float gx, float gy, float gz, float ax, float ay, float az);
+    //float getPitch(){return atan2f(2.0f * q2 * q3 - 2.0f * q0 * q1, 2.0f * q0 * q0 + 2.0f * q3 * q3 - 1.0f);};
+    //float getRoll(){return -1.0f * asinf(2.0f * q1 * q3 + 2.0f * q0 * q2);};
+    //float getYaw(){return atan2f(2.0f * q1 * q2 - 2.0f * q0 * q3, 2.0f * q0 * q0 + 2.0f * q1 * q1 - 1.0f);};
+    float getRoll() {
+        if (!anglesComputed) computeAngles();
+        return roll * 57.29578f;
+    }
+    float getPitch() {
+        if (!anglesComputed) computeAngles();
+        return pitch * 57.29578f;
+    }
+    float getYaw() {
+        if (!anglesComputed) computeAngles();
+        return yaw * 57.29578f + 180.0f;
+    }
+    float getRollRadians() {
+        if (!anglesComputed) computeAngles();
+        return roll;
+    }
+    float getPitchRadians() {
+        if (!anglesComputed) computeAngles();
+        return pitch;
+    }
+    float getYawRadians() {
+        if (!anglesComputed) computeAngles();
+        return yaw;
+    }
+};
+#endif
+
diff --git a/libraries/MegaServo.zip b/libraries/MegaServo.zip
new file mode 100644
index 0000000..bb08e10
Binary files /dev/null and b/libraries/MegaServo.zip differ
diff --git a/libraries/MegaServo/Examples/MegaServo.pde b/libraries/MegaServo/Examples/MegaServo.pde
new file mode 100644
index 0000000..117d5b9
--- /dev/null
+++ b/libraries/MegaServo/Examples/MegaServo.pde
@@ -0,0 +1,46 @@
+#include 
+
+// test sketch for MegaServo library
+// this will sweep all servos back and forth once, then position according to voltage on potPin
+
+
+#define FIRST_SERVO_PIN  22  
+
+MegaServo Servos[MAX_SERVOS] ; // max servos is 32 for mega, 8 for other boards
+
+int pos = 0;      // variable to store the servo position 
+int potPin = 0;   // connect a pot to this pin.
+
+void setup()
+{
+  for( int i =0; i < MAX_SERVOS; i++)
+    Servos[i].attach( FIRST_SERVO_PIN +i, 800, 2200);
+
+  sweep(0,180,2); // sweep once    
+}
+
+void sweep(int min, int max, int step)
+{
+  for(pos = min; pos < max; pos += step)  // goes from 0 degrees to 180 degrees    
+  {                                  // in steps of 1 degree 
+    for( int i =0; i < MAX_SERVOS; i++){ 
+      Servos[i].write( pos);     // tell servo to go to position  
+    }
+    delay(15);                  // waits 15ms for the servo to move 
+  } 
+  for(pos = max; pos>=min; pos-=step)     // goes from 180 degrees to 0 degrees 
+  {                                
+    for( int i =0; i < MAX_SERVOS; i++){ 
+      Servos[i].write( pos);     // tell servo to go to position  
+    }
+    delay(15);                  // waits 15ms for the servo to move 
+  }   
+}
+
+void loop()
+{ 
+  pos = analogRead(potPin);   // read a value from 0 to 1023
+  for( int i =0; i < MAX_SERVOS; i++) 
+    Servos[i].write( map(pos, 0,1023,0,180));   
+  delay(15);   
+}
diff --git a/libraries/MegaServo/MegaServo.cpp b/libraries/MegaServo/MegaServo.cpp
new file mode 100644
index 0000000..8269ca2
--- /dev/null
+++ b/libraries/MegaServo/MegaServo.cpp
@@ -0,0 +1,290 @@
+/*
+  MegaServo.cpp - Interrupt driven Servo library for Arduino using 16 bit timers- Version 0.1
+  Copyright (c) 2009 Michael Margolis.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+  Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+/* 
+  This library uses 16 bit timers to drive up to 12 servos on each timer.
+  It uses interrupts so no explicit refresh activity is required. 
+  The usage and method naming is similar to the Arduino servo library http://www.arduino.cc/en/Reference/Servo
+  except that it support up to 48 servos on a Mega (12 on a standard Arduino).
+  Also pulse widths can be in microseconds or degrees -
+  write() treats parameters less than 200 as degrees, larger values are treated as milliseconds.
+ 
+  
+  A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method.
+  The servos are pulsed in the background using the value most recently written using the write() method
+
+  Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached.
+  Timers are siezed as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four.
+
+  The methods are:
+
+   MegaServo - Class for manipulating servo motors connected to Arduino pins.
+
+   attach(pin )  - Attaches a servo motor to an i/o pin.
+   attach(pin, min, max  ) - Attaches to a pin setting min and max values in microseconds
+    default min is 544, max is 2400  
+ 
+   write()     - Sets the servo angle in degrees.  (invalid angle that is valid as pulse in microseconds is treated as microseconds)
+   writeMicroseconds() - Sets the servo pulse width in microseconds 
+   read()      - Gets the last written servo pulse width as an angle between 0 and 180. 
+   readMicroseconds()   - Gets the last written servo pulse width in microseconds. (was read_us() in first release)
+   attached()  - Returns true if there is a servo attached. 
+   detach()    - Stops an attached servos from pulsing its i/o pin. 
+  
+   March 31 2009: initial release 
+   Jun 10 2009   : release 2 - added writeMicroseconds method, renamed read_us to readMicroseconds. Added 8MHz clock support
+                   fixes to read method and ISR handler when less than maximum number of servo instances
+   
+ */
+#include 
+#include  
+
+
+#include "MegaServo.h"
+
+#define TICKS_PER_uS     (clockCyclesPerMicrosecond() / 8)  // number of timer ticks per microsecond with prescale of 8
+
+#define SERVOS_PER_TIMER   12                               // the maximum number of servos controlled by one timer 
+#define TRIM_DURATION     (SERVOS_PER_TIMER/2)             // compensation ticks to trim adjust for digitalWrite delays 
+
+#define NBR_TIMERS        (MAX_SERVOS / SERVOS_PER_TIMER)
+
+static servo_t servos[MAX_SERVOS];                         // static array of servo structures
+static volatile int8_t Channel[NBR_TIMERS];                // counter for the servo being pulsed for each timer (or -1 if refresh interval)
+#if defined(__AVR_ATmega1280__)
+typedef enum {  _timer5, _timer1, _timer3, _timer4 } servoTimer_t; // this is the sequence for timer utilization 
+#else
+typedef enum { _timer1 } servoTimer_t;                     // this is the sequence for timer utilization 
+#endif
+
+//uint8_t siezedTimers = 0;                                // bitmap of initialized timers (replaced by isTimerActive method)
+uint8_t ServoCount = 0;	                                   // the total number of attached servos
+
+// convenience macros
+#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((servoTimer_t)(_servo_nbr / SERVOS_PER_TIMER)) // returns the timer controlling this servo
+#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % SERVOS_PER_TIMER)       // returns the index of the servo on this timer
+#define SERVO_INDEX(_timer,_channel)  ((_timer*SERVOS_PER_TIMER) + _channel)     // macro to access servo index by timer and channel
+#define SERVO(_timer,_channel)  (servos[SERVO_INDEX(_timer,_channel)])            // macro to access servo class by timer and channel
+
+#define SERVO_MIN(_servo_nbr) (MIN_PULSE_WIDTH - servos[_servo_nbr].min * 4)  // minimum value in uS for this servo
+#define SERVO_MAX(_servo_nbr) (MAX_PULSE_WIDTH - servos[_servo_nbr].max * 4)  // maximum value in uS for this servo 
+
+/************ static functions common to all instances ***********************/
+
+static inline void handle_interrupts(servoTimer_t timer, volatile uint16_t *TCNTn, volatile uint16_t* OCRnA)
+{
+  if( Channel[timer] < 0 )
+    *TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer 
+  else{
+    if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && SERVO(timer,Channel[timer]).Pin.isActive == true )  
+      digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,LOW); // pulse this channel low if activated   
+  }
+
+  Channel[timer]++;    // increment to the next channel
+  if( SERVO_INDEX(timer,Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
+    *OCRnA = *TCNTn + SERVO(timer,Channel[timer]).ticks;
+    if(SERVO(timer,Channel[timer]).Pin.isActive == true)	   // check if activated
+      digitalWrite( SERVO(timer,Channel[timer]).Pin.nbr,HIGH); // its an active channel so pulse it high   
+  }	
+  else { 
+    // finished all channels so wait for the refresh period to expire before starting over 
+    if( (unsigned)*TCNTn < (((unsigned int)REFRESH_INTERVAL * TICKS_PER_uS) + 4) )	// allow a few ticks to ensure the next OCR1A not missed
+      *OCRnA = (unsigned int)REFRESH_INTERVAL * TICKS_PER_uS;	
+    else 
+      *OCRnA = *TCNTn + 4;  // at least REFRESH_INTERVAL has elapsed
+	Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
+  }
+}
+
+SIGNAL (TIMER1_COMPA_vect) 
+{ 
+  handle_interrupts(_timer1, &TCNT1, &OCR1A); 
+}
+
+#if defined(__AVR_ATmega1280__)
+SIGNAL (TIMER3_COMPA_vect) 
+{ 
+  handle_interrupts(_timer3, &TCNT3, &OCR3A); 
+}
+SIGNAL (TIMER4_COMPA_vect) 
+{
+  handle_interrupts(_timer4, &TCNT4, &OCR4A); 
+}
+SIGNAL (TIMER5_COMPA_vect) 
+{
+  handle_interrupts(_timer5, &TCNT5, &OCR5A); 
+}
+#endif
+
+static void initISR(servoTimer_t timer)
+{  
+  if(timer == _timer1) {
+    TCCR1A = 0;             // normal counting mode 
+    TCCR1B = _BV(CS11);     // set prescaler of 8 
+    TCNT1 = 0;              // clear the timer count 
+    TIFR1 = _BV(OCF1A);     // clear any pending interrupts; 
+    TIMSK1 =  _BV(OCIE1A) ; // enable the output compare interrupt	  
+  }
+#if defined(__AVR_ATmega1280__)
+  else if(timer == _timer3) {
+    TCCR3A = 0;             // normal counting mode 
+    TCCR3B = _BV(CS31);     // set prescaler of 8  
+    TCNT3 = 0;              // clear the timer count 
+    TIFR3 = _BV(OCF3A);     // clear any pending interrupts; 
+    TIMSK3 =  _BV(OCIE3A) ; // enable the output compare interrupt		  
+  }
+  else if(timer == _timer4) {
+    TCCR4A = 0;             // normal counting mode 
+    TCCR4B = _BV(CS41);     // set prescaler of 8  
+    TCNT4 = 0;              // clear the timer count 
+    TIFR4 = _BV(OCF4A);     // clear any pending interrupts; 
+    TIMSK4 =  _BV(OCIE4A) ; // enable the output compare interrupt		  
+  }
+  else if(timer == _timer5) {
+    TCCR5A = 0;             // normal counting mode 
+    TCCR5B = _BV(CS51);     // set prescaler of 8  
+    TCNT5 = 0;              // clear the timer count 
+    TIFR5 = _BV(OCF5A);     // clear any pending interrupts; 
+    TIMSK5 =  _BV(OCIE5A) ; // enable the output compare interrupt		  
+  }
+#endif
+} 
+
+static boolean isTimerActive(servoTimer_t timer)
+{
+  // returns true if any servo is active on this timer
+  for(uint8_t channel=0; channel < SERVOS_PER_TIMER; channel++) {
+	  if(SERVO(timer,channel).Pin.isActive == true)
+		 return true;
+  }
+  return false;
+}
+
+//#define DEBUG_SHOW
+#ifdef DEBUG_SHOW
+#include  
+void debugShow(int index, char *label)
+{
+  Serial.print(label);
+  Serial.print(" for servo: ");
+  Serial.print(index,DEC);
+  Serial.print(", pin= ");
+  Serial.print(servos[index].Pin.nbr,DEC);
+  Serial.print(", ticks=");
+  Serial.print(servos[index].ticks,DEC);
+  Serial.print(", min=");
+  Serial.print(SERVO_MIN(index),DEC);
+  Serial.print(", max=");
+  Serial.println(SERVO_MAX(index),DEC);
+}
+#endif
+
+
+/****************** end of static functions ******************************/
+
+MegaServo::MegaServo()
+{
+  if( ServoCount < MAX_SERVOS) {
+    this->servoIndex = ServoCount++;                    // assign a servo index to this instance
+	servos[this->servoIndex].ticks = DEFAULT_PULSE_WIDTH * TICKS_PER_uS;   // store default values	
+  }
+  else
+    this->servoIndex = INVALID_SERVO ;  // too many servos 
+}
+
+uint8_t MegaServo::attach(int pin)
+{
+  return this->attach(pin, MIN_PULSE_WIDTH, MAX_PULSE_WIDTH);
+}
+
+uint8_t MegaServo::attach(int pin, int min, int max)
+{
+  if(this->servoIndex < MAX_SERVOS ) {
+    pinMode( pin, OUTPUT) ;                                   // set servo pin to output
+    servos[this->servoIndex].Pin.nbr = pin;  
+	// todo min/max check: abs(min - MIN_PULSE_WIDTH) /4 < 128 
+	servos[this->servoIndex].min  = (MIN_PULSE_WIDTH - min)/4; //resolution of min/max is 4 uS
+    servos[this->servoIndex].max  = (MAX_PULSE_WIDTH - max)/4; 
+	// initialize the timer if it has not already been initialized 
+	servoTimer_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
+    if(isTimerActive(timer) == false)
+      initISR(timer);    
+	servos[this->servoIndex].Pin.isActive = true;  // this must be set after the check for isTimerActive
+  } 
+  return this->servoIndex ;
+}
+
+void MegaServo::detach()  
+{
+  servos[this->servoIndex].Pin.isActive = false;  
+
+#ifdef FREE_TIMERS
+  if(isTimerActive(SERVO_INDEX_TO_TIMER(servoIndex)) == false) {
+     ;// call to unimplimented function in wiring.c to re-init timer (set timer back to PWM mode) TODO? 
+  }
+#endif
+}
+
+void MegaServo::write(int value)
+{	
+  // calculate and store the values for the given channel
+  byte channel = this->servoIndex;
+  if( (channel >= 0) && (channel < MAX_SERVOS) )   // ensure channel is valid
+  {  
+    if(value < 200) // convert degrees if value < 200
+       value = map(value, 0, 180, SERVO_MIN(channel),  SERVO_MAX(channel));      
+    else {
+      if( value < SERVO_MIN(channel) )		       // ensure pulse width is valid
+        value = SERVO_MIN(channel);
+      else if( value > SERVO_MAX(channel) )
+        value = SERVO_MAX(channel);	 
+    }
+    value = (value-TRIM_DURATION) * TICKS_PER_uS;  // convert to ticks after compensating for interrupt overhead
+	uint8_t oldSREG = SREG;
+	cli();
+	servos[channel].ticks = value;  
+	SREG = oldSREG; 
+  } 
+}
+
+void MegaServo::writeMicroseconds(int value)
+{
+   this->write(value);
+}
+
+int MegaServo::read() // return the value as degrees
+{
+  return  map( this->readMicroseconds(), SERVO_MIN(this->servoIndex), SERVO_MAX(this->servoIndex), 0, 180);     
+}
+
+int MegaServo::readMicroseconds()
+{
+  unsigned int pulsewidth;
+  if( this->servoIndex != INVALID_SERVO )
+    pulsewidth = (servos[this->servoIndex].ticks /  TICKS_PER_uS) + TRIM_DURATION +1 ;
+  else 
+    pulsewidth  = 0;
+
+  return pulsewidth;   
+}
+
+bool MegaServo::attached()
+{
+  return servos[this->servoIndex].Pin.isActive ;
+}
\ No newline at end of file
diff --git a/libraries/MegaServo/MegaServo.h b/libraries/MegaServo/MegaServo.h
new file mode 100644
index 0000000..91f7def
--- /dev/null
+++ b/libraries/MegaServo/MegaServo.h
@@ -0,0 +1,101 @@
+/*
+  MegaServo.h - Interrupt driven Servo library for Arduino using 16 bit timers- Version 0.1
+  Copyright (c) 2009 Michael Margolis.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library is distributed in the hope that it will be useful,
+  but WITHOUT ANY WARRANTY; without even the implied warranty of
+  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+  Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+/* 
+  This library uses 16 bit timers to drive up to 12 servos on each timer.
+  It uses interrupts so no explicit refresh activity is required. 
+  The usage and method naming is similar to the Arduino servo library http://www.arduino.cc/en/Reference/Servo
+  except that it support up to 48 servos on a Mega (12 on a standard Arduino).
+  Also pulse widths can be in microseconds or degrees -
+  write() treats parameters less than 200 as degrees, larger values are treated as milliseconds.
+ 
+  
+  A servo is activated by creating an instance of the Servo class passing the desired pin to the attach() method.
+  The servos are pulsed in the background using the value most recently written using the write() method
+
+  Note that analogWrite of PWM on pins associated with the timer are disabled when the first servo is attached.
+  Timers are siezed as needed in groups of 12 servos - 24 servos use two timers, 48 servos will use four.
+
+  The methods are:
+
+   MegaServo - Class for manipulating servo motors connected to Arduino pins.
+
+   attach(pin )  - Attaches a servo motor to an i/o pin.
+   attach(pin, min, max  ) - Attaches to a pin setting min and max values in microseconds
+   default min is 544, max is 2400  
+ 
+   write()     - Sets the servo angle in degrees.  (invalid angle that is valid as pulse in microseconds is treated as microseconds)
+   writeMicroseconds() - Sets the servo pulse width in microseconds 
+   read()      - Gets the last written servo pulse width as an angle between 0 and 180. 
+   readMicroseconds()   - Gets the last written servo pulse width in microseconds. (was read_us() in first release)
+   attached()  - Returns true if there is a servo attached. 
+   detach()    - Stops an attached servos from pulsing its i/o pin. 
+ */
+
+#ifndef MegaServo_h
+#define MegaServo_h
+
+#include 
+
+#define MegaServo_VERSION	    2        // software version of this library
+
+#define MIN_PULSE_WIDTH       544        // the shortest pulse sent to a servo  
+#define MAX_PULSE_WIDTH      2400        // the longest pulse sent to a servo 
+#define DEFAULT_PULSE_WIDTH  1500        // default pulse width when servo is attached
+#define REFRESH_INTERVAL    20000        // minumim time to refresh servos in microseconds 
+
+#if defined(__AVR_ATmega1280__)
+#define MAX_SERVOS             48        // the maximum number of servos  (valid range is from 1 to 48)
+#else
+#define MAX_SERVOS             12        // this library supports up to 12 on a standard Arduino
+#endif
+
+#define INVALID_SERVO         255        // flag indicating an invalid servo index
+
+typedef struct  {
+      uint8_t nbr        :6 ;  // a pin number from 0 to 63
+      uint8_t isActive   :1 ;  // true if this channel is enabled, pin not pulsed if false 
+   } ServoPin_t   ;  
+
+typedef struct {
+    ServoPin_t Pin;
+    unsigned int ticks;
+    int8_t min;              // minimum is this value times 4 added to MIN_PULSE_WIDTH    
+	int8_t max;              // maximum is this value times 4 added to MAX_PULSE_WIDTH   
+  } servo_t;
+
+class MegaServo
+{
+  public:
+	// constructor:
+	MegaServo();
+
+	uint8_t attach(int pin);           // attach the given pin to the next free channel, sets pinMode, returns channel number or 0 if failure
+	uint8_t attach(int pin, int min, int max); // as above but also sets min and max values for writes. 
+    void detach();
+    void write(int value);            // if value is < 200 its treated as an angle, otherwise as pulse width in microseconds 
+	void writeMicroseconds(int value);// Write pulse width in microseconds 
+    int read(); 			          // returns current pulse width as an angle between 0 and 180 degrees
+	int readMicroseconds();           // returns current pulse width in microseconds for this servo (was read_us() in first release)
+	bool attached();                  // return true if this servo is attached, otherwise false 
+ private:
+	 uint8_t servoIndex;              // index into the channel data for this servo
+};
+
+#endif
diff --git a/libraries/MegaServo/keywords.txt b/libraries/MegaServo/keywords.txt
new file mode 100644
index 0000000..4a9372a
--- /dev/null
+++ b/libraries/MegaServo/keywords.txt
@@ -0,0 +1,23 @@
+#######################################
+# Syntax Coloring Map MegaServo
+#######################################
+
+#######################################
+# Datatypes (KEYWORD1)
+#######################################
+
+MegaServo  KEYWORD1
+
+#######################################
+# Methods and Functions (KEYWORD2)
+#######################################
+attach KEYWORD2
+detach KEYWORD2
+write KEYWORD2
+read KEYWORD2
+read_us KEYWORD2
+attached KEYWORD2
+
+#######################################
+# Constants (LITERAL1)
+#######################################
diff --git a/libraries/MotionDriver/dmpKey.h b/libraries/MotionDriver/dmpKey.h
new file mode 100644
index 0000000..c8f62a2
--- /dev/null
+++ b/libraries/MotionDriver/dmpKey.h
@@ -0,0 +1,494 @@
+/*
+ $License:
+    Copyright (C) 2011 InvenSense Corporation, All Rights Reserved.
+ $
+ */
+#ifndef DMPKEY_H__
+#define DMPKEY_H__
+
+#define KEY_CFG_25                  (0)
+#define KEY_CFG_24                  (KEY_CFG_25 + 1)
+#define KEY_CFG_26                  (KEY_CFG_24 + 1)
+#define KEY_CFG_27                  (KEY_CFG_26 + 1)
+#define KEY_CFG_21                  (KEY_CFG_27 + 1)
+#define KEY_CFG_20                  (KEY_CFG_21 + 1)
+#define KEY_CFG_TAP4                (KEY_CFG_20 + 1)
+#define KEY_CFG_TAP5                (KEY_CFG_TAP4 + 1)
+#define KEY_CFG_TAP6                (KEY_CFG_TAP5 + 1)
+#define KEY_CFG_TAP7                (KEY_CFG_TAP6 + 1)
+#define KEY_CFG_TAP0                (KEY_CFG_TAP7 + 1)
+#define KEY_CFG_TAP1                (KEY_CFG_TAP0 + 1)
+#define KEY_CFG_TAP2                (KEY_CFG_TAP1 + 1)
+#define KEY_CFG_TAP3                (KEY_CFG_TAP2 + 1)
+#define KEY_CFG_TAP_QUANTIZE        (KEY_CFG_TAP3 + 1)
+#define KEY_CFG_TAP_JERK            (KEY_CFG_TAP_QUANTIZE + 1)
+#define KEY_CFG_DR_INT              (KEY_CFG_TAP_JERK + 1)
+#define KEY_CFG_AUTH                (KEY_CFG_DR_INT + 1)
+#define KEY_CFG_TAP_SAVE_ACCB       (KEY_CFG_AUTH + 1)
+#define KEY_CFG_TAP_CLEAR_STICKY    (KEY_CFG_TAP_SAVE_ACCB + 1)
+#define KEY_CFG_FIFO_ON_EVENT       (KEY_CFG_TAP_CLEAR_STICKY + 1)
+#define KEY_FCFG_ACCEL_INPUT        (KEY_CFG_FIFO_ON_EVENT + 1)
+#define KEY_FCFG_ACCEL_INIT         (KEY_FCFG_ACCEL_INPUT + 1)
+#define KEY_CFG_23                  (KEY_FCFG_ACCEL_INIT + 1)
+#define KEY_FCFG_1                  (KEY_CFG_23 + 1)
+#define KEY_FCFG_3                  (KEY_FCFG_1 + 1)
+#define KEY_FCFG_2                  (KEY_FCFG_3 + 1)
+#define KEY_CFG_3D                  (KEY_FCFG_2 + 1)
+#define KEY_CFG_3B                  (KEY_CFG_3D + 1)
+#define KEY_CFG_3C                  (KEY_CFG_3B + 1)
+#define KEY_FCFG_5                  (KEY_CFG_3C + 1)
+#define KEY_FCFG_4                  (KEY_FCFG_5 + 1)
+#define KEY_FCFG_7                  (KEY_FCFG_4 + 1)
+#define KEY_FCFG_FSCALE             (KEY_FCFG_7 + 1)
+#define KEY_FCFG_AZ                 (KEY_FCFG_FSCALE + 1)
+#define KEY_FCFG_6                  (KEY_FCFG_AZ + 1)
+#define KEY_FCFG_LSB4               (KEY_FCFG_6 + 1)
+#define KEY_CFG_12                  (KEY_FCFG_LSB4 + 1)
+#define KEY_CFG_14                  (KEY_CFG_12 + 1)
+#define KEY_CFG_15                  (KEY_CFG_14 + 1)
+#define KEY_CFG_16                  (KEY_CFG_15 + 1)
+#define KEY_CFG_18                  (KEY_CFG_16 + 1)
+#define KEY_CFG_6                   (KEY_CFG_18 + 1)
+#define KEY_CFG_7                   (KEY_CFG_6 + 1)
+#define KEY_CFG_4                   (KEY_CFG_7 + 1)
+#define KEY_CFG_5                   (KEY_CFG_4 + 1)
+#define KEY_CFG_2                   (KEY_CFG_5 + 1)
+#define KEY_CFG_3                   (KEY_CFG_2 + 1)
+#define KEY_CFG_1                   (KEY_CFG_3 + 1)
+#define KEY_CFG_EXTERNAL            (KEY_CFG_1 + 1)
+#define KEY_CFG_8                   (KEY_CFG_EXTERNAL + 1)
+#define KEY_CFG_9                   (KEY_CFG_8 + 1)
+#define KEY_CFG_ORIENT_3            (KEY_CFG_9 + 1)
+#define KEY_CFG_ORIENT_2            (KEY_CFG_ORIENT_3 + 1)
+#define KEY_CFG_ORIENT_1            (KEY_CFG_ORIENT_2 + 1)
+#define KEY_CFG_GYRO_SOURCE         (KEY_CFG_ORIENT_1 + 1)
+#define KEY_CFG_ORIENT_IRQ_1        (KEY_CFG_GYRO_SOURCE + 1)
+#define KEY_CFG_ORIENT_IRQ_2        (KEY_CFG_ORIENT_IRQ_1 + 1)
+#define KEY_CFG_ORIENT_IRQ_3        (KEY_CFG_ORIENT_IRQ_2 + 1)
+#define KEY_FCFG_MAG_VAL            (KEY_CFG_ORIENT_IRQ_3 + 1)
+#define KEY_FCFG_MAG_MOV            (KEY_FCFG_MAG_VAL + 1)
+#define KEY_CFG_LP_QUAT             (KEY_FCFG_MAG_MOV + 1)
+
+/* MPU6050 keys */
+#define KEY_CFG_ACCEL_FILTER        (KEY_CFG_LP_QUAT + 1)
+#define KEY_CFG_MOTION_BIAS         (KEY_CFG_ACCEL_FILTER + 1)
+#define KEY_TEMPLABEL               (KEY_CFG_MOTION_BIAS + 1)
+
+#define KEY_D_0_22                  (KEY_TEMPLABEL + 1)
+#define KEY_D_0_24                  (KEY_D_0_22 + 1)
+#define KEY_D_0_36                  (KEY_D_0_24 + 1)
+#define KEY_D_0_52                  (KEY_D_0_36 + 1)
+#define KEY_D_0_96                  (KEY_D_0_52 + 1)
+#define KEY_D_0_104                 (KEY_D_0_96 + 1)
+#define KEY_D_0_108                 (KEY_D_0_104 + 1)
+#define KEY_D_0_163                 (KEY_D_0_108 + 1)
+#define KEY_D_0_188                 (KEY_D_0_163 + 1)
+#define KEY_D_0_192                 (KEY_D_0_188 + 1)
+#define KEY_D_0_224                 (KEY_D_0_192 + 1)
+#define KEY_D_0_228                 (KEY_D_0_224 + 1)
+#define KEY_D_0_232                 (KEY_D_0_228 + 1)
+#define KEY_D_0_236                 (KEY_D_0_232 + 1)
+
+#define KEY_DMP_PREVPTAT            (KEY_D_0_236 + 1)
+#define KEY_D_1_2                   (KEY_DMP_PREVPTAT + 1)
+#define KEY_D_1_4                   (KEY_D_1_2 + 1)
+#define KEY_D_1_8                   (KEY_D_1_4 + 1)
+#define KEY_D_1_10                  (KEY_D_1_8 + 1)
+#define KEY_D_1_24                  (KEY_D_1_10 + 1)
+#define KEY_D_1_28                  (KEY_D_1_24 + 1)
+#define KEY_D_1_36                  (KEY_D_1_28 + 1)
+#define KEY_D_1_40                  (KEY_D_1_36 + 1)
+#define KEY_D_1_44                  (KEY_D_1_40 + 1)
+#define KEY_D_1_72                  (KEY_D_1_44 + 1)
+#define KEY_D_1_74                  (KEY_D_1_72 + 1)
+#define KEY_D_1_79                  (KEY_D_1_74 + 1)
+#define KEY_D_1_88                  (KEY_D_1_79 + 1)
+#define KEY_D_1_90                  (KEY_D_1_88 + 1)
+#define KEY_D_1_92                  (KEY_D_1_90 + 1)
+#define KEY_D_1_96                  (KEY_D_1_92 + 1)
+#define KEY_D_1_98                  (KEY_D_1_96 + 1)
+#define KEY_D_1_100                 (KEY_D_1_98 + 1)
+#define KEY_D_1_106                 (KEY_D_1_100 + 1)
+#define KEY_D_1_108                 (KEY_D_1_106 + 1)
+#define KEY_D_1_112                 (KEY_D_1_108 + 1)
+#define KEY_D_1_128                 (KEY_D_1_112 + 1)
+#define KEY_D_1_152                 (KEY_D_1_128 + 1)
+#define KEY_D_1_160                 (KEY_D_1_152 + 1)
+#define KEY_D_1_168                 (KEY_D_1_160 + 1)
+#define KEY_D_1_175                 (KEY_D_1_168 + 1)
+#define KEY_D_1_176                 (KEY_D_1_175 + 1)
+#define KEY_D_1_178                 (KEY_D_1_176 + 1)
+#define KEY_D_1_179                 (KEY_D_1_178 + 1)
+#define KEY_D_1_218                 (KEY_D_1_179 + 1)
+#define KEY_D_1_232                 (KEY_D_1_218 + 1)
+#define KEY_D_1_236                 (KEY_D_1_232 + 1)
+#define KEY_D_1_240                 (KEY_D_1_236 + 1)
+#define KEY_D_1_244                 (KEY_D_1_240 + 1)
+#define KEY_D_1_250                 (KEY_D_1_244 + 1)
+#define KEY_D_1_252                 (KEY_D_1_250 + 1)
+#define KEY_D_2_12                  (KEY_D_1_252 + 1)
+#define KEY_D_2_96                  (KEY_D_2_12 + 1)
+#define KEY_D_2_108                 (KEY_D_2_96 + 1)
+#define KEY_D_2_208                 (KEY_D_2_108 + 1)
+#define KEY_FLICK_MSG               (KEY_D_2_208 + 1)
+#define KEY_FLICK_COUNTER           (KEY_FLICK_MSG + 1)
+#define KEY_FLICK_LOWER             (KEY_FLICK_COUNTER + 1)
+#define KEY_CFG_FLICK_IN            (KEY_FLICK_LOWER + 1)
+#define KEY_FLICK_UPPER             (KEY_CFG_FLICK_IN + 1)
+#define KEY_CGNOTICE_INTR           (KEY_FLICK_UPPER + 1)
+#define KEY_D_2_224                 (KEY_CGNOTICE_INTR + 1)
+#define KEY_D_2_244                 (KEY_D_2_224 + 1)
+#define KEY_D_2_248                 (KEY_D_2_244 + 1)
+#define KEY_D_2_252                 (KEY_D_2_248 + 1)
+
+#define KEY_D_GYRO_BIAS_X               (KEY_D_2_252 + 1)
+#define KEY_D_GYRO_BIAS_Y               (KEY_D_GYRO_BIAS_X + 1)
+#define KEY_D_GYRO_BIAS_Z               (KEY_D_GYRO_BIAS_Y + 1)
+#define KEY_D_ACC_BIAS_X                (KEY_D_GYRO_BIAS_Z + 1)
+#define KEY_D_ACC_BIAS_Y                (KEY_D_ACC_BIAS_X + 1)
+#define KEY_D_ACC_BIAS_Z                (KEY_D_ACC_BIAS_Y + 1)
+#define KEY_D_GYRO_ENABLE               (KEY_D_ACC_BIAS_Z + 1)
+#define KEY_D_ACCEL_ENABLE              (KEY_D_GYRO_ENABLE + 1)
+#define KEY_D_QUAT_ENABLE               (KEY_D_ACCEL_ENABLE +1)
+#define KEY_D_OUTPUT_ENABLE             (KEY_D_QUAT_ENABLE + 1)
+#define KEY_D_CR_TIME_G                 (KEY_D_OUTPUT_ENABLE + 1)
+#define KEY_D_CR_TIME_A                 (KEY_D_CR_TIME_G + 1)
+#define KEY_D_CR_TIME_Q                 (KEY_D_CR_TIME_A + 1)
+#define KEY_D_CS_TAX                    (KEY_D_CR_TIME_Q + 1)
+#define KEY_D_CS_TAY                    (KEY_D_CS_TAX + 1)
+#define KEY_D_CS_TAZ                    (KEY_D_CS_TAY + 1)
+#define KEY_D_CS_TGX                    (KEY_D_CS_TAZ + 1)
+#define KEY_D_CS_TGY                    (KEY_D_CS_TGX + 1)
+#define KEY_D_CS_TGZ                    (KEY_D_CS_TGY + 1)
+#define KEY_D_CS_TQ0                    (KEY_D_CS_TGZ + 1)
+#define KEY_D_CS_TQ1                    (KEY_D_CS_TQ0 + 1)
+#define KEY_D_CS_TQ2                    (KEY_D_CS_TQ1 + 1)
+#define KEY_D_CS_TQ3                    (KEY_D_CS_TQ2 + 1)
+
+/* Compass keys */
+#define KEY_CPASS_BIAS_X            (KEY_D_CS_TQ3 + 1)
+#define KEY_CPASS_BIAS_Y            (KEY_CPASS_BIAS_X + 1)
+#define KEY_CPASS_BIAS_Z            (KEY_CPASS_BIAS_Y + 1)
+#define KEY_CPASS_MTX_00            (KEY_CPASS_BIAS_Z + 1)
+#define KEY_CPASS_MTX_01            (KEY_CPASS_MTX_00 + 1)
+#define KEY_CPASS_MTX_02            (KEY_CPASS_MTX_01 + 1)
+#define KEY_CPASS_MTX_10            (KEY_CPASS_MTX_02 + 1)
+#define KEY_CPASS_MTX_11            (KEY_CPASS_MTX_10 + 1)
+#define KEY_CPASS_MTX_12            (KEY_CPASS_MTX_11 + 1)
+#define KEY_CPASS_MTX_20            (KEY_CPASS_MTX_12 + 1)
+#define KEY_CPASS_MTX_21            (KEY_CPASS_MTX_20 + 1)
+#define KEY_CPASS_MTX_22            (KEY_CPASS_MTX_21 + 1)
+
+/* Gesture Keys */
+#define KEY_DMP_TAPW_MIN            (KEY_CPASS_MTX_22 + 1)
+#define KEY_DMP_TAP_THR_X           (KEY_DMP_TAPW_MIN + 1)
+#define KEY_DMP_TAP_THR_Y           (KEY_DMP_TAP_THR_X + 1)
+#define KEY_DMP_TAP_THR_Z           (KEY_DMP_TAP_THR_Y + 1)
+#define KEY_DMP_SH_TH_Y             (KEY_DMP_TAP_THR_Z + 1)
+#define KEY_DMP_SH_TH_X             (KEY_DMP_SH_TH_Y + 1)
+#define KEY_DMP_SH_TH_Z             (KEY_DMP_SH_TH_X + 1)
+#define KEY_DMP_ORIENT              (KEY_DMP_SH_TH_Z + 1)
+#define KEY_D_ACT0                  (KEY_DMP_ORIENT + 1)
+#define KEY_D_ACSX                  (KEY_D_ACT0 + 1)
+#define KEY_D_ACSY                  (KEY_D_ACSX + 1)
+#define KEY_D_ACSZ                  (KEY_D_ACSY + 1)
+
+#define KEY_X_GRT_Y_TMP             (KEY_D_ACSZ + 1)
+#define KEY_SKIP_X_GRT_Y_TMP        (KEY_X_GRT_Y_TMP + 1)
+#define KEY_SKIP_END_COMPARE        (KEY_SKIP_X_GRT_Y_TMP + 1)
+#define KEY_END_COMPARE_Y_X_TMP2    (KEY_SKIP_END_COMPARE + 1)       
+#define KEY_CFG_ANDROID_ORIENT_INT  (KEY_END_COMPARE_Y_X_TMP2 + 1)
+#define KEY_NO_ORIENT_INTERRUPT     (KEY_CFG_ANDROID_ORIENT_INT + 1)
+#define KEY_END_COMPARE_Y_X_TMP     (KEY_NO_ORIENT_INTERRUPT + 1)
+#define KEY_END_ORIENT_1            (KEY_END_COMPARE_Y_X_TMP + 1)
+#define KEY_END_COMPARE_Y_X         (KEY_END_ORIENT_1 + 1) 
+#define KEY_END_ORIENT              (KEY_END_COMPARE_Y_X + 1)
+#define KEY_X_GRT_Y                 (KEY_END_ORIENT + 1)
+#define KEY_NOT_TIME_MINUS_1        (KEY_X_GRT_Y + 1)       
+#define KEY_END_COMPARE_Y_X_TMP3    (KEY_NOT_TIME_MINUS_1 + 1) 
+#define KEY_X_GRT_Y_TMP2            (KEY_END_COMPARE_Y_X_TMP3 + 1)
+
+/* Authenticate Keys */
+#define KEY_D_AUTH_OUT              (KEY_X_GRT_Y_TMP2 + 1)
+#define KEY_D_AUTH_IN               (KEY_D_AUTH_OUT + 1)
+#define KEY_D_AUTH_A                (KEY_D_AUTH_IN + 1)
+#define KEY_D_AUTH_B                (KEY_D_AUTH_A + 1)
+
+/* Pedometer standalone only keys */
+#define KEY_D_PEDSTD_BP_B           (KEY_D_AUTH_B + 1)
+#define KEY_D_PEDSTD_HP_A           (KEY_D_PEDSTD_BP_B + 1)
+#define KEY_D_PEDSTD_HP_B           (KEY_D_PEDSTD_HP_A + 1)
+#define KEY_D_PEDSTD_BP_A4          (KEY_D_PEDSTD_HP_B + 1)
+#define KEY_D_PEDSTD_BP_A3          (KEY_D_PEDSTD_BP_A4 + 1)
+#define KEY_D_PEDSTD_BP_A2          (KEY_D_PEDSTD_BP_A3 + 1)
+#define KEY_D_PEDSTD_BP_A1          (KEY_D_PEDSTD_BP_A2 + 1)
+#define KEY_D_PEDSTD_INT_THRSH      (KEY_D_PEDSTD_BP_A1 + 1)
+#define KEY_D_PEDSTD_CLIP           (KEY_D_PEDSTD_INT_THRSH + 1)
+#define KEY_D_PEDSTD_SB             (KEY_D_PEDSTD_CLIP + 1)
+#define KEY_D_PEDSTD_SB_TIME        (KEY_D_PEDSTD_SB + 1)
+#define KEY_D_PEDSTD_PEAKTHRSH      (KEY_D_PEDSTD_SB_TIME + 1)
+#define KEY_D_PEDSTD_TIML           (KEY_D_PEDSTD_PEAKTHRSH + 1)
+#define KEY_D_PEDSTD_TIMH           (KEY_D_PEDSTD_TIML + 1)
+#define KEY_D_PEDSTD_PEAK           (KEY_D_PEDSTD_TIMH + 1)
+#define KEY_D_PEDSTD_TIMECTR        (KEY_D_PEDSTD_PEAK + 1)
+#define KEY_D_PEDSTD_STEPCTR        (KEY_D_PEDSTD_TIMECTR + 1)
+#define KEY_D_PEDSTD_WALKTIME       (KEY_D_PEDSTD_STEPCTR + 1)
+#define KEY_D_PEDSTD_DECI           (KEY_D_PEDSTD_WALKTIME + 1)
+
+/*Host Based No Motion*/
+#define KEY_D_HOST_NO_MOT           (KEY_D_PEDSTD_DECI + 1)
+
+/* EIS keys */
+#define KEY_P_EIS_FIFO_FOOTER       (KEY_D_HOST_NO_MOT + 1)
+#define KEY_P_EIS_FIFO_YSHIFT       (KEY_P_EIS_FIFO_FOOTER + 1)
+#define KEY_P_EIS_DATA_RATE         (KEY_P_EIS_FIFO_YSHIFT + 1)
+#define KEY_P_EIS_FIFO_XSHIFT       (KEY_P_EIS_DATA_RATE + 1)
+#define KEY_P_EIS_FIFO_SYNC         (KEY_P_EIS_FIFO_XSHIFT + 1)
+#define KEY_P_EIS_FIFO_ZSHIFT       (KEY_P_EIS_FIFO_SYNC + 1)
+#define KEY_P_EIS_FIFO_READY        (KEY_P_EIS_FIFO_ZSHIFT + 1)
+#define KEY_DMP_FOOTER              (KEY_P_EIS_FIFO_READY + 1)
+#define KEY_DMP_INTX_HC             (KEY_DMP_FOOTER + 1)
+#define KEY_DMP_INTX_PH             (KEY_DMP_INTX_HC + 1)
+#define KEY_DMP_INTX_SH             (KEY_DMP_INTX_PH + 1)
+#define KEY_DMP_AINV_SH             (KEY_DMP_INTX_SH + 1)
+#define KEY_DMP_A_INV_XH            (KEY_DMP_AINV_SH + 1)
+#define KEY_DMP_AINV_PH             (KEY_DMP_A_INV_XH + 1)
+#define KEY_DMP_CTHX_H              (KEY_DMP_AINV_PH + 1)
+#define KEY_DMP_CTHY_H              (KEY_DMP_CTHX_H + 1)
+#define KEY_DMP_CTHZ_H              (KEY_DMP_CTHY_H + 1)
+#define KEY_DMP_NCTHX_H             (KEY_DMP_CTHZ_H + 1)
+#define KEY_DMP_NCTHY_H             (KEY_DMP_NCTHX_H + 1)
+#define KEY_DMP_NCTHZ_H             (KEY_DMP_NCTHY_H + 1)
+#define KEY_DMP_CTSQ_XH             (KEY_DMP_NCTHZ_H + 1)
+#define KEY_DMP_CTSQ_YH             (KEY_DMP_CTSQ_XH + 1)
+#define KEY_DMP_CTSQ_ZH             (KEY_DMP_CTSQ_YH + 1)
+#define KEY_DMP_INTX_H              (KEY_DMP_CTSQ_ZH + 1)
+#define KEY_DMP_INTY_H              (KEY_DMP_INTX_H + 1)
+#define KEY_DMP_INTZ_H              (KEY_DMP_INTY_H + 1)
+//#define KEY_DMP_HPX_H               (KEY_DMP_INTZ_H + 1)
+//#define KEY_DMP_HPY_H               (KEY_DMP_HPX_H + 1)
+//#define KEY_DMP_HPZ_H               (KEY_DMP_HPY_H + 1)
+
+/* Stream keys */
+#define KEY_STREAM_P_GYRO_Z         (KEY_DMP_INTZ_H + 1)
+#define KEY_STREAM_P_GYRO_Y         (KEY_STREAM_P_GYRO_Z + 1)
+#define KEY_STREAM_P_GYRO_X         (KEY_STREAM_P_GYRO_Y + 1)
+#define KEY_STREAM_P_TEMP           (KEY_STREAM_P_GYRO_X + 1)
+#define KEY_STREAM_P_AUX_Y          (KEY_STREAM_P_TEMP + 1)
+#define KEY_STREAM_P_AUX_X          (KEY_STREAM_P_AUX_Y + 1)
+#define KEY_STREAM_P_AUX_Z          (KEY_STREAM_P_AUX_X + 1)
+#define KEY_STREAM_P_ACCEL_Y        (KEY_STREAM_P_AUX_Z + 1)
+#define KEY_STREAM_P_ACCEL_X        (KEY_STREAM_P_ACCEL_Y + 1)
+#define KEY_STREAM_P_FOOTER         (KEY_STREAM_P_ACCEL_X + 1)
+#define KEY_STREAM_P_ACCEL_Z        (KEY_STREAM_P_FOOTER + 1)
+
+#define NUM_KEYS                    (KEY_STREAM_P_ACCEL_Z + 1)
+
+typedef struct {
+    unsigned short key;
+    unsigned short addr;
+} tKeyLabel;
+
+#define DINA0A 0x0a
+#define DINA22 0x22
+#define DINA42 0x42
+#define DINA5A 0x5a
+
+#define DINA06 0x06
+#define DINA0E 0x0e
+#define DINA16 0x16
+#define DINA1E 0x1e
+#define DINA26 0x26
+#define DINA2E 0x2e
+#define DINA36 0x36
+#define DINA3E 0x3e
+#define DINA46 0x46
+#define DINA4E 0x4e
+#define DINA56 0x56
+#define DINA5E 0x5e
+#define DINA66 0x66
+#define DINA6E 0x6e
+#define DINA76 0x76
+#define DINA7E 0x7e
+
+#define DINA00 0x00
+#define DINA08 0x08
+#define DINA10 0x10
+#define DINA18 0x18
+#define DINA20 0x20
+#define DINA28 0x28
+#define DINA30 0x30
+#define DINA38 0x38
+#define DINA40 0x40
+#define DINA48 0x48
+#define DINA50 0x50
+#define DINA58 0x58
+#define DINA60 0x60
+#define DINA68 0x68
+#define DINA70 0x70
+#define DINA78 0x78
+
+#define DINA04 0x04
+#define DINA0C 0x0c
+#define DINA14 0x14
+#define DINA1C 0x1C
+#define DINA24 0x24
+#define DINA2C 0x2c
+#define DINA34 0x34
+#define DINA3C 0x3c
+#define DINA44 0x44
+#define DINA4C 0x4c
+#define DINA54 0x54
+#define DINA5C 0x5c
+#define DINA64 0x64
+#define DINA6C 0x6c
+#define DINA74 0x74
+#define DINA7C 0x7c
+
+#define DINA01 0x01
+#define DINA09 0x09
+#define DINA11 0x11
+#define DINA19 0x19
+#define DINA21 0x21
+#define DINA29 0x29
+#define DINA31 0x31
+#define DINA39 0x39
+#define DINA41 0x41
+#define DINA49 0x49
+#define DINA51 0x51
+#define DINA59 0x59
+#define DINA61 0x61
+#define DINA69 0x69
+#define DINA71 0x71
+#define DINA79 0x79
+
+#define DINA25 0x25
+#define DINA2D 0x2d
+#define DINA35 0x35
+#define DINA3D 0x3d
+#define DINA4D 0x4d
+#define DINA55 0x55
+#define DINA5D 0x5D
+#define DINA6D 0x6d
+#define DINA75 0x75
+#define DINA7D 0x7d
+
+#define DINADC 0xdc
+#define DINAF2 0xf2
+#define DINAAB 0xab
+#define DINAAA 0xaa
+#define DINAF1 0xf1
+#define DINADF 0xdf
+#define DINADA 0xda
+#define DINAB1 0xb1
+#define DINAB9 0xb9
+#define DINAF3 0xf3
+#define DINA8B 0x8b
+#define DINAA3 0xa3
+#define DINA91 0x91
+#define DINAB6 0xb6
+#define DINAB4 0xb4
+
+
+#define DINC00 0x00
+#define DINC01 0x01
+#define DINC02 0x02
+#define DINC03 0x03
+#define DINC08 0x08
+#define DINC09 0x09
+#define DINC0A 0x0a
+#define DINC0B 0x0b
+#define DINC10 0x10
+#define DINC11 0x11
+#define DINC12 0x12
+#define DINC13 0x13
+#define DINC18 0x18
+#define DINC19 0x19
+#define DINC1A 0x1a
+#define DINC1B 0x1b
+
+#define DINC20 0x20
+#define DINC21 0x21
+#define DINC22 0x22
+#define DINC23 0x23
+#define DINC28 0x28
+#define DINC29 0x29
+#define DINC2A 0x2a
+#define DINC2B 0x2b
+#define DINC30 0x30
+#define DINC31 0x31
+#define DINC32 0x32
+#define DINC33 0x33
+#define DINC38 0x38
+#define DINC39 0x39
+#define DINC3A 0x3a
+#define DINC3B 0x3b
+
+#define DINC40 0x40
+#define DINC41 0x41
+#define DINC42 0x42
+#define DINC43 0x43
+#define DINC48 0x48
+#define DINC49 0x49
+#define DINC4A 0x4a
+#define DINC4B 0x4b
+#define DINC50 0x50
+#define DINC51 0x51
+#define DINC52 0x52
+#define DINC53 0x53
+#define DINC58 0x58
+#define DINC59 0x59
+#define DINC5A 0x5a
+#define DINC5B 0x5b
+
+#define DINC60 0x60
+#define DINC61 0x61
+#define DINC62 0x62
+#define DINC63 0x63
+#define DINC68 0x68
+#define DINC69 0x69
+#define DINC6A 0x6a
+#define DINC6B 0x6b
+#define DINC70 0x70
+#define DINC71 0x71
+#define DINC72 0x72
+#define DINC73 0x73
+#define DINC78 0x78
+#define DINC79 0x79
+#define DINC7A 0x7a
+#define DINC7B 0x7b
+
+#define DIND40 0x40
+
+
+#define DINA80 0x80
+#define DINA90 0x90
+#define DINAA0 0xa0
+#define DINAC9 0xc9
+#define DINACB 0xcb
+#define DINACD 0xcd
+#define DINACF 0xcf
+#define DINAC8 0xc8
+#define DINACA 0xca
+#define DINACC 0xcc
+#define DINACE 0xce
+#define DINAD8 0xd8
+#define DINADD 0xdd
+#define DINAF8 0xf0
+#define DINAFE 0xfe
+
+#define DINBF8 0xf8
+#define DINAC0 0xb0
+#define DINAC1 0xb1
+#define DINAC2 0xb4
+#define DINAC3 0xb5
+#define DINAC4 0xb8
+#define DINAC5 0xb9
+#define DINBC0 0xc0
+#define DINBC2 0xc2
+#define DINBC4 0xc4
+#define DINBC6 0xc6
+
+
+
+#endif // DMPKEY_H__
diff --git a/libraries/MotionDriver/dmpmap.h b/libraries/MotionDriver/dmpmap.h
new file mode 100644
index 0000000..391ba14
--- /dev/null
+++ b/libraries/MotionDriver/dmpmap.h
@@ -0,0 +1,264 @@
+/*
+ $License:
+    Copyright (C) 2011 InvenSense Corporation, All Rights Reserved.
+ $
+ */
+#ifndef DMPMAP_H
+#define DMPMAP_H
+
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+#define DMP_PTAT    0
+#define DMP_XGYR    2
+#define DMP_YGYR    4
+#define DMP_ZGYR    6
+#define DMP_XACC    8
+#define DMP_YACC    10
+#define DMP_ZACC    12
+#define DMP_ADC1    14
+#define DMP_ADC2    16
+#define DMP_ADC3    18
+#define DMP_BIASUNC    20
+#define DMP_FIFORT    22
+#define DMP_INVGSFH    24
+#define DMP_INVGSFL    26
+#define DMP_1H    28
+#define DMP_1L    30
+#define DMP_BLPFSTCH    32
+#define DMP_BLPFSTCL    34
+#define DMP_BLPFSXH    36
+#define DMP_BLPFSXL    38
+#define DMP_BLPFSYH    40
+#define DMP_BLPFSYL    42
+#define DMP_BLPFSZH    44
+#define DMP_BLPFSZL    46
+#define DMP_BLPFMTC    48
+#define DMP_SMC    50
+#define DMP_BLPFMXH    52
+#define DMP_BLPFMXL    54
+#define DMP_BLPFMYH    56
+#define DMP_BLPFMYL    58
+#define DMP_BLPFMZH    60
+#define DMP_BLPFMZL    62
+#define DMP_BLPFC    64
+#define DMP_SMCTH    66
+#define DMP_0H2    68
+#define DMP_0L2    70
+#define DMP_BERR2H    72
+#define DMP_BERR2L    74
+#define DMP_BERR2NH    76
+#define DMP_SMCINC    78
+#define DMP_ANGVBXH    80
+#define DMP_ANGVBXL    82
+#define DMP_ANGVBYH    84
+#define DMP_ANGVBYL    86
+#define DMP_ANGVBZH    88
+#define DMP_ANGVBZL    90
+#define DMP_BERR1H    92
+#define DMP_BERR1L    94
+#define DMP_ATCH    96
+#define DMP_BIASUNCSF    98
+#define DMP_ACT2H    100
+#define DMP_ACT2L    102
+#define DMP_GSFH    104
+#define DMP_GSFL    106
+#define DMP_GH    108
+#define DMP_GL    110
+#define DMP_0_5H    112
+#define DMP_0_5L    114
+#define DMP_0_0H    116
+#define DMP_0_0L    118
+#define DMP_1_0H    120
+#define DMP_1_0L    122
+#define DMP_1_5H    124
+#define DMP_1_5L    126
+#define DMP_TMP1AH    128
+#define DMP_TMP1AL    130
+#define DMP_TMP2AH    132
+#define DMP_TMP2AL    134
+#define DMP_TMP3AH    136
+#define DMP_TMP3AL    138
+#define DMP_TMP4AH    140
+#define DMP_TMP4AL    142
+#define DMP_XACCW    144
+#define DMP_TMP5    146
+#define DMP_XACCB    148
+#define DMP_TMP8    150
+#define DMP_YACCB    152
+#define DMP_TMP9    154
+#define DMP_ZACCB    156
+#define DMP_TMP10    158
+#define DMP_DZH    160
+#define DMP_DZL    162
+#define DMP_XGCH    164
+#define DMP_XGCL    166
+#define DMP_YGCH    168
+#define DMP_YGCL    170
+#define DMP_ZGCH    172
+#define DMP_ZGCL    174
+#define DMP_YACCW    176
+#define DMP_TMP7    178
+#define DMP_AFB1H    180
+#define DMP_AFB1L    182
+#define DMP_AFB2H    184
+#define DMP_AFB2L    186
+#define DMP_MAGFBH    188
+#define DMP_MAGFBL    190
+#define DMP_QT1H    192
+#define DMP_QT1L    194
+#define DMP_QT2H    196
+#define DMP_QT2L    198
+#define DMP_QT3H    200
+#define DMP_QT3L    202
+#define DMP_QT4H    204
+#define DMP_QT4L    206
+#define DMP_CTRL1H    208
+#define DMP_CTRL1L    210
+#define DMP_CTRL2H    212
+#define DMP_CTRL2L    214
+#define DMP_CTRL3H    216
+#define DMP_CTRL3L    218
+#define DMP_CTRL4H    220
+#define DMP_CTRL4L    222
+#define DMP_CTRLS1    224
+#define DMP_CTRLSF1    226
+#define DMP_CTRLS2    228
+#define DMP_CTRLSF2    230
+#define DMP_CTRLS3    232
+#define DMP_CTRLSFNLL    234
+#define DMP_CTRLS4    236
+#define DMP_CTRLSFNL2    238
+#define DMP_CTRLSFNL    240
+#define DMP_TMP30    242
+#define DMP_CTRLSFJT    244
+#define DMP_TMP31    246
+#define DMP_TMP11    248
+#define DMP_CTRLSF2_2    250
+#define DMP_TMP12    252
+#define DMP_CTRLSF1_2    254
+#define DMP_PREVPTAT    256
+#define DMP_ACCZB    258
+#define DMP_ACCXB    264
+#define DMP_ACCYB    266
+#define DMP_1HB    272
+#define DMP_1LB    274
+#define DMP_0H    276
+#define DMP_0L    278
+#define DMP_ASR22H    280
+#define DMP_ASR22L    282
+#define DMP_ASR6H    284
+#define DMP_ASR6L    286
+#define DMP_TMP13    288
+#define DMP_TMP14    290
+#define DMP_FINTXH    292
+#define DMP_FINTXL    294
+#define DMP_FINTYH    296
+#define DMP_FINTYL    298
+#define DMP_FINTZH    300
+#define DMP_FINTZL    302
+#define DMP_TMP1BH    304
+#define DMP_TMP1BL    306
+#define DMP_TMP2BH    308
+#define DMP_TMP2BL    310
+#define DMP_TMP3BH    312
+#define DMP_TMP3BL    314
+#define DMP_TMP4BH    316
+#define DMP_TMP4BL    318
+#define DMP_STXG    320
+#define DMP_ZCTXG    322
+#define DMP_STYG    324
+#define DMP_ZCTYG    326
+#define DMP_STZG    328
+#define DMP_ZCTZG    330
+#define DMP_CTRLSFJT2    332
+#define DMP_CTRLSFJTCNT    334
+#define DMP_PVXG    336
+#define DMP_TMP15    338
+#define DMP_PVYG    340
+#define DMP_TMP16    342
+#define DMP_PVZG    344
+#define DMP_TMP17    346
+#define DMP_MNMFLAGH    352
+#define DMP_MNMFLAGL    354
+#define DMP_MNMTMH    356
+#define DMP_MNMTML    358
+#define DMP_MNMTMTHRH    360
+#define DMP_MNMTMTHRL    362
+#define DMP_MNMTHRH    364
+#define DMP_MNMTHRL    366
+#define DMP_ACCQD4H    368
+#define DMP_ACCQD4L    370
+#define DMP_ACCQD5H    372
+#define DMP_ACCQD5L    374
+#define DMP_ACCQD6H    376
+#define DMP_ACCQD6L    378
+#define DMP_ACCQD7H    380
+#define DMP_ACCQD7L    382
+#define DMP_ACCQD0H    384
+#define DMP_ACCQD0L    386
+#define DMP_ACCQD1H    388
+#define DMP_ACCQD1L    390
+#define DMP_ACCQD2H    392
+#define DMP_ACCQD2L    394
+#define DMP_ACCQD3H    396
+#define DMP_ACCQD3L    398
+#define DMP_XN2H    400
+#define DMP_XN2L    402
+#define DMP_XN1H    404
+#define DMP_XN1L    406
+#define DMP_YN2H    408
+#define DMP_YN2L    410
+#define DMP_YN1H    412
+#define DMP_YN1L    414
+#define DMP_YH    416
+#define DMP_YL    418
+#define DMP_B0H    420
+#define DMP_B0L    422
+#define DMP_A1H    424
+#define DMP_A1L    426
+#define DMP_A2H    428
+#define DMP_A2L    430
+#define DMP_SEM1    432
+#define DMP_FIFOCNT    434
+#define DMP_SH_TH_X    436
+#define DMP_PACKET    438
+#define DMP_SH_TH_Y    440
+#define DMP_FOOTER    442
+#define DMP_SH_TH_Z    444
+#define DMP_TEMP29    448
+#define DMP_TEMP30    450
+#define DMP_XACCB_PRE    452
+#define DMP_XACCB_PREL    454
+#define DMP_YACCB_PRE    456
+#define DMP_YACCB_PREL    458
+#define DMP_ZACCB_PRE    460
+#define DMP_ZACCB_PREL    462
+#define DMP_TMP22    464
+#define DMP_TAP_TIMER    466
+#define DMP_TAP_THX    468
+#define DMP_TAP_THY    472
+#define DMP_TAP_THZ    476
+#define DMP_TAPW_MIN    478
+#define DMP_TMP25    480
+#define DMP_TMP26    482
+#define DMP_TMP27    484
+#define DMP_TMP28    486
+#define DMP_ORIENT    488
+#define DMP_THRSH    490
+#define DMP_ENDIANH    492
+#define DMP_ENDIANL    494
+#define DMP_BLPFNMTCH    496
+#define DMP_BLPFNMTCL    498
+#define DMP_BLPFNMXH    500
+#define DMP_BLPFNMXL    502
+#define DMP_BLPFNMYH    504
+#define DMP_BLPFNMYL    506
+#define DMP_BLPFNMZH    508
+#define DMP_BLPFNMZL    510
+#ifdef __cplusplus
+}
+#endif
+#endif // DMPMAP_H
diff --git a/libraries/MotionDriver/inv_mpu.cpp b/libraries/MotionDriver/inv_mpu.cpp
new file mode 100644
index 0000000..17cf031
--- /dev/null
+++ b/libraries/MotionDriver/inv_mpu.cpp
@@ -0,0 +1,2733 @@
+/*
+ $License:
+    Copyright (C) 2011-2012 InvenSense Corporation, All Rights Reserved.
+    See included License.txt for License information.
+ $
+ */
+/**
+ *  @addtogroup  DRIVERS Sensor Driver Layer
+ *  @brief       Hardware drivers to communicate with sensors via I2C.
+ *
+ *  @{
+ *      @file       inv_mpu.c
+ *      @brief      An I2C-based driver for Invensense gyroscopes.
+ *      @details    This driver currently works for the following devices:
+ *                  MPU6050
+ *                  MPU6500
+ *                  MPU9150 (or MPU6050 w/ AK8975 on the auxiliary bus)
+ *                  MPU9250 (or MPU6500 w/ AK8963 on the auxiliary bus)
+ */
+#include 
+#include 
+#include 
+#include 
+#include 
+#include "inv_mpu.h"
+
+/* The following functions must be defined for this platform:
+ * i2c_write(unsigned char slave_addr, unsigned char reg_addr,
+ *      unsigned char length, unsigned char const *data)
+ * i2c_read(unsigned char slave_addr, unsigned char reg_addr,
+ *      unsigned char length, unsigned char *data)
+ * delay_ms(unsigned long num_ms)
+ * get_ms(unsigned long *count)
+ * reg_int_cb(void (*cb)(void), unsigned char port, unsigned char pin)
+ * labs(long x)
+ * fabsf(float x)
+ * min(int a, int b)
+ */
+
+#define i2c_write   !I2Cdev::writeBytes
+#define i2c_read    !I2Cdev::readBytes
+#define delay_ms    delay
+
+static inline int reg_int_cb(struct int_param_s *int_param)
+{
+}
+#define min(a,b) ((a> 3 & 0x03 */
+    unsigned char gyro_fsr;
+    /* Matches accel_cfg >> 3 & 0x03 */
+    unsigned char accel_fsr;
+    /* Enabled sensors. Uses same masks as fifo_en, NOT pwr_mgmt_2. */
+    unsigned char sensors;
+    /* Matches config register. */
+    unsigned char lpf;
+    unsigned char clk_src;
+    /* Sample rate, NOT rate divider. */
+    unsigned short sample_rate;
+    /* Matches fifo_en register. */
+    unsigned char fifo_enable;
+    /* Matches int enable register. */
+    unsigned char int_enable;
+    /* 1 if devices on auxiliary I2C bus appear on the primary. */
+    unsigned char bypass_mode;
+    /* 1 if half-sensitivity.
+     * NOTE: This doesn't belong here, but everything else in hw_s is const,
+     * and this allows us to save some precious RAM.
+     */
+    unsigned char accel_half;
+    /* 1 if device in low-power accel-only mode. */
+    unsigned char lp_accel_mode;
+    /* 1 if interrupts are only triggered on motion events. */
+    unsigned char int_motion_only;
+    struct motion_int_cache_s cache;
+    /* 1 for active low interrupts. */
+    unsigned char active_low_int;
+    /* 1 for latched interrupts. */
+    unsigned char latched_int;
+    /* 1 if DMP is enabled. */
+    unsigned char dmp_on;
+    /* Ensures that DMP will only be loaded once. */
+    unsigned char dmp_loaded;
+    /* Sampling rate used when DMP is enabled. */
+    unsigned short dmp_sample_rate;
+#ifdef AK89xx_SECONDARY
+    /* Compass sample rate. */
+    unsigned short compass_sample_rate;
+    unsigned char compass_addr;
+    short mag_sens_adj[3];
+#endif
+};
+
+/* Information for self-test-> */
+struct test_s {
+    unsigned long gyro_sens;
+    unsigned long accel_sens;
+    unsigned char reg_rate_div;
+    unsigned char reg_lpf;
+    unsigned char reg_gyro_fsr;
+    unsigned char reg_accel_fsr;
+    unsigned short wait_ms;
+    unsigned char packet_thresh;
+    float min_dps;
+    float max_dps;
+    float max_gyro_var;
+    float min_g;
+    float max_g;
+    float max_accel_var;
+};
+
+/* Gyro driver state variables. */
+struct gyro_state_s {
+    const struct gyro_reg_s *reg;
+    const struct hw_s *hw;
+    struct chip_cfg_s chip_cfg;
+    const struct test_s *test;
+};
+
+/* Filter configurations. */
+enum lpf_e {
+    INV_FILTER_256HZ_NOLPF2 = 0,
+    INV_FILTER_188HZ,
+    INV_FILTER_98HZ,
+    INV_FILTER_42HZ,
+    INV_FILTER_20HZ,
+    INV_FILTER_10HZ,
+    INV_FILTER_5HZ,
+    INV_FILTER_2100HZ_NOLPF,
+    NUM_FILTER
+};
+
+/* Full scale ranges. */
+enum gyro_fsr_e {
+    INV_FSR_250DPS = 0,
+    INV_FSR_500DPS,
+    INV_FSR_1000DPS,
+    INV_FSR_2000DPS,
+    NUM_GYRO_FSR
+};
+
+/* Full scale ranges. */
+enum accel_fsr_e {
+    INV_FSR_2G = 0,
+    INV_FSR_4G,
+    INV_FSR_8G,
+    INV_FSR_16G,
+    NUM_ACCEL_FSR
+};
+
+/* Clock sources. */
+enum clock_sel_e {
+    INV_CLK_INTERNAL = 0,
+    INV_CLK_PLL,
+    NUM_CLK
+};
+
+/* Low-power accel wakeup rates. */
+enum lp_accel_rate_e {
+#if defined MPU6050
+    INV_LPA_1_25HZ,
+    INV_LPA_5HZ,
+    INV_LPA_20HZ,
+    INV_LPA_40HZ
+#elif defined MPU6500
+    INV_LPA_0_3125HZ,
+    INV_LPA_0_625HZ,
+    INV_LPA_1_25HZ,
+    INV_LPA_2_5HZ,
+    INV_LPA_5HZ,
+    INV_LPA_10HZ,
+    INV_LPA_20HZ,
+    INV_LPA_40HZ,
+    INV_LPA_80HZ,
+    INV_LPA_160HZ,
+    INV_LPA_320HZ,
+    INV_LPA_640HZ
+#endif
+};
+
+#define BIT_I2C_MST_VDDIO   (0x80)
+#define BIT_FIFO_EN         (0x40)
+#define BIT_DMP_EN          (0x80)
+#define BIT_FIFO_RST        (0x04)
+#define BIT_DMP_RST         (0x08)
+#define BIT_FIFO_OVERFLOW   (0x10)
+#define BIT_DATA_RDY_EN     (0x01)
+#define BIT_DMP_INT_EN      (0x02)
+#define BIT_MOT_INT_EN      (0x40)
+#define BITS_FSR            (0x18)
+#define BITS_LPF            (0x07)
+#define BITS_HPF            (0x07)
+#define BITS_CLK            (0x07)
+#define BIT_FIFO_SIZE_1024  (0x40)
+#define BIT_FIFO_SIZE_2048  (0x80)
+#define BIT_FIFO_SIZE_4096  (0xC0)
+#define BIT_RESET           (0x80)
+#define BIT_SLEEP           (0x40)
+#define BIT_S0_DELAY_EN     (0x01)
+#define BIT_S2_DELAY_EN     (0x04)
+#define BITS_SLAVE_LENGTH   (0x0F)
+#define BIT_SLAVE_BYTE_SW   (0x40)
+#define BIT_SLAVE_GROUP     (0x10)
+#define BIT_SLAVE_EN        (0x80)
+#define BIT_I2C_READ        (0x80)
+#define BITS_I2C_MASTER_DLY (0x1F)
+#define BIT_AUX_IF_EN       (0x20)
+#define BIT_ACTL            (0x80)
+#define BIT_LATCH_EN        (0x20)
+#define BIT_ANY_RD_CLR      (0x10)
+#define BIT_BYPASS_EN       (0x02)
+#define BITS_WOM_EN         (0xC0)
+#define BIT_LPA_CYCLE       (0x20)
+#define BIT_STBY_XA         (0x20)
+#define BIT_STBY_YA         (0x10)
+#define BIT_STBY_ZA         (0x08)
+#define BIT_STBY_XG         (0x04)
+#define BIT_STBY_YG         (0x02)
+#define BIT_STBY_ZG         (0x01)
+#define BIT_STBY_XYZA       (BIT_STBY_XA | BIT_STBY_YA | BIT_STBY_ZA)
+#define BIT_STBY_XYZG       (BIT_STBY_XG | BIT_STBY_YG | BIT_STBY_ZG)
+
+#if defined AK8975_SECONDARY
+#define SUPPORTS_AK89xx_HIGH_SENS   (0x00)
+#define AK89xx_FSR                  (9830)
+#elif defined AK8963_SECONDARY
+#define SUPPORTS_AK89xx_HIGH_SENS   (0x10)
+#define AK89xx_FSR                  (4915)
+#endif
+
+#ifdef AK89xx_SECONDARY
+#define AKM_REG_WHOAMI      (0x00)
+
+#define AKM_REG_ST1         (0x02)
+#define AKM_REG_HXL         (0x03)
+#define AKM_REG_ST2         (0x09)
+
+#define AKM_REG_CNTL        (0x0A)
+#define AKM_REG_ASTC        (0x0C)
+#define AKM_REG_ASAX        (0x10)
+#define AKM_REG_ASAY        (0x11)
+#define AKM_REG_ASAZ        (0x12)
+
+#define AKM_DATA_READY      (0x01)
+#define AKM_DATA_OVERRUN    (0x02)
+#define AKM_OVERFLOW        (0x80)
+#define AKM_DATA_ERROR      (0x40)
+
+#define AKM_BIT_SELF_TEST   (0x40)
+
+#define AKM_POWER_DOWN          (0x00 | SUPPORTS_AK89xx_HIGH_SENS)
+#define AKM_SINGLE_MEASUREMENT  (0x01 | SUPPORTS_AK89xx_HIGH_SENS)
+#define AKM_FUSE_ROM_ACCESS     (0x0F | SUPPORTS_AK89xx_HIGH_SENS)
+#define AKM_MODE_SELF_TEST      (0x08 | SUPPORTS_AK89xx_HIGH_SENS)
+
+#define AKM_WHOAMI      (0x48)
+#endif
+
+struct gyro_reg_s regArray[MPU_MAX_DEVICES];
+struct hw_s hwArray[MPU_MAX_DEVICES];
+struct test_s testArray[MPU_MAX_DEVICES];
+struct gyro_state_s gyroArray[MPU_MAX_DEVICES];
+
+//  These variables are set by the mpu_delect_device function
+
+struct gyro_reg_s *reg;
+struct hw_s *hw;
+struct test_s *test;
+struct gyro_state_s *st;
+static int deviceIndex = 0;
+
+int mpu_select_device(int device)
+{
+  if ((device < 0) || (device >= MPU_MAX_DEVICES))
+    return -1;
+
+  deviceIndex = device;
+  reg = regArray + device;
+  hw = hwArray + device;
+  test = testArray + device;
+  st = gyroArray + device;
+  return 0;
+}
+
+void mpu_init_structures()
+{
+    reg->who_am_i         = 0x75;
+    reg->rate_div         = 0x19;
+    reg->lpf              = 0x1A;
+    reg->prod_id          = 0x0C;
+    reg->user_ctrl        = 0x6A;
+    reg->fifo_en          = 0x23;
+    reg->gyro_cfg         = 0x1B;
+    reg->accel_cfg        = 0x1C;
+    reg->motion_thr       = 0x1F;
+    reg->motion_dur       = 0x20;
+    reg->fifo_count_h     = 0x72;
+    reg->fifo_r_w         = 0x74;
+    reg->raw_gyro         = 0x43;
+    reg->raw_accel        = 0x3B;
+    reg->temp             = 0x41;
+    reg->int_enable       = 0x38;
+    reg->dmp_int_status   = 0x39;
+    reg->int_status       = 0x3A;
+    reg->pwr_mgmt_1       = 0x6B;
+    reg->pwr_mgmt_2       = 0x6C;
+    reg->int_pin_cfg      = 0x37;
+    reg->mem_r_w          = 0x6F;
+    reg->accel_offs       = 0x06;
+    reg->i2c_mst          = 0x24;
+    reg->bank_sel         = 0x6D;
+    reg->mem_start_addr   = 0x6E;
+    reg->prgm_start_h     = 0x70;
+#ifdef AK89xx_SECONDARY
+    reg->raw_compass      = 0x49;
+    reg->yg_offs_tc       = 0x01;
+    reg->s0_addr          = 0x25;
+    reg->s0_reg           = 0x26;
+    reg->s0_ctrl          = 0x27;
+    reg->s1_addr          = 0x28;
+    reg->s1_reg           = 0x29;
+    reg->s1_ctrl          = 0x2A;
+    reg->s4_ctrl          = 0x34;
+    reg->s0_do            = 0x63;
+    reg->s1_do            = 0x64;
+    reg->i2c_delay_ctrl   = 0x67;
+#endif
+    switch (deviceIndex) {
+      case 0:
+        hw->addr = 0x68;
+        break;
+
+      case 1:
+        hw->addr = 0x69;
+        break;
+    }
+    hw->max_fifo          = 1024;
+    hw->num_reg           = 118;
+    hw->temp_sens         = 340;
+    hw->temp_offset       = -521;
+    hw->bank_size         = 256;
+#if defined AK89xx_SECONDARY
+    hw->compass_fsr      = AK89xx_FSR;
+#endif
+
+    test->gyro_sens      = 32768/250;
+    test->accel_sens     = 32768/16;
+    test->reg_rate_div   = 0;    /* 1kHz. */
+    test->reg_lpf        = 1;    /* 188Hz. */
+    test->reg_gyro_fsr   = 0;    /* 250dps. */
+    test->reg_accel_fsr  = 0x18; /* 16g. */
+    test->wait_ms        = 50;
+    test->packet_thresh  = 5;    /* 5% */
+    test->min_dps        = 10.f;
+    test->max_dps        = 105.f;
+    test->max_gyro_var   = 0.14f;
+    test->min_g          = 0.3f;
+    test->max_g          = 0.95f;
+    test->max_accel_var  = 0.14f;
+
+    st->reg = reg;
+    st->hw = hw;
+    st->test = test;
+};
+
+#define MAX_PACKET_LENGTH (12)
+
+#ifdef AK89xx_SECONDARY
+static int setup_compass(void);
+#define MAX_COMPASS_SAMPLE_RATE (100)
+#endif
+
+/**
+ *  @brief      Enable/disable data ready interrupt.
+ *  If the DMP is on, the DMP interrupt is enabled. Otherwise, the data ready
+ *  interrupt is used.
+ *  @param[in]  enable      1 to enable interrupt.
+ *  @return     0 if successful.
+ */
+static int set_int_enable(unsigned char enable)
+{
+    unsigned char tmp;
+
+    if (st->chip_cfg.dmp_on) {
+        if (enable)
+            tmp = BIT_DMP_INT_EN;
+        else
+            tmp = 0x00;
+        if (i2c_write(st->hw->addr, st->reg->int_enable, 1, &tmp))
+            return -1;
+        st->chip_cfg.int_enable = tmp;
+    } else {
+        if (!st->chip_cfg.sensors)
+            return -1;
+        if (enable && st->chip_cfg.int_enable)
+            return 0;
+        if (enable)
+            tmp = BIT_DATA_RDY_EN;
+        else
+            tmp = 0x00;
+        if (i2c_write(st->hw->addr, st->reg->int_enable, 1, &tmp))
+            return -1;
+        st->chip_cfg.int_enable = tmp;
+    }
+    return 0;
+}
+
+/**
+ *  @brief      Register dump for testing.
+ *  @return     0 if successful.
+ */
+int mpu_reg_dump(void)
+{
+    unsigned char ii;
+    unsigned char data;
+
+    for (ii = 0; ii < st->hw->num_reg; ii++) {
+        if (ii == st->reg->fifo_r_w || ii == st->reg->mem_r_w)
+            continue;
+        if (i2c_read(st->hw->addr, ii, 1, &data))
+            return -1;
+//      log_i("%#5x: %#5x\r\n", ii, data);
+    }
+    return 0;
+}
+
+/**
+ *  @brief      Read from a single register.
+ *  NOTE: The memory and FIFO read/write registers cannot be accessed.
+ *  @param[in]  reg     Register address.
+ *  @param[out] data    Register data.
+ *  @return     0 if successful.
+ */
+int mpu_read_reg(unsigned char reg, unsigned char *data)
+{
+    if (reg == st->reg->fifo_r_w || reg == st->reg->mem_r_w)
+        return -1;
+    if (reg >= st->hw->num_reg)
+        return -1;
+    return i2c_read(st->hw->addr, reg, 1, data);
+}
+
+/**
+ *  @brief      Initialize hardware.
+ *  Initial configuration:\n
+ *  Gyro FSR: +/- 2000DPS\n
+ *  Accel FSR +/- 2G\n
+ *  DLPF: 42Hz\n
+ *  FIFO rate: 50Hz\n
+ *  Clock source: Gyro PLL\n
+ *  FIFO: Disabled.\n
+ *  Data ready interrupt: Disabled, active low, unlatched.
+ *  @param[in]  int_param   Platform-specific parameters to interrupt API.
+ *  @return     0 if successful.
+ */
+int mpu_init(struct int_param_s *int_param)
+{
+    unsigned char data[6], rev;
+    int errCode;
+    
+    /* Reset device. */
+    data[0] = BIT_RESET;
+    if (i2c_write(st->hw->addr, st->reg->pwr_mgmt_1, 1, data))
+        return -1;
+    delay_ms(100);
+
+    /* Wake up chip. */
+    data[0] = 0x00;
+    if (i2c_write(st->hw->addr, st->reg->pwr_mgmt_1, 1, data))
+        return -2;
+
+#if defined MPU6050
+    /* Check product revision. */
+    if (i2c_read(st->hw->addr, st->reg->accel_offs, 6, data))
+        return -3;
+    rev = ((data[5] & 0x01) << 2) | ((data[3] & 0x01) << 1) |
+        (data[1] & 0x01);
+
+    if (rev) {
+        /* Congrats, these parts are better. */
+        if (rev == 1)
+            st->chip_cfg.accel_half = 1;
+        else if (rev == 2)
+            st->chip_cfg.accel_half = 0;
+        else {
+#ifdef MPU_DEBUG
+            Serial.print("Unsupported software product rev: "); Serial.println(rev);
+#endif
+            return -4;
+        }
+    } else {
+        if (i2c_read(st->hw->addr, st->reg->prod_id, 1, data))
+            return -5;
+        rev = data[0] & 0x0F;
+        if (!rev) {
+#ifdef MPU_DEBUG
+            Serial.println("Product ID read as 0 indicates device is either incompatible or an MPU3050");
+#endif
+            return -6;
+        } else if (rev == 4) {
+#ifdef MPU_DEBUG
+            Serial.println("Half sensitivity part found.");
+#endif
+            st->chip_cfg.accel_half = 1;
+        } else
+            st->chip_cfg.accel_half = 0;
+    }
+#elif defined MPU6500
+#define MPU6500_MEM_REV_ADDR    (0x17)
+    if (mpu_read_mem(MPU6500_MEM_REV_ADDR, 1, &rev))
+        return -7;
+    if (rev == 0x1)
+        st->chip_cfg.accel_half = 0;
+    else {
+#ifdef MPU_DEBUG
+        Serial.print("Unsupported software product rev: "); Serial.println(rev);
+#endif
+        return -7;
+    }
+
+    /* MPU6500 shares 4kB of memory between the DMP and the FIFO. Since the
+     * first 3kB are needed by the DMP, we'll use the last 1kB for the FIFO.
+     */
+    data[0] = BIT_FIFO_SIZE_1024 | 0x8;
+    if (i2c_write(st->hw->addr, st->reg->accel_cfg2, 1, data))
+        return -1;
+#endif
+
+    /* Set to invalid values to ensure no I2C writes are skipped. */
+    st->chip_cfg.sensors = 0xFF;
+    st->chip_cfg.gyro_fsr = 0xFF;
+    st->chip_cfg.accel_fsr = 0xFF;
+    st->chip_cfg.lpf = 0xFF;
+    st->chip_cfg.sample_rate = 0xFFFF;
+    st->chip_cfg.fifo_enable = 0xFF;
+    st->chip_cfg.bypass_mode = 0xFF;
+#ifdef AK89xx_SECONDARY
+    st->chip_cfg.compass_sample_rate = 0xFFFF;
+#endif
+    /* mpu_set_sensors always preserves this setting. */
+    st->chip_cfg.clk_src = INV_CLK_PLL;
+    /* Handled in next call to mpu_set_bypass. */
+    st->chip_cfg.active_low_int = 1;
+    st->chip_cfg.latched_int = 0;
+    st->chip_cfg.int_motion_only = 0;
+    st->chip_cfg.lp_accel_mode = 0;
+    memset(&st->chip_cfg.cache, 0, sizeof(st->chip_cfg.cache));
+    st->chip_cfg.dmp_on = 0;
+    st->chip_cfg.dmp_loaded = 0;
+    st->chip_cfg.dmp_sample_rate = 0;
+
+    if (mpu_set_gyro_fsr(2000))
+        return -1;
+    if (mpu_set_accel_fsr(2))
+        return -1;
+    if (mpu_set_lpf(42))
+        return -1;
+    if (mpu_set_sample_rate(50))
+        return -1;
+    if (mpu_configure_fifo(0))
+        return -1;
+
+    if (int_param)
+        reg_int_cb(int_param);
+
+#ifdef AK89xx_SECONDARY
+#ifdef MPU_DEBUG
+    Serial.println("Setting up compass");
+#endif
+    errCode = setup_compass();
+    if (errCode != 0) {
+#ifdef MPU_DEBUG
+       Serial.print("Setup compass failed: "); Serial.println(errCode); 
+#endif
+    }
+    if (mpu_set_compass_sample_rate(10))
+        return -1;
+#else
+    /* Already disabled by setup_compass. */
+    if (mpu_set_bypass(0))
+        return -1;
+#endif
+
+    mpu_set_sensors(0);
+    return 0;
+}
+
+/**
+ *  @brief      Enter low-power accel-only mode.
+ *  In low-power accel mode, the chip goes to sleep and only wakes up to sample
+ *  the accelerometer at one of the following frequencies:
+ *  \n MPU6050: 1.25Hz, 5Hz, 20Hz, 40Hz
+ *  \n MPU6500: 1.25Hz, 2.5Hz, 5Hz, 10Hz, 20Hz, 40Hz, 80Hz, 160Hz, 320Hz, 640Hz
+ *  \n If the requested rate is not one listed above, the device will be set to
+ *  the next highest rate. Requesting a rate above the maximum supported
+ *  frequency will result in an error.
+ *  \n To select a fractional wake-up frequency, round down the value passed to
+ *  @e rate.
+ *  @param[in]  rate        Minimum sampling rate, or zero to disable LP
+ *                          accel mode.
+ *  @return     0 if successful.
+ */
+int mpu_lp_accel_mode(unsigned char rate)
+{
+    unsigned char tmp[2];
+
+    if (rate > 40)
+        return -1;
+
+    if (!rate) {
+        mpu_set_int_latched(0);
+        tmp[0] = 0;
+        tmp[1] = BIT_STBY_XYZG;
+        if (i2c_write(st->hw->addr, st->reg->pwr_mgmt_1, 2, tmp))
+            return -1;
+        st->chip_cfg.lp_accel_mode = 0;
+        return 0;
+    }
+    /* For LP accel, we automatically configure the hardware to produce latched
+     * interrupts. In LP accel mode, the hardware cycles into sleep mode before
+     * it gets a chance to deassert the interrupt pin; therefore, we shift this
+     * responsibility over to the MCU.
+     *
+     * Any register read will clear the interrupt.
+     */
+    mpu_set_int_latched(1);
+#if defined MPU6050
+    tmp[0] = BIT_LPA_CYCLE;
+    if (rate == 1) {
+        tmp[1] = INV_LPA_1_25HZ;
+        mpu_set_lpf(5);
+    } else if (rate <= 5) {
+        tmp[1] = INV_LPA_5HZ;
+        mpu_set_lpf(5);
+    } else if (rate <= 20) {
+        tmp[1] = INV_LPA_20HZ;
+        mpu_set_lpf(10);
+    } else {
+        tmp[1] = INV_LPA_40HZ;
+        mpu_set_lpf(20);
+    }
+    tmp[1] = (tmp[1] << 6) | BIT_STBY_XYZG;
+    if (i2c_write(st->hw->addr, st->reg->pwr_mgmt_1, 2, tmp))
+        return -1;
+#elif defined MPU6500
+    /* Set wake frequency. */
+    if (rate == 1)
+        tmp[0] = INV_LPA_1_25HZ;
+    else if (rate == 2)
+        tmp[0] = INV_LPA_2_5HZ;
+    else if (rate <= 5)
+        tmp[0] = INV_LPA_5HZ;
+    else if (rate <= 10)
+        tmp[0] = INV_LPA_10HZ;
+    else if (rate <= 20)
+        tmp[0] = INV_LPA_20HZ;
+    else if (rate <= 40)
+        tmp[0] = INV_LPA_40HZ;
+    else if (rate <= 80)
+        tmp[0] = INV_LPA_80HZ;
+    else if (rate <= 160)
+        tmp[0] = INV_LPA_160HZ;
+    else if (rate <= 320)
+        tmp[0] = INV_LPA_320HZ;
+    else
+        tmp[0] = INV_LPA_640HZ;
+    if (i2c_write(st->hw->addr, st->reg->lp_accel_odr, 1, tmp))
+        return -1;
+    tmp[0] = BIT_LPA_CYCLE;
+    if (i2c_write(st->hw->addr, st->reg->pwr_mgmt_1, 1, tmp))
+        return -1;
+#endif
+    st->chip_cfg.sensors = INV_XYZ_ACCEL;
+    st->chip_cfg.clk_src = 0;
+    st->chip_cfg.lp_accel_mode = 1;
+    mpu_configure_fifo(0);
+
+    return 0;
+}
+
+/**
+ *  @brief      Read raw gyro data directly from the registers.
+ *  @param[out] data        Raw data in hardware units.
+ *  @param[out] timestamp   Timestamp in milliseconds. Null if not needed.
+ *  @return     0 if successful.
+ */
+int mpu_get_gyro_reg(short *data, unsigned long *timestamp)
+{
+    unsigned char tmp[6];
+
+    if (!(st->chip_cfg.sensors & INV_XYZ_GYRO))
+        return -1;
+
+    if (i2c_read(st->hw->addr, st->reg->raw_gyro, 6, tmp))
+        return -1;
+    data[0] = (tmp[0] << 8) | tmp[1];
+    data[1] = (tmp[2] << 8) | tmp[3];
+    data[2] = (tmp[4] << 8) | tmp[5];
+    if (timestamp)
+        get_ms(timestamp);
+    return 0;
+}
+
+/**
+ *  @brief      Read raw accel data directly from the registers.
+ *  @param[out] data        Raw data in hardware units.
+ *  @param[out] timestamp   Timestamp in milliseconds. Null if not needed.
+ *  @return     0 if successful.
+ */
+int mpu_get_accel_reg(short *data, unsigned long *timestamp)
+{
+    unsigned char tmp[6];
+
+    if (!(st->chip_cfg.sensors & INV_XYZ_ACCEL))
+        return -1;
+
+    if (i2c_read(st->hw->addr, st->reg->raw_accel, 6, tmp))
+        return -1;
+    data[0] = (tmp[0] << 8) | tmp[1];
+    data[1] = (tmp[2] << 8) | tmp[3];
+    data[2] = (tmp[4] << 8) | tmp[5];
+    if (timestamp)
+        get_ms(timestamp);
+    return 0;
+}
+
+/**
+ *  @brief      Read temperature data directly from the registers.
+ *  @param[out] data        Data in q16 format.
+ *  @param[out] timestamp   Timestamp in milliseconds. Null if not needed.
+ *  @return     0 if successful.
+ */
+int mpu_get_temperature(long *data, unsigned long *timestamp)
+{
+    unsigned char tmp[2];
+    short raw;
+
+    if (!(st->chip_cfg.sensors))
+        return -1;
+
+    if (i2c_read(st->hw->addr, st->reg->temp, 2, tmp))
+        return -1;
+    raw = (tmp[0] << 8) | tmp[1];
+    if (timestamp)
+        get_ms(timestamp);
+
+    data[0] = (long)((35 + ((raw - (float)st->hw->temp_offset) / st->hw->temp_sens)) * 65536L);
+    return 0;
+}
+
+/**
+ *  @brief      Push biases to the accel bias registers.
+ *  This function expects biases relative to the current sensor output, and
+ *  these biases will be added to the factory-supplied values.
+ *  @param[in]  accel_bias  New biases.
+ *  @return     0 if successful.
+ */
+int mpu_set_accel_bias(const long *accel_bias)
+{
+    unsigned char data[6];
+    short accel_hw[3];
+    short got_accel[3];
+    short fg[3];
+
+    if (!accel_bias)
+        return -1;
+    if (!accel_bias[0] && !accel_bias[1] && !accel_bias[2])
+        return 0;
+
+    if (i2c_read(st->hw->addr, 3, 3, data))
+        return -1;
+    fg[0] = ((data[0] >> 4) + 8) & 0xf;
+    fg[1] = ((data[1] >> 4) + 8) & 0xf;
+    fg[2] = ((data[2] >> 4) + 8) & 0xf;
+
+    accel_hw[0] = (short)(accel_bias[0] * 2 / (64 + fg[0]));
+    accel_hw[1] = (short)(accel_bias[1] * 2 / (64 + fg[1]));
+    accel_hw[2] = (short)(accel_bias[2] * 2 / (64 + fg[2]));
+
+    if (i2c_read(st->hw->addr, 0x06, 6, data))
+        return -1;
+
+    got_accel[0] = ((short)data[0] << 8) | data[1];
+    got_accel[1] = ((short)data[2] << 8) | data[3];
+    got_accel[2] = ((short)data[4] << 8) | data[5];
+
+    accel_hw[0] += got_accel[0];
+    accel_hw[1] += got_accel[1];
+    accel_hw[2] += got_accel[2];
+
+    data[0] = (accel_hw[0] >> 8) & 0xff;
+    data[1] = (accel_hw[0]) & 0xff;
+    data[2] = (accel_hw[1] >> 8) & 0xff;
+    data[3] = (accel_hw[1]) & 0xff;
+    data[4] = (accel_hw[2] >> 8) & 0xff;
+    data[5] = (accel_hw[2]) & 0xff;
+
+    if (i2c_write(st->hw->addr, 0x06, 6, data))
+        return -1;
+    return 0;
+}
+
+/**
+ *  @brief  Reset FIFO read/write pointers.
+ *  @return 0 if successful.
+ */
+int mpu_reset_fifo(void)
+{
+    unsigned char data;
+
+    if (!(st->chip_cfg.sensors))
+        return -1;
+
+    data = 0;
+    if (i2c_write(st->hw->addr, st->reg->int_enable, 1, &data))
+        return -1;
+    if (i2c_write(st->hw->addr, st->reg->fifo_en, 1, &data))
+        return -1;
+    if (i2c_write(st->hw->addr, st->reg->user_ctrl, 1, &data))
+        return -1;
+
+    if (st->chip_cfg.dmp_on) {
+        data = BIT_FIFO_RST | BIT_DMP_RST;
+        if (i2c_write(st->hw->addr, st->reg->user_ctrl, 1, &data))
+            return -1;
+        delay_ms(50);
+        data = BIT_DMP_EN | BIT_FIFO_EN;
+        if (st->chip_cfg.sensors & INV_XYZ_COMPASS)
+            data |= BIT_AUX_IF_EN;
+        if (i2c_write(st->hw->addr, st->reg->user_ctrl, 1, &data))
+            return -1;
+        if (st->chip_cfg.int_enable)
+            data = BIT_DMP_INT_EN;
+        else
+            data = 0;
+        if (i2c_write(st->hw->addr, st->reg->int_enable, 1, &data))
+            return -1;
+        data = 0;
+        if (i2c_write(st->hw->addr, st->reg->fifo_en, 1, &data))
+            return -1;
+    } else {
+        data = BIT_FIFO_RST;
+        if (i2c_write(st->hw->addr, st->reg->user_ctrl, 1, &data))
+            return -1;
+        if (st->chip_cfg.bypass_mode || !(st->chip_cfg.sensors & INV_XYZ_COMPASS))
+            data = BIT_FIFO_EN;
+        else
+            data = BIT_FIFO_EN | BIT_AUX_IF_EN;
+        if (i2c_write(st->hw->addr, st->reg->user_ctrl, 1, &data))
+            return -1;
+        delay_ms(50);
+        if (st->chip_cfg.int_enable)
+            data = BIT_DATA_RDY_EN;
+        else
+            data = 0;
+        if (i2c_write(st->hw->addr, st->reg->int_enable, 1, &data))
+            return -1;
+        if (i2c_write(st->hw->addr, st->reg->fifo_en, 1, &st->chip_cfg.fifo_enable))
+            return -1;
+    }
+    return 0;
+}
+
+/**
+ *  @brief      Get the gyro full-scale range.
+ *  @param[out] fsr Current full-scale range.
+ *  @return     0 if successful.
+ */
+int mpu_get_gyro_fsr(unsigned short *fsr)
+{
+    switch (st->chip_cfg.gyro_fsr) {
+    case INV_FSR_250DPS:
+        fsr[0] = 250;
+        break;
+    case INV_FSR_500DPS:
+        fsr[0] = 500;
+        break;
+    case INV_FSR_1000DPS:
+        fsr[0] = 1000;
+        break;
+    case INV_FSR_2000DPS:
+        fsr[0] = 2000;
+        break;
+    default:
+        fsr[0] = 0;
+        break;
+    }
+    return 0;
+}
+
+/**
+ *  @brief      Set the gyro full-scale range.
+ *  @param[in]  fsr Desired full-scale range.
+ *  @return     0 if successful.
+ */
+int mpu_set_gyro_fsr(unsigned short fsr)
+{
+    unsigned char data;
+
+    if (!(st->chip_cfg.sensors))
+        return -1;
+
+    switch (fsr) {
+    case 250:
+        data = INV_FSR_250DPS << 3;
+        break;
+    case 500:
+        data = INV_FSR_500DPS << 3;
+        break;
+    case 1000:
+        data = INV_FSR_1000DPS << 3;
+        break;
+    case 2000:
+        data = INV_FSR_2000DPS << 3;
+        break;
+    default:
+        return -1;
+    }
+
+    if (st->chip_cfg.gyro_fsr == (data >> 3))
+        return 0;
+    if (i2c_write(st->hw->addr, st->reg->gyro_cfg, 1, &data))
+        return -1;
+    st->chip_cfg.gyro_fsr = data >> 3;
+    return 0;
+}
+
+/**
+ *  @brief      Get the accel full-scale range.
+ *  @param[out] fsr Current full-scale range.
+ *  @return     0 if successful.
+ */
+int mpu_get_accel_fsr(unsigned char *fsr)
+{
+    switch (st->chip_cfg.accel_fsr) {
+    case INV_FSR_2G:
+        fsr[0] = 2;
+        break;
+    case INV_FSR_4G:
+        fsr[0] = 4;
+        break;
+    case INV_FSR_8G:
+        fsr[0] = 8;
+        break;
+    case INV_FSR_16G:
+        fsr[0] = 16;
+        break;
+    default:
+        return -1;
+    }
+    if (st->chip_cfg.accel_half)
+        fsr[0] <<= 1;
+    return 0;
+}
+
+/**
+ *  @brief      Set the accel full-scale range.
+ *  @param[in]  fsr Desired full-scale range.
+ *  @return     0 if successful.
+ */
+int mpu_set_accel_fsr(unsigned char fsr)
+{
+    unsigned char data;
+
+    if (!(st->chip_cfg.sensors))
+        return -1;
+
+    switch (fsr) {
+    case 2:
+        data = INV_FSR_2G << 3;
+        break;
+    case 4:
+        data = INV_FSR_4G << 3;
+        break;
+    case 8:
+        data = INV_FSR_8G << 3;
+        break;
+    case 16:
+        data = INV_FSR_16G << 3;
+        break;
+    default:
+        return -1;
+    }
+
+    if (st->chip_cfg.accel_fsr == (data >> 3))
+        return 0;
+    if (i2c_write(st->hw->addr, st->reg->accel_cfg, 1, &data))
+        return -1;
+    st->chip_cfg.accel_fsr = data >> 3;
+    return 0;
+}
+
+/**
+ *  @brief      Get the current DLPF setting.
+ *  @param[out] lpf Current LPF setting.
+ *  0 if successful.
+ */
+int mpu_get_lpf(unsigned short *lpf)
+{
+    switch (st->chip_cfg.lpf) {
+    case INV_FILTER_188HZ:
+        lpf[0] = 188;
+        break;
+    case INV_FILTER_98HZ:
+        lpf[0] = 98;
+        break;
+    case INV_FILTER_42HZ:
+        lpf[0] = 42;
+        break;
+    case INV_FILTER_20HZ:
+        lpf[0] = 20;
+        break;
+    case INV_FILTER_10HZ:
+        lpf[0] = 10;
+        break;
+    case INV_FILTER_5HZ:
+        lpf[0] = 5;
+        break;
+    case INV_FILTER_256HZ_NOLPF2:
+    case INV_FILTER_2100HZ_NOLPF:
+    default:
+        lpf[0] = 0;
+        break;
+    }
+    return 0;
+}
+
+/**
+ *  @brief      Set digital low pass filter.
+ *  The following LPF settings are supported: 188, 98, 42, 20, 10, 5.
+ *  @param[in]  lpf Desired LPF setting.
+ *  @return     0 if successful.
+ */
+int mpu_set_lpf(unsigned short lpf)
+{
+    unsigned char data;
+    if (!(st->chip_cfg.sensors))
+        return -1;
+
+    if (lpf >= 188)
+        data = INV_FILTER_188HZ;
+    else if (lpf >= 98)
+        data = INV_FILTER_98HZ;
+    else if (lpf >= 42)
+        data = INV_FILTER_42HZ;
+    else if (lpf >= 20)
+        data = INV_FILTER_20HZ;
+    else if (lpf >= 10)
+        data = INV_FILTER_10HZ;
+    else
+        data = INV_FILTER_5HZ;
+
+    if (st->chip_cfg.lpf == data)
+        return 0;
+    if (i2c_write(st->hw->addr, st->reg->lpf, 1, &data))
+        return -1;
+    st->chip_cfg.lpf = data;
+    return 0;
+}
+
+/**
+ *  @brief      Get sampling rate.
+ *  @param[out] rate    Current sampling rate (Hz).
+ *  @return     0 if successful.
+ */
+int mpu_get_sample_rate(unsigned short *rate)
+{
+    if (st->chip_cfg.dmp_on)
+        return -1;
+    else
+        rate[0] = st->chip_cfg.sample_rate;
+    return 0;
+}
+
+/**
+ *  @brief      Set sampling rate.
+ *  Sampling rate must be between 4Hz and 1kHz.
+ *  @param[in]  rate    Desired sampling rate (Hz).
+ *  @return     0 if successful.
+ */
+int mpu_set_sample_rate(unsigned short rate)
+{
+    unsigned char data;
+
+    if (!(st->chip_cfg.sensors))
+        return -1;
+
+    if (st->chip_cfg.dmp_on)
+        return -1;
+    else {
+        if (st->chip_cfg.lp_accel_mode) {
+            if (rate && (rate <= 40)) {
+                /* Just stay in low-power accel mode. */
+                mpu_lp_accel_mode(rate);
+                return 0;
+            }
+            /* Requested rate exceeds the allowed frequencies in LP accel mode,
+             * switch back to full-power mode.
+             */
+            mpu_lp_accel_mode(0);
+        }
+        if (rate < 4)
+            rate = 4;
+        else if (rate > 1000)
+            rate = 1000;
+
+        data = 1000 / rate - 1;
+        if (i2c_write(st->hw->addr, st->reg->rate_div, 1, &data))
+            return -1;
+
+        st->chip_cfg.sample_rate = 1000 / (1 + data);
+
+#ifdef AK89xx_SECONDARY
+        mpu_set_compass_sample_rate(min(st->chip_cfg.compass_sample_rate, MAX_COMPASS_SAMPLE_RATE));
+#endif
+
+        /* Automatically set LPF to 1/2 sampling rate. */
+        mpu_set_lpf(st->chip_cfg.sample_rate >> 1);
+        return 0;
+    }
+}
+
+/**
+ *  @brief      Get compass sampling rate.
+ *  @param[out] rate    Current compass sampling rate (Hz).
+ *  @return     0 if successful.
+ */
+int mpu_get_compass_sample_rate(unsigned short *rate)
+{
+#ifdef AK89xx_SECONDARY
+    rate[0] = st->chip_cfg.compass_sample_rate;
+    return 0;
+#else
+    rate[0] = 0;
+    return -1;
+#endif
+}
+
+/**
+ *  @brief      Set compass sampling rate.
+ *  The compass on the auxiliary I2C bus is read by the MPU hardware at a
+ *  maximum of 100Hz. The actual rate can be set to a fraction of the gyro
+ *  sampling rate.
+ *
+ *  \n WARNING: The new rate may be different than what was requested. Call
+ *  mpu_get_compass_sample_rate to check the actual setting.
+ *  @param[in]  rate    Desired compass sampling rate (Hz).
+ *  @return     0 if successful.
+ */
+int mpu_set_compass_sample_rate(unsigned short rate)
+{
+#ifdef AK89xx_SECONDARY
+    unsigned char div;
+    if (!rate || rate > st->chip_cfg.sample_rate || rate > MAX_COMPASS_SAMPLE_RATE)
+        return -1;
+
+    div = st->chip_cfg.sample_rate / rate - 1;
+    if (i2c_write(st->hw->addr, st->reg->s4_ctrl, 1, &div))
+        return -1;
+    st->chip_cfg.compass_sample_rate = st->chip_cfg.sample_rate / (div + 1);
+    return 0;
+#else
+    return -1;
+#endif
+}
+
+/**
+ *  @brief      Get gyro sensitivity scale factor.
+ *  @param[out] sens    Conversion from hardware units to dps.
+ *  @return     0 if successful.
+ */
+int mpu_get_gyro_sens(float *sens)
+{
+    switch (st->chip_cfg.gyro_fsr) {
+    case INV_FSR_250DPS:
+        sens[0] = 131.f;
+        break;
+    case INV_FSR_500DPS:
+        sens[0] = 65.5f;
+        break;
+    case INV_FSR_1000DPS:
+        sens[0] = 32.8f;
+        break;
+    case INV_FSR_2000DPS:
+        sens[0] = 16.4f;
+        break;
+    default:
+        return -1;
+    }
+    return 0;
+}
+
+/**
+ *  @brief      Get accel sensitivity scale factor.
+ *  @param[out] sens    Conversion from hardware units to g's.
+ *  @return     0 if successful.
+ */
+int mpu_get_accel_sens(unsigned short *sens)
+{
+    switch (st->chip_cfg.accel_fsr) {
+    case INV_FSR_2G:
+        sens[0] = 16384;
+        break;
+    case INV_FSR_4G:
+        sens[0] = 8092;
+        break;
+    case INV_FSR_8G:
+        sens[0] = 4096;
+        break;
+    case INV_FSR_16G:
+        sens[0] = 2048;
+        break;
+    default:
+        return -1;
+    }
+    if (st->chip_cfg.accel_half)
+        sens[0] >>= 1;
+    return 0;
+}
+
+/**
+ *  @brief      Get current FIFO configuration.
+ *  @e sensors can contain a combination of the following flags:
+ *  \n INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO
+ *  \n INV_XYZ_GYRO
+ *  \n INV_XYZ_ACCEL
+ *  @param[out] sensors Mask of sensors in FIFO.
+ *  @return     0 if successful.
+ */
+int mpu_get_fifo_config(unsigned char *sensors)
+{
+    sensors[0] = st->chip_cfg.fifo_enable;
+    return 0;
+}
+
+/**
+ *  @brief      Select which sensors are pushed to FIFO.
+ *  @e sensors can contain a combination of the following flags:
+ *  \n INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO
+ *  \n INV_XYZ_GYRO
+ *  \n INV_XYZ_ACCEL
+ *  @param[in]  sensors Mask of sensors to push to FIFO.
+ *  @return     0 if successful.
+ */
+int mpu_configure_fifo(unsigned char sensors)
+{
+    unsigned char prev;
+    int result = 0;
+
+    /* Compass data isn't going into the FIFO. Stop trying. */
+    sensors &= ~INV_XYZ_COMPASS;
+
+    if (st->chip_cfg.dmp_on)
+        return 0;
+    else {
+        if (!(st->chip_cfg.sensors))
+            return -1;
+        prev = st->chip_cfg.fifo_enable;
+        st->chip_cfg.fifo_enable = sensors & st->chip_cfg.sensors;
+        if (st->chip_cfg.fifo_enable != sensors)
+            /* You're not getting what you asked for. Some sensors are
+             * asleep.
+             */
+            result = -1;
+        else
+            result = 0;
+        if (sensors || st->chip_cfg.lp_accel_mode)
+            set_int_enable(1);
+        else
+            set_int_enable(0);
+        if (sensors) {
+            if (mpu_reset_fifo()) {
+                st->chip_cfg.fifo_enable = prev;
+                return -1;
+            }
+        }
+    }
+
+    return result;
+}
+
+/**
+ *  @brief      Get current power state.
+ *  @param[in]  power_on    1 if turned on, 0 if suspended.
+ *  @return     0 if successful.
+ */
+int mpu_get_power_state(unsigned char *power_on)
+{
+    if (st->chip_cfg.sensors)
+        power_on[0] = 1;
+    else
+        power_on[0] = 0;
+    return 0;
+}
+
+/**
+ *  @brief      Turn specific sensors on/off.
+ *  @e sensors can contain a combination of the following flags:
+ *  \n INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO
+ *  \n INV_XYZ_GYRO
+ *  \n INV_XYZ_ACCEL
+ *  \n INV_XYZ_COMPASS
+ *  @param[in]  sensors    Mask of sensors to wake.
+ *  @return     0 if successful.
+ */
+int mpu_set_sensors(unsigned char sensors)
+{
+    unsigned char data;
+#ifdef AK89xx_SECONDARY
+    unsigned char user_ctrl;
+#endif
+
+    if (sensors & INV_XYZ_GYRO)
+        data = INV_CLK_PLL;
+    else if (sensors)
+        data = 0;
+    else
+        data = BIT_SLEEP;
+    if (i2c_write(st->hw->addr, st->reg->pwr_mgmt_1, 1, &data)) {
+        st->chip_cfg.sensors = 0;
+        return -1;
+    }
+    st->chip_cfg.clk_src = data & ~BIT_SLEEP;
+
+    data = 0;
+    if (!(sensors & INV_X_GYRO))
+        data |= BIT_STBY_XG;
+    if (!(sensors & INV_Y_GYRO))
+        data |= BIT_STBY_YG;
+    if (!(sensors & INV_Z_GYRO))
+        data |= BIT_STBY_ZG;
+    if (!(sensors & INV_XYZ_ACCEL))
+        data |= BIT_STBY_XYZA;
+    if (i2c_write(st->hw->addr, st->reg->pwr_mgmt_2, 1, &data)) {
+        st->chip_cfg.sensors = 0;
+        return -1;
+    }
+
+    if (sensors && (sensors != INV_XYZ_ACCEL))
+        /* Latched interrupts only used in LP accel mode. */
+        mpu_set_int_latched(0);
+
+#ifdef AK89xx_SECONDARY
+#ifdef AK89xx_BYPASS
+    if (sensors & INV_XYZ_COMPASS)
+        mpu_set_bypass(1);
+    else
+        mpu_set_bypass(0);
+#else
+    if (i2c_read(st->hw->addr, st->reg->user_ctrl, 1, &user_ctrl))
+        return -1;
+    /* Handle AKM power management. */
+    if (sensors & INV_XYZ_COMPASS) {
+        data = AKM_SINGLE_MEASUREMENT;
+        user_ctrl |= BIT_AUX_IF_EN;
+    } else {
+        data = AKM_POWER_DOWN;
+        user_ctrl &= ~BIT_AUX_IF_EN;
+    }
+    if (st->chip_cfg.dmp_on)
+        user_ctrl |= BIT_DMP_EN;
+    else
+        user_ctrl &= ~BIT_DMP_EN;
+    if (i2c_write(st->hw->addr, st->reg->s1_do, 1, &data))
+        return -1;
+    /* Enable/disable I2C master mode. */
+    if (i2c_write(st->hw->addr, st->reg->user_ctrl, 1, &user_ctrl))
+        return -1;
+#endif
+#endif
+
+    st->chip_cfg.sensors = sensors;
+    st->chip_cfg.lp_accel_mode = 0;
+    delay_ms(50);
+    return 0;
+}
+
+/**
+ *  @brief      Read the MPU interrupt status registers.
+ *  @param[out] status  Mask of interrupt bits.
+ *  @return     0 if successful.
+ */
+int mpu_get_int_status(short *status)
+{
+    unsigned char tmp[2];
+    if (!st->chip_cfg.sensors)
+        return -1;
+    if (i2c_read(st->hw->addr, st->reg->dmp_int_status, 2, tmp))
+        return -1;
+    status[0] = (tmp[0] << 8) | tmp[1];
+    return 0;
+}
+
+/**
+ *  @brief      Get one packet from the FIFO.
+ *  If @e sensors does not contain a particular sensor, disregard the data
+ *  returned to that pointer.
+ *  \n @e sensors can contain a combination of the following flags:
+ *  \n INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO
+ *  \n INV_XYZ_GYRO
+ *  \n INV_XYZ_ACCEL
+ *  \n If the FIFO has no new data, @e sensors will be zero.
+ *  \n If the FIFO is disabled, @e sensors will be zero and this function will
+ *  return a non-zero error code.
+ *  @param[out] gyro        Gyro data in hardware units.
+ *  @param[out] accel       Accel data in hardware units.
+ *  @param[out] timestamp   Timestamp in milliseconds.
+ *  @param[out] sensors     Mask of sensors read from FIFO.
+ *  @param[out] more        Number of remaining packets.
+ *  @return     0 if successful.
+ */
+int mpu_read_fifo(short *gyro, short *accel, unsigned long *timestamp,
+        unsigned char *sensors, unsigned char *more)
+{
+    /* Assumes maximum packet size is gyro (6) + accel (6). */
+    unsigned char data[MAX_PACKET_LENGTH];
+    unsigned char packet_size = 0;
+    unsigned short fifo_count, index = 0;
+
+    if (st->chip_cfg.dmp_on)
+        return -1;
+
+    sensors[0] = 0;
+    if (!st->chip_cfg.sensors)
+        return -2;
+    if (!st->chip_cfg.fifo_enable)
+        return -3;
+
+    if (st->chip_cfg.fifo_enable & INV_X_GYRO)
+        packet_size += 2;
+    if (st->chip_cfg.fifo_enable & INV_Y_GYRO)
+        packet_size += 2;
+    if (st->chip_cfg.fifo_enable & INV_Z_GYRO)
+        packet_size += 2;
+    if (st->chip_cfg.fifo_enable & INV_XYZ_ACCEL)
+        packet_size += 6;
+
+    if (i2c_read(st->hw->addr, st->reg->fifo_count_h, 2, data))
+        return -4;
+    fifo_count = (data[0] << 8) | data[1];
+    if (fifo_count < packet_size)
+        return 0;
+//    log_i("FIFO count: %hd\n", fifo_count);
+    if (fifo_count > (st->hw->max_fifo >> 1)) {
+        /* FIFO is 50% full, better check overflow bit. */
+        if (i2c_read(st->hw->addr, st->reg->int_status, 1, data))
+            return -5;
+        if (data[0] & BIT_FIFO_OVERFLOW) {
+            mpu_reset_fifo();
+            return -6;
+        }
+    }
+    get_ms((unsigned long*)timestamp);
+
+    if (i2c_read(st->hw->addr, st->reg->fifo_r_w, packet_size, data))
+        return -7;
+    more[0] = fifo_count / packet_size - 1;
+    sensors[0] = 0;
+
+    if ((index != packet_size) && st->chip_cfg.fifo_enable & INV_XYZ_ACCEL) {
+        accel[0] = (data[index+0] << 8) | data[index+1];
+        accel[1] = (data[index+2] << 8) | data[index+3];
+        accel[2] = (data[index+4] << 8) | data[index+5];
+        sensors[0] |= INV_XYZ_ACCEL;
+        index += 6;
+    }
+    if ((index != packet_size) && st->chip_cfg.fifo_enable & INV_X_GYRO) {
+        gyro[0] = (data[index+0] << 8) | data[index+1];
+        sensors[0] |= INV_X_GYRO;
+        index += 2;
+    }
+    if ((index != packet_size) && st->chip_cfg.fifo_enable & INV_Y_GYRO) {
+        gyro[1] = (data[index+0] << 8) | data[index+1];
+        sensors[0] |= INV_Y_GYRO;
+        index += 2;
+    }
+    if ((index != packet_size) && st->chip_cfg.fifo_enable & INV_Z_GYRO) {
+        gyro[2] = (data[index+0] << 8) | data[index+1];
+        sensors[0] |= INV_Z_GYRO;
+        index += 2;
+    }
+
+    return 0;
+}
+
+/**
+ *  @brief      Get one unparsed packet from the FIFO.
+ *  This function should be used if the packet is to be parsed elsewhere.
+ *  @param[in]  length  Length of one FIFO packet.
+ *  @param[in]  data    FIFO packet.
+ *  @param[in]  more    Number of remaining packets.
+ */
+int mpu_read_fifo_stream(unsigned short length, unsigned char *data,
+    unsigned char *more)
+{
+    unsigned char tmp[2];
+    unsigned short fifo_count;
+    if (!st->chip_cfg.dmp_on)
+        return -1;
+    if (!st->chip_cfg.sensors)
+        return -2;
+
+    if (i2c_read(st->hw->addr, st->reg->fifo_count_h, 2, tmp))
+        return -3;
+    fifo_count = (tmp[0] << 8) | tmp[1];
+    if (fifo_count < length) {
+        more[0] = 0;
+        return -4;
+    }
+    if (fifo_count > (st->hw->max_fifo >> 1)) {
+        /* FIFO is 50% full, better check overflow bit. */
+        if (i2c_read(st->hw->addr, st->reg->int_status, 1, tmp))
+            return -5;
+        if (tmp[0] & BIT_FIFO_OVERFLOW) {
+            mpu_reset_fifo();
+            return -6;
+        }
+    }
+
+    if (i2c_read(st->hw->addr, st->reg->fifo_r_w, length, data))
+        return -7;
+    more[0] = fifo_count / length - 1;
+    return 0;
+}
+
+/**
+ *  @brief      Set device to bypass mode.
+ *  @param[in]  bypass_on   1 to enable bypass mode.
+ *  @return     0 if successful.
+ */
+int mpu_set_bypass(unsigned char bypass_on)
+{
+    unsigned char tmp;
+
+    if (st->chip_cfg.bypass_mode == bypass_on)
+        return 0;
+
+    if (bypass_on) {
+        if (i2c_read(st->hw->addr, st->reg->user_ctrl, 1, &tmp))
+            return -1;
+        tmp &= ~BIT_AUX_IF_EN;
+        if (i2c_write(st->hw->addr, st->reg->user_ctrl, 1, &tmp))
+            return -1;
+        delay_ms(3);
+        tmp = BIT_BYPASS_EN;
+        if (st->chip_cfg.active_low_int)
+            tmp |= BIT_ACTL;
+        if (st->chip_cfg.latched_int)
+            tmp |= BIT_LATCH_EN | BIT_ANY_RD_CLR;
+        if (i2c_write(st->hw->addr, st->reg->int_pin_cfg, 1, &tmp))
+            return -1;
+    } else {
+        /* Enable I2C master mode if compass is being used. */
+        if (i2c_read(st->hw->addr, st->reg->user_ctrl, 1, &tmp))
+            return -1;
+        if (st->chip_cfg.sensors & INV_XYZ_COMPASS)
+            tmp |= BIT_AUX_IF_EN;
+        else
+            tmp &= ~BIT_AUX_IF_EN;
+        if (i2c_write(st->hw->addr, st->reg->user_ctrl, 1, &tmp))
+            return -1;
+        delay_ms(3);
+        if (st->chip_cfg.active_low_int)
+            tmp = BIT_ACTL;
+        else
+            tmp = 0;
+        if (st->chip_cfg.latched_int)
+            tmp |= BIT_LATCH_EN | BIT_ANY_RD_CLR;
+        if (i2c_write(st->hw->addr, st->reg->int_pin_cfg, 1, &tmp))
+            return -1;
+    }
+    st->chip_cfg.bypass_mode = bypass_on;
+    return 0;
+}
+
+/**
+ *  @brief      Set interrupt level.
+ *  @param[in]  active_low  1 for active low, 0 for active high.
+ *  @return     0 if successful.
+ */
+int mpu_set_int_level(unsigned char active_low)
+{
+    st->chip_cfg.active_low_int = active_low;
+    return 0;
+}
+
+/**
+ *  @brief      Enable latched interrupts.
+ *  Any MPU register will clear the interrupt.
+ *  @param[in]  enable  1 to enable, 0 to disable.
+ *  @return     0 if successful.
+ */
+int mpu_set_int_latched(unsigned char enable)
+{
+    unsigned char tmp;
+    if (st->chip_cfg.latched_int == enable)
+        return 0;
+
+    if (enable)
+        tmp = BIT_LATCH_EN | BIT_ANY_RD_CLR;
+    else
+        tmp = 0;
+    if (st->chip_cfg.bypass_mode)
+        tmp |= BIT_BYPASS_EN;
+    if (st->chip_cfg.active_low_int)
+        tmp |= BIT_ACTL;
+    if (i2c_write(st->hw->addr, st->reg->int_pin_cfg, 1, &tmp))
+        return -1;
+    st->chip_cfg.latched_int = enable;
+    return 0;
+}
+
+#ifdef MPU6050
+static int get_accel_prod_shift(float *st_shift)
+{
+    unsigned char tmp[4], shift_code[3], ii;
+
+    if (i2c_read(st->hw->addr, 0x0D, 4, tmp))
+        return 0x07;
+
+    shift_code[0] = ((tmp[0] & 0xE0) >> 3) | ((tmp[3] & 0x30) >> 4);
+    shift_code[1] = ((tmp[1] & 0xE0) >> 3) | ((tmp[3] & 0x0C) >> 2);
+    shift_code[2] = ((tmp[2] & 0xE0) >> 3) | (tmp[3] & 0x03);
+    for (ii = 0; ii < 3; ii++) {
+        if (!shift_code[ii]) {
+            st_shift[ii] = 0.f;
+            continue;
+        }
+        /* Equivalent to..
+         * st_shift[ii] = 0.34f * powf(0.92f/0.34f, (shift_code[ii]-1) / 30.f)
+         */
+        st_shift[ii] = 0.34f;
+        while (--shift_code[ii])
+            st_shift[ii] *= 1.034f;
+    }
+    return 0;
+}
+
+static int accel_self_test(long *bias_regular, long *bias_st)
+{
+    int jj, result = 0;
+    float st_shift[3], st_shift_cust, st_shift_var;
+
+    get_accel_prod_shift(st_shift);
+    for(jj = 0; jj < 3; jj++) {
+        st_shift_cust = labs(bias_regular[jj] - bias_st[jj]) / 65536.f;
+        if (st_shift[jj]) {
+            st_shift_var = st_shift_cust / st_shift[jj] - 1.f;
+            if (fabs(st_shift_var) > test->max_accel_var)
+                result |= 1 << jj;
+        } else if ((st_shift_cust < test->min_g) ||
+            (st_shift_cust > test->max_g))
+            result |= 1 << jj;
+    }
+
+    return result;
+}
+
+static int gyro_self_test(long *bias_regular, long *bias_st)
+{
+    int jj, result = 0;
+    unsigned char tmp[3];
+    float st_shift, st_shift_cust, st_shift_var;
+
+    if (i2c_read(st->hw->addr, 0x0D, 3, tmp))
+        return 0x07;
+
+    tmp[0] &= 0x1F;
+    tmp[1] &= 0x1F;
+    tmp[2] &= 0x1F;
+
+    for (jj = 0; jj < 3; jj++) {
+        st_shift_cust = labs(bias_regular[jj] - bias_st[jj]) / 65536.f;
+        if (tmp[jj]) {
+            st_shift = 3275.f / test->gyro_sens;
+            while (--tmp[jj])
+                st_shift *= 1.046f;
+            st_shift_var = st_shift_cust / st_shift - 1.f;
+            if (fabs(st_shift_var) > test->max_gyro_var)
+                result |= 1 << jj;
+        } else if ((st_shift_cust < test->min_dps) ||
+            (st_shift_cust > test->max_dps))
+            result |= 1 << jj;
+    }
+    return result;
+}
+
+#ifdef AK89xx_SECONDARY
+static int compass_self_test(void)
+{
+    unsigned char tmp[6];
+    unsigned char tries = 10;
+    int result = 0x07;
+    short data;
+
+    mpu_set_bypass(1);
+
+    tmp[0] = AKM_POWER_DOWN;
+    if (i2c_write(st->chip_cfg.compass_addr, AKM_REG_CNTL, 1, tmp))
+        return 0x07;
+    tmp[0] = AKM_BIT_SELF_TEST;
+    if (i2c_write(st->chip_cfg.compass_addr, AKM_REG_ASTC, 1, tmp))
+        goto AKM_restore;
+    tmp[0] = AKM_MODE_SELF_TEST;
+    if (i2c_write(st->chip_cfg.compass_addr, AKM_REG_CNTL, 1, tmp))
+        goto AKM_restore;
+
+    do {
+        delay_ms(10);
+        if (i2c_read(st->chip_cfg.compass_addr, AKM_REG_ST1, 1, tmp))
+            goto AKM_restore;
+        if (tmp[0] & AKM_DATA_READY)
+            break;
+    } while (tries--);
+    if (!(tmp[0] & AKM_DATA_READY))
+        goto AKM_restore;
+
+    if (i2c_read(st->chip_cfg.compass_addr, AKM_REG_HXL, 6, tmp))
+        goto AKM_restore;
+
+    result = 0;
+    data = (short)(tmp[1] << 8) | tmp[0];
+    if ((data > 100) || (data < -100))
+        result |= 0x01;
+    data = (short)(tmp[3] << 8) | tmp[2];
+    if ((data > 100) || (data < -100))
+        result |= 0x02;
+    data = (short)(tmp[5] << 8) | tmp[4];
+    if ((data > -300) || (data < -1000))
+        result |= 0x04;
+
+AKM_restore:
+    tmp[0] = 0 | SUPPORTS_AK89xx_HIGH_SENS;
+    i2c_write(st->chip_cfg.compass_addr, AKM_REG_ASTC, 1, tmp);
+    tmp[0] = SUPPORTS_AK89xx_HIGH_SENS;
+    i2c_write(st->chip_cfg.compass_addr, AKM_REG_CNTL, 1, tmp);
+    mpu_set_bypass(0);
+    return result;
+}
+#endif
+#endif
+
+static int get_st_biases(long *gyro, long *accel, unsigned char hw_test)
+{
+    unsigned char data[MAX_PACKET_LENGTH];
+    unsigned char packet_count, ii;
+    unsigned short fifo_count;
+
+    data[0] = 0x01;
+    data[1] = 0;
+    if (i2c_write(st->hw->addr, st->reg->pwr_mgmt_1, 2, data))
+        return -1;
+    delay_ms(200);
+    data[0] = 0;
+    if (i2c_write(st->hw->addr, st->reg->int_enable, 1, data))
+        return -1;
+    if (i2c_write(st->hw->addr, st->reg->fifo_en, 1, data))
+        return -1;
+    if (i2c_write(st->hw->addr, st->reg->pwr_mgmt_1, 1, data))
+        return -1;
+    if (i2c_write(st->hw->addr, st->reg->i2c_mst, 1, data))
+        return -1;
+    if (i2c_write(st->hw->addr, st->reg->user_ctrl, 1, data))
+        return -1;
+    data[0] = BIT_FIFO_RST | BIT_DMP_RST;
+    if (i2c_write(st->hw->addr, st->reg->user_ctrl, 1, data))
+        return -1;
+    delay_ms(15);
+    data[0] = st->test->reg_lpf;
+    if (i2c_write(st->hw->addr, st->reg->lpf, 1, data))
+        return -1;
+    data[0] = st->test->reg_rate_div;
+    if (i2c_write(st->hw->addr, st->reg->rate_div, 1, data))
+        return -1;
+    if (hw_test)
+        data[0] = st->test->reg_gyro_fsr | 0xE0;
+    else
+        data[0] = st->test->reg_gyro_fsr;
+    if (i2c_write(st->hw->addr, st->reg->gyro_cfg, 1, data))
+        return -1;
+
+    if (hw_test)
+        data[0] = st->test->reg_accel_fsr | 0xE0;
+    else
+        data[0] = test->reg_accel_fsr;
+    if (i2c_write(st->hw->addr, st->reg->accel_cfg, 1, data))
+        return -1;
+    if (hw_test)
+        delay_ms(200);
+
+    /* Fill FIFO for test->wait_ms milliseconds. */
+    data[0] = BIT_FIFO_EN;
+    if (i2c_write(st->hw->addr, st->reg->user_ctrl, 1, data))
+        return -1;
+
+    data[0] = INV_XYZ_GYRO | INV_XYZ_ACCEL;
+    if (i2c_write(st->hw->addr, st->reg->fifo_en, 1, data))
+        return -1;
+    delay_ms(test->wait_ms);
+    data[0] = 0;
+    if (i2c_write(st->hw->addr, st->reg->fifo_en, 1, data))
+        return -1;
+
+    if (i2c_read(st->hw->addr, st->reg->fifo_count_h, 2, data))
+        return -1;
+
+    fifo_count = (data[0] << 8) | data[1];
+    packet_count = fifo_count / MAX_PACKET_LENGTH;
+    gyro[0] = gyro[1] = gyro[2] = 0;
+    accel[0] = accel[1] = accel[2] = 0;
+
+    for (ii = 0; ii < packet_count; ii++) {
+        short accel_cur[3], gyro_cur[3];
+        if (i2c_read(st->hw->addr, st->reg->fifo_r_w, MAX_PACKET_LENGTH, data))
+            return -1;
+        accel_cur[0] = ((short)data[0] << 8) | data[1];
+        accel_cur[1] = ((short)data[2] << 8) | data[3];
+        accel_cur[2] = ((short)data[4] << 8) | data[5];
+        accel[0] += (long)accel_cur[0];
+        accel[1] += (long)accel_cur[1];
+        accel[2] += (long)accel_cur[2];
+        gyro_cur[0] = (((short)data[6] << 8) | data[7]);
+        gyro_cur[1] = (((short)data[8] << 8) | data[9]);
+        gyro_cur[2] = (((short)data[10] << 8) | data[11]);
+        gyro[0] += (long)gyro_cur[0];
+        gyro[1] += (long)gyro_cur[1];
+        gyro[2] += (long)gyro_cur[2];
+    }
+#ifdef EMPL_NO_64BIT
+    gyro[0] = (long)(((float)gyro[0]*65536.f) / test->gyro_sens / packet_count);
+    gyro[1] = (long)(((float)gyro[1]*65536.f) / test->gyro_sens / packet_count);
+    gyro[2] = (long)(((float)gyro[2]*65536.f) / test->gyro_sens / packet_count);
+    if (has_accel) {
+        accel[0] = (long)(((float)accel[0]*65536.f) / test->accel_sens /
+            packet_count);
+        accel[1] = (long)(((float)accel[1]*65536.f) / test->accel_sens /
+            packet_count);
+        accel[2] = (long)(((float)accel[2]*65536.f) / test->accel_sens /
+            packet_count);
+        /* Don't remove gravity! */
+        accel[2] -= 65536L;
+    }
+#else
+    gyro[0] = (long)(((long long)gyro[0]<<16) / test->gyro_sens / packet_count);
+    gyro[1] = (long)(((long long)gyro[1]<<16) / test->gyro_sens / packet_count);
+    gyro[2] = (long)(((long long)gyro[2]<<16) / test->gyro_sens / packet_count);
+    accel[0] = (long)(((long long)accel[0]<<16) / test->accel_sens /
+        packet_count);
+    accel[1] = (long)(((long long)accel[1]<<16) / test->accel_sens /
+        packet_count);
+    accel[2] = (long)(((long long)accel[2]<<16) / test->accel_sens /
+        packet_count);
+    /* Don't remove gravity! */
+    if (accel[2] > 0L)
+        accel[2] -= 65536L;
+    else
+        accel[2] += 65536L;
+#endif
+
+    return 0;
+}
+
+/**
+ *  @brief      Trigger gyro/accel/compass self-test->
+ *  On success/error, the self-test returns a mask representing the sensor(s)
+ *  that failed. For each bit, a one (1) represents a "pass" case; conversely,
+ *  a zero (0) indicates a failure.
+ *
+ *  \n The mask is defined as follows:
+ *  \n Bit 0:   Gyro.
+ *  \n Bit 1:   Accel.
+ *  \n Bit 2:   Compass.
+ *
+ *  \n Currently, the hardware self-test is unsupported for MPU6500. However,
+ *  this function can still be used to obtain the accel and gyro biases.
+ *
+ *  \n This function must be called with the device either face-up or face-down
+ *  (z-axis is parallel to gravity).
+ *  @param[out] gyro        Gyro biases in q16 format.
+ *  @param[out] accel       Accel biases (if applicable) in q16 format.
+ *  @return     Result mask (see above).
+ */
+int mpu_run_self_test(long *gyro, long *accel)
+{
+#ifdef MPU6050
+    const unsigned char tries = 2;
+    long gyro_st[3], accel_st[3];
+    unsigned char accel_result, gyro_result;
+#ifdef AK89xx_SECONDARY
+    unsigned char compass_result;
+#endif
+    int ii;
+#endif
+    int result;
+    unsigned char accel_fsr, fifo_sensors, sensors_on;
+    unsigned short gyro_fsr, sample_rate, lpf;
+    unsigned char dmp_was_on;
+
+    if (st->chip_cfg.dmp_on) {
+        mpu_set_dmp_state(0);
+        dmp_was_on = 1;
+    } else
+        dmp_was_on = 0;
+
+    /* Get initial settings. */
+    mpu_get_gyro_fsr(&gyro_fsr);
+    mpu_get_accel_fsr(&accel_fsr);
+    mpu_get_lpf(&lpf);
+    mpu_get_sample_rate(&sample_rate);
+    sensors_on = st->chip_cfg.sensors;
+    mpu_get_fifo_config(&fifo_sensors);
+
+    /* For older chips, the self-test will be different. */
+#if defined MPU6050
+    for (ii = 0; ii < tries; ii++)
+        if (!get_st_biases(gyro, accel, 0))
+            break;
+    if (ii == tries) {
+        /* If we reach this point, we most likely encountered an I2C error.
+         * We'll just report an error for all three sensors.
+         */
+        result = 0;
+        goto restore;
+    }
+    for (ii = 0; ii < tries; ii++)
+        if (!get_st_biases(gyro_st, accel_st, 1))
+            break;
+    if (ii == tries) {
+        /* Again, probably an I2C error. */
+        result = 0;
+        goto restore;
+    }
+    accel_result = accel_self_test(accel, accel_st);
+    gyro_result = gyro_self_test(gyro, gyro_st);
+
+    result = 0;
+    if (!gyro_result)
+        result |= 0x01;
+    if (!accel_result)
+        result |= 0x02;
+
+#ifdef AK89xx_SECONDARY
+    compass_result = compass_self_test();
+    if (!compass_result)
+        result |= 0x04;
+#endif
+restore:
+#elif defined MPU6500
+    /* For now, this function will return a "pass" result for all three sensors
+     * for compatibility with current test applications.
+     */
+    get_st_biases(gyro, accel, 0);
+    result = 0x7;
+#endif
+    /* Set to invalid values to ensure no I2C writes are skipped. */
+    st->chip_cfg.gyro_fsr = 0xFF;
+    st->chip_cfg.accel_fsr = 0xFF;
+    st->chip_cfg.lpf = 0xFF;
+    st->chip_cfg.sample_rate = 0xFFFF;
+    st->chip_cfg.sensors = 0xFF;
+    st->chip_cfg.fifo_enable = 0xFF;
+    st->chip_cfg.clk_src = INV_CLK_PLL;
+    mpu_set_gyro_fsr(gyro_fsr);
+    mpu_set_accel_fsr(accel_fsr);
+    mpu_set_lpf(lpf);
+    mpu_set_sample_rate(sample_rate);
+    mpu_set_sensors(sensors_on);
+    mpu_configure_fifo(fifo_sensors);
+
+    if (dmp_was_on)
+        mpu_set_dmp_state(1);
+
+    return result;
+}
+
+/**
+ *  @brief      Write to the DMP memory.
+ *  This function prevents I2C writes past the bank boundaries. The DMP memory
+ *  is only accessible when the chip is awake.
+ *  @param[in]  mem_addr    Memory location (bank << 8 | start address)
+ *  @param[in]  length      Number of bytes to write.
+ *  @param[in]  data        Bytes to write to memory.
+ *  @return     0 if successful.
+ */
+int mpu_write_mem(unsigned short mem_addr, unsigned short length,
+        unsigned char *data)
+{
+    unsigned char tmp[2];
+
+    if (!data)
+        return -1;
+    if (!st->chip_cfg.sensors)
+        return -2;
+
+    tmp[0] = (unsigned char)(mem_addr >> 8);
+    tmp[1] = (unsigned char)(mem_addr & 0xFF);
+
+    /* Check bank boundaries. */
+    if (tmp[1] + length > st->hw->bank_size)
+        return -3;
+
+    if (i2c_write(st->hw->addr, st->reg->bank_sel, 2, tmp))
+        return -4;
+    if (i2c_write(st->hw->addr, st->reg->mem_r_w, length, data))
+        return -5;
+    return 0;
+}
+
+/**
+ *  @brief      Read from the DMP memory.
+ *  This function prevents I2C reads past the bank boundaries. The DMP memory
+ *  is only accessible when the chip is awake.
+ *  @param[in]  mem_addr    Memory location (bank << 8 | start address)
+ *  @param[in]  length      Number of bytes to read.
+ *  @param[out] data        Bytes read from memory.
+ *  @return     0 if successful.
+ */
+int mpu_read_mem(unsigned short mem_addr, unsigned short length,
+        unsigned char *data)
+{
+    unsigned char tmp[2];
+
+    if (!data)
+        return -1;
+    if (!st->chip_cfg.sensors)
+        return -1;
+
+    tmp[0] = (unsigned char)(mem_addr >> 8);
+    tmp[1] = (unsigned char)(mem_addr & 0xFF);
+
+    /* Check bank boundaries. */
+    if (tmp[1] + length > st->hw->bank_size)
+        return -1;
+
+    if (i2c_write(st->hw->addr, st->reg->bank_sel, 2, tmp))
+        return -1;
+    if (i2c_read(st->hw->addr, st->reg->mem_r_w, length, data))
+        return -1;
+    return 0;
+}
+
+/**
+ *  @brief      Load and verify DMP image.
+ *  @param[in]  length      Length of DMP image.
+ *  @param[in]  firmware    DMP code.
+ *  @param[in]  start_addr  Starting address of DMP code memory.
+ *  @param[in]  sample_rate Fixed sampling rate used when DMP is enabled.
+ *  @return     0 if successful.
+ */
+int mpu_load_firmware(unsigned short length, const unsigned char *firmware,
+    unsigned short start_addr, unsigned short sample_rate)
+{
+    unsigned short ii;
+    unsigned short this_write;
+    int errCode;
+    uint8_t *progBuffer;
+    /* Must divide evenly into st->hw->bank_size to avoid bank crossings. */
+#define LOAD_CHUNK  (16)
+    unsigned char cur[LOAD_CHUNK], tmp[2];
+
+    if (st->chip_cfg.dmp_loaded)
+        /* DMP should only be loaded once. */
+        return -1;
+
+    if (!firmware)
+        return -2;
+        
+    progBuffer = (uint8_t *)malloc(LOAD_CHUNK);
+    for (ii = 0; ii < length; ii += this_write) {
+        this_write = min(LOAD_CHUNK, length - ii);
+        
+        for (int progIndex = 0; progIndex < this_write; progIndex++)
+#ifdef __SAM3X8E__
+            progBuffer[progIndex] = firmware[ii + progIndex];
+#else
+            progBuffer[progIndex] = pgm_read_byte(firmware + ii + progIndex);
+#endif
+            
+        if ((errCode = mpu_write_mem(ii, this_write, progBuffer))) {
+#ifdef MPU_DEBUG
+            Serial.print("fimrware write failed: ");
+            Serial.println(errCode);
+#endif
+            return -3;
+        }
+        
+        if (mpu_read_mem(ii, this_write, cur))
+            return -4;
+            
+        if (memcmp(progBuffer, cur, this_write)) {
+#ifdef MPU_DEBUG
+            Serial.print("Firmware compare failed addr "); Serial.println(ii);
+            for (int i = 0; i < 10; i++) {
+              Serial.print(progBuffer[i]); 
+              Serial.print(" ");
+            }
+            Serial.println();
+            for (int i = 0; i < 10; i++) {
+              Serial.print(cur[i]); 
+              Serial.print(" ");
+            }
+            Serial.println();
+#endif
+            return -5;
+        }
+    }
+
+    /* Set program start address. */
+    tmp[0] = start_addr >> 8;
+    tmp[1] = start_addr & 0xFF;
+    if (i2c_write(st->hw->addr, st->reg->prgm_start_h, 2, tmp))
+        return -6;
+
+    st->chip_cfg.dmp_loaded = 1;
+    st->chip_cfg.dmp_sample_rate = sample_rate;
+#ifdef MPU_DEBUG
+    Serial.println("Firmware loaded");
+#endif
+    return 0;
+}
+
+/**
+ *  @brief      Enable/disable DMP support.
+ *  @param[in]  enable  1 to turn on the DMP.
+ *  @return     0 if successful.
+ */
+int mpu_set_dmp_state(unsigned char enable)
+{
+    unsigned char tmp;
+    if (st->chip_cfg.dmp_on == enable)
+        return 0;
+
+    if (enable) {
+        if (!st->chip_cfg.dmp_loaded)
+            return -1;
+        /* Disable data ready interrupt. */
+        set_int_enable(0);
+        /* Disable bypass mode. */
+        mpu_set_bypass(0);
+        /* Keep constant sample rate, FIFO rate controlled by DMP. */
+        mpu_set_sample_rate(st->chip_cfg.dmp_sample_rate);
+        /* Remove FIFO elements. */
+        tmp = 0;
+        i2c_write(st->hw->addr, 0x23, 1, &tmp);
+        st->chip_cfg.dmp_on = 1;
+        /* Enable DMP interrupt. */
+        set_int_enable(1);
+        mpu_reset_fifo();
+    } else {
+        /* Disable DMP interrupt. */
+        set_int_enable(0);
+        /* Restore FIFO settings. */
+        tmp = st->chip_cfg.fifo_enable;
+        i2c_write(st->hw->addr, 0x23, 1, &tmp);
+        st->chip_cfg.dmp_on = 0;
+        mpu_reset_fifo();
+    }
+    return 0;
+}
+
+/**
+ *  @brief      Get DMP state.
+ *  @param[out] enabled 1 if enabled.
+ *  @return     0 if successful.
+ */
+int mpu_get_dmp_state(unsigned char *enabled)
+{
+    enabled[0] = st->chip_cfg.dmp_on;
+    return 0;
+}
+
+
+/* This initialization is similar to the one in ak8975.c. */
+static int setup_compass(void)
+{
+#ifdef AK89xx_SECONDARY
+    unsigned char data[4], akm_addr;
+
+    mpu_set_bypass(1);
+
+    /* Find compass. Possible addresses range from 0x0C to 0x0F. */
+    for (akm_addr = 0x0C; akm_addr <= 0x0F; akm_addr++) {
+        int result;
+        result = i2c_read(akm_addr, AKM_REG_WHOAMI, 1, data);
+        if (!result && (data[0] == AKM_WHOAMI))
+            break;
+    }
+
+    if (akm_addr > 0x0F) {
+        /* TODO: Handle this case in all compass-related functions. */
+#ifdef MPU_DEBUG
+        Serial.println("Compass not found.");
+#endif
+        return -1;
+    }
+
+    st->chip_cfg.compass_addr = akm_addr;
+
+    data[0] = AKM_POWER_DOWN;
+    if (i2c_write(st->chip_cfg.compass_addr, AKM_REG_CNTL, 1, data))
+        return -2;
+    delay_ms(1);
+
+    data[0] = AKM_FUSE_ROM_ACCESS;
+    if (i2c_write(st->chip_cfg.compass_addr, AKM_REG_CNTL, 1, data))
+        return -3;
+    delay_ms(1);
+
+    /* Get sensitivity adjustment data from fuse ROM. */
+    if (i2c_read(st->chip_cfg.compass_addr, AKM_REG_ASAX, 3, data))
+        return -4;
+    st->chip_cfg.mag_sens_adj[0] = (long)data[0] + 128;
+    st->chip_cfg.mag_sens_adj[1] = (long)data[1] + 128;
+    st->chip_cfg.mag_sens_adj[2] = (long)data[2] + 128;
+#ifdef MPU_DEBUG
+    Serial.print("Compass sens: "); Serial.print(st->chip_cfg.mag_sens_adj[0]); Serial.print(" ");
+    Serial.print(st->chip_cfg.mag_sens_adj[1]); Serial.print(" ");
+    Serial.print(st->chip_cfg.mag_sens_adj[2]); Serial.println();
+#endif
+
+    data[0] = AKM_POWER_DOWN;
+    if (i2c_write(st->chip_cfg.compass_addr, AKM_REG_CNTL, 1, data))
+        return -5;
+    delay_ms(1);
+
+    mpu_set_bypass(0);
+
+    /* Set up master mode, master clock, and ES bit. */
+    data[0] = 0x40;
+    if (i2c_write(st->hw->addr, st->reg->i2c_mst, 1, data))
+        return -6;
+
+    /* Slave 0 reads from AKM data registers. */
+    data[0] = BIT_I2C_READ | st->chip_cfg.compass_addr;
+    if (i2c_write(st->hw->addr, st->reg->s0_addr, 1, data))
+        return -7;
+
+    /* Compass reads start at this register. */
+    data[0] = AKM_REG_ST1;
+    if (i2c_write(st->hw->addr, st->reg->s0_reg, 1, data))
+        return -8;
+
+    /* Enable slave 0, 8-byte reads. */
+    data[0] = BIT_SLAVE_EN | 8;
+    if (i2c_write(st->hw->addr, st->reg->s0_ctrl, 1, data))
+        return -9;
+
+    /* Slave 1 changes AKM measurement mode. */
+    data[0] = st->chip_cfg.compass_addr;
+    if (i2c_write(st->hw->addr, st->reg->s1_addr, 1, data))
+        return -10;
+
+    /* AKM measurement mode register. */
+    data[0] = AKM_REG_CNTL;
+    if (i2c_write(st->hw->addr, st->reg->s1_reg, 1, data))
+        return -11;
+
+    /* Enable slave 1, 1-byte writes. */
+    data[0] = BIT_SLAVE_EN | 1;
+    if (i2c_write(st->hw->addr, st->reg->s1_ctrl, 1, data))
+        return -12;
+
+    /* Set slave 1 data. */
+    data[0] = AKM_SINGLE_MEASUREMENT;
+    if (i2c_write(st->hw->addr, st->reg->s1_do, 1, data))
+        return -13;
+
+    /* Trigger slave 0 and slave 1 actions at each sample. */
+    data[0] = 0x03;
+    if (i2c_write(st->hw->addr, st->reg->i2c_delay_ctrl, 1, data))
+        return -14;
+
+#ifdef MPU9150
+    /* For the MPU9150, the auxiliary I2C bus needs to be set to VDD. */
+    data[0] = BIT_I2C_MST_VDDIO;
+    if (i2c_write(st->hw->addr, st->reg->yg_offs_tc, 1, data))
+        return -15;
+#endif
+
+    return 0;
+#else
+    return -16;
+#endif
+}
+
+/**
+ *  @brief      Read raw compass data.
+ *  @param[out] data        Raw data in hardware units.
+ *  @param[out] timestamp   Timestamp in milliseconds. Null if not needed.
+ *  @return     0 if successful.
+ */
+int mpu_get_compass_reg(short *data, unsigned long *timestamp)
+{
+#ifdef AK89xx_SECONDARY
+    unsigned char tmp[9];
+
+    if (!(st->chip_cfg.sensors & INV_XYZ_COMPASS))
+        return -1;
+
+#ifdef AK89xx_BYPASS
+    if (i2c_read(st->chip_cfg.compass_addr, AKM_REG_ST1, 8, tmp))
+        return -2;
+    tmp[8] = AKM_SINGLE_MEASUREMENT;
+    if (i2c_write(st->chip_cfg.compass_addr, AKM_REG_CNTL, 1, tmp+8))
+        return -3;
+#else
+    if (i2c_read(st->hw->addr, st->reg->raw_compass, 8, tmp))
+        return -4;
+#endif
+
+#if defined AK8975_SECONDARY
+    /* AK8975 doesn't have the overrun error bit. */
+    if (!(tmp[0] & AKM_DATA_READY))
+        return -5;
+    if ((tmp[7] & AKM_OVERFLOW) || (tmp[7] & AKM_DATA_ERROR))
+        return -6;
+#elif defined AK8963_SECONDARY
+    /* AK8963 doesn't have the data read error bit. */
+    if (!(tmp[0] & AKM_DATA_READY) || (tmp[0] & AKM_DATA_OVERRUN))
+        return -7;
+    if (tmp[7] & AKM_OVERFLOW)
+        return -8;
+#endif
+    data[0] = ((unsigned short)tmp[2] << 8) | (unsigned short)tmp[1];
+    data[1] = ((unsigned short)tmp[4] << 8) | (unsigned short)tmp[3];
+    data[2] = ((unsigned short)tmp[6] << 8) | (unsigned short)tmp[5];
+
+    data[0] = ((long)data[0] * st->chip_cfg.mag_sens_adj[0]) >> 8;
+    data[1] = ((long)data[1] * st->chip_cfg.mag_sens_adj[1]) >> 8;
+    data[2] = ((long)data[2] * st->chip_cfg.mag_sens_adj[2]) >> 8;
+
+    if (timestamp)
+        get_ms(timestamp);
+    return 0;
+#else
+    return -9;
+#endif
+}
+
+/**
+ *  @brief      Get the compass full-scale range.
+ *  @param[out] fsr Current full-scale range.
+ *  @return     0 if successful.
+ */
+int mpu_get_compass_fsr(unsigned short *fsr)
+{
+#ifdef AK89xx_SECONDARY
+    fsr[0] = st->hw->compass_fsr;
+    return 0;
+#else
+    return -1;
+#endif
+}
+
+/**
+ *  @brief      Enters LP accel motion interrupt mode.
+ *  The behavior of this feature is very different between the MPU6050 and the
+ *  MPU6500. Each chip's version of this feature is explained below.
+ *
+ *  \n MPU6050:
+ *  \n When this mode is first enabled, the hardware captures a single accel
+ *  sample, and subsequent samples are compared with this one to determine if
+ *  the device is in motion. Therefore, whenever this "locked" sample needs to
+ *  be changed, this function must be called again.
+ *
+ *  \n The hardware motion threshold can be between 32mg and 8160mg in 32mg
+ *  increments.
+ *
+ *  \n Low-power accel mode supports the following frequencies:
+ *  \n 1.25Hz, 5Hz, 20Hz, 40Hz
+ *
+ *  \n MPU6500:
+ *  \n Unlike the MPU6050 version, the hardware does not "lock in" a reference
+ *  sample. The hardware monitors the accel data and detects any large change
+ *  over a short period of time.
+ *
+ *  \n The hardware motion threshold can be between 4mg and 1020mg in 4mg
+ *  increments.
+ *
+ *  \n MPU6500 Low-power accel mode supports the following frequencies:
+ *  \n 1.25Hz, 2.5Hz, 5Hz, 10Hz, 20Hz, 40Hz, 80Hz, 160Hz, 320Hz, 640Hz
+ *
+ *  \n\n NOTES:
+ *  \n The driver will round down @e thresh to the nearest supported value if
+ *  an unsupported threshold is selected.
+ *  \n To select a fractional wake-up frequency, round down the value passed to
+ *  @e lpa_freq.
+ *  \n The MPU6500 does not support a delay parameter. If this function is used
+ *  for the MPU6500, the value passed to @e time will be ignored.
+ *  \n To disable this mode, set @e lpa_freq to zero. The driver will restore
+ *  the previous configuration.
+ *
+ *  @param[in]  thresh      Motion threshold in mg.
+ *  @param[in]  time        Duration in milliseconds that the accel data must
+ *                          exceed @e thresh before motion is reported.
+ *  @param[in]  lpa_freq    Minimum sampling rate, or zero to disable.
+ *  @return     0 if successful.
+ */
+int mpu_lp_motion_interrupt(unsigned short thresh, unsigned char time,
+    unsigned char lpa_freq)
+{
+    unsigned char data[3];
+
+    if (lpa_freq) {
+        unsigned char thresh_hw;
+
+#if defined MPU6050
+        /* TODO: Make these const/#defines. */
+        /* 1LSb = 32mg. */
+        if (thresh > 8160)
+            thresh_hw = 255;
+        else if (thresh < 32)
+            thresh_hw = 1;
+        else
+            thresh_hw = thresh >> 5;
+#elif defined MPU6500
+        /* 1LSb = 4mg. */
+        if (thresh > 1020)
+            thresh_hw = 255;
+        else if (thresh < 4)
+            thresh_hw = 1;
+        else
+            thresh_hw = thresh >> 2;
+#endif
+
+        if (!time)
+            /* Minimum duration must be 1ms. */
+            time = 1;
+
+#if defined MPU6050
+        if (lpa_freq > 40)
+#elif defined MPU6500
+        if (lpa_freq > 640)
+#endif
+            /* At this point, the chip has not been re-configured, so the
+             * function can safely exit.
+             */
+            return -1;
+
+        if (!st->chip_cfg.int_motion_only) {
+            /* Store current settings for later. */
+            if (st->chip_cfg.dmp_on) {
+                mpu_set_dmp_state(0);
+                st->chip_cfg.cache.dmp_on = 1;
+            } else
+                st->chip_cfg.cache.dmp_on = 0;
+            mpu_get_gyro_fsr(&st->chip_cfg.cache.gyro_fsr);
+            mpu_get_accel_fsr(&st->chip_cfg.cache.accel_fsr);
+            mpu_get_lpf(&st->chip_cfg.cache.lpf);
+            mpu_get_sample_rate(&st->chip_cfg.cache.sample_rate);
+            st->chip_cfg.cache.sensors_on = st->chip_cfg.sensors;
+            mpu_get_fifo_config(&st->chip_cfg.cache.fifo_sensors);
+        }
+
+#ifdef MPU6050
+        /* Disable hardware interrupts for now. */
+        set_int_enable(0);
+
+        /* Enter full-power accel-only mode. */
+        mpu_lp_accel_mode(0);
+
+        /* Override current LPF (and HPF) settings to obtain a valid accel
+         * reading.
+         */
+        data[0] = INV_FILTER_256HZ_NOLPF2;
+        if (i2c_write(st->hw->addr, st->reg->lpf, 1, data))
+            return -1;
+
+        /* NOTE: Digital high pass filter should be configured here. Since this
+         * driver doesn't modify those bits anywhere, they should already be
+         * cleared by default.
+         */
+
+        /* Configure the device to send motion interrupts. */
+        /* Enable motion interrupt. */
+        data[0] = BIT_MOT_INT_EN;
+        if (i2c_write(st->hw->addr, st->reg->int_enable, 1, data))
+            goto lp_int_restore;
+
+        /* Set motion interrupt parameters. */
+        data[0] = thresh_hw;
+        data[1] = time;
+        if (i2c_write(st->hw->addr, st->reg->motion_thr, 2, data))
+            goto lp_int_restore;
+
+        /* Force hardware to "lock" current accel sample. */
+        delay_ms(5);
+        data[0] = (st->chip_cfg.accel_fsr << 3) | BITS_HPF;
+        if (i2c_write(st->hw->addr, st->reg->accel_cfg, 1, data))
+            goto lp_int_restore;
+
+        /* Set up LP accel mode. */
+        data[0] = BIT_LPA_CYCLE;
+        if (lpa_freq == 1)
+            data[1] = INV_LPA_1_25HZ;
+        else if (lpa_freq <= 5)
+            data[1] = INV_LPA_5HZ;
+        else if (lpa_freq <= 20)
+            data[1] = INV_LPA_20HZ;
+        else
+            data[1] = INV_LPA_40HZ;
+        data[1] = (data[1] << 6) | BIT_STBY_XYZG;
+        if (i2c_write(st->hw->addr, st->reg->pwr_mgmt_1, 2, data))
+            goto lp_int_restore;
+
+        st->chip_cfg.int_motion_only = 1;
+        return 0;
+#elif defined MPU6500
+        /* Disable hardware interrupts. */
+        set_int_enable(0);
+
+        /* Enter full-power accel-only mode, no FIFO/DMP. */
+        data[0] = 0;
+        data[1] = 0;
+        data[2] = BIT_STBY_XYZG;
+        if (i2c_write(st->hw->addr, st->reg->user_ctrl, 3, data))
+            goto lp_int_restore;
+
+        /* Set motion threshold. */
+        data[0] = thresh_hw;
+        if (i2c_write(st->hw->addr, st->reg->motion_thr, 1, data))
+            goto lp_int_restore;
+
+        /* Set wake frequency. */
+        if (lpa_freq == 1)
+            data[0] = INV_LPA_1_25HZ;
+        else if (lpa_freq == 2)
+            data[0] = INV_LPA_2_5HZ;
+        else if (lpa_freq <= 5)
+            data[0] = INV_LPA_5HZ;
+        else if (lpa_freq <= 10)
+            data[0] = INV_LPA_10HZ;
+        else if (lpa_freq <= 20)
+            data[0] = INV_LPA_20HZ;
+        else if (lpa_freq <= 40)
+            data[0] = INV_LPA_40HZ;
+        else if (lpa_freq <= 80)
+            data[0] = INV_LPA_80HZ;
+        else if (lpa_freq <= 160)
+            data[0] = INV_LPA_160HZ;
+        else if (lpa_freq <= 320)
+            data[0] = INV_LPA_320HZ;
+        else
+            data[0] = INV_LPA_640HZ;
+        if (i2c_write(st->hw->addr, st->reg->lp_accel_odr, 1, data))
+            goto lp_int_restore;
+
+        /* Enable motion interrupt (MPU6500 version). */
+        data[0] = BITS_WOM_EN;
+        if (i2c_write(st->hw->addr, st->reg->accel_intel, 1, data))
+            goto lp_int_restore;
+
+        /* Enable cycle mode. */
+        data[0] = BIT_LPA_CYCLE;
+        if (i2c_write(st->hw->addr, st->reg->pwr_mgmt_1, 1, data))
+            goto lp_int_restore;
+
+        /* Enable interrupt. */
+        data[0] = BIT_MOT_INT_EN;
+        if (i2c_write(st->hw->addr, st->reg->int_enable, 1, data))
+            goto lp_int_restore;
+
+        st->chip_cfg.int_motion_only = 1;
+        return 0;
+#endif
+    } else {
+        /* Don't "restore" the previous state if no state has been saved. */
+        int ii;
+        char *cache_ptr = (char*)&st->chip_cfg.cache;
+        for (ii = 0; ii < sizeof(st->chip_cfg.cache); ii++) {
+            if (cache_ptr[ii] != 0)
+                goto lp_int_restore;
+        }
+        /* If we reach this point, motion interrupt mode hasn't been used yet. */
+        return -1;
+    }
+lp_int_restore:
+    /* Set to invalid values to ensure no I2C writes are skipped. */
+    st->chip_cfg.gyro_fsr = 0xFF;
+    st->chip_cfg.accel_fsr = 0xFF;
+    st->chip_cfg.lpf = 0xFF;
+    st->chip_cfg.sample_rate = 0xFFFF;
+    st->chip_cfg.sensors = 0xFF;
+    st->chip_cfg.fifo_enable = 0xFF;
+    st->chip_cfg.clk_src = INV_CLK_PLL;
+    mpu_set_sensors(st->chip_cfg.cache.sensors_on);
+    mpu_set_gyro_fsr(st->chip_cfg.cache.gyro_fsr);
+    mpu_set_accel_fsr(st->chip_cfg.cache.accel_fsr);
+    mpu_set_lpf(st->chip_cfg.cache.lpf);
+    mpu_set_sample_rate(st->chip_cfg.cache.sample_rate);
+    mpu_configure_fifo(st->chip_cfg.cache.fifo_sensors);
+
+    if (st->chip_cfg.cache.dmp_on)
+        mpu_set_dmp_state(1);
+
+#ifdef MPU6500
+    /* Disable motion interrupt (MPU6500 version). */
+    data[0] = 0;
+    if (i2c_write(st->hw->addr, st->reg->accel_intel, 1, data))
+        goto lp_int_restore;
+#endif
+
+    st->chip_cfg.int_motion_only = 0;
+    return 0;
+}
+
+/**
+ *  @}
+ */
+
diff --git a/libraries/MotionDriver/inv_mpu.h b/libraries/MotionDriver/inv_mpu.h
new file mode 100644
index 0000000..3b419e5
--- /dev/null
+++ b/libraries/MotionDriver/inv_mpu.h
@@ -0,0 +1,146 @@
+/*
+ $License:
+    Copyright (C) 2011-2012 InvenSense Corporation, All Rights Reserved.
+    See included License.txt for License information.
+ $
+ */
+/**
+ *  @addtogroup  DRIVERS Sensor Driver Layer
+ *  @brief       Hardware drivers to communicate with sensors via I2C.
+ *
+ *  @{
+ *      @file       inv_mpu.h
+ *      @brief      An I2C-based driver for Invensense gyroscopes.
+ *      @details    This driver currently works for the following devices:
+ *                  MPU6050
+ *                  MPU6500
+ *                  MPU9150 (or MPU6050 w/ AK8975 on the auxiliary bus)
+ *                  MPU9250 (or MPU6500 w/ AK8963 on the auxiliary bus)
+ */
+
+#ifndef _INV_MPU_H_
+#define _INV_MPU_H_
+
+#include "I2Cdev.h"
+
+//  Define this symbol to get debug messages
+
+#define  MPU_DEBUG
+
+//  This symbol defines how many devices are supported
+
+#define MPU_MAX_DEVICES 2
+
+//  Call this function before using the MPU to select the correct device
+
+int mpu_select_device(int device);
+
+inline void get_ms(long unsigned int *timestamp)
+{
+    *timestamp = millis(); 
+}
+
+//  IMU hardware device defines
+
+#define MPU9150
+
+#define INV_X_GYRO      (0x40)
+#define INV_Y_GYRO      (0x20)
+#define INV_Z_GYRO      (0x10)
+#define INV_XYZ_GYRO    (INV_X_GYRO | INV_Y_GYRO | INV_Z_GYRO)
+#define INV_XYZ_ACCEL   (0x08)
+#define INV_XYZ_COMPASS (0x01)
+
+struct int_param_s {
+    void (*cb)(void);
+    unsigned short pin;
+    unsigned char lp_exit;
+    unsigned char active_low;
+};
+
+#define MPU_INT_STATUS_DATA_READY       (0x0001)
+#define MPU_INT_STATUS_DMP              (0x0002)
+#define MPU_INT_STATUS_PLL_READY        (0x0004)
+#define MPU_INT_STATUS_I2C_MST          (0x0008)
+#define MPU_INT_STATUS_FIFO_OVERFLOW    (0x0010)
+#define MPU_INT_STATUS_ZMOT             (0x0020)
+#define MPU_INT_STATUS_MOT              (0x0040)
+#define MPU_INT_STATUS_FREE_FALL        (0x0080)
+#define MPU_INT_STATUS_DMP_0            (0x0100)
+#define MPU_INT_STATUS_DMP_1            (0x0200)
+#define MPU_INT_STATUS_DMP_2            (0x0400)
+#define MPU_INT_STATUS_DMP_3            (0x0800)
+#define MPU_INT_STATUS_DMP_4            (0x1000)
+#define MPU_INT_STATUS_DMP_5            (0x2000)
+
+/* Set up APIs */
+void mpu_init_structures();
+
+int mpu_init(struct int_param_s *int_param);
+int mpu_init_slave(void);
+int mpu_set_bypass(unsigned char bypass_on);
+
+/* Configuration APIs */
+int mpu_lp_accel_mode(unsigned char rate);
+int mpu_lp_motion_interrupt(unsigned short thresh, unsigned char time,
+    unsigned char lpa_freq);
+int mpu_set_int_level(unsigned char active_low);
+int mpu_set_int_latched(unsigned char enable);
+
+int mpu_set_dmp_state(unsigned char enable);
+int mpu_get_dmp_state(unsigned char *enabled);
+
+int mpu_get_lpf(unsigned short *lpf);
+int mpu_set_lpf(unsigned short lpf);
+
+int mpu_get_gyro_fsr(unsigned short *fsr);
+int mpu_set_gyro_fsr(unsigned short fsr);
+
+int mpu_get_accel_fsr(unsigned char *fsr);
+int mpu_set_accel_fsr(unsigned char fsr);
+
+int mpu_get_compass_fsr(unsigned short *fsr);
+
+int mpu_get_gyro_sens(float *sens);
+int mpu_get_accel_sens(unsigned short *sens);
+
+int mpu_get_sample_rate(unsigned short *rate);
+int mpu_set_sample_rate(unsigned short rate);
+int mpu_get_compass_sample_rate(unsigned short *rate);
+int mpu_set_compass_sample_rate(unsigned short rate);
+
+int mpu_get_fifo_config(unsigned char *sensors);
+int mpu_configure_fifo(unsigned char sensors);
+
+int mpu_get_power_state(unsigned char *power_on);
+int mpu_set_sensors(unsigned char sensors);
+
+int mpu_set_accel_bias(const long *accel_bias);
+
+/* Data getter/setter APIs */
+int mpu_get_gyro_reg(short *data, unsigned long *timestamp);
+int mpu_get_accel_reg(short *data, unsigned long *timestamp);
+int mpu_get_compass_reg(short *data, unsigned long *timestamp);
+int mpu_get_temperature(long *data, unsigned long *timestamp);
+
+int mpu_get_int_status(short *status);
+int mpu_read_fifo(short *gyro, short *accel, unsigned long *timestamp,
+    unsigned char *sensors, unsigned char *more);
+int mpu_read_fifo_stream(unsigned short length, unsigned char *data,
+    unsigned char *more);
+int mpu_reset_fifo(void);
+
+int mpu_write_mem(unsigned short mem_addr, unsigned short length,
+    unsigned char *data);
+int mpu_read_mem(unsigned short mem_addr, unsigned short length,
+    unsigned char *data);
+int mpu_load_firmware(unsigned short length, const unsigned char *firmware,
+    unsigned short start_addr, unsigned short sample_rate);
+
+int mpu_reg_dump(void);
+int mpu_read_reg(unsigned char reg, unsigned char *data);
+int mpu_run_self_test(long *gyro, long *accel);
+int mpu_register_tap_cb(void (*func)(unsigned char, unsigned char));
+
+#endif  /* #ifndef _INV_MPU_H_ */
+
diff --git a/libraries/MotionDriver/inv_mpu_dmp_motion_driver.cpp b/libraries/MotionDriver/inv_mpu_dmp_motion_driver.cpp
new file mode 100644
index 0000000..cc4d973
--- /dev/null
+++ b/libraries/MotionDriver/inv_mpu_dmp_motion_driver.cpp
@@ -0,0 +1,1363 @@
+/*
+ $License:
+    Copyright (C) 2011-2012 InvenSense Corporation, All Rights Reserved.
+    See included License.txt for License information.
+ $
+ */
+/**
+ *  @addtogroup  DRIVERS Sensor Driver Layer
+ *  @brief       Hardware drivers to communicate with sensors via I2C.
+ *
+ *  @{
+ *      @file       inv_mpu_dmp_motion_driver.c
+ *      @brief      DMP image and interface functions.
+ *      @details    All functions are preceded by the dmp_ prefix to
+ *                  differentiate among MPL and general driver function calls.
+ */
+#include 
+#include 
+#include 
+#include 
+#include 
+#include "inv_mpu.h"
+#include "inv_mpu_dmp_motion_driver.h"
+#include "dmpKey.h"
+#include "dmpmap.h"
+
+/* The following functions must be defined for this platform:
+ * i2c_write(unsigned char slave_addr, unsigned char reg_addr,
+ *      unsigned char length, unsigned char const *data)
+ * i2c_read(unsigned char slave_addr, unsigned char reg_addr,
+ *      unsigned char length, unsigned char *data)
+ * delay_ms(unsigned long num_ms)
+ * get_ms(unsigned long *count)
+ */
+
+#define delay_ms    delay
+
+#define log_i(...)     do {} while (0)
+#define log_e(...)     do {} while (0)
+
+
+/* These defines are copied from dmpDefaultMPU6050.c in the general MPL
+ * releases. These defines may change for each DMP image, so be sure to modify
+ * these values when switching to a new image.
+ */
+#define CFG_LP_QUAT             (2712)
+#define END_ORIENT_TEMP         (1866)
+#define CFG_27                  (2742)
+#define CFG_20                  (2224)
+#define CFG_23                  (2745)
+#define CFG_FIFO_ON_EVENT       (2690)
+#define END_PREDICTION_UPDATE   (1761)
+#define CGNOTICE_INTR           (2620)
+#define X_GRT_Y_TMP             (1358)
+#define CFG_DR_INT              (1029)
+#define CFG_AUTH                (1035)
+#define UPDATE_PROP_ROT         (1835)
+#define END_COMPARE_Y_X_TMP2    (1455)
+#define SKIP_X_GRT_Y_TMP        (1359)
+#define SKIP_END_COMPARE        (1435)
+#define FCFG_3                  (1088)
+#define FCFG_2                  (1066)
+#define FCFG_1                  (1062)
+#define END_COMPARE_Y_X_TMP3    (1434)
+#define FCFG_7                  (1073)
+#define FCFG_6                  (1106)
+#define FLAT_STATE_END          (1713)
+#define SWING_END_4             (1616)
+#define SWING_END_2             (1565)
+#define SWING_END_3             (1587)
+#define SWING_END_1             (1550)
+#define CFG_8                   (2718)
+#define CFG_15                  (2727)
+#define CFG_16                  (2746)
+#define CFG_EXT_GYRO_BIAS       (1189)
+#define END_COMPARE_Y_X_TMP     (1407)
+#define DO_NOT_UPDATE_PROP_ROT  (1839)
+#define CFG_7                   (1205)
+#define FLAT_STATE_END_TEMP     (1683)
+#define END_COMPARE_Y_X         (1484)
+#define SKIP_SWING_END_1        (1551)
+#define SKIP_SWING_END_3        (1588)
+#define SKIP_SWING_END_2        (1566)
+#define TILTG75_START           (1672)
+#define CFG_6                   (2753)
+#define TILTL75_END             (1669)
+#define END_ORIENT              (1884)
+#define CFG_FLICK_IN            (2573)
+#define TILTL75_START           (1643)
+#define CFG_MOTION_BIAS         (1208)
+#define X_GRT_Y                 (1408)
+#define TEMPLABEL               (2324)
+#define CFG_ANDROID_ORIENT_INT  (1853)
+#define CFG_GYRO_RAW_DATA       (2722)
+#define X_GRT_Y_TMP2            (1379)
+
+#define D_0_22                  (22+512)
+#define D_0_24                  (24+512)
+
+#define D_0_36                  (36)
+#define D_0_52                  (52)
+#define D_0_96                  (96)
+#define D_0_104                 (104)
+#define D_0_108                 (108)
+#define D_0_163                 (163)
+#define D_0_188                 (188)
+#define D_0_192                 (192)
+#define D_0_224                 (224)
+#define D_0_228                 (228)
+#define D_0_232                 (232)
+#define D_0_236                 (236)
+
+#define D_1_2                   (256 + 2)
+#define D_1_4                   (256 + 4)
+#define D_1_8                   (256 + 8)
+#define D_1_10                  (256 + 10)
+#define D_1_24                  (256 + 24)
+#define D_1_28                  (256 + 28)
+#define D_1_36                  (256 + 36)
+#define D_1_40                  (256 + 40)
+#define D_1_44                  (256 + 44)
+#define D_1_72                  (256 + 72)
+#define D_1_74                  (256 + 74)
+#define D_1_79                  (256 + 79)
+#define D_1_88                  (256 + 88)
+#define D_1_90                  (256 + 90)
+#define D_1_92                  (256 + 92)
+#define D_1_96                  (256 + 96)
+#define D_1_98                  (256 + 98)
+#define D_1_106                 (256 + 106)
+#define D_1_108                 (256 + 108)
+#define D_1_112                 (256 + 112)
+#define D_1_128                 (256 + 144)
+#define D_1_152                 (256 + 12)
+#define D_1_160                 (256 + 160)
+#define D_1_176                 (256 + 176)
+#define D_1_178                 (256 + 178)
+#define D_1_218                 (256 + 218)
+#define D_1_232                 (256 + 232)
+#define D_1_236                 (256 + 236)
+#define D_1_240                 (256 + 240)
+#define D_1_244                 (256 + 244)
+#define D_1_250                 (256 + 250)
+#define D_1_252                 (256 + 252)
+#define D_2_12                  (512 + 12)
+#define D_2_96                  (512 + 96)
+#define D_2_108                 (512 + 108)
+#define D_2_208                 (512 + 208)
+#define D_2_224                 (512 + 224)
+#define D_2_236                 (512 + 236)
+#define D_2_244                 (512 + 244)
+#define D_2_248                 (512 + 248)
+#define D_2_252                 (512 + 252)
+
+#define CPASS_BIAS_X            (35 * 16 + 4)
+#define CPASS_BIAS_Y            (35 * 16 + 8)
+#define CPASS_BIAS_Z            (35 * 16 + 12)
+#define CPASS_MTX_00            (36 * 16)
+#define CPASS_MTX_01            (36 * 16 + 4)
+#define CPASS_MTX_02            (36 * 16 + 8)
+#define CPASS_MTX_10            (36 * 16 + 12)
+#define CPASS_MTX_11            (37 * 16)
+#define CPASS_MTX_12            (37 * 16 + 4)
+#define CPASS_MTX_20            (37 * 16 + 8)
+#define CPASS_MTX_21            (37 * 16 + 12)
+#define CPASS_MTX_22            (43 * 16 + 12)
+#define D_EXT_GYRO_BIAS_X       (61 * 16)
+#define D_EXT_GYRO_BIAS_Y       (61 * 16) + 4
+#define D_EXT_GYRO_BIAS_Z       (61 * 16) + 8
+#define D_ACT0                  (40 * 16)
+#define D_ACSX                  (40 * 16 + 4)
+#define D_ACSY                  (40 * 16 + 8)
+#define D_ACSZ                  (40 * 16 + 12)
+
+#define FLICK_MSG               (45 * 16 + 4)
+#define FLICK_COUNTER           (45 * 16 + 8)
+#define FLICK_LOWER             (45 * 16 + 12)
+#define FLICK_UPPER             (46 * 16 + 12)
+
+#define D_AUTH_OUT              (992)
+#define D_AUTH_IN               (996)
+#define D_AUTH_A                (1000)
+#define D_AUTH_B                (1004)
+
+#define D_PEDSTD_BP_B           (768 + 0x1C)
+#define D_PEDSTD_HP_A           (768 + 0x78)
+#define D_PEDSTD_HP_B           (768 + 0x7C)
+#define D_PEDSTD_BP_A4          (768 + 0x40)
+#define D_PEDSTD_BP_A3          (768 + 0x44)
+#define D_PEDSTD_BP_A2          (768 + 0x48)
+#define D_PEDSTD_BP_A1          (768 + 0x4C)
+#define D_PEDSTD_INT_THRSH      (768 + 0x68)
+#define D_PEDSTD_CLIP           (768 + 0x6C)
+#define D_PEDSTD_SB             (768 + 0x28)
+#define D_PEDSTD_SB_TIME        (768 + 0x2C)
+#define D_PEDSTD_PEAKTHRSH      (768 + 0x98)
+#define D_PEDSTD_TIML           (768 + 0x2A)
+#define D_PEDSTD_TIMH           (768 + 0x2E)
+#define D_PEDSTD_PEAK           (768 + 0X94)
+#define D_PEDSTD_STEPCTR        (768 + 0x60)
+#define D_PEDSTD_TIMECTR        (964)
+#define D_PEDSTD_DECI           (768 + 0xA0)
+
+#define D_HOST_NO_MOT           (976)
+#define D_ACCEL_BIAS            (660)
+
+#define D_ORIENT_GAP            (76)
+
+#define D_TILT0_H               (48)
+#define D_TILT0_L               (50)
+#define D_TILT1_H               (52)
+#define D_TILT1_L               (54)
+#define D_TILT2_H               (56)
+#define D_TILT2_L               (58)
+#define D_TILT3_H               (60)
+#define D_TILT3_L               (62)
+
+#define DMP_CODE_SIZE           (3062)
+
+#ifdef __SAM3X8E__
+const uint8_t dmp_memory[DMP_CODE_SIZE] = {
+#else
+const unsigned char dmp_memory[DMP_CODE_SIZE] PROGMEM = {
+#endif
+    /* bank # 0 */
+    0x00, 0x00, 0x70, 0x00, 0x00, 0x00, 0x00, 0x24, 0x00, 0x00, 0x00, 0x02, 0x00, 0x03, 0x00, 0x00,
+    0x00, 0x65, 0x00, 0x54, 0xff, 0xef, 0x00, 0x00, 0xfa, 0x80, 0x00, 0x0b, 0x12, 0x82, 0x00, 0x01,
+    0x03, 0x0c, 0x30, 0xc3, 0x0e, 0x8c, 0x8c, 0xe9, 0x14, 0xd5, 0x40, 0x02, 0x13, 0x71, 0x0f, 0x8e,
+    0x38, 0x83, 0xf8, 0x83, 0x30, 0x00, 0xf8, 0x83, 0x25, 0x8e, 0xf8, 0x83, 0x30, 0x00, 0xf8, 0x83,
+    0xff, 0xff, 0xff, 0xff, 0x0f, 0xfe, 0xa9, 0xd6, 0x24, 0x00, 0x04, 0x00, 0x1a, 0x82, 0x79, 0xa1,
+    0x00, 0x00, 0x00, 0x3c, 0xff, 0xff, 0x00, 0x00, 0x00, 0x10, 0x00, 0x00, 0x38, 0x83, 0x6f, 0xa2,
+    0x00, 0x3e, 0x03, 0x30, 0x40, 0x00, 0x00, 0x00, 0x02, 0xca, 0xe3, 0x09, 0x3e, 0x80, 0x00, 0x00,
+    0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x60, 0x00, 0x00, 0x00,
+    0x00, 0x0c, 0x00, 0x00, 0x00, 0x0c, 0x18, 0x6e, 0x00, 0x00, 0x06, 0x92, 0x0a, 0x16, 0xc0, 0xdf,
+    0xff, 0xff, 0x02, 0x56, 0xfd, 0x8c, 0xd3, 0x77, 0xff, 0xe1, 0xc4, 0x96, 0xe0, 0xc5, 0xbe, 0xaa,
+    0x00, 0x00, 0x00, 0x00, 0xff, 0xff, 0x0b, 0x2b, 0x00, 0x00, 0x16, 0x57, 0x00, 0x00, 0x03, 0x59,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x1d, 0xfa, 0x00, 0x02, 0x6c, 0x1d, 0x00, 0x00, 0x00, 0x00,
+    0x3f, 0xff, 0xdf, 0xeb, 0x00, 0x3e, 0xb3, 0xb6, 0x00, 0x0d, 0x22, 0x78, 0x00, 0x00, 0x2f, 0x3c,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x19, 0x42, 0xb5, 0x00, 0x00, 0x39, 0xa2, 0x00, 0x00, 0xb3, 0x65,
+    0xd9, 0x0e, 0x9f, 0xc9, 0x1d, 0xcf, 0x4c, 0x34, 0x30, 0x00, 0x00, 0x00, 0x50, 0x00, 0x00, 0x00,
+    0x3b, 0xb6, 0x7a, 0xe8, 0x00, 0x64, 0x00, 0x00, 0x00, 0xc8, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    /* bank # 1 */
+    0x10, 0x00, 0x00, 0x00, 0x10, 0x00, 0xfa, 0x92, 0x10, 0x00, 0x22, 0x5e, 0x00, 0x0d, 0x22, 0x9f,
+    0x00, 0x01, 0x00, 0x00, 0x00, 0x32, 0x00, 0x00, 0xff, 0x46, 0x00, 0x00, 0x63, 0xd4, 0x00, 0x00,
+    0x10, 0x00, 0x00, 0x00, 0x04, 0xd6, 0x00, 0x00, 0x04, 0xcc, 0x00, 0x00, 0x04, 0xcc, 0x00, 0x00,
+    0x00, 0x00, 0x10, 0x72, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x06, 0x00, 0x02, 0x00, 0x05, 0x00, 0x07, 0x00, 0x00, 0x00, 0x00, 0x00, 0x64, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x05, 0x00, 0x05, 0x00, 0x64, 0x00, 0x20, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x40, 0x00, 0x00, 0x00, 0x03, 0x00,
+    0x00, 0x00, 0x00, 0x32, 0xf8, 0x98, 0x00, 0x00, 0xff, 0x65, 0x00, 0x00, 0x83, 0x0f, 0x00, 0x00,
+    0xff, 0x9b, 0xfc, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0xb2, 0x6a, 0x00, 0x02, 0x00, 0x00,
+    0x00, 0x01, 0xfb, 0x83, 0x00, 0x68, 0x00, 0x00, 0x00, 0xd9, 0xfc, 0x00, 0x7c, 0xf1, 0xff, 0x83,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x65, 0x00, 0x00, 0x00, 0x64, 0x03, 0xe8, 0x00, 0x64, 0x00, 0x28,
+    0x00, 0x00, 0x00, 0x25, 0x00, 0x00, 0x00, 0x00, 0x16, 0xa0, 0x00, 0x00, 0x00, 0x00, 0x10, 0x00,
+    0x00, 0x00, 0x10, 0x00, 0x00, 0x2f, 0x00, 0x00, 0x00, 0x00, 0x01, 0xf4, 0x00, 0x00, 0x10, 0x00,
+    /* bank # 2 */
+    0x00, 0x28, 0x00, 0x00, 0xff, 0xff, 0x45, 0x81, 0xff, 0xff, 0xfa, 0x72, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x44, 0x00, 0x05, 0x00, 0x05, 0xba, 0xc6, 0x00, 0x47, 0x78, 0xa2,
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x00, 0x00, 0x00, 0x14,
+    0x00, 0x00, 0x25, 0x4d, 0x00, 0x2f, 0x70, 0x6d, 0x00, 0x00, 0x05, 0xae, 0x00, 0x0c, 0x02, 0xd0,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x1b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x64, 0x00, 0x00, 0x00, 0x08, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x1b, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x0e, 0x00, 0x0e,
+    0x00, 0x00, 0x0a, 0xc7, 0x00, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x32, 0xff, 0xff, 0xff, 0x9c,
+    0x00, 0x00, 0x0b, 0x2b, 0x00, 0x00, 0x00, 0x02, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x64,
+    0xff, 0xe5, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    /* bank # 3 */
+    0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x01, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x01, 0x80, 0x00, 0x00, 0x24, 0x26, 0xd3,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x06, 0x00, 0x10, 0x00, 0x96, 0x00, 0x3c,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x0c, 0x0a, 0x4e, 0x68, 0xcd, 0xcf, 0x77, 0x09, 0x50, 0x16, 0x67, 0x59, 0xc6, 0x19, 0xce, 0x82,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x17, 0xd7, 0x84, 0x00, 0x03, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xc7, 0x93, 0x8f, 0x9d, 0x1e, 0x1b, 0x1c, 0x19,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x02, 0x03, 0x18, 0x85, 0x00, 0x00, 0x40, 0x00,
+    0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x40, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x00, 0x67, 0x7d, 0xdf, 0x7e, 0x72, 0x90, 0x2e, 0x55, 0x4c, 0xf6, 0xe6, 0x88,
+    0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+
+    /* bank # 4 */
+    0xd8, 0xdc, 0xb4, 0xb8, 0xb0, 0xd8, 0xb9, 0xab, 0xf3, 0xf8, 0xfa, 0xb3, 0xb7, 0xbb, 0x8e, 0x9e,
+    0xae, 0xf1, 0x32, 0xf5, 0x1b, 0xf1, 0xb4, 0xb8, 0xb0, 0x80, 0x97, 0xf1, 0xa9, 0xdf, 0xdf, 0xdf,
+    0xaa, 0xdf, 0xdf, 0xdf, 0xf2, 0xaa, 0xc5, 0xcd, 0xc7, 0xa9, 0x0c, 0xc9, 0x2c, 0x97, 0xf1, 0xa9,
+    0x89, 0x26, 0x46, 0x66, 0xb2, 0x89, 0x99, 0xa9, 0x2d, 0x55, 0x7d, 0xb0, 0xb0, 0x8a, 0xa8, 0x96,
+    0x36, 0x56, 0x76, 0xf1, 0xba, 0xa3, 0xb4, 0xb2, 0x80, 0xc0, 0xb8, 0xa8, 0x97, 0x11, 0xb2, 0x83,
+    0x98, 0xba, 0xa3, 0xf0, 0x24, 0x08, 0x44, 0x10, 0x64, 0x18, 0xb2, 0xb9, 0xb4, 0x98, 0x83, 0xf1,
+    0xa3, 0x29, 0x55, 0x7d, 0xba, 0xb5, 0xb1, 0xa3, 0x83, 0x93, 0xf0, 0x00, 0x28, 0x50, 0xf5, 0xb2,
+    0xb6, 0xaa, 0x83, 0x93, 0x28, 0x54, 0x7c, 0xf1, 0xb9, 0xa3, 0x82, 0x93, 0x61, 0xba, 0xa2, 0xda,
+    0xde, 0xdf, 0xdb, 0x81, 0x9a, 0xb9, 0xae, 0xf5, 0x60, 0x68, 0x70, 0xf1, 0xda, 0xba, 0xa2, 0xdf,
+    0xd9, 0xba, 0xa2, 0xfa, 0xb9, 0xa3, 0x82, 0x92, 0xdb, 0x31, 0xba, 0xa2, 0xd9, 0xba, 0xa2, 0xf8,
+    0xdf, 0x85, 0xa4, 0xd0, 0xc1, 0xbb, 0xad, 0x83, 0xc2, 0xc5, 0xc7, 0xb8, 0xa2, 0xdf, 0xdf, 0xdf,
+    0xba, 0xa0, 0xdf, 0xdf, 0xdf, 0xd8, 0xd8, 0xf1, 0xb8, 0xaa, 0xb3, 0x8d, 0xb4, 0x98, 0x0d, 0x35,
+    0x5d, 0xb2, 0xb6, 0xba, 0xaf, 0x8c, 0x96, 0x19, 0x8f, 0x9f, 0xa7, 0x0e, 0x16, 0x1e, 0xb4, 0x9a,
+    0xb8, 0xaa, 0x87, 0x2c, 0x54, 0x7c, 0xba, 0xa4, 0xb0, 0x8a, 0xb6, 0x91, 0x32, 0x56, 0x76, 0xb2,
+    0x84, 0x94, 0xa4, 0xc8, 0x08, 0xcd, 0xd8, 0xb8, 0xb4, 0xb0, 0xf1, 0x99, 0x82, 0xa8, 0x2d, 0x55,
+    0x7d, 0x98, 0xa8, 0x0e, 0x16, 0x1e, 0xa2, 0x2c, 0x54, 0x7c, 0x92, 0xa4, 0xf0, 0x2c, 0x50, 0x78,
+    /* bank # 5 */
+    0xf1, 0x84, 0xa8, 0x98, 0xc4, 0xcd, 0xfc, 0xd8, 0x0d, 0xdb, 0xa8, 0xfc, 0x2d, 0xf3, 0xd9, 0xba,
+    0xa6, 0xf8, 0xda, 0xba, 0xa6, 0xde, 0xd8, 0xba, 0xb2, 0xb6, 0x86, 0x96, 0xa6, 0xd0, 0xf3, 0xc8,
+    0x41, 0xda, 0xa6, 0xc8, 0xf8, 0xd8, 0xb0, 0xb4, 0xb8, 0x82, 0xa8, 0x92, 0xf5, 0x2c, 0x54, 0x88,
+    0x98, 0xf1, 0x35, 0xd9, 0xf4, 0x18, 0xd8, 0xf1, 0xa2, 0xd0, 0xf8, 0xf9, 0xa8, 0x84, 0xd9, 0xc7,
+    0xdf, 0xf8, 0xf8, 0x83, 0xc5, 0xda, 0xdf, 0x69, 0xdf, 0x83, 0xc1, 0xd8, 0xf4, 0x01, 0x14, 0xf1,
+    0xa8, 0x82, 0x4e, 0xa8, 0x84, 0xf3, 0x11, 0xd1, 0x82, 0xf5, 0xd9, 0x92, 0x28, 0x97, 0x88, 0xf1,
+    0x09, 0xf4, 0x1c, 0x1c, 0xd8, 0x84, 0xa8, 0xf3, 0xc0, 0xf9, 0xd1, 0xd9, 0x97, 0x82, 0xf1, 0x29,
+    0xf4, 0x0d, 0xd8, 0xf3, 0xf9, 0xf9, 0xd1, 0xd9, 0x82, 0xf4, 0xc2, 0x03, 0xd8, 0xde, 0xdf, 0x1a,
+    0xd8, 0xf1, 0xa2, 0xfa, 0xf9, 0xa8, 0x84, 0x98, 0xd9, 0xc7, 0xdf, 0xf8, 0xf8, 0xf8, 0x83, 0xc7,
+    0xda, 0xdf, 0x69, 0xdf, 0xf8, 0x83, 0xc3, 0xd8, 0xf4, 0x01, 0x14, 0xf1, 0x98, 0xa8, 0x82, 0x2e,
+    0xa8, 0x84, 0xf3, 0x11, 0xd1, 0x82, 0xf5, 0xd9, 0x92, 0x50, 0x97, 0x88, 0xf1, 0x09, 0xf4, 0x1c,
+    0xd8, 0x84, 0xa8, 0xf3, 0xc0, 0xf8, 0xf9, 0xd1, 0xd9, 0x97, 0x82, 0xf1, 0x49, 0xf4, 0x0d, 0xd8,
+    0xf3, 0xf9, 0xf9, 0xd1, 0xd9, 0x82, 0xf4, 0xc4, 0x03, 0xd8, 0xde, 0xdf, 0xd8, 0xf1, 0xad, 0x88,
+    0x98, 0xcc, 0xa8, 0x09, 0xf9, 0xd9, 0x82, 0x92, 0xa8, 0xf5, 0x7c, 0xf1, 0x88, 0x3a, 0xcf, 0x94,
+    0x4a, 0x6e, 0x98, 0xdb, 0x69, 0x31, 0xda, 0xad, 0xf2, 0xde, 0xf9, 0xd8, 0x87, 0x95, 0xa8, 0xf2,
+    0x21, 0xd1, 0xda, 0xa5, 0xf9, 0xf4, 0x17, 0xd9, 0xf1, 0xae, 0x8e, 0xd0, 0xc0, 0xc3, 0xae, 0x82,
+    /* bank # 6 */
+    0xc6, 0x84, 0xc3, 0xa8, 0x85, 0x95, 0xc8, 0xa5, 0x88, 0xf2, 0xc0, 0xf1, 0xf4, 0x01, 0x0e, 0xf1,
+    0x8e, 0x9e, 0xa8, 0xc6, 0x3e, 0x56, 0xf5, 0x54, 0xf1, 0x88, 0x72, 0xf4, 0x01, 0x15, 0xf1, 0x98,
+    0x45, 0x85, 0x6e, 0xf5, 0x8e, 0x9e, 0x04, 0x88, 0xf1, 0x42, 0x98, 0x5a, 0x8e, 0x9e, 0x06, 0x88,
+    0x69, 0xf4, 0x01, 0x1c, 0xf1, 0x98, 0x1e, 0x11, 0x08, 0xd0, 0xf5, 0x04, 0xf1, 0x1e, 0x97, 0x02,
+    0x02, 0x98, 0x36, 0x25, 0xdb, 0xf9, 0xd9, 0x85, 0xa5, 0xf3, 0xc1, 0xda, 0x85, 0xa5, 0xf3, 0xdf,
+    0xd8, 0x85, 0x95, 0xa8, 0xf3, 0x09, 0xda, 0xa5, 0xfa, 0xd8, 0x82, 0x92, 0xa8, 0xf5, 0x78, 0xf1,
+    0x88, 0x1a, 0x84, 0x9f, 0x26, 0x88, 0x98, 0x21, 0xda, 0xf4, 0x1d, 0xf3, 0xd8, 0x87, 0x9f, 0x39,
+    0xd1, 0xaf, 0xd9, 0xdf, 0xdf, 0xfb, 0xf9, 0xf4, 0x0c, 0xf3, 0xd8, 0xfa, 0xd0, 0xf8, 0xda, 0xf9,
+    0xf9, 0xd0, 0xdf, 0xd9, 0xf9, 0xd8, 0xf4, 0x0b, 0xd8, 0xf3, 0x87, 0x9f, 0x39, 0xd1, 0xaf, 0xd9,
+    0xdf, 0xdf, 0xf4, 0x1d, 0xf3, 0xd8, 0xfa, 0xfc, 0xa8, 0x69, 0xf9, 0xf9, 0xaf, 0xd0, 0xda, 0xde,
+    0xfa, 0xd9, 0xf8, 0x8f, 0x9f, 0xa8, 0xf1, 0xcc, 0xf3, 0x98, 0xdb, 0x45, 0xd9, 0xaf, 0xdf, 0xd0,
+    0xf8, 0xd8, 0xf1, 0x8f, 0x9f, 0xa8, 0xca, 0xf3, 0x88, 0x09, 0xda, 0xaf, 0x8f, 0xcb, 0xf8, 0xd8,
+    0xf2, 0xad, 0x97, 0x8d, 0x0c, 0xd9, 0xa5, 0xdf, 0xf9, 0xba, 0xa6, 0xf3, 0xfa, 0xf4, 0x12, 0xf2,
+    0xd8, 0x95, 0x0d, 0xd1, 0xd9, 0xba, 0xa6, 0xf3, 0xfa, 0xda, 0xa5, 0xf2, 0xc1, 0xba, 0xa6, 0xf3,
+    0xdf, 0xd8, 0xf1, 0xba, 0xb2, 0xb6, 0x86, 0x96, 0xa6, 0xd0, 0xca, 0xf3, 0x49, 0xda, 0xa6, 0xcb,
+    0xf8, 0xd8, 0xb0, 0xb4, 0xb8, 0xd8, 0xad, 0x84, 0xf2, 0xc0, 0xdf, 0xf1, 0x8f, 0xcb, 0xc3, 0xa8,
+    /* bank # 7 */
+    0xb2, 0xb6, 0x86, 0x96, 0xc8, 0xc1, 0xcb, 0xc3, 0xf3, 0xb0, 0xb4, 0x88, 0x98, 0xa8, 0x21, 0xdb,
+    0x71, 0x8d, 0x9d, 0x71, 0x85, 0x95, 0x21, 0xd9, 0xad, 0xf2, 0xfa, 0xd8, 0x85, 0x97, 0xa8, 0x28,
+    0xd9, 0xf4, 0x08, 0xd8, 0xf2, 0x8d, 0x29, 0xda, 0xf4, 0x05, 0xd9, 0xf2, 0x85, 0xa4, 0xc2, 0xf2,
+    0xd8, 0xa8, 0x8d, 0x94, 0x01, 0xd1, 0xd9, 0xf4, 0x11, 0xf2, 0xd8, 0x87, 0x21, 0xd8, 0xf4, 0x0a,
+    0xd8, 0xf2, 0x84, 0x98, 0xa8, 0xc8, 0x01, 0xd1, 0xd9, 0xf4, 0x11, 0xd8, 0xf3, 0xa4, 0xc8, 0xbb,
+    0xaf, 0xd0, 0xf2, 0xde, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xd8, 0xf1, 0xb8, 0xf6,
+    0xb5, 0xb9, 0xb0, 0x8a, 0x95, 0xa3, 0xde, 0x3c, 0xa3, 0xd9, 0xf8, 0xd8, 0x5c, 0xa3, 0xd9, 0xf8,
+    0xd8, 0x7c, 0xa3, 0xd9, 0xf8, 0xd8, 0xf8, 0xf9, 0xd1, 0xa5, 0xd9, 0xdf, 0xda, 0xfa, 0xd8, 0xb1,
+    0x85, 0x30, 0xf7, 0xd9, 0xde, 0xd8, 0xf8, 0x30, 0xad, 0xda, 0xde, 0xd8, 0xf2, 0xb4, 0x8c, 0x99,
+    0xa3, 0x2d, 0x55, 0x7d, 0xa0, 0x83, 0xdf, 0xdf, 0xdf, 0xb5, 0x91, 0xa0, 0xf6, 0x29, 0xd9, 0xfb,
+    0xd8, 0xa0, 0xfc, 0x29, 0xd9, 0xfa, 0xd8, 0xa0, 0xd0, 0x51, 0xd9, 0xf8, 0xd8, 0xfc, 0x51, 0xd9,
+    0xf9, 0xd8, 0x79, 0xd9, 0xfb, 0xd8, 0xa0, 0xd0, 0xfc, 0x79, 0xd9, 0xfa, 0xd8, 0xa1, 0xf9, 0xf9,
+    0xf9, 0xf9, 0xf9, 0xa0, 0xda, 0xdf, 0xdf, 0xdf, 0xd8, 0xa1, 0xf8, 0xf8, 0xf8, 0xf8, 0xf8, 0xac,
+    0xde, 0xf8, 0xad, 0xde, 0x83, 0x93, 0xac, 0x2c, 0x54, 0x7c, 0xf1, 0xa8, 0xdf, 0xdf, 0xdf, 0xf6,
+    0x9d, 0x2c, 0xda, 0xa0, 0xdf, 0xd9, 0xfa, 0xdb, 0x2d, 0xf8, 0xd8, 0xa8, 0x50, 0xda, 0xa0, 0xd0,
+    0xde, 0xd9, 0xd0, 0xf8, 0xf8, 0xf8, 0xdb, 0x55, 0xf8, 0xd8, 0xa8, 0x78, 0xda, 0xa0, 0xd0, 0xdf,
+    /* bank # 8 */
+    0xd9, 0xd0, 0xfa, 0xf8, 0xf8, 0xf8, 0xf8, 0xdb, 0x7d, 0xf8, 0xd8, 0x9c, 0xa8, 0x8c, 0xf5, 0x30,
+    0xdb, 0x38, 0xd9, 0xd0, 0xde, 0xdf, 0xa0, 0xd0, 0xde, 0xdf, 0xd8, 0xa8, 0x48, 0xdb, 0x58, 0xd9,
+    0xdf, 0xd0, 0xde, 0xa0, 0xdf, 0xd0, 0xde, 0xd8, 0xa8, 0x68, 0xdb, 0x70, 0xd9, 0xdf, 0xdf, 0xa0,
+    0xdf, 0xdf, 0xd8, 0xf1, 0xa8, 0x88, 0x90, 0x2c, 0x54, 0x7c, 0x98, 0xa8, 0xd0, 0x5c, 0x38, 0xd1,
+    0xda, 0xf2, 0xae, 0x8c, 0xdf, 0xf9, 0xd8, 0xb0, 0x87, 0xa8, 0xc1, 0xc1, 0xb1, 0x88, 0xa8, 0xc6,
+    0xf9, 0xf9, 0xda, 0x36, 0xd8, 0xa8, 0xf9, 0xda, 0x36, 0xd8, 0xa8, 0xf9, 0xda, 0x36, 0xd8, 0xa8,
+    0xf9, 0xda, 0x36, 0xd8, 0xa8, 0xf9, 0xda, 0x36, 0xd8, 0xf7, 0x8d, 0x9d, 0xad, 0xf8, 0x18, 0xda,
+    0xf2, 0xae, 0xdf, 0xd8, 0xf7, 0xad, 0xfa, 0x30, 0xd9, 0xa4, 0xde, 0xf9, 0xd8, 0xf2, 0xae, 0xde,
+    0xfa, 0xf9, 0x83, 0xa7, 0xd9, 0xc3, 0xc5, 0xc7, 0xf1, 0x88, 0x9b, 0xa7, 0x7a, 0xad, 0xf7, 0xde,
+    0xdf, 0xa4, 0xf8, 0x84, 0x94, 0x08, 0xa7, 0x97, 0xf3, 0x00, 0xae, 0xf2, 0x98, 0x19, 0xa4, 0x88,
+    0xc6, 0xa3, 0x94, 0x88, 0xf6, 0x32, 0xdf, 0xf2, 0x83, 0x93, 0xdb, 0x09, 0xd9, 0xf2, 0xaa, 0xdf,
+    0xd8, 0xd8, 0xae, 0xf8, 0xf9, 0xd1, 0xda, 0xf3, 0xa4, 0xde, 0xa7, 0xf1, 0x88, 0x9b, 0x7a, 0xd8,
+    0xf3, 0x84, 0x94, 0xae, 0x19, 0xf9, 0xda, 0xaa, 0xf1, 0xdf, 0xd8, 0xa8, 0x81, 0xc0, 0xc3, 0xc5,
+    0xc7, 0xa3, 0x92, 0x83, 0xf6, 0x28, 0xad, 0xde, 0xd9, 0xf8, 0xd8, 0xa3, 0x50, 0xad, 0xd9, 0xf8,
+    0xd8, 0xa3, 0x78, 0xad, 0xd9, 0xf8, 0xd8, 0xf8, 0xf9, 0xd1, 0xa1, 0xda, 0xde, 0xc3, 0xc5, 0xc7,
+    0xd8, 0xa1, 0x81, 0x94, 0xf8, 0x18, 0xf2, 0xb0, 0x89, 0xac, 0xc3, 0xc5, 0xc7, 0xf1, 0xd8, 0xb8,
+    /* bank # 9 */
+    0xb4, 0xb0, 0x97, 0x86, 0xa8, 0x31, 0x9b, 0x06, 0x99, 0x07, 0xab, 0x97, 0x28, 0x88, 0x9b, 0xf0,
+    0x0c, 0x20, 0x14, 0x40, 0xb0, 0xb4, 0xb8, 0xf0, 0xa8, 0x8a, 0x9a, 0x28, 0x50, 0x78, 0xb7, 0x9b,
+    0xa8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31, 0xf1, 0xbb, 0xab,
+    0x88, 0x00, 0x2c, 0x54, 0x7c, 0xf0, 0xb3, 0x8b, 0xb8, 0xa8, 0x04, 0x28, 0x50, 0x78, 0xf1, 0xb0,
+    0x88, 0xb4, 0x97, 0x26, 0xa8, 0x59, 0x98, 0xbb, 0xab, 0xb3, 0x8b, 0x02, 0x26, 0x46, 0x66, 0xb0,
+    0xb8, 0xf0, 0x8a, 0x9c, 0xa8, 0x29, 0x51, 0x79, 0x8b, 0x29, 0x51, 0x79, 0x8a, 0x24, 0x70, 0x59,
+    0x8b, 0x20, 0x58, 0x71, 0x8a, 0x44, 0x69, 0x38, 0x8b, 0x39, 0x40, 0x68, 0x8a, 0x64, 0x48, 0x31,
+    0x8b, 0x30, 0x49, 0x60, 0x88, 0xf1, 0xac, 0x00, 0x2c, 0x54, 0x7c, 0xf0, 0x8c, 0xa8, 0x04, 0x28,
+    0x50, 0x78, 0xf1, 0x88, 0x97, 0x26, 0xa8, 0x59, 0x98, 0xac, 0x8c, 0x02, 0x26, 0x46, 0x66, 0xf0,
+    0x89, 0x9c, 0xa8, 0x29, 0x51, 0x79, 0x24, 0x70, 0x59, 0x44, 0x69, 0x38, 0x64, 0x48, 0x31, 0xa9,
+    0x88, 0x09, 0x20, 0x59, 0x70, 0xab, 0x11, 0x38, 0x40, 0x69, 0xa8, 0x19, 0x31, 0x48, 0x60, 0x8c,
+    0xa8, 0x3c, 0x41, 0x5c, 0x20, 0x7c, 0x00, 0xf1, 0x87, 0x98, 0x19, 0x86, 0xa8, 0x6e, 0x76, 0x7e,
+    0xa9, 0x99, 0x88, 0x2d, 0x55, 0x7d, 0xd8, 0xb1, 0xb5, 0xb9, 0xa3, 0xdf, 0xdf, 0xdf, 0xae, 0xd0,
+    0xdf, 0xaa, 0xd0, 0xde, 0xf2, 0xab, 0xf8, 0xf9, 0xd9, 0xb0, 0x87, 0xc4, 0xaa, 0xf1, 0xdf, 0xdf,
+    0xbb, 0xaf, 0xdf, 0xdf, 0xb9, 0xd8, 0xb1, 0xf1, 0xa3, 0x97, 0x8e, 0x60, 0xdf, 0xb0, 0x84, 0xf2,
+    0xc8, 0xf8, 0xf9, 0xd9, 0xde, 0xd8, 0x93, 0x85, 0xf1, 0x4a, 0xb1, 0x83, 0xa3, 0x08, 0xb5, 0x83,
+    /* bank # 10 */
+    0x9a, 0x08, 0x10, 0xb7, 0x9f, 0x10, 0xd8, 0xf1, 0xb0, 0xba, 0xae, 0xb0, 0x8a, 0xc2, 0xb2, 0xb6,
+    0x8e, 0x9e, 0xf1, 0xfb, 0xd9, 0xf4, 0x1d, 0xd8, 0xf9, 0xd9, 0x0c, 0xf1, 0xd8, 0xf8, 0xf8, 0xad,
+    0x61, 0xd9, 0xae, 0xfb, 0xd8, 0xf4, 0x0c, 0xf1, 0xd8, 0xf8, 0xf8, 0xad, 0x19, 0xd9, 0xae, 0xfb,
+    0xdf, 0xd8, 0xf4, 0x16, 0xf1, 0xd8, 0xf8, 0xad, 0x8d, 0x61, 0xd9, 0xf4, 0xf4, 0xac, 0xf5, 0x9c,
+    0x9c, 0x8d, 0xdf, 0x2b, 0xba, 0xb6, 0xae, 0xfa, 0xf8, 0xf4, 0x0b, 0xd8, 0xf1, 0xae, 0xd0, 0xf8,
+    0xad, 0x51, 0xda, 0xae, 0xfa, 0xf8, 0xf1, 0xd8, 0xb9, 0xb1, 0xb6, 0xa3, 0x83, 0x9c, 0x08, 0xb9,
+    0xb1, 0x83, 0x9a, 0xb5, 0xaa, 0xc0, 0xfd, 0x30, 0x83, 0xb7, 0x9f, 0x10, 0xb5, 0x8b, 0x93, 0xf2,
+    0x02, 0x02, 0xd1, 0xab, 0xda, 0xde, 0xd8, 0xf1, 0xb0, 0x80, 0xba, 0xab, 0xc0, 0xc3, 0xb2, 0x84,
+    0xc1, 0xc3, 0xd8, 0xb1, 0xb9, 0xf3, 0x8b, 0xa3, 0x91, 0xb6, 0x09, 0xb4, 0xd9, 0xab, 0xde, 0xb0,
+    0x87, 0x9c, 0xb9, 0xa3, 0xdd, 0xf1, 0xb3, 0x8b, 0x8b, 0x8b, 0x8b, 0x8b, 0xb0, 0x87, 0xa3, 0xa3,
+    0xa3, 0xa3, 0xb2, 0x8b, 0xb6, 0x9b, 0xf2, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3,
+    0xa3, 0xf1, 0xb0, 0x87, 0xb5, 0x9a, 0xa3, 0xf3, 0x9b, 0xa3, 0xa3, 0xdc, 0xba, 0xac, 0xdf, 0xb9,
+    0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3, 0xa3,
+    0xd8, 0xd8, 0xd8, 0xbb, 0xb3, 0xb7, 0xf1, 0xaa, 0xf9, 0xda, 0xff, 0xd9, 0x80, 0x9a, 0xaa, 0x28,
+    0xb4, 0x80, 0x98, 0xa7, 0x20, 0xb7, 0x97, 0x87, 0xa8, 0x66, 0x88, 0xf0, 0x79, 0x51, 0xf1, 0x90,
+    0x2c, 0x87, 0x0c, 0xa7, 0x81, 0x97, 0x62, 0x93, 0xf0, 0x71, 0x71, 0x60, 0x85, 0x94, 0x01, 0x29,
+    /* bank # 11 */
+    0x51, 0x79, 0x90, 0xa5, 0xf1, 0x28, 0x4c, 0x6c, 0x87, 0x0c, 0x95, 0x18, 0x85, 0x78, 0xa3, 0x83,
+    0x90, 0x28, 0x4c, 0x6c, 0x88, 0x6c, 0xd8, 0xf3, 0xa2, 0x82, 0x00, 0xf2, 0x10, 0xa8, 0x92, 0x19,
+    0x80, 0xa2, 0xf2, 0xd9, 0x26, 0xd8, 0xf1, 0x88, 0xa8, 0x4d, 0xd9, 0x48, 0xd8, 0x96, 0xa8, 0x39,
+    0x80, 0xd9, 0x3c, 0xd8, 0x95, 0x80, 0xa8, 0x39, 0xa6, 0x86, 0x98, 0xd9, 0x2c, 0xda, 0x87, 0xa7,
+    0x2c, 0xd8, 0xa8, 0x89, 0x95, 0x19, 0xa9, 0x80, 0xd9, 0x38, 0xd8, 0xa8, 0x89, 0x39, 0xa9, 0x80,
+    0xda, 0x3c, 0xd8, 0xa8, 0x2e, 0xa8, 0x39, 0x90, 0xd9, 0x0c, 0xd8, 0xa8, 0x95, 0x31, 0x98, 0xd9,
+    0x0c, 0xd8, 0xa8, 0x09, 0xd9, 0xff, 0xd8, 0x01, 0xda, 0xff, 0xd8, 0x95, 0x39, 0xa9, 0xda, 0x26,
+    0xff, 0xd8, 0x90, 0xa8, 0x0d, 0x89, 0x99, 0xa8, 0x10, 0x80, 0x98, 0x21, 0xda, 0x2e, 0xd8, 0x89,
+    0x99, 0xa8, 0x31, 0x80, 0xda, 0x2e, 0xd8, 0xa8, 0x86, 0x96, 0x31, 0x80, 0xda, 0x2e, 0xd8, 0xa8,
+    0x87, 0x31, 0x80, 0xda, 0x2e, 0xd8, 0xa8, 0x82, 0x92, 0xf3, 0x41, 0x80, 0xf1, 0xd9, 0x2e, 0xd8,
+    0xa8, 0x82, 0xf3, 0x19, 0x80, 0xf1, 0xd9, 0x2e, 0xd8, 0x82, 0xac, 0xf3, 0xc0, 0xa2, 0x80, 0x22,
+    0xf1, 0xa6, 0x2e, 0xa7, 0x2e, 0xa9, 0x22, 0x98, 0xa8, 0x29, 0xda, 0xac, 0xde, 0xff, 0xd8, 0xa2,
+    0xf2, 0x2a, 0xf1, 0xa9, 0x2e, 0x82, 0x92, 0xa8, 0xf2, 0x31, 0x80, 0xa6, 0x96, 0xf1, 0xd9, 0x00,
+    0xac, 0x8c, 0x9c, 0x0c, 0x30, 0xac, 0xde, 0xd0, 0xde, 0xff, 0xd8, 0x8c, 0x9c, 0xac, 0xd0, 0x10,
+    0xac, 0xde, 0x80, 0x92, 0xa2, 0xf2, 0x4c, 0x82, 0xa8, 0xf1, 0xca, 0xf2, 0x35, 0xf1, 0x96, 0x88,
+    0xa6, 0xd9, 0x00, 0xd8, 0xf1, 0xff
+};
+
+static const unsigned short sStartAddress = 0x0400;
+
+/* END OF SECTION COPIED FROM dmpDefaultMPU6050.c */
+
+#define INT_SRC_TAP             (0x01)
+#define INT_SRC_ANDROID_ORIENT  (0x08)
+
+#define DMP_FEATURE_SEND_ANY_GYRO   (DMP_FEATURE_SEND_RAW_GYRO | \
+                                     DMP_FEATURE_SEND_CAL_GYRO)
+
+#define MAX_PACKET_LENGTH   (32)
+
+#define DMP_SAMPLE_RATE     (200)
+#define GYRO_SF             (46850825LL * 200 / DMP_SAMPLE_RATE)
+
+#define FIFO_CORRUPTION_CHECK
+#ifdef FIFO_CORRUPTION_CHECK
+#define QUAT_ERROR_THRESH       (1L<<24)
+#define QUAT_MAG_SQ_NORMALIZED  (1L<<28)
+#define QUAT_MAG_SQ_MIN         (QUAT_MAG_SQ_NORMALIZED - QUAT_ERROR_THRESH)
+#define QUAT_MAG_SQ_MAX         (QUAT_MAG_SQ_NORMALIZED + QUAT_ERROR_THRESH)
+#endif
+
+struct dmp_s {
+    void (*tap_cb)(unsigned char count, unsigned char direction);
+    void (*android_orient_cb)(unsigned char orientation);
+    unsigned short orient;
+    unsigned short feature_mask;
+    unsigned short fifo_rate;
+    unsigned char packet_length;
+};
+
+struct dmp_s dmpArray[MPU_MAX_DEVICES];
+
+struct dmp_s *dmp;
+static int deviceIndex = 0;
+
+int dmp_select_device(int device)
+{
+  if ((device < 0) || (device >= MPU_MAX_DEVICES))
+    return -1;
+
+  deviceIndex = device;
+  dmp = dmpArray + device;
+  return 0;
+}
+
+void dmp_init_structures()
+{
+  dmp->tap_cb = NULL;
+  dmp->android_orient_cb = NULL;
+  dmp->orient = 0;
+  dmp->feature_mask = 0;
+  dmp->fifo_rate = 0;
+  dmp->packet_length = 0;
+}
+
+/**
+ *  @brief  Load the DMP with this image.
+ *  @return 0 if successful.
+ */
+int dmp_load_motion_driver_firmware(void)
+{
+    return mpu_load_firmware(DMP_CODE_SIZE, dmp_memory, sStartAddress,
+        DMP_SAMPLE_RATE);
+}
+
+/**
+ *  @brief      Push gyro and accel orientation to the dmp->
+ *  The orientation is represented here as the output of
+ *  @e inv_orientation_matrix_to_scalar.
+ *  @param[in]  orient  Gyro and accel orientation in body frame.
+ *  @return     0 if successful.
+ */
+int dmp_set_orientation(unsigned short orient)
+{
+    unsigned char gyro_regs[3], accel_regs[3];
+    const unsigned char gyro_axes[3] = {DINA4C, DINACD, DINA6C};
+    const unsigned char accel_axes[3] = {DINA0C, DINAC9, DINA2C};
+    const unsigned char gyro_sign[3] = {DINA36, DINA56, DINA76};
+    const unsigned char accel_sign[3] = {DINA26, DINA46, DINA66};
+
+    gyro_regs[0] = gyro_axes[orient & 3];
+    gyro_regs[1] = gyro_axes[(orient >> 3) & 3];
+    gyro_regs[2] = gyro_axes[(orient >> 6) & 3];
+    accel_regs[0] = accel_axes[orient & 3];
+    accel_regs[1] = accel_axes[(orient >> 3) & 3];
+    accel_regs[2] = accel_axes[(orient >> 6) & 3];
+
+    /* Chip-to-body, axes only. */
+    if (mpu_write_mem(FCFG_1, 3, gyro_regs))
+        return -1;
+    if (mpu_write_mem(FCFG_2, 3, accel_regs))
+        return -1;
+
+    memcpy(gyro_regs, gyro_sign, 3);
+    memcpy(accel_regs, accel_sign, 3);
+    if (orient & 4) {
+        gyro_regs[0] |= 1;
+        accel_regs[0] |= 1;
+    }
+    if (orient & 0x20) {
+        gyro_regs[1] |= 1;
+        accel_regs[1] |= 1;
+    }
+    if (orient & 0x100) {
+        gyro_regs[2] |= 1;
+        accel_regs[2] |= 1;
+    }
+
+    /* Chip-to-body, sign only. */
+    if (mpu_write_mem(FCFG_3, 3, gyro_regs))
+        return -1;
+    if (mpu_write_mem(FCFG_7, 3, accel_regs))
+        return -1;
+    dmp->orient = orient;
+    return 0;
+}
+
+/**
+ *  @brief      Push gyro biases to the dmp->
+ *  Because the gyro integration is handled in the DMP, any gyro biases
+ *  calculated by the MPL should be pushed down to DMP memory to remove
+ *  3-axis quaternion drift.
+ *  \n NOTE: If the DMP-based gyro calibration is enabled, the DMP will
+ *  overwrite the biases written to this location once a new one is computed.
+ *  @param[in]  bias    Gyro biases in q16.
+ *  @return     0 if successful.
+ */
+int dmp_set_gyro_bias(long *bias)
+{
+    long gyro_bias_body[3];
+    unsigned char regs[4];
+
+    gyro_bias_body[0] = bias[dmp->orient & 3];
+    if (dmp->orient & 4)
+        gyro_bias_body[0] *= -1;
+    gyro_bias_body[1] = bias[(dmp->orient >> 3) & 3];
+    if (dmp->orient & 0x20)
+        gyro_bias_body[1] *= -1;
+    gyro_bias_body[2] = bias[(dmp->orient >> 6) & 3];
+    if (dmp->orient & 0x100)
+        gyro_bias_body[2] *= -1;
+
+#ifdef EMPL_NO_64BIT
+    gyro_bias_body[0] = (long)(((float)gyro_bias_body[0] * GYRO_SF) / 1073741824.f);
+    gyro_bias_body[1] = (long)(((float)gyro_bias_body[1] * GYRO_SF) / 1073741824.f);
+    gyro_bias_body[2] = (long)(((float)gyro_bias_body[2] * GYRO_SF) / 1073741824.f);
+#else
+    gyro_bias_body[0] = (long)(((long long)gyro_bias_body[0] * GYRO_SF) >> 30);
+    gyro_bias_body[1] = (long)(((long long)gyro_bias_body[1] * GYRO_SF) >> 30);
+    gyro_bias_body[2] = (long)(((long long)gyro_bias_body[2] * GYRO_SF) >> 30);
+#endif
+
+    regs[0] = (unsigned char)((gyro_bias_body[0] >> 24) & 0xFF);
+    regs[1] = (unsigned char)((gyro_bias_body[0] >> 16) & 0xFF);
+    regs[2] = (unsigned char)((gyro_bias_body[0] >> 8) & 0xFF);
+    regs[3] = (unsigned char)(gyro_bias_body[0] & 0xFF);
+    if (mpu_write_mem(D_EXT_GYRO_BIAS_X, 4, regs))
+        return -1;
+
+    regs[0] = (unsigned char)((gyro_bias_body[1] >> 24) & 0xFF);
+    regs[1] = (unsigned char)((gyro_bias_body[1] >> 16) & 0xFF);
+    regs[2] = (unsigned char)((gyro_bias_body[1] >> 8) & 0xFF);
+    regs[3] = (unsigned char)(gyro_bias_body[1] & 0xFF);
+    if (mpu_write_mem(D_EXT_GYRO_BIAS_Y, 4, regs))
+        return -1;
+
+    regs[0] = (unsigned char)((gyro_bias_body[2] >> 24) & 0xFF);
+    regs[1] = (unsigned char)((gyro_bias_body[2] >> 16) & 0xFF);
+    regs[2] = (unsigned char)((gyro_bias_body[2] >> 8) & 0xFF);
+    regs[3] = (unsigned char)(gyro_bias_body[2] & 0xFF);
+    return mpu_write_mem(D_EXT_GYRO_BIAS_Z, 4, regs);
+}
+
+/**
+ *  @brief      Push accel biases to the dmp->
+ *  These biases will be removed from the DMP 6-axis quaternion.
+ *  @param[in]  bias    Accel biases in q16.
+ *  @return     0 if successful.
+ */
+int dmp_set_accel_bias(long *bias)
+{
+    long accel_bias_body[3];
+    unsigned char regs[12];
+    long long accel_sf;
+    unsigned short accel_sens;
+
+    mpu_get_accel_sens(&accel_sens);
+    accel_sf = (long long)accel_sens << 15;
+    delay(1);
+
+    accel_bias_body[0] = bias[dmp->orient & 3];
+    if (dmp->orient & 4)
+        accel_bias_body[0] *= -1;
+    accel_bias_body[1] = bias[(dmp->orient >> 3) & 3];
+    if (dmp->orient & 0x20)
+        accel_bias_body[1] *= -1;
+    accel_bias_body[2] = bias[(dmp->orient >> 6) & 3];
+    if (dmp->orient & 0x100)
+        accel_bias_body[2] *= -1;
+
+#ifdef EMPL_NO_64BIT
+    accel_bias_body[0] = (long)(((float)accel_bias_body[0] * accel_sf) / 1073741824.f);
+    accel_bias_body[1] = (long)(((float)accel_bias_body[1] * accel_sf) / 1073741824.f);
+    accel_bias_body[2] = (long)(((float)accel_bias_body[2] * accel_sf) / 1073741824.f);
+#else
+    accel_bias_body[0] = (long)(((long long)accel_bias_body[0] * accel_sf) >> 30);
+    accel_bias_body[1] = (long)(((long long)accel_bias_body[1] * accel_sf) >> 30);
+    accel_bias_body[2] = (long)(((long long)accel_bias_body[2] * accel_sf) >> 30);
+#endif
+
+    regs[0] = (unsigned char)((accel_bias_body[0] >> 24) & 0xFF);
+    regs[1] = (unsigned char)((accel_bias_body[0] >> 16) & 0xFF);
+    regs[2] = (unsigned char)((accel_bias_body[0] >> 8) & 0xFF);
+    regs[3] = (unsigned char)(accel_bias_body[0] & 0xFF);
+    regs[4] = (unsigned char)((accel_bias_body[1] >> 24) & 0xFF);
+    regs[5] = (unsigned char)((accel_bias_body[1] >> 16) & 0xFF);
+    regs[6] = (unsigned char)((accel_bias_body[1] >> 8) & 0xFF);
+    regs[7] = (unsigned char)(accel_bias_body[1] & 0xFF);
+    regs[8] = (unsigned char)((accel_bias_body[2] >> 24) & 0xFF);
+    regs[9] = (unsigned char)((accel_bias_body[2] >> 16) & 0xFF);
+    regs[10] = (unsigned char)((accel_bias_body[2] >> 8) & 0xFF);
+    regs[11] = (unsigned char)(accel_bias_body[2] & 0xFF);
+    return mpu_write_mem(D_ACCEL_BIAS, 12, regs);
+}
+
+/**
+ *  @brief      Set DMP output rate.
+ *  Only used when DMP is on.
+ *  @param[in]  rate    Desired fifo rate (Hz).
+ *  @return     0 if successful.
+ */
+int dmp_set_fifo_rate(unsigned short rate)
+{
+    const unsigned char regs_end[12] = {DINAFE, DINAF2, DINAAB,
+        0xc4, DINAAA, DINAF1, DINADF, DINADF, 0xBB, 0xAF, DINADF, DINADF};
+    unsigned short div;
+    unsigned char tmp[8];
+
+    if (rate > DMP_SAMPLE_RATE)
+        return -1;
+    div = DMP_SAMPLE_RATE / rate - 1;
+    tmp[0] = (unsigned char)((div >> 8) & 0xFF);
+    tmp[1] = (unsigned char)(div & 0xFF);
+    if (mpu_write_mem(D_0_22, 2, tmp))
+        return -1;
+    if (mpu_write_mem(CFG_6, 12, (unsigned char*)regs_end))
+        return -1;
+
+    dmp->fifo_rate = rate;
+    return 0;
+}
+
+/**
+ *  @brief      Get DMP output rate.
+ *  @param[out] rate    Current fifo rate (Hz).
+ *  @return     0 if successful.
+ */
+int dmp_get_fifo_rate(unsigned short *rate)
+{
+    rate[0] = dmp->fifo_rate;
+    return 0;
+}
+
+/**
+ *  @brief      Set tap threshold for a specific axis.
+ *  @param[in]  axis    1, 2, and 4 for XYZ accel, respectively.
+ *  @param[in]  thresh  Tap threshold, in mg/ms.
+ *  @return     0 if successful.
+ */
+int dmp_set_tap_thresh(unsigned char axis, unsigned short thresh)
+{
+    unsigned char tmp[4], accel_fsr;
+    float scaled_thresh;
+    unsigned short dmp_thresh, dmp_thresh_2;
+    if (!(axis & TAP_XYZ) || thresh > 1600)
+        return -1;
+
+    scaled_thresh = (float)thresh / DMP_SAMPLE_RATE;
+
+    mpu_get_accel_fsr(&accel_fsr);
+    switch (accel_fsr) {
+    case 2:
+        dmp_thresh = (unsigned short)(scaled_thresh * 16384);
+        /* dmp_thresh * 0.75 */
+        dmp_thresh_2 = (unsigned short)(scaled_thresh * 12288);
+        break;
+    case 4:
+        dmp_thresh = (unsigned short)(scaled_thresh * 8192);
+        /* dmp_thresh * 0.75 */
+        dmp_thresh_2 = (unsigned short)(scaled_thresh * 6144);
+        break;
+    case 8:
+        dmp_thresh = (unsigned short)(scaled_thresh * 4096);
+        /* dmp_thresh * 0.75 */
+        dmp_thresh_2 = (unsigned short)(scaled_thresh * 3072);
+        break;
+    case 16:
+        dmp_thresh = (unsigned short)(scaled_thresh * 2048);
+        /* dmp_thresh * 0.75 */
+        dmp_thresh_2 = (unsigned short)(scaled_thresh * 1536);
+        break;
+    default:
+        return -1;
+    }
+    tmp[0] = (unsigned char)(dmp_thresh >> 8);
+    tmp[1] = (unsigned char)(dmp_thresh & 0xFF);
+    tmp[2] = (unsigned char)(dmp_thresh_2 >> 8);
+    tmp[3] = (unsigned char)(dmp_thresh_2 & 0xFF);
+
+    if (axis & TAP_X) {
+        if (mpu_write_mem(DMP_TAP_THX, 2, tmp))
+            return -1;
+        if (mpu_write_mem(D_1_36, 2, tmp+2))
+            return -1;
+    }
+    if (axis & TAP_Y) {
+        if (mpu_write_mem(DMP_TAP_THY, 2, tmp))
+            return -1;
+        if (mpu_write_mem(D_1_40, 2, tmp+2))
+            return -1;
+    }
+    if (axis & TAP_Z) {
+        if (mpu_write_mem(DMP_TAP_THZ, 2, tmp))
+            return -1;
+        if (mpu_write_mem(D_1_44, 2, tmp+2))
+            return -1;
+    }
+    return 0;
+}
+
+/**
+ *  @brief      Set which axes will register a tap.
+ *  @param[in]  axis    1, 2, and 4 for XYZ, respectively.
+ *  @return     0 if successful.
+ */
+int dmp_set_tap_axes(unsigned char axis)
+{
+    unsigned char tmp = 0;
+
+    if (axis & TAP_X)
+        tmp |= 0x30;
+    if (axis & TAP_Y)
+        tmp |= 0x0C;
+    if (axis & TAP_Z)
+        tmp |= 0x03;
+    return mpu_write_mem(D_1_72, 1, &tmp);
+}
+
+/**
+ *  @brief      Set minimum number of taps needed for an interrupt.
+ *  @param[in]  min_taps    Minimum consecutive taps (1-4).
+ *  @return     0 if successful.
+ */
+int dmp_set_tap_count(unsigned char min_taps)
+{
+    unsigned char tmp;
+
+    if (min_taps < 1)
+        min_taps = 1;
+    else if (min_taps > 4)
+        min_taps = 4;
+
+    tmp = min_taps - 1;
+    return mpu_write_mem(D_1_79, 1, &tmp);
+}
+
+/**
+ *  @brief      Set length between valid taps.
+ *  @param[in]  time    Milliseconds between taps.
+ *  @return     0 if successful.
+ */
+int dmp_set_tap_time(unsigned short time)
+{
+    unsigned short dmp_time;
+    unsigned char tmp[2];
+
+    dmp_time = time / (1000 / DMP_SAMPLE_RATE);
+    tmp[0] = (unsigned char)(dmp_time >> 8);
+    tmp[1] = (unsigned char)(dmp_time & 0xFF);
+    return mpu_write_mem(DMP_TAPW_MIN, 2, tmp);
+}
+
+/**
+ *  @brief      Set max time between taps to register as a multi-tap.
+ *  @param[in]  time    Max milliseconds between taps.
+ *  @return     0 if successful.
+ */
+int dmp_set_tap_time_multi(unsigned short time)
+{
+    unsigned short dmp_time;
+    unsigned char tmp[2];
+
+    dmp_time = time / (1000 / DMP_SAMPLE_RATE);
+    tmp[0] = (unsigned char)(dmp_time >> 8);
+    tmp[1] = (unsigned char)(dmp_time & 0xFF);
+    return mpu_write_mem(D_1_218, 2, tmp);
+}
+
+/**
+ *  @brief      Set shake rejection threshold.
+ *  If the DMP detects a gyro sample larger than @e thresh, taps are rejected.
+ *  @param[in]  sf      Gyro scale factor.
+ *  @param[in]  thresh  Gyro threshold in dps.
+ *  @return     0 if successful.
+ */
+int dmp_set_shake_reject_thresh(long sf, unsigned short thresh)
+{
+    unsigned char tmp[4];
+    long thresh_scaled = sf / 1000 * thresh;
+    tmp[0] = (unsigned char)(((long)thresh_scaled >> 24) & 0xFF);
+    tmp[1] = (unsigned char)(((long)thresh_scaled >> 16) & 0xFF);
+    tmp[2] = (unsigned char)(((long)thresh_scaled >> 8) & 0xFF);
+    tmp[3] = (unsigned char)((long)thresh_scaled & 0xFF);
+    return mpu_write_mem(D_1_92, 4, tmp);
+}
+
+/**
+ *  @brief      Set shake rejection time.
+ *  Sets the length of time that the gyro must be outside of the threshold set
+ *  by @e gyro_set_shake_reject_thresh before taps are rejected. A mandatory
+ *  60 ms is added to this parameter.
+ *  @param[in]  time    Time in milliseconds.
+ *  @return     0 if successful.
+ */
+int dmp_set_shake_reject_time(unsigned short time)
+{
+    unsigned char tmp[2];
+
+    time /= (1000 / DMP_SAMPLE_RATE);
+    tmp[0] = time >> 8;
+    tmp[1] = time & 0xFF;
+    return mpu_write_mem(D_1_90,2,tmp);
+}
+
+/**
+ *  @brief      Set shake rejection timeout.
+ *  Sets the length of time after a shake rejection that the gyro must stay
+ *  inside of the threshold before taps can be detected again. A mandatory
+ *  60 ms is added to this parameter.
+ *  @param[in]  time    Time in milliseconds.
+ *  @return     0 if successful.
+ */
+int dmp_set_shake_reject_timeout(unsigned short time)
+{
+    unsigned char tmp[2];
+
+    time /= (1000 / DMP_SAMPLE_RATE);
+    tmp[0] = time >> 8;
+    tmp[1] = time & 0xFF;
+    return mpu_write_mem(D_1_88,2,tmp);
+}
+
+/**
+ *  @brief      Get current step count.
+ *  @param[out] count   Number of steps detected.
+ *  @return     0 if successful.
+ */
+int dmp_get_pedometer_step_count(unsigned long *count)
+{
+    unsigned char tmp[4];
+    if (!count)
+        return -1;
+
+    if (mpu_read_mem(D_PEDSTD_STEPCTR, 4, tmp))
+        return -1;
+
+    count[0] = ((unsigned long)tmp[0] << 24) | ((unsigned long)tmp[1] << 16) |
+        ((unsigned long)tmp[2] << 8) | tmp[3];
+    return 0;
+}
+
+/**
+ *  @brief      Overwrite current step count.
+ *  WARNING: This function writes to DMP memory and could potentially encounter
+ *  a race condition if called while the pedometer is enabled.
+ *  @param[in]  count   New step count.
+ *  @return     0 if successful.
+ */
+int dmp_set_pedometer_step_count(unsigned long count)
+{
+    unsigned char tmp[4];
+
+    tmp[0] = (unsigned char)((count >> 24) & 0xFF);
+    tmp[1] = (unsigned char)((count >> 16) & 0xFF);
+    tmp[2] = (unsigned char)((count >> 8) & 0xFF);
+    tmp[3] = (unsigned char)(count & 0xFF);
+    return mpu_write_mem(D_PEDSTD_STEPCTR, 4, tmp);
+}
+
+/**
+ *  @brief      Get duration of walking time.
+ *  @param[in]  time    Walk time in milliseconds.
+ *  @return     0 if successful.
+ */
+int dmp_get_pedometer_walk_time(unsigned long *time)
+{
+    unsigned char tmp[4];
+    if (!time)
+        return -1;
+
+    if (mpu_read_mem(D_PEDSTD_TIMECTR, 4, tmp))
+        return -1;
+
+    time[0] = (((unsigned long)tmp[0] << 24) | ((unsigned long)tmp[1] << 16) |
+        ((unsigned long)tmp[2] << 8) | tmp[3]) * 20;
+    return 0;
+}
+
+/**
+ *  @brief      Overwrite current walk time.
+ *  WARNING: This function writes to DMP memory and could potentially encounter
+ *  a race condition if called while the pedometer is enabled.
+ *  @param[in]  time    New walk time in milliseconds.
+ */
+int dmp_set_pedometer_walk_time(unsigned long time)
+{
+    unsigned char tmp[4];
+
+    time /= 20;
+
+    tmp[0] = (unsigned char)((time >> 24) & 0xFF);
+    tmp[1] = (unsigned char)((time >> 16) & 0xFF);
+    tmp[2] = (unsigned char)((time >> 8) & 0xFF);
+    tmp[3] = (unsigned char)(time & 0xFF);
+    return mpu_write_mem(D_PEDSTD_TIMECTR, 4, tmp);
+}
+
+/**
+ *  @brief      Enable DMP features.
+ *  The following \#define's are used in the input mask:
+ *  \n DMP_FEATURE_TAP
+ *  \n DMP_FEATURE_ANDROID_ORIENT
+ *  \n DMP_FEATURE_LP_QUAT
+ *  \n DMP_FEATURE_6X_LP_QUAT
+ *  \n DMP_FEATURE_GYRO_CAL
+ *  \n DMP_FEATURE_SEND_RAW_ACCEL
+ *  \n DMP_FEATURE_SEND_RAW_GYRO
+ *  \n NOTE: DMP_FEATURE_LP_QUAT and DMP_FEATURE_6X_LP_QUAT are mutually
+ *  exclusive.
+ *  \n NOTE: DMP_FEATURE_SEND_RAW_GYRO and DMP_FEATURE_SEND_CAL_GYRO are also
+ *  mutually exclusive.
+ *  @param[in]  mask    Mask of features to enable.
+ *  @return     0 if successful.
+ */
+int dmp_enable_feature(unsigned short mask)
+{
+    unsigned char tmp[10];
+
+    /* TODO: All of these settings can probably be integrated into the default
+     * DMP image.
+     */
+    /* Set integration scale factor. */
+    tmp[0] = (unsigned char)((GYRO_SF >> 24) & 0xFF);
+    tmp[1] = (unsigned char)((GYRO_SF >> 16) & 0xFF);
+    tmp[2] = (unsigned char)((GYRO_SF >> 8) & 0xFF);
+    tmp[3] = (unsigned char)(GYRO_SF & 0xFF);
+    mpu_write_mem(D_0_104, 4, tmp);
+
+    /* Send sensor data to the FIFO. */
+    tmp[0] = 0xA3;
+    if (mask & DMP_FEATURE_SEND_RAW_ACCEL) {
+        tmp[1] = 0xC0;
+        tmp[2] = 0xC8;
+        tmp[3] = 0xC2;
+    } else {
+        tmp[1] = 0xA3;
+        tmp[2] = 0xA3;
+        tmp[3] = 0xA3;
+    }
+    if (mask & DMP_FEATURE_SEND_ANY_GYRO) {
+        tmp[4] = 0xC4;
+        tmp[5] = 0xCC;
+        tmp[6] = 0xC6;
+    } else {
+        tmp[4] = 0xA3;
+        tmp[5] = 0xA3;
+        tmp[6] = 0xA3;
+    }
+    tmp[7] = 0xA3;
+    tmp[8] = 0xA3;
+    tmp[9] = 0xA3;
+    mpu_write_mem(CFG_15,10,tmp);
+
+    /* Send gesture data to the FIFO. */
+    if (mask & (DMP_FEATURE_TAP | DMP_FEATURE_ANDROID_ORIENT))
+        tmp[0] = DINA20;
+    else
+        tmp[0] = 0xD8;
+    mpu_write_mem(CFG_27,1,tmp);
+
+    if (mask & DMP_FEATURE_GYRO_CAL)
+        dmp_enable_gyro_cal(1);
+    else
+        dmp_enable_gyro_cal(0);
+
+    if (mask & DMP_FEATURE_SEND_ANY_GYRO) {
+        if (mask & DMP_FEATURE_SEND_CAL_GYRO) {
+            tmp[0] = 0xB2;
+            tmp[1] = 0x8B;
+            tmp[2] = 0xB6;
+            tmp[3] = 0x9B;
+        } else {
+            tmp[0] = DINAC0;
+            tmp[1] = DINA80;
+            tmp[2] = DINAC2;
+            tmp[3] = DINA90;
+        }
+        mpu_write_mem(CFG_GYRO_RAW_DATA, 4, tmp);
+    }
+
+    if (mask & DMP_FEATURE_TAP) {
+        /* Enable tap. */
+        tmp[0] = 0xF8;
+        mpu_write_mem(CFG_20, 1, tmp);
+        dmp_set_tap_thresh(TAP_XYZ, 250);
+        dmp_set_tap_axes(TAP_XYZ);
+        dmp_set_tap_count(1);
+        dmp_set_tap_time(100);
+        dmp_set_tap_time_multi(500);
+
+        dmp_set_shake_reject_thresh(GYRO_SF, 200);
+        dmp_set_shake_reject_time(40);
+        dmp_set_shake_reject_timeout(10);
+    } else {
+        tmp[0] = 0xD8;
+        mpu_write_mem(CFG_20, 1, tmp);
+    }
+
+    if (mask & DMP_FEATURE_ANDROID_ORIENT) {
+        tmp[0] = 0xD9;
+    } else
+        tmp[0] = 0xD8;
+    mpu_write_mem(CFG_ANDROID_ORIENT_INT, 1, tmp);
+
+    if (mask & DMP_FEATURE_LP_QUAT)
+        dmp_enable_lp_quat(1);
+    else
+        dmp_enable_lp_quat(0);
+
+    if (mask & DMP_FEATURE_6X_LP_QUAT)
+        dmp_enable_6x_lp_quat(1);
+    else
+        dmp_enable_6x_lp_quat(0);
+
+    /* Pedometer is always enabled. */
+    dmp->feature_mask = mask | DMP_FEATURE_PEDOMETER;
+    mpu_reset_fifo();
+
+    dmp->packet_length = 0;
+    if (mask & DMP_FEATURE_SEND_RAW_ACCEL)
+        dmp->packet_length += 6;
+    if (mask & DMP_FEATURE_SEND_ANY_GYRO)
+        dmp->packet_length += 6;
+    if (mask & (DMP_FEATURE_LP_QUAT | DMP_FEATURE_6X_LP_QUAT))
+        dmp->packet_length += 16;
+    if (mask & (DMP_FEATURE_TAP | DMP_FEATURE_ANDROID_ORIENT))
+        dmp->packet_length += 4;
+
+    return 0;
+}
+
+/**
+ *  @brief      Get list of currently enabled DMP features.
+ *  @param[out] Mask of enabled features.
+ *  @return     0 if successful.
+ */
+int dmp_get_enabled_features(unsigned short *mask)
+{
+    mask[0] = dmp->feature_mask;
+    return 0;
+}
+
+/**
+ *  @brief      Calibrate the gyro data in the dmp->
+ *  After eight seconds of no motion, the DMP will compute gyro biases and
+ *  subtract them from the quaternion output. If @e dmp_enable_feature is
+ *  called with @e DMP_FEATURE_SEND_CAL_GYRO, the biases will also be
+ *  subtracted from the gyro output.
+ *  @param[in]  enable  1 to enable gyro calibration.
+ *  @return     0 if successful.
+ */
+int dmp_enable_gyro_cal(unsigned char enable)
+{
+    if (enable) {
+        unsigned char regs[9] = {0xb8, 0xaa, 0xb3, 0x8d, 0xb4, 0x98, 0x0d, 0x35, 0x5d};
+        return mpu_write_mem(CFG_MOTION_BIAS, 9, regs);
+    } else {
+        unsigned char regs[9] = {0xb8, 0xaa, 0xaa, 0xaa, 0xb0, 0x88, 0xc3, 0xc5, 0xc7};
+        return mpu_write_mem(CFG_MOTION_BIAS, 9, regs);
+    }
+}
+
+/**
+ *  @brief      Generate 3-axis quaternions from the dmp->
+ *  In this driver, the 3-axis and 6-axis DMP quaternion features are mutually
+ *  exclusive.
+ *  @param[in]  enable  1 to enable 3-axis quaternion.
+ *  @return     0 if successful.
+ */
+int dmp_enable_lp_quat(unsigned char enable)
+{
+    unsigned char regs[4];
+    if (enable) {
+        regs[0] = DINBC0;
+        regs[1] = DINBC2;
+        regs[2] = DINBC4;
+        regs[3] = DINBC6;
+    }
+    else
+        memset(regs, 0x8B, 4);
+
+    mpu_write_mem(CFG_LP_QUAT, 4, regs);
+
+    return mpu_reset_fifo();
+}
+
+/**
+ *  @brief       Generate 6-axis quaternions from the dmp->
+ *  In this driver, the 3-axis and 6-axis DMP quaternion features are mutually
+ *  exclusive.
+ *  @param[in]   enable  1 to enable 6-axis quaternion.
+ *  @return      0 if successful.
+ */
+int dmp_enable_6x_lp_quat(unsigned char enable)
+{
+    unsigned char regs[4];
+    if (enable) {
+        regs[0] = DINA20;
+        regs[1] = DINA28;
+        regs[2] = DINA30;
+        regs[3] = DINA38;
+    } else
+        memset(regs, 0xA3, 4);
+
+    mpu_write_mem(CFG_8, 4, regs);
+
+    return mpu_reset_fifo();
+}
+
+/**
+ *  @brief      Decode the four-byte gesture data and execute any callbacks.
+ *  @param[in]  gesture Gesture data from DMP packet.
+ *  @return     0 if successful.
+ */
+static int decode_gesture(unsigned char *gesture)
+{
+    unsigned char tap, android_orient;
+
+    android_orient = gesture[3] & 0xC0;
+    tap = 0x3F & gesture[3];
+
+    if (gesture[1] & INT_SRC_TAP) {
+        unsigned char direction, count;
+        direction = tap >> 3;
+        count = (tap % 8) + 1;
+        if (dmp->tap_cb)
+            dmp->tap_cb(direction, count);
+    }
+
+    if (gesture[1] & INT_SRC_ANDROID_ORIENT) {
+        if (dmp->android_orient_cb)
+            dmp->android_orient_cb(android_orient >> 6);
+    }
+
+    return 0;
+}
+
+/**
+ *  @brief      Specify when a DMP interrupt should occur.
+ *  A DMP interrupt can be configured to trigger on either of the two
+ *  conditions below:
+ *  \n a. One FIFO period has elapsed (set by @e mpu_set_sample_rate).
+ *  \n b. A tap event has been detected.
+ *  @param[in]  mode    DMP_INT_GESTURE or DMP_INT_CONTINUOUS.
+ *  @return     0 if successful.
+ */
+int dmp_set_interrupt_mode(unsigned char mode)
+{
+    const unsigned char regs_continuous[11] =
+        {0xd8, 0xb1, 0xb9, 0xf3, 0x8b, 0xa3, 0x91, 0xb6, 0x09, 0xb4, 0xd9};
+    const unsigned char regs_gesture[11] =
+        {0xda, 0xb1, 0xb9, 0xf3, 0x8b, 0xa3, 0x91, 0xb6, 0xda, 0xb4, 0xda};
+
+    switch (mode) {
+    case DMP_INT_CONTINUOUS:
+        return mpu_write_mem(CFG_FIFO_ON_EVENT, 11,
+            (unsigned char*)regs_continuous);
+    case DMP_INT_GESTURE:
+        return mpu_write_mem(CFG_FIFO_ON_EVENT, 11,
+            (unsigned char*)regs_gesture);
+    default:
+        return -1;
+    }
+}
+
+/**
+ *  @brief      Get one packet from the FIFO.
+ *  If @e sensors does not contain a particular sensor, disregard the data
+ *  returned to that pointer.
+ *  \n @e sensors can contain a combination of the following flags:
+ *  \n INV_X_GYRO, INV_Y_GYRO, INV_Z_GYRO
+ *  \n INV_XYZ_GYRO
+ *  \n INV_XYZ_ACCEL
+ *  \n INV_WXYZ_QUAT
+ *  \n If the FIFO has no new data, @e sensors will be zero.
+ *  \n If the FIFO is disabled, @e sensors will be zero and this function will
+ *  return a non-zero error code.
+ *  @param[out] gyro        Gyro data in hardware units.
+ *  @param[out] accel       Accel data in hardware units.
+ *  @param[out] quat        3-axis quaternion data in hardware units.
+ *  @param[out] timestamp   Timestamp in milliseconds.
+ *  @param[out] sensors     Mask of sensors read from FIFO.
+ *  @param[out] more        Number of remaining packets.
+ *  @return     0 if successful.
+ */
+int dmp_read_fifo(short *gyro, short *accel, long *quat,
+    unsigned long *timestamp, short *sensors, unsigned char *more)
+{
+    unsigned char fifo_data[MAX_PACKET_LENGTH];
+    unsigned char ii = 0;
+    int errCode;
+
+    /* TODO: sensors[0] only changes when dmp_enable_feature is called. We can
+     * cache this value and save some cycles.
+     */
+    sensors[0] = 0;
+
+    /* Get a packet. */
+    if ((errCode = mpu_read_fifo_stream(dmp->packet_length, fifo_data, more)))
+        return -1;
+
+    /* Parse DMP packet. */
+    if (dmp->feature_mask & (DMP_FEATURE_LP_QUAT | DMP_FEATURE_6X_LP_QUAT)) {
+#ifdef FIFO_CORRUPTION_CHECK
+        long quat_q14[4], quat_mag_sq;
+#endif
+        quat[0] = ((long)fifo_data[0] << 24) | ((long)fifo_data[1] << 16) |
+            ((long)fifo_data[2] << 8) | fifo_data[3];
+        quat[1] = ((long)fifo_data[4] << 24) | ((long)fifo_data[5] << 16) |
+            ((long)fifo_data[6] << 8) | fifo_data[7];
+        quat[2] = ((long)fifo_data[8] << 24) | ((long)fifo_data[9] << 16) |
+            ((long)fifo_data[10] << 8) | fifo_data[11];
+        quat[3] = ((long)fifo_data[12] << 24) | ((long)fifo_data[13] << 16) |
+            ((long)fifo_data[14] << 8) | fifo_data[15];
+        ii += 16;
+#ifdef FIFO_CORRUPTION_CHECK
+        /* We can detect a corrupted FIFO by monitoring the quaternion data and
+         * ensuring that the magnitude is always normalized to one. This
+         * shouldn't happen in normal operation, but if an I2C error occurs,
+         * the FIFO reads might become misaligned.
+         *
+         * Let's start by scaling down the quaternion data to avoid long long
+         * math.
+         */
+        quat_q14[0] = quat[0] >> 16;
+        quat_q14[1] = quat[1] >> 16;
+        quat_q14[2] = quat[2] >> 16;
+        quat_q14[3] = quat[3] >> 16;
+        quat_mag_sq = quat_q14[0] * quat_q14[0] + quat_q14[1] * quat_q14[1] +
+            quat_q14[2] * quat_q14[2] + quat_q14[3] * quat_q14[3];
+        if ((quat_mag_sq < QUAT_MAG_SQ_MIN) ||
+            (quat_mag_sq > QUAT_MAG_SQ_MAX)) {
+            /* Quaternion is outside of the acceptable threshold. */
+            mpu_reset_fifo();
+            sensors[0] = 0;
+            return -2;
+        }
+        sensors[0] |= INV_WXYZ_QUAT;
+#endif
+    }
+
+    if (dmp->feature_mask & DMP_FEATURE_SEND_RAW_ACCEL) {
+        accel[0] = ((short)fifo_data[ii+0] << 8) | fifo_data[ii+1];
+        accel[1] = ((short)fifo_data[ii+2] << 8) | fifo_data[ii+3];
+        accel[2] = ((short)fifo_data[ii+4] << 8) | fifo_data[ii+5];
+        ii += 6;
+        sensors[0] |= INV_XYZ_ACCEL;
+    }
+
+    if (dmp->feature_mask & DMP_FEATURE_SEND_ANY_GYRO) {
+        gyro[0] = ((short)fifo_data[ii+0] << 8) | fifo_data[ii+1];
+        gyro[1] = ((short)fifo_data[ii+2] << 8) | fifo_data[ii+3];
+        gyro[2] = ((short)fifo_data[ii+4] << 8) | fifo_data[ii+5];
+        ii += 6;
+        sensors[0] |= INV_XYZ_GYRO;
+    }
+
+    /* Gesture data is at the end of the DMP packet. Parse it and call
+     * the gesture callbacks (if registered).
+     */
+    if (dmp->feature_mask & (DMP_FEATURE_TAP | DMP_FEATURE_ANDROID_ORIENT))
+        decode_gesture(fifo_data + ii);
+
+    get_ms(timestamp);
+    return 0;
+}
+
+/**
+ *  @brief      Register a function to be executed on a tap event.
+ *  The tap direction is represented by one of the following:
+ *  \n TAP_X_UP
+ *  \n TAP_X_DOWN
+ *  \n TAP_Y_UP
+ *  \n TAP_Y_DOWN
+ *  \n TAP_Z_UP
+ *  \n TAP_Z_DOWN
+ *  @param[in]  func    Callback function.
+ *  @return     0 if successful.
+ */
+int dmp_register_tap_cb(void (*func)(unsigned char, unsigned char))
+{
+    dmp->tap_cb = func;
+    return 0;
+}
+
+/**
+ *  @brief      Register a function to be executed on a android orientation event.
+ *  @param[in]  func    Callback function.
+ *  @return     0 if successful.
+ */
+int dmp_register_android_orient_cb(void (*func)(unsigned char))
+{
+    dmp->android_orient_cb = func;
+    return 0;
+}
+
+/**
+ *  @}
+ */
+
diff --git a/libraries/MotionDriver/inv_mpu_dmp_motion_driver.h b/libraries/MotionDriver/inv_mpu_dmp_motion_driver.h
new file mode 100644
index 0000000..777e02f
--- /dev/null
+++ b/libraries/MotionDriver/inv_mpu_dmp_motion_driver.h
@@ -0,0 +1,99 @@
+/*
+ $License:
+    Copyright (C) 2011-2012 InvenSense Corporation, All Rights Reserved.
+    See included License.txt for License information.
+ $
+ */
+/**
+ *  @addtogroup  DRIVERS Sensor Driver Layer
+ *  @brief       Hardware drivers to communicate with sensors via I2C.
+ *
+ *  @{
+ *      @file       inv_mpu_dmp_motion_driver.h
+ *      @brief      DMP image and interface functions.
+ *      @details    All functions are preceded by the dmp_ prefix to
+ *                  differentiate among MPL and general driver function calls.
+ */
+#ifndef _INV_MPU_DMP_MOTION_DRIVER_H_
+#define _INV_MPU_DMP_MOTION_DRIVER_H_
+
+#define TAP_X               (0x01)
+#define TAP_Y               (0x02)
+#define TAP_Z               (0x04)
+#define TAP_XYZ             (0x07)
+
+#define TAP_X_UP            (0x01)
+#define TAP_X_DOWN          (0x02)
+#define TAP_Y_UP            (0x03)
+#define TAP_Y_DOWN          (0x04)
+#define TAP_Z_UP            (0x05)
+#define TAP_Z_DOWN          (0x06)
+
+#define ANDROID_ORIENT_PORTRAIT             (0x00)
+#define ANDROID_ORIENT_LANDSCAPE            (0x01)
+#define ANDROID_ORIENT_REVERSE_PORTRAIT     (0x02)
+#define ANDROID_ORIENT_REVERSE_LANDSCAPE    (0x03)
+
+#define DMP_INT_GESTURE     (0x01)
+#define DMP_INT_CONTINUOUS  (0x02)
+
+#define DMP_FEATURE_TAP             (0x001)
+#define DMP_FEATURE_ANDROID_ORIENT  (0x002)
+#define DMP_FEATURE_LP_QUAT         (0x004)
+#define DMP_FEATURE_PEDOMETER       (0x008)
+#define DMP_FEATURE_6X_LP_QUAT      (0x010)
+#define DMP_FEATURE_GYRO_CAL        (0x020)
+#define DMP_FEATURE_SEND_RAW_ACCEL  (0x040)
+#define DMP_FEATURE_SEND_RAW_GYRO   (0x080)
+#define DMP_FEATURE_SEND_CAL_GYRO   (0x100)
+
+#define INV_WXYZ_QUAT       (0x100)
+
+/* Set up functions. */
+void dmp_init_structures();
+int dmp_select_device(int device);
+int dmp_load_motion_driver_firmware(void);
+int dmp_set_fifo_rate(unsigned short rate);
+int dmp_get_fifo_rate(unsigned short *rate);
+int dmp_enable_feature(unsigned short mask);
+int dmp_get_enabled_features(unsigned short *mask);
+int dmp_set_interrupt_mode(unsigned char mode);
+int dmp_set_orientation(unsigned short orient);
+int dmp_set_gyro_bias(long *bias);
+int dmp_set_accel_bias(long *bias);
+
+/* Tap functions. */
+int dmp_register_tap_cb(void (*func)(unsigned char, unsigned char));
+int dmp_set_tap_thresh(unsigned char axis, unsigned short thresh);
+int dmp_set_tap_axes(unsigned char axis);
+int dmp_set_tap_count(unsigned char min_taps);
+int dmp_set_tap_time(unsigned short time);
+int dmp_set_tap_time_multi(unsigned short time);
+int dmp_set_shake_reject_thresh(long sf, unsigned short thresh);
+int dmp_set_shake_reject_time(unsigned short time);
+int dmp_set_shake_reject_timeout(unsigned short time);
+
+/* Android orientation functions. */
+int dmp_register_android_orient_cb(void (*func)(unsigned char));
+
+/* LP quaternion functions. */
+int dmp_enable_lp_quat(unsigned char enable);
+int dmp_enable_6x_lp_quat(unsigned char enable);
+
+/* Pedometer functions. */
+int dmp_get_pedometer_step_count(unsigned long *count);
+int dmp_set_pedometer_step_count(unsigned long count);
+int dmp_get_pedometer_walk_time(unsigned long *time);
+int dmp_set_pedometer_walk_time(unsigned long time);
+
+/* DMP gyro calibration functions. */
+int dmp_enable_gyro_cal(unsigned char enable);
+
+/* Read function. This function should be called whenever the MPU interrupt is
+ * detected.
+ */
+int dmp_read_fifo(short *gyro, short *accel, long *quat,
+    unsigned long *timestamp, short *sensors, unsigned char *more);
+
+#endif  /* #ifndef _INV_MPU_DMP_MOTION_DRIVER_H_ */
+
diff --git a/libraries/NewPing/NewPing.cpp b/libraries/NewPing/NewPing.cpp
new file mode 100644
index 0000000..bfa874d
--- /dev/null
+++ b/libraries/NewPing/NewPing.cpp
@@ -0,0 +1,362 @@
+// ---------------------------------------------------------------------------
+// Created by Tim Eckel - teckel@leethost.com
+// Copyright 2016 License: GNU GPL v3 http://www.gnu.org/licenses/gpl.html
+//
+// See "NewPing.h" for purpose, syntax, version history, links, and more.
+// ---------------------------------------------------------------------------
+
+#include "NewPing.h"
+
+
+// ---------------------------------------------------------------------------
+// NewPing constructor
+// ---------------------------------------------------------------------------
+
+NewPing::NewPing(uint8_t trigger_pin, uint8_t echo_pin, unsigned int max_cm_distance) {
+#if DO_BITWISE == true
+	_triggerBit = digitalPinToBitMask(trigger_pin); // Get the port register bitmask for the trigger pin.
+	_echoBit = digitalPinToBitMask(echo_pin);       // Get the port register bitmask for the echo pin.
+
+	_triggerOutput = portOutputRegister(digitalPinToPort(trigger_pin)); // Get the output port register for the trigger pin.
+	_echoInput = portInputRegister(digitalPinToPort(echo_pin));         // Get the input port register for the echo pin.
+
+	_triggerMode = (uint8_t *) portModeRegister(digitalPinToPort(trigger_pin)); // Get the port mode register for the trigger pin.
+#else
+	_triggerPin = trigger_pin;
+	_echoPin = echo_pin;
+#endif
+
+	set_max_distance(max_cm_distance); // Call function to set the max sensor distance.
+
+#if (defined (__arm__) && defined (TEENSYDUINO)) || DO_BITWISE != true
+	pinMode(echo_pin, INPUT);     // Set echo pin to input (on Teensy 3.x (ARM), pins default to disabled, at least one pinMode() is needed for GPIO mode).
+	pinMode(trigger_pin, OUTPUT); // Set trigger pin to output (on Teensy 3.x (ARM), pins default to disabled, at least one pinMode() is needed for GPIO mode).
+#endif
+
+#if defined (ARDUINO_AVR_YUN)
+	pinMode(echo_pin, INPUT);     // Set echo pin to input for the Arduino Yun, not sure why it doesn't default this way.
+#endif
+
+#if ONE_PIN_ENABLED != true && DO_BITWISE == true
+	*_triggerMode |= _triggerBit; // Set trigger pin to output.
+#endif
+}
+
+
+// ---------------------------------------------------------------------------
+// Standard ping methods
+// ---------------------------------------------------------------------------
+
+unsigned int NewPing::ping(unsigned int max_cm_distance) {
+	if (max_cm_distance > 0) set_max_distance(max_cm_distance); // Call function to set a new max sensor distance.
+
+	if (!ping_trigger()) return NO_ECHO; // Trigger a ping, if it returns false, return NO_ECHO to the calling function.
+
+#if URM37_ENABLED == true
+	#if DO_BITWISE == true
+		while (!(*_echoInput & _echoBit))             // Wait for the ping echo.
+	#else
+		while (!digitalRead(_echoPin))                // Wait for the ping echo.
+	#endif
+			if (micros() > _max_time) return NO_ECHO; // Stop the loop and return NO_ECHO (false) if we're beyond the set maximum distance.
+#else
+	#if DO_BITWISE == true
+		while (*_echoInput & _echoBit)                // Wait for the ping echo.
+	#else
+		while (digitalRead(_echoPin))                 // Wait for the ping echo.
+	#endif
+			if (micros() > _max_time) return NO_ECHO; // Stop the loop and return NO_ECHO (false) if we're beyond the set maximum distance.
+#endif
+
+	return (micros() - (_max_time - _maxEchoTime) - PING_OVERHEAD); // Calculate ping time, include overhead.
+}
+
+
+unsigned long NewPing::ping_cm(unsigned int max_cm_distance) {
+	unsigned long echoTime = NewPing::ping(max_cm_distance); // Calls the ping method and returns with the ping echo distance in uS.
+#if ROUNDING_ENABLED == false
+	return (echoTime / US_ROUNDTRIP_CM);              // Call the ping method and returns the distance in centimeters (no rounding).
+#else
+	return NewPingConvert(echoTime, US_ROUNDTRIP_CM); // Convert uS to centimeters.
+#endif
+}
+
+
+unsigned long NewPing::ping_in(unsigned int max_cm_distance) {
+	unsigned long echoTime = NewPing::ping(max_cm_distance); // Calls the ping method and returns with the ping echo distance in uS.
+#if ROUNDING_ENABLED == false
+	return (echoTime / US_ROUNDTRIP_IN);              // Call the ping method and returns the distance in inches (no rounding).
+#else
+	return NewPingConvert(echoTime, US_ROUNDTRIP_IN); // Convert uS to inches.
+#endif
+}
+
+
+unsigned long NewPing::ping_median(uint8_t it, unsigned int max_cm_distance) {
+	unsigned int uS[it], last;
+	uint8_t j, i = 0;
+	unsigned long t;
+	uS[0] = NO_ECHO;
+
+	while (i < it) {
+		t = micros();                  // Start ping timestamp.
+		last = ping(max_cm_distance);  // Send ping.
+
+		if (last != NO_ECHO) {         // Ping in range, include as part of median.
+			if (i > 0) {               // Don't start sort till second ping.
+				for (j = i; j > 0 && uS[j - 1] < last; j--) // Insertion sort loop.
+					uS[j] = uS[j - 1];                      // Shift ping array to correct position for sort insertion.
+			} else j = 0;              // First ping is sort starting point.
+			uS[j] = last;              // Add last ping to array in sorted position.
+			i++;                       // Move to next ping.
+		} else it--;                   // Ping out of range, skip and don't include as part of median.
+
+		if (i < it && micros() - t < PING_MEDIAN_DELAY)
+			delay((PING_MEDIAN_DELAY + t - micros()) / 1000); // Millisecond delay between pings.
+
+	}
+	return (uS[it >> 1]); // Return the ping distance median.
+}
+
+
+// ---------------------------------------------------------------------------
+// Standard and timer interrupt ping method support functions (not called directly)
+// ---------------------------------------------------------------------------
+
+boolean NewPing::ping_trigger() {
+#if DO_BITWISE == true
+	#if ONE_PIN_ENABLED == true
+		*_triggerMode |= _triggerBit;  // Set trigger pin to output.
+	#endif
+
+	*_triggerOutput &= ~_triggerBit;   // Set the trigger pin low, should already be low, but this will make sure it is.
+	delayMicroseconds(4);              // Wait for pin to go low.
+	*_triggerOutput |= _triggerBit;    // Set trigger pin high, this tells the sensor to send out a ping.
+	delayMicroseconds(10);             // Wait long enough for the sensor to realize the trigger pin is high. Sensor specs say to wait 10uS.
+	*_triggerOutput &= ~_triggerBit;   // Set trigger pin back to low.
+
+	#if ONE_PIN_ENABLED == true
+		*_triggerMode &= ~_triggerBit; // Set trigger pin to input (when using one Arduino pin, this is technically setting the echo pin to input as both are tied to the same Arduino pin).
+	#endif
+
+	#if URM37_ENABLED == true
+		if (!(*_echoInput & _echoBit)) return false;            // Previous ping hasn't finished, abort.
+		_max_time = micros() + _maxEchoTime + MAX_SENSOR_DELAY; // Maximum time we'll wait for ping to start (most sensors are <450uS, the SRF06 can take up to 34,300uS!)
+		while (*_echoInput & _echoBit)                          // Wait for ping to start.
+			if (micros() > _max_time) return false;             // Took too long to start, abort.
+	#else
+		if (*_echoInput & _echoBit) return false;               // Previous ping hasn't finished, abort.
+		_max_time = micros() + _maxEchoTime + MAX_SENSOR_DELAY; // Maximum time we'll wait for ping to start (most sensors are <450uS, the SRF06 can take up to 34,300uS!)
+		while (!(*_echoInput & _echoBit))                       // Wait for ping to start.
+			if (micros() > _max_time) return false;             // Took too long to start, abort.
+	#endif
+#else
+	#if ONE_PIN_ENABLED == true
+		pinMode(_triggerPin, OUTPUT); // Set trigger pin to output.
+	#endif
+	
+	digitalWrite(_triggerPin, LOW);   // Set the trigger pin low, should already be low, but this will make sure it is.
+	delayMicroseconds(4);             // Wait for pin to go low.
+	digitalWrite(_triggerPin, HIGH);  // Set trigger pin high, this tells the sensor to send out a ping.
+	delayMicroseconds(10);            // Wait long enough for the sensor to realize the trigger pin is high. Sensor specs say to wait 10uS.
+	digitalWrite(_triggerPin, LOW);   // Set trigger pin back to low.
+
+	#if ONE_PIN_ENABLED == true
+		pinMode(_triggerPin, INPUT);  // Set trigger pin to input (when using one Arduino pin, this is technically setting the echo pin to input as both are tied to the same Arduino pin).
+	#endif
+
+	#if URM37_ENABLED == true
+		if (!digitalRead(_echoPin)) return false;               // Previous ping hasn't finished, abort.
+		_max_time = micros() + _maxEchoTime + MAX_SENSOR_DELAY; // Maximum time we'll wait for ping to start (most sensors are <450uS, the SRF06 can take up to 34,300uS!)
+		while (digitalRead(_echoPin))                           // Wait for ping to start.
+			if (micros() > _max_time) return false;             // Took too long to start, abort.
+	#else
+		if (digitalRead(_echoPin)) return false;                // Previous ping hasn't finished, abort.
+		_max_time = micros() + _maxEchoTime + MAX_SENSOR_DELAY; // Maximum time we'll wait for ping to start (most sensors are <450uS, the SRF06 can take up to 34,300uS!)
+		while (!digitalRead(_echoPin))                          // Wait for ping to start.
+			if (micros() > _max_time) return false;             // Took too long to start, abort.
+	#endif
+#endif
+
+	_max_time = micros() + _maxEchoTime; // Ping started, set the time-out.
+	return true;                         // Ping started successfully.
+}
+
+
+void NewPing::set_max_distance(unsigned int max_cm_distance) {
+#if ROUNDING_ENABLED == false
+	_maxEchoTime = min(max_cm_distance + 1, (unsigned int) MAX_SENSOR_DISTANCE + 1) * US_ROUNDTRIP_CM; // Calculate the maximum distance in uS (no rounding).
+#else
+	_maxEchoTime = min(max_cm_distance, (unsigned int) MAX_SENSOR_DISTANCE) * US_ROUNDTRIP_CM + (US_ROUNDTRIP_CM / 2); // Calculate the maximum distance in uS.
+#endif
+}
+
+
+#if TIMER_ENABLED == true && DO_BITWISE == true
+
+// ---------------------------------------------------------------------------
+// Timer interrupt ping methods (won't work with non-AVR, ATmega128 and all ATtiny microcontrollers)
+// ---------------------------------------------------------------------------
+
+void NewPing::ping_timer(void (*userFunc)(void), unsigned int max_cm_distance) {
+	if (max_cm_distance > 0) set_max_distance(max_cm_distance); // Call function to set a new max sensor distance.
+
+	if (!ping_trigger()) return;         // Trigger a ping, if it returns false, return without starting the echo timer.
+	timer_us(ECHO_TIMER_FREQ, userFunc); // Set ping echo timer check every ECHO_TIMER_FREQ uS.
+}
+
+
+boolean NewPing::check_timer() {
+	if (micros() > _max_time) { // Outside the time-out limit.
+		timer_stop();           // Disable timer interrupt
+		return false;           // Cancel ping timer.
+	}
+
+#if URM37_ENABLED == false
+	if (!(*_echoInput & _echoBit)) { // Ping echo received.
+#else
+	if (*_echoInput & _echoBit) {    // Ping echo received.
+#endif
+		timer_stop();                // Disable timer interrupt
+		ping_result = (micros() - (_max_time - _maxEchoTime) - PING_TIMER_OVERHEAD); // Calculate ping time including overhead.
+		return true;                 // Return ping echo true.
+	}
+
+	return false; // Return false because there's no ping echo yet.
+}
+
+
+// ---------------------------------------------------------------------------
+// Timer2/Timer4 interrupt methods (can be used for non-ultrasonic needs)
+// ---------------------------------------------------------------------------
+
+// Variables used for timer functions
+void (*intFunc)();
+void (*intFunc2)();
+unsigned long _ms_cnt_reset;
+volatile unsigned long _ms_cnt;
+#if defined(__arm__) && defined(TEENSYDUINO)
+	IntervalTimer itimer;
+#endif
+
+
+void NewPing::timer_us(unsigned int frequency, void (*userFunc)(void)) {
+	intFunc = userFunc; // User's function to call when there's a timer event.
+	timer_setup();      // Configure the timer interrupt.
+
+#if defined (__AVR_ATmega32U4__) // Use Timer4 for ATmega32U4 (Teensy/Leonardo).
+	OCR4C = min((frequency>>2) - 1, 255); // Every count is 4uS, so divide by 4 (bitwise shift right 2) subtract one, then make sure we don't go over 255 limit.
+	TIMSK4 = (1<>2) - 1, 255); // Every count is 4uS, so divide by 4 (bitwise shift right 2) subtract one, then make sure we don't go over 255 limit.
+	TIMSK2 |= (1<= 100
+	#include 
+#else
+	#include 
+	#include 
+#endif
+
+#if defined (__AVR__)
+	#include 
+	#include 
+#endif
+
+// Shouldn't need to change these values unless you have a specific need to do so.
+#define MAX_SENSOR_DISTANCE 500 // Maximum sensor distance can be as high as 500cm, no reason to wait for ping longer than sound takes to travel this distance and back. Default=500
+#define US_ROUNDTRIP_CM 57      // Microseconds (uS) it takes sound to travel round-trip 1cm (2cm total), uses integer to save compiled code space. Default=57
+#define US_ROUNDTRIP_IN 146     // Microseconds (uS) it takes sound to travel round-trip 1 inch (2 inches total), uses integer to save compiled code space. Defalult=146
+#define ONE_PIN_ENABLED true    // Set to "false" to disable one pin mode which saves around 14-26 bytes of binary size. Default=true
+#define ROUNDING_ENABLED false  // Set to "true" to enable distance rounding which also adds 64 bytes to binary size. Default=false
+#define URM37_ENABLED false     // Set to "true" to enable support for the URM37 sensor in PWM mode. Default=false
+#define TIMER_ENABLED true      // Set to "false" to disable the timer ISR (if getting "__vector_7" compile errors set this to false). Default=true
+
+// Probably shouldn't change these values unless you really know what you're doing.
+#define NO_ECHO 0               // Value returned if there's no ping echo within the specified MAX_SENSOR_DISTANCE or max_cm_distance. Default=0
+#define MAX_SENSOR_DELAY 5800   // Maximum uS it takes for sensor to start the ping. Default=5800
+#define ECHO_TIMER_FREQ 24      // Frequency to check for a ping echo (every 24uS is about 0.4cm accuracy). Default=24
+#define PING_MEDIAN_DELAY 29000 // Microsecond delay between pings in the ping_median method. Default=29000
+#define PING_OVERHEAD 5         // Ping overhead in microseconds (uS). Default=5
+#define PING_TIMER_OVERHEAD 13  // Ping timer overhead in microseconds (uS). Default=13
+#if URM37_ENABLED == true
+	#undef  US_ROUNDTRIP_CM
+	#undef  US_ROUNDTRIP_IN
+	#define US_ROUNDTRIP_CM 50  // Every 50uS PWM signal is low indicates 1cm distance. Default=50
+	#define US_ROUNDTRIP_IN 127 // If 50uS is 1cm, 1 inch would be 127uS (50 x 2.54 = 127). Default=127
+#endif
+
+// Conversion from uS to distance (round result to nearest cm or inch).
+#define NewPingConvert(echoTime, conversionFactor) (max(((unsigned int)echoTime + conversionFactor / 2) / conversionFactor, (echoTime ? 1 : 0)))
+
+// Detect non-AVR microcontrollers (Teensy 3.x, Arduino DUE, etc.) and don't use port registers or timer interrupts as required.
+#if (defined (__arm__) && defined (TEENSYDUINO))
+	#undef  PING_OVERHEAD
+	#define PING_OVERHEAD 1
+	#undef  PING_TIMER_OVERHEAD
+	#define PING_TIMER_OVERHEAD 1
+	#define DO_BITWISE true
+#elif !defined (__AVR__)
+	#undef  PING_OVERHEAD
+	#define PING_OVERHEAD 1
+	#undef  PING_TIMER_OVERHEAD
+	#define PING_TIMER_OVERHEAD 1
+	#undef  TIMER_ENABLED
+	#define TIMER_ENABLED false
+	#define DO_BITWISE false
+#else
+	#define DO_BITWISE true
+#endif
+
+// Disable the timer interrupts when using ATmega128 and all ATtiny microcontrollers.
+#if defined (__AVR_ATmega128__) || defined (__AVR_ATtiny24__) || defined (__AVR_ATtiny44__) || defined (__AVR_ATtiny84__) || defined (__AVR_ATtiny25__) || defined (__AVR_ATtiny45__) || defined (__AVR_ATtiny85__) || defined (__AVR_ATtiny261__) || defined (__AVR_ATtiny461__) || defined (__AVR_ATtiny861__) || defined (__AVR_ATtiny43U__)
+	#undef  TIMER_ENABLED
+	#define TIMER_ENABLED false
+#endif
+
+// Define timers when using ATmega8, ATmega16, ATmega32 and ATmega8535 microcontrollers.
+#if defined (__AVR_ATmega8__) || defined (__AVR_ATmega16__) || defined (__AVR_ATmega32__) || defined (__AVR_ATmega8535__)
+	#define OCR2A OCR2
+	#define TIMSK2 TIMSK
+	#define OCIE2A OCIE2
+#endif
+
+class NewPing {
+	public:
+		NewPing(uint8_t trigger_pin, uint8_t echo_pin, unsigned int max_cm_distance = MAX_SENSOR_DISTANCE);
+		unsigned int ping(unsigned int max_cm_distance = 0);
+		unsigned long ping_cm(unsigned int max_cm_distance = 0);
+		unsigned long ping_in(unsigned int max_cm_distance = 0);
+		unsigned long ping_median(uint8_t it = 5, unsigned int max_cm_distance = 0);
+		static unsigned int convert_cm(unsigned int echoTime);
+		static unsigned int convert_in(unsigned int echoTime);
+#if TIMER_ENABLED == true
+		void ping_timer(void (*userFunc)(void), unsigned int max_cm_distance = 0);
+		boolean check_timer();
+		unsigned long ping_result;
+		static void timer_us(unsigned int frequency, void (*userFunc)(void));
+		static void timer_ms(unsigned long frequency, void (*userFunc)(void));
+		static void timer_stop();
+#endif
+	private:
+		boolean ping_trigger();
+		void set_max_distance(unsigned int max_cm_distance);
+#if TIMER_ENABLED == true
+		boolean ping_trigger_timer(unsigned int trigger_delay);
+		boolean ping_wait_timer();
+		static void timer_setup();
+		static void timer_ms_cntdwn();
+#endif
+#if DO_BITWISE == true
+		uint8_t _triggerBit;
+		uint8_t _echoBit;
+		volatile uint8_t *_triggerOutput;
+		volatile uint8_t *_echoInput;
+		volatile uint8_t *_triggerMode;
+#else
+		uint8_t _triggerPin;
+		uint8_t _echoPin;
+#endif
+		unsigned int _maxEchoTime;
+		unsigned long _max_time;
+};
+
+
+#endif
diff --git a/libraries/NewPing/examples/NewPing15Sensors/NewPing15Sensors.pde b/libraries/NewPing/examples/NewPing15Sensors/NewPing15Sensors.pde
new file mode 100644
index 0000000..e2527ff
--- /dev/null
+++ b/libraries/NewPing/examples/NewPing15Sensors/NewPing15Sensors.pde
@@ -0,0 +1,75 @@
+// ---------------------------------------------------------------------------
+// This example code was used to successfully communicate with 15 ultrasonic sensors. You can adjust
+// the number of sensors in your project by changing SONAR_NUM and the number of NewPing objects in the
+// "sonar" array. You also need to change the pins for each sensor for the NewPing objects. Each sensor
+// is pinged at 33ms intervals. So, one cycle of all sensors takes 495ms (33 * 15 = 495ms). The results
+// are sent to the "oneSensorCycle" function which currently just displays the distance data. Your project
+// would normally process the sensor results in this function (for example, decide if a robot needs to
+// turn and call the turn function). Keep in mind this example is event-driven. Your complete sketch needs
+// to be written so there's no "delay" commands and the loop() cycles at faster than a 33ms rate. If other
+// processes take longer than 33ms, you'll need to increase PING_INTERVAL so it doesn't get behind.
+// ---------------------------------------------------------------------------
+#include 
+
+#define SONAR_NUM     15 // Number of sensors.
+#define MAX_DISTANCE 200 // Maximum distance (in cm) to ping.
+#define PING_INTERVAL 33 // Milliseconds between sensor pings (29ms is about the min to avoid cross-sensor echo).
+
+unsigned long pingTimer[SONAR_NUM]; // Holds the times when the next ping should happen for each sensor.
+unsigned int cm[SONAR_NUM];         // Where the ping distances are stored.
+uint8_t currentSensor = 0;          // Keeps track of which sensor is active.
+
+NewPing sonar[SONAR_NUM] = {     // Sensor object array.
+  NewPing(41, 42, MAX_DISTANCE), // Each sensor's trigger pin, echo pin, and max distance to ping.
+  NewPing(43, 44, MAX_DISTANCE),
+  NewPing(45, 20, MAX_DISTANCE),
+  NewPing(21, 22, MAX_DISTANCE),
+  NewPing(23, 24, MAX_DISTANCE),
+  NewPing(25, 26, MAX_DISTANCE),
+  NewPing(27, 28, MAX_DISTANCE),
+  NewPing(29, 30, MAX_DISTANCE),
+  NewPing(31, 32, MAX_DISTANCE),
+  NewPing(34, 33, MAX_DISTANCE),
+  NewPing(35, 36, MAX_DISTANCE),
+  NewPing(37, 38, MAX_DISTANCE),
+  NewPing(39, 40, MAX_DISTANCE),
+  NewPing(50, 51, MAX_DISTANCE),
+  NewPing(52, 53, MAX_DISTANCE)
+};
+
+void setup() {
+  Serial.begin(115200);
+  pingTimer[0] = millis() + 75;           // First ping starts at 75ms, gives time for the Arduino to chill before starting.
+  for (uint8_t i = 1; i < SONAR_NUM; i++) // Set the starting time for each sensor.
+    pingTimer[i] = pingTimer[i - 1] + PING_INTERVAL;
+}
+
+void loop() {
+  for (uint8_t i = 0; i < SONAR_NUM; i++) { // Loop through all the sensors.
+    if (millis() >= pingTimer[i]) {         // Is it this sensor's time to ping?
+      pingTimer[i] += PING_INTERVAL * SONAR_NUM;  // Set next time this sensor will be pinged.
+      if (i == 0 && currentSensor == SONAR_NUM - 1) oneSensorCycle(); // Sensor ping cycle complete, do something with the results.
+      sonar[currentSensor].timer_stop();          // Make sure previous timer is canceled before starting a new ping (insurance).
+      currentSensor = i;                          // Sensor being accessed.
+      cm[currentSensor] = 0;                      // Make distance zero in case there's no ping echo for this sensor.
+      sonar[currentSensor].ping_timer(echoCheck); // Do the ping (processing continues, interrupt will call echoCheck to look for echo).
+    }
+  }
+  // Other code that *DOESN'T* analyze ping results can go here.
+}
+
+void echoCheck() { // If ping received, set the sensor distance to array.
+  if (sonar[currentSensor].check_timer())
+    cm[currentSensor] = sonar[currentSensor].ping_result / US_ROUNDTRIP_CM;
+}
+
+void oneSensorCycle() { // Sensor ping cycle complete, do something with the results.
+  // The following code would be replaced with your code that does something with the ping results.
+  for (uint8_t i = 0; i < SONAR_NUM; i++) {
+    Serial.print(i);
+    Serial.print("=");
+    Serial.print(cm[i]);
+    Serial.print("cm ");
+  }
+  Serial.println();
+}
\ No newline at end of file
diff --git a/libraries/NewPing/examples/NewPingEventTimer/NewPingEventTimer.pde b/libraries/NewPing/examples/NewPingEventTimer/NewPingEventTimer.pde
new file mode 100644
index 0000000..d9d2667
--- /dev/null
+++ b/libraries/NewPing/examples/NewPingEventTimer/NewPingEventTimer.pde
@@ -0,0 +1,46 @@
+// ---------------------------------------------------------------------------
+// This example shows how to use NewPing's ping_timer method which uses the Timer2 interrupt to get the
+// ping time. The advantage of using this method over the standard ping method is that it permits a more
+// event-driven sketch which allows you to appear to do two things at once. An example would be to ping
+// an ultrasonic sensor for a possible collision while at the same time navigating. This allows a
+// properly developed sketch to multitask. Be aware that because the ping_timer method uses Timer2,
+// other features or libraries that also use Timer2 would be effected. For example, the PWM function on
+// pins 3 & 11 on Arduino Uno (pins 9 and 11 on Arduino Mega) and the Tone library. Note, only the PWM
+// functionality of the pins is lost (as they use Timer2 to do PWM), the pins are still available to use.
+// NOTE: For Teensy/Leonardo (ATmega32U4) the library uses Timer4 instead of Timer2.
+// ---------------------------------------------------------------------------
+#include 
+
+#define TRIGGER_PIN   12 // Arduino pin tied to trigger pin on ping sensor.
+#define ECHO_PIN      11 // Arduino pin tied to echo pin on ping sensor.
+#define MAX_DISTANCE 200 // Maximum distance we want to ping for (in centimeters). Maximum sensor distance is rated at 400-500cm.
+
+NewPing sonar(TRIGGER_PIN, ECHO_PIN, MAX_DISTANCE); // NewPing setup of pins and maximum distance.
+
+unsigned int pingSpeed = 50; // How frequently are we going to send out a ping (in milliseconds). 50ms would be 20 times a second.
+unsigned long pingTimer;     // Holds the next ping time.
+
+void setup() {
+  Serial.begin(115200); // Open serial monitor at 115200 baud to see ping results.
+  pingTimer = millis(); // Start now.
+}
+
+void loop() {
+  // Notice how there's no delays in this sketch to allow you to do other processing in-line while doing distance pings.
+  if (millis() >= pingTimer) {   // pingSpeed milliseconds since last ping, do another ping.
+    pingTimer += pingSpeed;      // Set the next ping time.
+    sonar.ping_timer(echoCheck); // Send out the ping, calls "echoCheck" function every 24uS where you can check the ping status.
+  }
+  // Do other stuff here, really. Think of it as multi-tasking.
+}
+
+void echoCheck() { // Timer2 interrupt calls this function every 24uS where you can check the ping status.
+  // Don't do anything here!
+  if (sonar.check_timer()) { // This is how you check to see if the ping was received.
+    // Here's where you can add code.
+    Serial.print("Ping: ");
+    Serial.print(sonar.ping_result / US_ROUNDTRIP_CM); // Ping returned, uS result in ping_result, convert to cm with US_ROUNDTRIP_CM.
+    Serial.println("cm");
+  }
+  // Don't do anything here!
+}
\ No newline at end of file
diff --git a/libraries/NewPing/examples/NewPingExample/NewPingExample.pde b/libraries/NewPing/examples/NewPingExample/NewPingExample.pde
new file mode 100644
index 0000000..12f6fda
--- /dev/null
+++ b/libraries/NewPing/examples/NewPingExample/NewPingExample.pde
@@ -0,0 +1,22 @@
+// ---------------------------------------------------------------------------
+// Example NewPing library sketch that does a ping about 20 times per second.
+// ---------------------------------------------------------------------------
+
+#include 
+
+#define TRIGGER_PIN  12  // Arduino pin tied to trigger pin on the ultrasonic sensor.
+#define ECHO_PIN     11  // Arduino pin tied to echo pin on the ultrasonic sensor.
+#define MAX_DISTANCE 200 // Maximum distance we want to ping for (in centimeters). Maximum sensor distance is rated at 400-500cm.
+
+NewPing sonar(TRIGGER_PIN, ECHO_PIN, MAX_DISTANCE); // NewPing setup of pins and maximum distance.
+
+void setup() {
+  Serial.begin(115200); // Open serial monitor at 115200 baud to see ping results.
+}
+
+void loop() {
+  delay(50);                     // Wait 50ms between pings (about 20 pings/sec). 29ms should be the shortest delay between pings.
+  Serial.print("Ping: ");
+  Serial.print(sonar.ping_cm()); // Send ping, get distance in cm and print result (0 = outside set distance range)
+  Serial.println("cm");
+}
\ No newline at end of file
diff --git a/libraries/NewPing/examples/TimerExample/TimerExample.pde b/libraries/NewPing/examples/TimerExample/TimerExample.pde
new file mode 100644
index 0000000..35e1db2
--- /dev/null
+++ b/libraries/NewPing/examples/TimerExample/TimerExample.pde
@@ -0,0 +1,25 @@
+// ---------------------------------------------------------------------------
+// While the NewPing library's primary goal is to interface with ultrasonic sensors, interfacing with
+// the Timer2 interrupt was a result of creating an interrupt-based ping method. Since these Timer2
+// interrupt methods were built, the library may as well provide the functionality to use these methods
+// in your sketches.  This shows how simple it is (no ultrasonic sensor required).  Keep in mind that
+// these methods use Timer2, as does NewPing's ping_timer method for using ultrasonic sensors.  You
+// can't use ping_timer at the same time you're using timer_ms or timer_us as all use the same timer.
+// ---------------------------------------------------------------------------
+
+#include 
+
+#define LED_PIN 13 // Pin with LED attached.
+
+void setup() {
+  pinMode(LED_PIN, OUTPUT);
+  NewPing::timer_ms(500, toggleLED); // Create a Timer2 interrupt that calls toggleLED in your sketch once every 500 milliseconds.
+}
+
+void loop() {
+  // Do anything here, the Timer2 interrupt will take care of the flashing LED without your intervention.
+}
+
+void toggleLED() {
+  digitalWrite(LED_PIN, !digitalRead(LED_PIN)); // Toggle the LED.
+}
\ No newline at end of file
diff --git a/libraries/NewPing/keywords.txt b/libraries/NewPing/keywords.txt
new file mode 100644
index 0000000..aad926a
--- /dev/null
+++ b/libraries/NewPing/keywords.txt
@@ -0,0 +1,30 @@
+###################################
+# Syntax Coloring Map For NewPing
+###################################
+
+###################################
+# Datatypes (KEYWORD1)
+###################################
+
+NewPing	KEYWORD1
+
+###################################
+# Methods and Functions (KEYWORD2)
+###################################
+
+ping	KEYWORD2
+ping_in	KEYWORD2
+ping_cm	KEYWORD2
+ping_median	KEYWORD2
+ping_timer	KEYWORD2
+check_timer	KEYWORD2
+timer_us	KEYWORD2
+timer_ms	KEYWORD2
+timer_stop	KEYWORD2
+convert_in	KEYWORD2
+convert_cm	KEYWORD2
+
+###################################
+# Constants (LITERAL1)
+###################################
+
diff --git a/libraries/RTIMULib/RTFusion.cpp b/libraries/RTIMULib/RTFusion.cpp
new file mode 100644
index 0000000..9cb2e3e
--- /dev/null
+++ b/libraries/RTIMULib/RTFusion.cpp
@@ -0,0 +1,137 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTFusion.h"
+#include "RTIMUHal.h"
+
+//  The slerp power valule controls the influence of the measured state to correct the predicted state
+//  0 = measured state ignored (just gyros), 1 = measured state overrides predicted state.
+//  In between 0 and 1 mixes the two conditions
+
+#define RTQF_SLERP_POWER (RTFLOAT)0.02;
+
+const char *RTFusion::m_fusionNameMap[] = {
+    "NULL",
+    "Kalman STATE4",
+    "RTQF"};
+
+RTFusion::RTFusion()
+{
+    m_debug = false;
+    m_firstTime = true;
+    m_enableGyro = true;
+    m_enableAccel = true;
+    m_enableCompass = true;
+
+    m_gravity.setScalar(0);
+    m_gravity.setX(0);
+    m_gravity.setY(0);
+    m_gravity.setZ(1);
+
+    m_slerpPower = RTQF_SLERP_POWER;
+}
+
+RTFusion::~RTFusion()
+{
+}
+
+void RTFusion::calculatePose(const RTVector3& accel, const RTVector3& mag, float magDeclination)
+{
+    RTQuaternion m;
+    RTQuaternion q;
+
+    if (m_enableAccel) {
+        accel.accelToEuler(m_measuredPose);
+    } else {
+        m_measuredPose = m_fusionPose;
+        m_measuredPose.setZ(0);
+    }
+
+    if (m_enableCompass && m_compassValid) {
+        q.fromEuler(m_measuredPose);
+        m.setScalar(0);
+        m.setX(mag.x());
+        m.setY(mag.y());
+        m.setZ(mag.z());
+
+        m = q * m * q.conjugate();
+        m_measuredPose.setZ(-atan2(m.y(), m.x()) - magDeclination);
+    } else {
+        m_measuredPose.setZ(m_fusionPose.z());
+    }
+
+    m_measuredQPose.fromEuler(m_measuredPose);
+
+    //  check for quaternion aliasing. If the quaternion has the wrong sign
+    //  the kalman filter will be very unhappy.
+
+    int maxIndex = -1;
+    RTFLOAT maxVal = -1000;
+
+    for (int i = 0; i < 4; i++) {
+        if (fabs(m_measuredQPose.data(i)) > maxVal) {
+            maxVal = fabs(m_measuredQPose.data(i));
+            maxIndex = i;
+        }
+    }
+
+    //  if the biggest component has a different sign in the measured and kalman poses,
+    //  change the sign of the measured pose to match.
+
+    if (((m_measuredQPose.data(maxIndex) < 0) && (m_fusionQPose.data(maxIndex) > 0)) ||
+            ((m_measuredQPose.data(maxIndex) > 0) && (m_fusionQPose.data(maxIndex) < 0))) {
+        m_measuredQPose.setScalar(-m_measuredQPose.scalar());
+        m_measuredQPose.setX(-m_measuredQPose.x());
+        m_measuredQPose.setY(-m_measuredQPose.y());
+        m_measuredQPose.setZ(-m_measuredQPose.z());
+        m_measuredQPose.toEuler(m_measuredPose);
+    }
+}
+
+
+RTVector3 RTFusion::getAccelResiduals()
+{
+    RTQuaternion rotatedGravity;
+    RTQuaternion fusedConjugate;
+    RTQuaternion qTemp;
+    RTVector3 residuals;
+
+    //  do gravity rotation and subtraction
+
+    // create the conjugate of the pose
+
+    fusedConjugate = m_fusionQPose.conjugate();
+
+    // now do the rotation - takes two steps with qTemp as the intermediate variable
+
+    qTemp = m_gravity * m_fusionQPose;
+    rotatedGravity = fusedConjugate * qTemp;
+
+    // now adjust the measured accel and change the signs to make sense
+
+    residuals.setX(-(m_accel.x() - rotatedGravity.x()));
+    residuals.setY(-(m_accel.y() - rotatedGravity.y()));
+    residuals.setZ(-(m_accel.z() - rotatedGravity.z()));
+    return residuals;
+}
diff --git a/libraries/RTIMULib/RTFusion.h b/libraries/RTIMULib/RTFusion.h
new file mode 100644
index 0000000..37a260b
--- /dev/null
+++ b/libraries/RTIMULib/RTFusion.h
@@ -0,0 +1,105 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTFUSION_H
+#define	_RTFUSION_H
+
+#include "RTIMULibDefs.h"
+
+class RTIMUSettings;
+
+class RTFusion
+{
+public:
+
+    RTFusion();
+    virtual ~RTFusion();
+
+    //  fusionType returns the type code of the fusion algorithm
+
+    virtual int fusionType() { return RTFUSION_TYPE_NULL; }
+
+    //  the following function can be called to set the SLERP power
+
+    void setSlerpPower(RTFLOAT power) { m_slerpPower = power; }
+
+    //  reset() resets the fusion state but keeps any setting changes (such as enables)
+
+    virtual void reset() {}
+
+    //  newIMUData() should be called for subsequent updates
+    //  the fusion fields are updated with the results
+
+    virtual void newIMUData(RTIMU_DATA& /* data */, const RTIMUSettings * /* settings */) {}
+
+    //  This static function returns performs the type to name mapping
+
+    static const char *fusionName(int fusionType) { return m_fusionNameMap[fusionType]; }
+
+    //  the following three functions control the influence of the gyro, accel and compass sensors
+
+    void setGyroEnable(bool enable) { m_enableGyro = enable;}
+    void setAccelEnable(bool enable) { m_enableAccel = enable; }
+    void setCompassEnable(bool enable) { m_enableCompass = enable;}
+
+    inline const RTVector3& getMeasuredPose() {return m_measuredPose;}
+    inline const RTQuaternion& getMeasuredQPose() {return m_measuredQPose;}
+
+    //  getAccelResiduals() gets the residual after subtracting gravity
+
+    RTVector3 getAccelResiduals();
+
+    void setDebugEnable(bool enable) { m_debug = enable; }
+
+protected:
+    void calculatePose(const RTVector3& accel, const RTVector3& mag, float magDeclination); // generates pose from accels and mag
+
+    RTVector3 m_gyro;                                       // current gyro sample
+    RTVector3 m_accel;                                      // current accel sample
+    RTVector3 m_compass;                                    // current compass sample
+
+    RTQuaternion m_measuredQPose;       					// quaternion form of pose from measurement
+    RTVector3 m_measuredPose;								// vector form of pose from measurement
+    RTQuaternion m_fusionQPose;                             // quaternion form of pose from fusion
+    RTVector3 m_fusionPose;                                 // vector form of pose from fusion
+
+    RTQuaternion m_gravity;                                 // the gravity vector as a quaternion
+
+    RTFLOAT m_slerpPower;                                   // a value 0 to 1 that controls measured state influence
+    RTQuaternion m_rotationDelta;                           // amount by which measured state differs from predicted
+    RTQuaternion m_rotationPower;                           // delta raised to the appopriate power
+    RTVector3 m_rotationUnitVector;                         // the vector part of the rotation delta
+
+    bool m_debug;
+    bool m_enableGyro;                                      // enables gyro as input
+    bool m_enableAccel;                                     // enables accel as input
+    bool m_enableCompass;                                   // enables compass a input
+    bool m_compassValid;                                    // true if compass data valid
+
+    bool m_firstTime;                                       // if first time after reset
+    uint64_t m_lastFusionTime;                              // for delta time calculation
+
+    static const char *m_fusionNameMap[];                   // the fusion name array
+};
+
+#endif // _RTFUSION_H
diff --git a/libraries/RTIMULib/RTFusionKalman4.cpp b/libraries/RTIMULib/RTFusionKalman4.cpp
new file mode 100644
index 0000000..ffd87c5
--- /dev/null
+++ b/libraries/RTIMULib/RTFusionKalman4.cpp
@@ -0,0 +1,238 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTFusionKalman4.h"
+#include "RTIMUSettings.h"
+
+//  The QVALUE affects the gyro response.
+
+#define KALMAN_QVALUE	0.001f
+
+//  The RVALUE controls the influence of the accels and compass.
+//  The bigger the value, the more sluggish the response.
+
+#define KALMAN_RVALUE	0.0005f
+
+#define KALMAN_QUATERNION_LENGTH	4
+
+#define	KALMAN_STATE_LENGTH	4								// just the quaternion for the moment
+
+
+RTFusionKalman4::RTFusionKalman4()
+{
+    reset();
+}
+
+RTFusionKalman4::~RTFusionKalman4()
+{
+}
+
+void RTFusionKalman4::reset()
+{
+    m_firstTime = true;
+    m_fusionPose = RTVector3();
+    m_fusionQPose.fromEuler(m_fusionPose);
+    m_gyro = RTVector3();
+    m_accel = RTVector3();
+    m_compass = RTVector3();
+    m_measuredPose = RTVector3();
+    m_measuredQPose.fromEuler(m_measuredPose);
+    m_Rk.fill(0);
+    m_Q.fill(0);
+
+    // initialize process noise covariance matrix
+
+    for (int i = 0; i < KALMAN_STATE_LENGTH; i++)
+        for (int j = 0; j < KALMAN_STATE_LENGTH; j++)
+            m_Q.setVal(i, i, KALMAN_QVALUE);
+
+    // initialize observation noise covariance matrix
+
+
+    for (int i = 0; i < KALMAN_STATE_LENGTH; i++)
+        for (int j = 0; j < KALMAN_STATE_LENGTH; j++)
+            m_Rk.setVal(i, i, KALMAN_RVALUE);
+ }
+
+void RTFusionKalman4::predict()
+{
+    RTMatrix4x4 mat;
+    RTQuaternion tQuat;
+    RTFLOAT x2, y2, z2;
+
+    //  compute the state transition matrix
+
+    x2 = m_gyro.x() / (RTFLOAT)2.0;
+    y2 = m_gyro.y() / (RTFLOAT)2.0;
+    z2 = m_gyro.z() / (RTFLOAT)2.0;
+
+    m_Fk.setVal(0, 1, -x2);
+    m_Fk.setVal(0, 2, -y2);
+    m_Fk.setVal(0, 3, -z2);
+
+    m_Fk.setVal(1, 0, x2);
+    m_Fk.setVal(1, 2, z2);
+    m_Fk.setVal(1, 3, -y2);
+
+    m_Fk.setVal(2, 0, y2);
+    m_Fk.setVal(2, 1, -z2);
+    m_Fk.setVal(2, 3, x2);
+
+    m_Fk.setVal(3, 0, z2);
+    m_Fk.setVal(3, 1, y2);
+    m_Fk.setVal(3, 2, -x2);
+
+    m_FkTranspose = m_Fk.transposed();
+
+    // Predict new state estimate Xkk_1 = Fk * Xk_1k_1
+
+    tQuat = m_Fk * m_stateQ;
+    tQuat *= m_timeDelta;
+    m_stateQ += tQuat;
+
+//    m_stateQ.normalize();
+
+    // Compute PDot = Fk * Pk_1k_1 + Pk_1k_1 * FkTranspose (note Pkk == Pk_1k_1 at this stage)
+
+    m_PDot = m_Fk * m_Pkk;
+    mat = m_Pkk * m_FkTranspose;
+    m_PDot += mat;
+
+    // add in Q to get the new prediction
+
+    m_Pkk_1 = m_PDot + m_Q;
+
+    //  multiply by deltaTime (variable name is now misleading though)
+
+    m_Pkk_1 *= m_timeDelta;
+}
+
+
+void RTFusionKalman4::update()
+{
+    RTQuaternion delta;
+    RTMatrix4x4 Sk, SkInverse;
+
+    if (m_enableCompass || m_enableAccel) {
+        m_stateQError = m_measuredQPose - m_stateQ;
+    } else {
+        m_stateQError = RTQuaternion();
+    }
+
+    //	Compute residual covariance Sk = Hk * Pkk_1 * HkTranspose + Rk
+    //  Note: since Hk is the identity matrix, this has been simplified
+
+    Sk = m_Pkk_1 + m_Rk;
+
+    //	Compute Kalman gain Kk = Pkk_1 * HkTranspose * SkInverse
+    //  Note: again, the HkTranspose part is omitted
+
+    SkInverse = Sk.inverted();
+
+    m_Kk = m_Pkk_1 * SkInverse;
+
+    if (m_debug)
+        HAL_INFO(RTMath::display("Gain", m_Kk));
+
+    // make new state estimate
+
+    delta = m_Kk * m_stateQError;
+
+    m_stateQ += delta;
+
+    m_stateQ.normalize();
+
+    //  produce new estimate covariance Pkk = (I - Kk * Hk) * Pkk_1
+    //  Note: since Hk is the identity matrix, it is omitted
+
+    m_Pkk.setToIdentity();
+    m_Pkk -= m_Kk;
+    m_Pkk = m_Pkk * m_Pkk_1;
+
+    if (m_debug)
+        HAL_INFO(RTMath::display("Cov", m_Pkk));
+}
+
+void RTFusionKalman4::newIMUData(RTIMU_DATA& data, const RTIMUSettings *settings)
+{
+    if (m_enableGyro)
+        m_gyro = data.gyro;
+    else
+        m_gyro = RTVector3();
+    m_accel = data.accel;
+    m_compass = data.compass;
+    m_compassValid = data.compassValid;
+
+    if (m_firstTime) {
+        m_lastFusionTime = data.timestamp;
+        calculatePose(m_accel, m_compass, settings->m_compassAdjDeclination);
+        m_Fk.fill(0);
+
+        //  init covariance matrix to something
+
+        m_Pkk.fill(0);
+        for (int i = 0; i < 4; i++)
+            for (int j = 0; j < 4; j++)
+                m_Pkk.setVal(i,j, 0.5);
+
+        // initialize the observation model Hk
+        // Note: since the model is the state vector, this is an identity matrix so it won't be used
+
+        //  initialize the poses
+
+        m_stateQ.fromEuler(m_measuredPose);
+        m_fusionQPose = m_stateQ;
+        m_fusionPose = m_measuredPose;
+        m_firstTime = false;
+    } else {
+        m_timeDelta = (RTFLOAT)(data.timestamp - m_lastFusionTime) / (RTFLOAT)1000000;
+        m_lastFusionTime = data.timestamp;
+        if (m_timeDelta <= 0)
+            return;
+
+        if (m_debug) {
+            HAL_INFO("\n------\n");
+            HAL_INFO1("IMU update delta time: %f\n", m_timeDelta);
+        }
+
+        calculatePose(data.accel, data.compass, settings->m_compassAdjDeclination);
+
+        predict();
+        update();
+        m_stateQ.toEuler(m_fusionPose);
+        m_fusionQPose = m_stateQ;
+
+        if (m_debug) {
+            HAL_INFO(RTMath::displayRadians("Measured pose", m_measuredPose));
+            HAL_INFO(RTMath::displayRadians("Kalman pose", m_fusionPose));
+            HAL_INFO(RTMath::displayRadians("Measured quat", m_measuredPose));
+            HAL_INFO(RTMath::display("Kalman quat", m_stateQ));
+            HAL_INFO(RTMath::display("Error quat", m_stateQError));
+         }
+    }
+    data.fusionPoseValid = true;
+    data.fusionQPoseValid = true;
+    data.fusionPose = m_fusionPose;
+    data.fusionQPose = m_fusionQPose;
+}
diff --git a/libraries/RTIMULib/RTFusionKalman4.h b/libraries/RTIMULib/RTFusionKalman4.h
new file mode 100644
index 0000000..71b7abe
--- /dev/null
+++ b/libraries/RTIMULib/RTFusionKalman4.h
@@ -0,0 +1,79 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTFUSIONKALMAN4_H
+#define	_RTFUSIONKALMAN4_H
+
+#include "RTFusion.h"
+
+class RTFusionKalman4 : public RTFusion
+{
+public:
+    RTFusionKalman4();
+    ~RTFusionKalman4();
+
+    //  fusionType returns the type code of the fusion algorithm
+
+    virtual int fusionType() { return RTFUSION_TYPE_KALMANSTATE4; }
+
+    //  reset() resets the kalman state but keeps any setting changes (such as enables)
+
+    void reset();
+
+    //  newIMUData() should be called for subsequent updates
+    //  deltaTime is in units of seconds
+
+    void newIMUData(RTIMU_DATA& data, const RTIMUSettings *settings);
+
+    //  the following two functions can be called to customize the covariance matrices
+
+    void setQMatrix(RTMatrix4x4 Q) {  m_Q = Q; reset();}
+    void setRkMatrix(RTMatrix4x4 Rk) { m_Rk = Rk; reset();}
+
+private:
+    void predict();
+    void update();
+
+    RTVector3 m_gyro;										// unbiased gyro data
+    RTFLOAT m_timeDelta;                                    // time between predictions
+
+    RTQuaternion m_stateQ;									// quaternion state vector
+    RTQuaternion m_stateQError;                             // difference between stateQ and measuredQ
+
+    RTMatrix4x4 m_Kk;                                       // the Kalman gain matrix
+    RTMatrix4x4 m_Pkk_1;                                    // the predicted estimated covariance matrix
+    RTMatrix4x4 m_Pkk;                                      // the updated estimated covariance matrix
+    RTMatrix4x4 m_PDot;                                     // the derivative of the covariance matrix
+    RTMatrix4x4 m_Q;                                        // process noise covariance
+    RTMatrix4x4 m_Fk;                                       // the state transition matrix
+    RTMatrix4x4 m_FkTranspose;                              // the state transition matrix transposed
+    RTMatrix4x4 m_Rk;                                       // the measurement noise covariance
+
+    //  Note: SInce Hk ends up being the identity matrix, these are omitted
+
+//    RTMatrix4x4 m_Hk;                                     // map from state to measurement
+//    RTMatrix4x4> m_HkTranspose;                           // transpose of map
+};
+
+#endif // _RTFUSIONKALMAN4_H
diff --git a/libraries/RTIMULib/RTFusionRTQF.cpp b/libraries/RTIMULib/RTFusionRTQF.cpp
new file mode 100644
index 0000000..1697baa
--- /dev/null
+++ b/libraries/RTIMULib/RTFusionRTQF.cpp
@@ -0,0 +1,163 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTFusionRTQF.h"
+#include "RTIMUSettings.h"
+
+
+RTFusionRTQF::RTFusionRTQF()
+{
+    reset();
+}
+
+RTFusionRTQF::~RTFusionRTQF()
+{
+}
+
+void RTFusionRTQF::reset()
+{
+    m_firstTime = true;
+    m_fusionPose = RTVector3();
+    m_fusionQPose.fromEuler(m_fusionPose);
+    m_gyro = RTVector3();
+    m_accel = RTVector3();
+    m_compass = RTVector3();
+    m_measuredPose = RTVector3();
+    m_measuredQPose.fromEuler(m_measuredPose);
+    m_sampleNumber = 0;
+ }
+
+void RTFusionRTQF::predict()
+{
+    RTFLOAT x2, y2, z2;
+    RTFLOAT qs, qx, qy,qz;
+
+    if (!m_enableGyro)
+        return;
+
+    qs = m_stateQ.scalar();
+    qx = m_stateQ.x();
+    qy = m_stateQ.y();
+    qz = m_stateQ.z();
+
+    x2 = m_gyro.x() / (RTFLOAT)2.0;
+    y2 = m_gyro.y() / (RTFLOAT)2.0;
+    z2 = m_gyro.z() / (RTFLOAT)2.0;
+
+    // Predict new state
+
+    m_stateQ.setScalar(qs + (-x2 * qx - y2 * qy - z2 * qz) * m_timeDelta);
+    m_stateQ.setX(qx + (x2 * qs + z2 * qy - y2 * qz) * m_timeDelta);
+    m_stateQ.setY(qy + (y2 * qs - z2 * qx + x2 * qz) * m_timeDelta);
+    m_stateQ.setZ(qz + (z2 * qs + y2 * qx - x2 * qy) * m_timeDelta);
+    m_stateQ.normalize();
+}
+
+
+void RTFusionRTQF::update()
+{
+    if (m_enableCompass || m_enableAccel) {
+
+        // calculate rotation delta
+
+        m_rotationDelta = m_stateQ.conjugate() * m_measuredQPose;
+        m_rotationDelta.normalize();
+
+        // take it to the power (0 to 1) to give the desired amount of correction
+
+        RTFLOAT theta = acos(m_rotationDelta.scalar());
+
+        RTFLOAT sinPowerTheta = sin(theta * m_slerpPower);
+        RTFLOAT cosPowerTheta = cos(theta * m_slerpPower);
+
+        m_rotationUnitVector.setX(m_rotationDelta.x());
+        m_rotationUnitVector.setY(m_rotationDelta.y());
+        m_rotationUnitVector.setZ(m_rotationDelta.z());
+        m_rotationUnitVector.normalize();
+
+        m_rotationPower.setScalar(cosPowerTheta);
+        m_rotationPower.setX(sinPowerTheta * m_rotationUnitVector.x());
+        m_rotationPower.setY(sinPowerTheta * m_rotationUnitVector.y());
+        m_rotationPower.setZ(sinPowerTheta * m_rotationUnitVector.z());
+        m_rotationPower.normalize();
+
+        //  multiple this by predicted value to get result
+
+        m_stateQ *= m_rotationPower;
+        m_stateQ.normalize();
+    }
+}
+
+void RTFusionRTQF::newIMUData(RTIMU_DATA& data, const RTIMUSettings *settings)
+{
+    if (m_debug) {
+        HAL_INFO("\n------\n");
+        HAL_INFO2("IMU update delta time: %f, sample %d\n", m_timeDelta, m_sampleNumber++);
+    }
+    m_sampleNumber++;
+
+    if (m_enableGyro)
+        m_gyro = data.gyro;
+    else
+        m_gyro = RTVector3();
+    m_accel = data.accel;
+    m_compass = data.compass;
+    m_compassValid = data.compassValid;
+
+    if (m_firstTime) {
+        m_lastFusionTime = data.timestamp;
+        calculatePose(m_accel, m_compass, settings->m_compassAdjDeclination);
+
+        //  initialize the poses
+
+        m_stateQ.fromEuler(m_measuredPose);
+        m_fusionQPose = m_stateQ;
+        m_fusionPose = m_measuredPose;
+        m_firstTime = false;
+    } else {
+        m_timeDelta = (RTFLOAT)(data.timestamp - m_lastFusionTime) / (RTFLOAT)1000000;
+        m_lastFusionTime = data.timestamp;
+        if (m_timeDelta <= 0)
+            return;
+
+        calculatePose(data.accel, data.compass, settings->m_compassAdjDeclination);
+
+        predict();
+        update();
+        m_stateQ.toEuler(m_fusionPose);
+        m_fusionQPose = m_stateQ;
+
+        if (m_debug) {
+            HAL_INFO(RTMath::displayRadians("Measured pose", m_measuredPose));
+            HAL_INFO(RTMath::displayRadians("RTQF pose", m_fusionPose));
+            HAL_INFO(RTMath::displayRadians("Measured quat", m_measuredPose));
+            HAL_INFO(RTMath::display("RTQF quat", m_stateQ));
+            HAL_INFO(RTMath::display("Error quat", m_stateQError));
+         }
+    }
+    data.fusionPoseValid = true;
+    data.fusionQPoseValid = true;
+    data.fusionPose = m_fusionPose;
+    data.fusionQPose = m_fusionQPose;
+}
diff --git a/libraries/RTIMULib/RTFusionRTQF.h b/libraries/RTIMULib/RTFusionRTQF.h
new file mode 100644
index 0000000..c4395e0
--- /dev/null
+++ b/libraries/RTIMULib/RTFusionRTQF.h
@@ -0,0 +1,62 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTFUSIONRTQF_H
+#define	_RTFUSIONRTQF_H
+
+#include "RTFusion.h"
+
+class RTFusionRTQF : public RTFusion
+{
+public:
+    RTFusionRTQF();
+    ~RTFusionRTQF();
+
+    //  fusionType returns the type code of the fusion algorithm
+
+    virtual int fusionType() { return RTFUSION_TYPE_RTQF; }
+
+    //  reset() resets the state but keeps any setting changes (such as enables)
+
+    void reset();
+
+    //  newIMUData() should be called for subsequent updates
+    //  deltaTime is in units of seconds
+
+    void newIMUData(RTIMU_DATA& data, const RTIMUSettings *settings);
+
+private:
+    void predict();
+    void update();
+
+    RTVector3 m_gyro;										// unbiased gyro data
+    RTFLOAT m_timeDelta;                                    // time between predictions
+
+    RTQuaternion m_stateQ;									// quaternion state vector
+    RTQuaternion m_stateQError;                             // difference between stateQ and measuredQ
+
+    int m_sampleNumber;
+};
+
+#endif // _RTFUSIONRTQF_H
diff --git a/libraries/RTIMULib/RTIMUCalDefs.h b/libraries/RTIMULib/RTIMUCalDefs.h
new file mode 100644
index 0000000..2949e8a
--- /dev/null
+++ b/libraries/RTIMULib/RTIMUCalDefs.h
@@ -0,0 +1,57 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 RTIMUCALDEFS_H
+#define RTIMUCALDEFS_H
+
+#define RTIMUCALDEFS_DEFAULT_MIN        1000                // a large min
+#define RTIMUCALDEFS_DEFAULT_MAX        -1000               // a small max
+
+#define	RTIMUCALDEFS_MAX_MAG_SAMPLES	   20000            // max saved mag records
+
+#define RTIMUCALDEFS_OCTANT_MIN_SAMPLES    200              // must have at least this in each octant
+
+#define RTIMUCALDEFS_ELLIPSOID_MIN_SPACING  0.1f            // min distnace between ellipsoid samples to be recorded
+
+//  Octant defs
+
+#define RTIMUCALDEFS_OCTANT_COUNT       8                   // there are 8 octants of course
+
+#define RTIMUCALDEFS_OCTANT_NNN         0                   // x, y, z all negative
+#define RTIMUCALDEFS_OCTANT_PNN         1                   // x positive - y, z neagtive
+#define RTIMUCALDEFS_OCTANT_NPN         2                   // y positive - x, z negative
+#define RTIMUCALDEFS_OCTANT_PPN         3                   // x, y positive - z negative
+#define RTIMUCALDEFS_OCTANT_NNP         4                   // z positive - x, y negative
+#define RTIMUCALDEFS_OCTANT_PNP         5                   // x, z positive - y negative
+#define RTIMUCALDEFS_OCTANT_NPP         6                   // y, z positive - x negative
+#define RTIMUCALDEFS_OCTANT_PPP         7                   // x, y, z all positive
+
+//  File name for Octave processing
+
+#define RTIMUCALDEFS_MAG_RAW_FILE          "magRaw.dta"     // the raw sample file - input to ellispoid fit code
+#define RTIMUCALDEFS_MAG_CORR_FILE         "magCorr.dta"    // the output from the ellipsoid fit code
+
+#define RTIMUCALDEFS_OCTAVE_CODE           "RTEllipsoidFit.m"
+#define RTIMUCALDEFS_OCTAVE_COMMAND        "octave RTEllipsoidFit.m"
+
+#endif // RTIMUCALDEFS_H
diff --git a/libraries/RTIMULib/RTIMUHal.cpp b/libraries/RTIMULib/RTIMUHal.cpp
new file mode 100644
index 0000000..6118173
--- /dev/null
+++ b/libraries/RTIMULib/RTIMUHal.cpp
@@ -0,0 +1,137 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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.
+
+//  The MPU-9250 driver code is based on code generously supplied by
+//  staslock@gmail.com (www.clickdrive.io)
+
+#include "RTIMUHal.h"
+#include "I2Cdev.h"
+#include 
+
+RTIMUHal::RTIMUHal()
+{
+}
+
+RTIMUHal::~RTIMUHal()
+{
+}
+
+bool RTIMUHal::HALOpen()
+{
+    if (m_busIsI2C)
+        return true;
+
+    SPI.begin();
+    pinMode(m_SPISelect, OUTPUT);
+    m_SPISettings = SPISettings(m_SPISpeed, MSBFIRST, SPI_MODE0);
+    return true;
+}
+
+void RTIMUHal::HALClose()
+{
+    I2CClose();
+    SPIClose();
+}
+
+void RTIMUHal::I2CClose()
+{
+}
+
+void RTIMUHal::SPIClose()
+{
+    SPI.end();
+}
+
+bool RTIMUHal::HALRead(unsigned char slaveAddr, unsigned char regAddr, unsigned char length,
+                 unsigned char *data, const char *errorMsg)
+{
+    if (m_busIsI2C) {
+        if (I2Cdev::readBytes(slaveAddr, regAddr, length, data, 10) == length)
+             return true;
+
+        if (strlen(errorMsg) > 0)
+            HAL_ERROR1("I2C read failed - %s\n", errorMsg);
+
+        return false;
+    } else {
+        SPI.beginTransaction(m_SPISettings);
+        digitalWrite(m_SPISelect, LOW);
+        SPI.transfer(regAddr | 0x80);
+        for (int i = 0; i < length; i++)
+            data[i] = SPI.transfer(0);
+        digitalWrite(m_SPISelect, HIGH);
+        SPI.endTransaction();
+        return true;
+    }
+}
+
+bool RTIMUHal::HALWrite(unsigned char slaveAddr, unsigned char regAddr,
+                  unsigned char length, unsigned char const *data, const char *errorMsg)
+{
+    if (m_busIsI2C) {
+        if (I2Cdev::writeBytes(slaveAddr, regAddr, length, (unsigned char *)data) > 0)
+            return true;
+
+        if (strlen(errorMsg) > 0)
+            HAL_ERROR1("I2C write failed - %s\n", errorMsg);
+
+        return false;
+    } else {
+        SPI.beginTransaction(m_SPISettings);
+        digitalWrite(m_SPISelect, LOW);
+        SPI.transfer(regAddr);
+        for (int i = 0; i < length; i++)
+            SPI.transfer(data[i]);
+        digitalWrite(m_SPISelect, HIGH);
+        SPI.endTransaction();
+        return true;
+    }
+}
+
+bool RTIMUHal::HALWrite(unsigned char slaveAddr, unsigned char regAddr,
+                  unsigned char const data, const char *errorMsg)
+{
+    if (m_busIsI2C) {
+        if (I2Cdev::writeByte(slaveAddr, regAddr, data))
+            return true;
+
+        if (strlen(errorMsg) > 0)
+            HAL_ERROR1("I2C write failed - %s\n", errorMsg);
+
+        return false;
+    } else {
+        SPI.beginTransaction(m_SPISettings);
+        digitalWrite(m_SPISelect, LOW);
+        SPI.transfer(regAddr);
+        SPI.transfer(data);
+        digitalWrite(m_SPISelect, HIGH);
+        SPI.endTransaction();
+        return true;
+    }
+}
+
+void RTIMUHal::delayMs(int milliSeconds)
+{
+    delay(milliSeconds);
+}
+
diff --git a/libraries/RTIMULib/RTIMUHal.h b/libraries/RTIMULib/RTIMUHal.h
new file mode 100644
index 0000000..7f02d8b
--- /dev/null
+++ b/libraries/RTIMULib/RTIMUHal.h
@@ -0,0 +1,97 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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.
+
+//  The MPU-9250 driver code is based on code generously supplied by
+//  staslock@gmail.com (www.clickdrive.io)
+
+#ifndef _RTIMUHAL_H
+#define	_RTIMUHAL_H
+
+#include 
+#include 
+#include 
+#include 
+
+#define HAL_QUIET
+
+#ifndef HAL_QUIET
+#define HAL_INFO(m) Serial.printf(m);
+#define HAL_INFO1(m, x)  Serial.printf(m, x);
+#define HAL_INFO2(m, x, y)  Serial.printf(m, x, y);
+#define HAL_INFO3(m, x, y, z)  Serial.printf(m, x, y, z);
+#define HAL_INFO4(m, x, y, z, a)  Serial.printf(m, x, y, z, a);
+#define HAL_INFO5(m, x, y, z, a, b)  Serial.printf(m, x, y, z, a, b);
+#define HAL_ERROR(m)     Serial.printf(m);
+#define HAL_ERROR1(m, x)     Serial.printf(m, x);
+#define HAL_ERROR2(m, x, y)     Serial.printf(m, x, y);
+#define HAL_ERROR3(m, x, y, z)     Serial.printf(m, x, y, z);
+#define HAL_ERROR4(m, x, y, z, a)     Serial.printf(m, x, y, z, a);
+
+#else
+
+#define HAL_INFO(m) 
+#define HAL_INFO1(m, x)
+#define HAL_INFO2(m, x, y)
+#define HAL_INFO3(m, x, y, z)
+#define HAL_INFO4(m, x, y, z, a)
+#define HAL_INFO5(m, x, y, z, a, b)
+#define HAL_ERROR(m)     Serial.printf(m);
+#define HAL_ERROR1(m, x)     Serial.printf(m, x);
+#define HAL_ERROR2(m, x, y)     Serial.printf(m, x, y);
+#define HAL_ERROR3(m, x, y, z)     Serial.printf(m, x, y, z);
+#define HAL_ERROR4(m, x, y, z, a)     Serial.printf(m, x, y, z, a);
+
+#endif
+
+
+class RTIMUHal
+{
+public:
+    RTIMUHal();
+    virtual ~RTIMUHal();
+
+    bool m_busIsI2C;                                        // true if I2C bus in use, false if SPI in use
+    unsigned char m_I2CBus;                                 // I2C bus of the imu
+    unsigned char m_SPIBus;                                 // SPI bus of the imu
+    unsigned char m_SPISelect;                              // SPI select line
+    unsigned int m_SPISpeed;                                // speed of interface
+
+    bool HALOpen();
+    void HALClose();
+    bool HALRead(unsigned char slaveAddr, unsigned char regAddr, unsigned char length,
+                 unsigned char *data, const char *errorMsg);
+    bool HALWrite(unsigned char slaveAddr, unsigned char regAddr,
+                  unsigned char length, unsigned char const *data, const char *errorMsg);
+    bool HALWrite(unsigned char slaveAddr, unsigned char regAddr,
+                  unsigned char const data, const char *errorMsg);
+
+    void delayMs(int milliSeconds);
+
+private:
+    void I2CClose();
+    void SPIClose();
+
+    SPISettings m_SPISettings;
+};
+
+#endif // _RTIMUHAL_H
diff --git a/libraries/RTIMULib/RTIMULIB LICENSE b/libraries/RTIMULib/RTIMULIB LICENSE
new file mode 100644
index 0000000..95aded8
--- /dev/null
+++ b/libraries/RTIMULib/RTIMULIB LICENSE	
@@ -0,0 +1,26 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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.
+
+//  The MPU-9250 and SPI driver code is based on code generously supplied by 
+//  staslock@gmail.com (www.clickdrive.io)
+
diff --git a/libraries/RTIMULib/RTIMULib.h b/libraries/RTIMULib/RTIMULib.h
new file mode 100644
index 0000000..cf5f21b
--- /dev/null
+++ b/libraries/RTIMULib/RTIMULib.h
@@ -0,0 +1,50 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTIMULIB_H
+#define	_RTIMULIB_H
+
+#include "RTIMULibDefs.h"
+
+#include "RTMath.h"
+
+#include "RTFusion.h"
+#include "RTFusionRTQF.h"
+#include "RTFusionKalman4.h"
+
+#include "RTIMUHal.h"
+#include "utility/RTIMU.h"
+#include "utility/RTIMUNull.h"
+#include "utility/RTIMUMPU9150.h"
+#include "utility/RTIMUGD20HM303D.h"
+#include "utility/RTIMUGD20M303DLHC.h"
+#include "utility/RTIMULSM9DS0.h"
+
+#include "utility/RTPressure.h"
+#include "utility/RTPressureBMP180.h"
+
+#include "RTIMUSettings.h"
+
+
+#endif // _RTIMULIB_H
diff --git a/libraries/RTIMULib/RTIMULibDefs.h b/libraries/RTIMULib/RTIMULibDefs.h
new file mode 100644
index 0000000..b3050b4
--- /dev/null
+++ b/libraries/RTIMULib/RTIMULibDefs.h
@@ -0,0 +1,64 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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.
+
+//  The MPU-9250 driver code is based on code generously supplied by
+//  staslock@gmail.com (www.clickdrive.io)
+
+#ifndef _RTIMULIBDEFS_H
+#define	_RTIMULIBDEFS_H
+
+#include "RTMath.h"
+#include "utility/RTIMUDefs.h"
+
+//  these defines describe the various fusion filter options
+
+#define RTFUSION_TYPE_NULL                  0                   // just a dummy to keep things happy if not needed
+#define RTFUSION_TYPE_KALMANSTATE4          1                   // kalman state is the quaternion pose
+#define RTFUSION_TYPE_RTQF                  2                   // RT quaternion fusion
+
+#define RTFUSION_TYPE_COUNT                 3                   // number of fusion algorithm types
+
+//  This is a convenience structure that can be used to pass IMU data around
+
+typedef struct
+{
+    uint64_t timestamp;
+    bool fusionPoseValid;
+    RTVector3 fusionPose;
+    bool fusionQPoseValid;
+    RTQuaternion fusionQPose;
+    bool gyroValid;
+    RTVector3 gyro;
+    bool accelValid;
+    RTVector3 accel;
+    bool compassValid;
+    RTVector3 compass;
+    bool pressureValid;
+    RTFLOAT pressure;
+    bool temperatureValid;
+    RTFLOAT temperature;
+    bool humidityValid;
+    RTFLOAT humidity;
+} RTIMU_DATA;
+
+#endif // _RTIMULIBDEFS_H
diff --git a/libraries/RTIMULib/RTIMUMagCal.cpp b/libraries/RTIMULib/RTIMUMagCal.cpp
new file mode 100644
index 0000000..ff7e6c7
--- /dev/null
+++ b/libraries/RTIMULib/RTIMUMagCal.cpp
@@ -0,0 +1,80 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTIMUMagCal.h"
+
+RTIMUMagCal::RTIMUMagCal(RTIMUSettings *settings)
+{
+    m_settings = settings;
+}
+
+RTIMUMagCal::~RTIMUMagCal()
+{
+
+}
+
+void RTIMUMagCal::magCalInit()
+{
+    magCalReset();
+}
+
+void RTIMUMagCal::magCalReset()
+{
+    m_magMin = RTVector3(RTIMUCALDEFS_DEFAULT_MIN, RTIMUCALDEFS_DEFAULT_MIN, RTIMUCALDEFS_DEFAULT_MIN);
+    m_magMax = RTVector3(RTIMUCALDEFS_DEFAULT_MAX, RTIMUCALDEFS_DEFAULT_MAX, RTIMUCALDEFS_DEFAULT_MAX);
+}
+
+void RTIMUMagCal::newMinMaxData(const RTVector3& data)
+{
+    for (int i = 0; i < 3; i++) {
+	    if (m_magMin.data(i) > data.data(i)) {
+		    m_magMin.setData(i, data.data(i));
+	    }
+
+	    if (m_magMax.data(i) < data.data(i)) {
+		    m_magMax.setData(i, data.data(i));
+	    }
+    }
+}
+
+bool RTIMUMagCal::magCalValid()
+{
+    bool valid = true;
+
+     for (int i = 0; i < 3; i++) {
+        if (m_magMax.data(i) < m_magMin.data(i))
+            valid = false;
+    }
+    return valid;
+
+}
+
+void RTIMUMagCal::magCalSaveMinMax()
+{
+    m_settings->m_compassCalValid = true;
+    m_settings->m_compassCalMin = m_magMin;
+    m_settings->m_compassCalMax = m_magMax;
+    m_settings->m_compassCalEllipsoidValid = false;
+    m_settings->saveSettings();
+}
diff --git a/libraries/RTIMULib/RTIMUMagCal.h b/libraries/RTIMULib/RTIMUMagCal.h
new file mode 100644
index 0000000..9158d23
--- /dev/null
+++ b/libraries/RTIMULib/RTIMUMagCal.h
@@ -0,0 +1,62 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTIMUMAGCAL_H
+#define	_RTIMUMAGCAL_H
+
+#include "RTIMUCalDefs.h"
+#include "RTIMULib.h"
+
+class RTIMUMagCal
+{
+
+public:
+    RTIMUMagCal(RTIMUSettings *settings);
+    virtual ~RTIMUMagCal();
+
+    void magCalInit();                                      // inits everything
+    void magCalReset();                                     // clears everything
+
+    // newMinMaxData() is used to submit a new sample for min/max processing
+    void newMinMaxData(const RTVector3& data);
+
+    // magCalValid() determines if the min/max data is basically valid
+    bool magCalValid();
+
+    // magCalSaveMinMax() saves the current min/max values to settings
+    void magCalSaveMinMax();
+
+    // these vars used during the calibration process
+
+   	RTVector3 m_magMin;                                     // the min values
+	RTVector3 m_magMax;                                     // the max values
+
+    RTIMUSettings *m_settings;
+
+private:
+    RTVector3 m_minMaxOffset;                               // the min/max calibration offset
+    RTVector3 m_minMaxScale;                                // the min/max scale
+};
+
+#endif // _RTIMUMAGCAL_H
diff --git a/libraries/RTIMULib/RTIMUSettings.cpp b/libraries/RTIMULib/RTIMUSettings.cpp
new file mode 100644
index 0000000..78d3c22
--- /dev/null
+++ b/libraries/RTIMULib/RTIMUSettings.cpp
@@ -0,0 +1,1555 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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.
+
+//  The MPU-9250 driver code is based on code generously supplied by
+//  staslock@gmail.com (www.clickdrive.io)
+
+
+#include "RTIMUSettings.h"
+#include "utility/RTIMUMPU9150.h"
+#include "utility/RTIMUMPU9250.h"
+#include "utility/RTIMUGD20HM303D.h"
+#include "utility/RTIMUGD20M303DLHC.h"
+#include "utility/RTIMUGD20HM303DLHC.h"
+#include "utility/RTIMULSM9DS0.h"
+#include "utility/RTIMUBMX055.h"
+
+#include "utility/RTPressureBMP180.h"
+#include "utility/RTPressureLPS25H.h"
+#include "utility/RTPressureMS5611.h"
+
+#define BUFFER_SIZE 200
+
+RTIMUSettings::RTIMUSettings(const char *productType)
+{
+    if ((strlen(productType) > 200) || (strlen(productType) == 0)) {
+        HAL_ERROR("Product name too long or null - using default\n");
+        strcpy(m_filename, "RTIMULib.ini");
+    } else {
+        sprintf(m_filename, "%s.ini", productType);
+    }
+    pinMode(SD_CHIP_SELECT, OUTPUT);
+    if (!SD.begin(SD_CHIP_SELECT)) {
+        Serial.println("SD card not found - using EEPROM mag calibration settings");
+        m_usingSD = false;
+    } else {
+        Serial.println("Using SD card for settings");
+        m_usingSD = true;
+    }
+
+    loadSettings();
+}
+
+bool RTIMUSettings::discoverIMU(int& imuType, bool& busIsI2C, unsigned char& slaveAddress)
+{
+    unsigned char result;
+    unsigned char altResult;
+
+    //  auto detect on I2C bus
+
+    m_busIsI2C = true;
+
+    if (HALOpen()) {
+
+        if (HALRead(MPU9150_ADDRESS0, MPU9150_WHO_AM_I, 1, &result, "")) {
+            if (result == MPU9250_ID) {
+                imuType = RTIMU_TYPE_MPU9250;
+                slaveAddress = MPU9250_ADDRESS0;
+                busIsI2C = true;
+                HAL_INFO("Detected MPU9250 at standard address\n");
+                return true;
+            } else if (result == MPU9150_ID) {
+                imuType = RTIMU_TYPE_MPU9150;
+                slaveAddress = MPU9150_ADDRESS0;
+                busIsI2C = true;
+                HAL_INFO("Detected MPU9150 at standard address\n");
+                return true;
+            }
+        }
+
+        if (HALRead(MPU9150_ADDRESS1, MPU9150_WHO_AM_I, 1, &result, "")) {
+            if (result == MPU9250_ID) {
+                imuType = RTIMU_TYPE_MPU9250;
+                slaveAddress = MPU9250_ADDRESS1;
+                busIsI2C = true;
+                HAL_INFO("Detected MPU9250 at option address\n");
+                return true;
+            } else if (result == MPU9150_ID) {
+                imuType = RTIMU_TYPE_MPU9150;
+                slaveAddress = MPU9150_ADDRESS1;
+                busIsI2C = true;
+                HAL_INFO("Detected MPU9150 at option address\n");
+                return true;
+            }
+        }
+
+        if (HALRead(L3GD20H_ADDRESS0, L3GD20H_WHO_AM_I, 1, &result, "")) {
+            if (result == L3GD20H_ID) {
+                if (HALRead(LSM303D_ADDRESS0, LSM303D_WHO_AM_I, 1, &altResult, "")) {
+                    if (altResult == LSM303D_ID) {
+                        imuType = RTIMU_TYPE_GD20HM303D;
+                        slaveAddress = L3GD20H_ADDRESS0;
+                        busIsI2C = true;
+                        HAL_INFO("Detected L3GD20H/LSM303D at standard/standard address\n");
+                        return true;
+                    }
+                }
+                if (HALRead(LSM303D_ADDRESS1, LSM303D_WHO_AM_I, 1, &altResult, "")) {
+                    if (altResult == LSM303D_ID) {
+                        imuType = RTIMU_TYPE_GD20HM303D;
+                        slaveAddress = L3GD20H_ADDRESS0;
+                        busIsI2C = true;
+                        HAL_INFO("Detected L3GD20H/LSM303D at standard/option address\n");
+                        return true;
+                    }
+                }
+                if (HALRead(LSM303DLHC_ACCEL_ADDRESS, LSM303DLHC_STATUS_A, 1, &altResult, "")) {
+                    imuType = RTIMU_TYPE_GD20HM303DLHC;
+                    slaveAddress = L3GD20H_ADDRESS0;
+                    busIsI2C = true;
+                    HAL_INFO("Detected L3GD20H/LSM303DLHC at standard/standard address\n");
+                    return true;
+                }
+            } else if (result == LSM9DS0_GYRO_ID) {
+                if (HALRead(LSM9DS0_ACCELMAG_ADDRESS0, LSM9DS0_WHO_AM_I, 1, &altResult, "")) {
+                    if (altResult == LSM9DS0_ACCELMAG_ID) {
+                        imuType = RTIMU_TYPE_LSM9DS0;
+                        slaveAddress = LSM9DS0_GYRO_ADDRESS0;
+                        busIsI2C = true;
+                        HAL_INFO("Detected LSM9DS0 at standard/standard address\n");
+                        return true;
+                    }
+                }
+                if (HALRead(LSM9DS0_ACCELMAG_ADDRESS1, LSM9DS0_WHO_AM_I, 1, &altResult, "")) {
+                    if (altResult == LSM9DS0_ACCELMAG_ID) {
+                        imuType = RTIMU_TYPE_LSM9DS0;
+                        slaveAddress = LSM9DS0_GYRO_ADDRESS0;
+                        busIsI2C = true;
+                        HAL_INFO("Detected LSM9DS0 at standard/option address\n");
+                        return true;
+                    }
+                }
+            }
+        }
+
+        if (HALRead(L3GD20H_ADDRESS1, L3GD20H_WHO_AM_I, 1, &result, "")) {
+            if (result == L3GD20H_ID) {
+                if (HALRead(LSM303D_ADDRESS1, LSM303D_WHO_AM_I, 1, &altResult, "")) {
+                    if (altResult == LSM303D_ID) {
+                        imuType = RTIMU_TYPE_GD20HM303D;
+                        slaveAddress = L3GD20H_ADDRESS1;
+                        busIsI2C = true;
+                        HAL_INFO("Detected L3GD20H/LSM303D at option/option address\n");
+                        return true;
+                    }
+                }
+                if (HALRead(LSM303D_ADDRESS0, LSM303D_WHO_AM_I, 1, &altResult, "")) {
+                    if (altResult == LSM303D_ID) {
+                        imuType = RTIMU_TYPE_GD20HM303D;
+                        slaveAddress = L3GD20H_ADDRESS1;
+                        busIsI2C = true;
+                        HAL_INFO("Detected L3GD20H/LSM303D at option/standard address\n");
+                        return true;
+                    }
+                }
+                if (HALRead(LSM303DLHC_ACCEL_ADDRESS, LSM303DLHC_STATUS_A, 1, &altResult, "")) {
+                    imuType = RTIMU_TYPE_GD20HM303DLHC;
+                    slaveAddress = L3GD20H_ADDRESS1;
+                    busIsI2C = true;
+                    HAL_INFO("Detected L3GD20H/LSM303DLHC at option/standard address\n");
+                    return true;
+                }
+            } else if (result == LSM9DS0_GYRO_ID) {
+                if (HALRead(LSM9DS0_ACCELMAG_ADDRESS1, LSM9DS0_WHO_AM_I, 1, &altResult, "")) {
+                    if (altResult == LSM9DS0_ACCELMAG_ID) {
+                        imuType = RTIMU_TYPE_LSM9DS0;
+                        slaveAddress = LSM9DS0_GYRO_ADDRESS1;
+                        busIsI2C = true;
+                        HAL_INFO("Detected LSM9DS0 at option/option address\n");
+                        return true;
+                    }
+                }
+                if (HALRead(LSM9DS0_ACCELMAG_ADDRESS0, LSM9DS0_WHO_AM_I, 1, &altResult, "")) {
+                    if (altResult == LSM9DS0_ACCELMAG_ID) {
+                        imuType = RTIMU_TYPE_LSM9DS0;
+                        slaveAddress = LSM9DS0_GYRO_ADDRESS1;
+                        busIsI2C = true;
+                        HAL_INFO("Detected LSM9DS0 at option/standard address\n");
+                        return true;
+                    }
+                }
+            }
+        }
+
+        if (HALRead(L3GD20_ADDRESS0, L3GD20_WHO_AM_I, 1, &result, "")) {
+            if (result == L3GD20_ID) {
+                imuType = RTIMU_TYPE_GD20M303DLHC;
+                slaveAddress = L3GD20_ADDRESS0;
+                busIsI2C = true;
+                HAL_INFO("Detected L3GD20 at standard address\n");
+                return true;
+            }
+        }
+
+        if (HALRead(L3GD20_ADDRESS1, L3GD20_WHO_AM_I, 1, &result, "")) {
+            if (result == L3GD20_ID) {
+                imuType = RTIMU_TYPE_GD20M303DLHC;
+                slaveAddress = L3GD20_ADDRESS1;
+                busIsI2C = true;
+                HAL_INFO("Detected L3GD20 at option address\n");
+                return true;
+            }
+        }
+
+        if (HALRead(BMX055_GYRO_ADDRESS0, BMX055_GYRO_WHO_AM_I, 1, &result, "")) {
+            if (result == BMX055_GYRO_ID) {
+                imuType = RTIMU_TYPE_BMX055;
+                slaveAddress = BMX055_GYRO_ADDRESS0;
+                busIsI2C = true;
+                HAL_INFO("Detected BMX055 at standard address\n");
+                return true;
+            }
+        }
+        if (HALRead(BMX055_GYRO_ADDRESS1, BMX055_GYRO_WHO_AM_I, 1, &result, "")) {
+            if (result == BMX055_GYRO_ID) {
+                imuType = RTIMU_TYPE_BMX055;
+                slaveAddress = BMX055_GYRO_ADDRESS1;
+                busIsI2C = true;
+                HAL_INFO("Detected BMX055 at option address\n");
+                return true;
+            }
+        }
+        if (HALRead(BNO055_ADDRESS0, BNO055_WHO_AM_I, 1, &result, "")) {
+            if (result == BNO055_ID) {
+                imuType = RTIMU_TYPE_BNO055;
+                slaveAddress = BNO055_ADDRESS0;
+                busIsI2C = true;
+                HAL_INFO("Detected BNO055 at standard address\n");
+                return true;
+            }
+        }
+        if (HALRead(BNO055_ADDRESS1, BNO055_WHO_AM_I, 1, &result, "")) {
+            if (result == BNO055_ID) {
+                imuType = RTIMU_TYPE_BNO055;
+                slaveAddress = BNO055_ADDRESS1;
+                busIsI2C = true;
+                HAL_INFO("Detected BNO055 at option address\n");
+                return true;
+            }
+        }
+        HALClose();
+    }
+
+    //  nothing found on I2C bus - try SPI instead
+
+    m_busIsI2C = false;
+    m_SPIBus = 0;
+    m_SPISelect = IMU_CHIP_SELECT;
+
+    if (HALOpen()) {
+        if (HALRead(MPU9250_ADDRESS0, MPU9250_WHO_AM_I, 1, &result, "")) {
+            if (result == MPU9250_ID) {
+                imuType = RTIMU_TYPE_MPU9250;
+                slaveAddress = MPU9250_ADDRESS0;
+                busIsI2C = false;
+                HAL_INFO1("Detected MPU9250 on SPI bus 0, select %d\n", IMU_CHIP_SELECT);
+                return true;
+            }
+        }
+        HALClose();
+    }
+
+    HAL_ERROR("No IMU detected\n");
+    return false;
+}
+
+bool RTIMUSettings::discoverPressure(int& pressureType, unsigned char& pressureAddress)
+{
+    unsigned char result;
+
+    //  auto detect on current bus
+
+    if (HALOpen()) {
+
+        if (HALRead(BMP180_ADDRESS, BMP180_REG_ID, 1, &result, "")) {
+            if (result == BMP180_ID) {
+                pressureType = RTPRESSURE_TYPE_BMP180;
+                pressureAddress = BMP180_ADDRESS;
+                HAL_INFO("Detected BMP180\n");
+                return true;
+            }
+        }
+
+        if (HALRead(LPS25H_ADDRESS0, LPS25H_REG_ID, 1, &result, "")) {
+            if (result == LPS25H_ID) {
+                pressureType = RTPRESSURE_TYPE_LPS25H;
+                pressureAddress = LPS25H_ADDRESS0;
+                HAL_INFO("Detected LPS25H at standard address\n");
+                return true;
+            }
+        }
+
+        if (HALRead(LPS25H_ADDRESS1, LPS25H_REG_ID, 1, &result, "")) {
+            if (result == LPS25H_ID) {
+                pressureType = RTPRESSURE_TYPE_LPS25H;
+                pressureAddress = LPS25H_ADDRESS1;
+                HAL_INFO("Detected LPS25H at option address\n");
+                return true;
+            }
+        }
+        // check for MS5611 (which unfortunately has no ID reg)
+
+        if (HALRead(MS5611_ADDRESS0, 0, 1, &result, "")) {
+            pressureType = RTPRESSURE_TYPE_MS5611;
+            pressureAddress = MS5611_ADDRESS0;
+            HAL_INFO("Detected MS5611 at standard address\n");
+            return true;
+        }
+        if (HALRead(MS5611_ADDRESS1, 0, 1, &result, "")) {
+            pressureType = RTPRESSURE_TYPE_MS5611;
+            pressureAddress = MS5611_ADDRESS1;
+            HAL_INFO("Detected MS5611 at option address\n");
+            return true;
+        }
+    }
+    HAL_ERROR("No pressure sensor detected\n");
+    return false;
+}
+
+void RTIMUSettings::setDefaults()
+{
+    //  preset general defaults
+
+    m_imuType = RTIMU_TYPE_AUTODISCOVER;
+    m_I2CSlaveAddress = 0;
+    m_busIsI2C = true;
+    m_I2CBus = 1;
+    m_SPIBus = 0;
+    m_SPISelect = IMU_CHIP_SELECT;
+    m_SPISpeed = 500000;
+    m_fusionType = RTFUSION_TYPE_RTQF;
+    m_axisRotation = RTIMU_XNORTH_YEAST;
+    m_pressureType = RTPRESSURE_TYPE_AUTODISCOVER;
+    m_I2CPressureAddress = 0;
+    m_compassCalValid = false;
+    m_compassCalEllipsoidValid = false;
+    for (int i = 0; i < 3; i++) {
+        for (int j = 0; j < 3; j++) {
+            m_compassCalEllipsoidCorr[i][j] = 0;
+        }
+    }
+    m_compassCalEllipsoidCorr[0][0] = 1;
+    m_compassCalEllipsoidCorr[1][1] = 1;
+    m_compassCalEllipsoidCorr[2][2] = 1;
+
+    m_compassAdjDeclination = 0;
+
+    m_accelCalValid = false;
+    m_gyroBiasValid = false;
+
+    //  MPU9150 defaults
+
+    m_MPU9150GyroAccelSampleRate = 50;
+    m_MPU9150CompassSampleRate = 25;
+    m_MPU9150GyroAccelLpf = MPU9150_LPF_20;
+    m_MPU9150GyroFsr = MPU9150_GYROFSR_1000;
+    m_MPU9150AccelFsr = MPU9150_ACCELFSR_8;
+
+    //  MPU9250 defaults
+
+    m_MPU9250GyroAccelSampleRate = 80;
+    m_MPU9250CompassSampleRate = 40;
+    m_MPU9250GyroLpf = MPU9250_GYRO_LPF_41;
+    m_MPU9250AccelLpf = MPU9250_ACCEL_LPF_41;
+    m_MPU9250GyroFsr = MPU9250_GYROFSR_1000;
+    m_MPU9250AccelFsr = MPU9250_ACCELFSR_8;
+
+    //  GD20HM303D defaults
+
+    m_GD20HM303DGyroSampleRate = L3GD20H_SAMPLERATE_50;
+    m_GD20HM303DGyroBW = L3GD20H_BANDWIDTH_1;
+    m_GD20HM303DGyroHpf = L3GD20H_HPF_4;
+    m_GD20HM303DGyroFsr = L3GD20H_FSR_500;
+
+    m_GD20HM303DAccelSampleRate = LSM303D_ACCEL_SAMPLERATE_50;
+    m_GD20HM303DAccelFsr = LSM303D_ACCEL_FSR_8;
+    m_GD20HM303DAccelLpf = LSM303D_ACCEL_LPF_50;
+
+    m_GD20HM303DCompassSampleRate = LSM303D_COMPASS_SAMPLERATE_50;
+    m_GD20HM303DCompassFsr = LSM303D_COMPASS_FSR_2;
+
+    //  GD20M303DLHC defaults
+
+    m_GD20M303DLHCGyroSampleRate = L3GD20_SAMPLERATE_95;
+    m_GD20M303DLHCGyroBW = L3GD20_BANDWIDTH_1;
+    m_GD20M303DLHCGyroHpf = L3GD20_HPF_4;
+    m_GD20M303DLHCGyroFsr = L3GD20H_FSR_500;
+
+    m_GD20M303DLHCAccelSampleRate = LSM303DLHC_ACCEL_SAMPLERATE_50;
+    m_GD20M303DLHCAccelFsr = LSM303DLHC_ACCEL_FSR_8;
+
+    m_GD20M303DLHCCompassSampleRate = LSM303DLHC_COMPASS_SAMPLERATE_30;
+    m_GD20M303DLHCCompassFsr = LSM303DLHC_COMPASS_FSR_1_3;
+
+    //  GD20HM303DLHC defaults
+
+    m_GD20HM303DLHCGyroSampleRate = L3GD20H_SAMPLERATE_50;
+    m_GD20HM303DLHCGyroBW = L3GD20H_BANDWIDTH_1;
+    m_GD20HM303DLHCGyroHpf = L3GD20H_HPF_4;
+    m_GD20HM303DLHCGyroFsr = L3GD20H_FSR_500;
+
+    m_GD20HM303DLHCAccelSampleRate = LSM303DLHC_ACCEL_SAMPLERATE_50;
+    m_GD20HM303DLHCAccelFsr = LSM303DLHC_ACCEL_FSR_8;
+
+    m_GD20HM303DLHCCompassSampleRate = LSM303DLHC_COMPASS_SAMPLERATE_30;
+    m_GD20HM303DLHCCompassFsr = LSM303DLHC_COMPASS_FSR_1_3;
+
+    //  LSM9DS0 defaults
+
+    m_LSM9DS0GyroSampleRate = LSM9DS0_GYRO_SAMPLERATE_95;
+    m_LSM9DS0GyroBW = LSM9DS0_GYRO_BANDWIDTH_1;
+    m_LSM9DS0GyroHpf = LSM9DS0_GYRO_HPF_4;
+    m_LSM9DS0GyroFsr = LSM9DS0_GYRO_FSR_500;
+
+    m_LSM9DS0AccelSampleRate = LSM9DS0_ACCEL_SAMPLERATE_50;
+    m_LSM9DS0AccelFsr = LSM9DS0_ACCEL_FSR_8;
+    m_LSM9DS0AccelLpf = LSM9DS0_ACCEL_LPF_50;
+
+    m_LSM9DS0CompassSampleRate = LSM9DS0_COMPASS_SAMPLERATE_50;
+    m_LSM9DS0CompassFsr = LSM9DS0_COMPASS_FSR_2;
+
+    // BMX055 defaults
+
+    m_BMX055GyroSampleRate = BMX055_GYRO_SAMPLERATE_100_32;
+    m_BMX055GyroFsr = BMX055_GYRO_FSR_500;
+
+    m_BMX055AccelSampleRate = BMX055_ACCEL_SAMPLERATE_125;
+    m_BMX055AccelFsr = BMX055_ACCEL_FSR_8;
+
+    m_BMX055MagPreset = BMX055_MAG_REGULAR;
+}
+
+bool RTIMUSettings::loadSettings()
+{
+    char buf[BUFFER_SIZE];
+    char key[BUFFER_SIZE];
+    char val[BUFFER_SIZE];
+    RTFLOAT ftemp;
+    int bufIndex;
+
+    setDefaults();
+
+    if (!m_usingSD) {
+        //  see if EEPROM has valid cal data
+        m_compassCalValid = false;
+
+        RTIMULIB_CAL_DATA calData;
+        if (EERead(0, &calData)) {
+            if (calData.magValid != 1) {
+                 return true;
+            }
+        } else {
+            return true;
+        }
+        m_compassCalValid = true;
+        m_compassCalMin.setX(calData.magMin[0]);
+        m_compassCalMin.setY(calData.magMin[1]);
+        m_compassCalMin.setZ(calData.magMin[2]);
+        m_compassCalMax.setX(calData.magMax[0]);
+        m_compassCalMax.setY(calData.magMax[1]);
+        m_compassCalMax.setZ(calData.magMax[2]);
+        return true;
+    }
+
+    //  check to see if settings file exists
+
+    if (!(m_fd = SD.open(m_filename))) {
+        HAL_INFO("Settings file not found. Using defaults and creating settings file\n");
+        return saveSettings();
+    }
+
+    while (true) {
+
+        //  read in a line
+
+        for (bufIndex = 0; bufIndex < BUFFER_SIZE; bufIndex++) {
+            if ((buf[bufIndex] = m_fd.read()) == 0xff) {
+                m_fd.close();
+                return true;                                // end of file
+            }
+            if ((buf[bufIndex] == '\r') || (buf[bufIndex] == '\n')) {
+                buf[bufIndex] = 0;
+                break;
+            }
+        }
+        if (bufIndex == BUFFER_SIZE)
+            buf[BUFFER_SIZE - 1] = 0;
+ 
+        if ((buf[0] == '#') || (buf[0] == ' ') || (buf[0] == 0))
+            // just a comment
+            continue;
+ 
+        if (sscanf(buf, "%[^=]=%s", key, val) != 2) {
+            HAL_ERROR1("Bad line in settings file: %s\n", buf);
+            m_fd.close();
+            return false;
+        }
+
+        //  now decode keys
+
+        //  general config
+
+        if (strcmp(key, RTIMULIB_IMU_TYPE) == 0) {
+            m_imuType = atoi(val);
+        } else if (strcmp(key, RTIMULIB_FUSION_TYPE) == 0) {
+            m_fusionType = atoi(val);
+        } else if (strcmp(key, RTIMULIB_BUS_IS_I2C) == 0) {
+            m_busIsI2C = strcmp(val, "true") == 0;
+        } else if (strcmp(key, RTIMULIB_I2C_BUS) == 0) {
+            m_I2CBus = atoi(val);
+        } else if (strcmp(key, RTIMULIB_SPI_BUS) == 0) {
+            m_SPIBus = atoi(val);
+        } else if (strcmp(key, RTIMULIB_SPI_SELECT) == 0) {
+            m_SPISelect = atoi(val);
+        } else if (strcmp(key, RTIMULIB_SPI_SPEED) == 0) {
+            m_SPISpeed = atoi(val);
+        } else if (strcmp(key, RTIMULIB_I2C_SLAVEADDRESS) == 0) {
+            m_I2CSlaveAddress = atoi(val);
+        } else if (strcmp(key, RTIMULIB_AXIS_ROTATION) == 0) {
+            m_axisRotation = atoi(val);
+        } else if (strcmp(key, RTIMULIB_PRESSURE_TYPE) == 0) {
+            m_pressureType = atoi(val);
+        } else if (strcmp(key, RTIMULIB_I2C_PRESSUREADDRESS) == 0) {
+            m_I2CPressureAddress = atoi(val);
+
+        // compass calibration
+
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_VALID) == 0) {
+            m_compassCalValid = strcmp(val, "true") == 0;
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_MINX) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalMin.setX(ftemp);
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_MINY) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalMin.setY(ftemp);
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_MINZ) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalMin.setZ(ftemp);
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_MAXX) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalMax.setX(ftemp);
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_MAXY) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalMax.setY(ftemp);
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_MAXZ) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalMax.setZ(ftemp);
+        } else if (strcmp(key, RTIMULIB_COMPASSADJ_DECLINATION) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassAdjDeclination = ftemp;
+
+        // compass ellipsoid calibration
+
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_ELLIPSOID_VALID) == 0) {
+            m_compassCalEllipsoidValid = strcmp(val, "true") == 0;
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_OFFSET_X) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalEllipsoidOffset.setX(ftemp);
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_OFFSET_Y) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalEllipsoidOffset.setY(ftemp);
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_OFFSET_Z) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalEllipsoidOffset.setZ(ftemp);
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_CORR11) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalEllipsoidCorr[0][0] = ftemp;
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_CORR12) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalEllipsoidCorr[0][1] = ftemp;
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_CORR13) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalEllipsoidCorr[0][2] = ftemp;
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_CORR21) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalEllipsoidCorr[1][0] = ftemp;
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_CORR22) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalEllipsoidCorr[1][1] = ftemp;
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_CORR23) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalEllipsoidCorr[1][2] = ftemp;
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_CORR31) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalEllipsoidCorr[2][0] = ftemp;
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_CORR32) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalEllipsoidCorr[2][1] = ftemp;
+        } else if (strcmp(key, RTIMULIB_COMPASSCAL_CORR33) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_compassCalEllipsoidCorr[2][2] = ftemp;
+
+            // accel calibration
+
+        } else if (strcmp(key, RTIMULIB_ACCELCAL_VALID) == 0) {
+            m_accelCalValid = strcmp(val, "true") == 0;
+        } else if (strcmp(key, RTIMULIB_ACCELCAL_MINX) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_accelCalMin.setX(ftemp);
+        } else if (strcmp(key, RTIMULIB_ACCELCAL_MINY) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_accelCalMin.setY(ftemp);
+        } else if (strcmp(key, RTIMULIB_ACCELCAL_MINZ) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_accelCalMin.setZ(ftemp);
+        } else if (strcmp(key, RTIMULIB_ACCELCAL_MAXX) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_accelCalMax.setX(ftemp);
+        } else if (strcmp(key, RTIMULIB_ACCELCAL_MAXY) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_accelCalMax.setY(ftemp);
+        } else if (strcmp(key, RTIMULIB_ACCELCAL_MAXZ) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_accelCalMax.setZ(ftemp);
+
+            // gyro bias
+
+        } else if (strcmp(key, RTIMULIB_GYRO_BIAS_VALID) == 0) {
+            m_gyroBiasValid = strcmp(val, "true") == 0;
+        } else if (strcmp(key, RTIMULIB_GYRO_BIAS_X) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_gyroBias.setX(ftemp);
+        } else if (strcmp(key, RTIMULIB_GYRO_BIAS_Y) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_gyroBias.setY(ftemp);
+        } else if (strcmp(key, RTIMULIB_GYRO_BIAS_Z) == 0) {
+            sscanf(val, "%f", &ftemp);
+            m_gyroBias.setZ(ftemp);
+
+        //  MPU9150 settings
+
+        } else if (strcmp(key, RTIMULIB_MPU9150_GYROACCEL_SAMPLERATE) == 0) {
+            m_MPU9150GyroAccelSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_MPU9150_COMPASS_SAMPLERATE) == 0) {
+            m_MPU9150CompassSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_MPU9150_GYROACCEL_LPF) == 0) {
+            m_MPU9150GyroAccelLpf = atoi(val);
+        } else if (strcmp(key, RTIMULIB_MPU9150_GYRO_FSR) == 0) {
+            m_MPU9150GyroFsr = atoi(val);
+        } else if (strcmp(key, RTIMULIB_MPU9150_ACCEL_FSR) == 0) {
+            m_MPU9150AccelFsr = atoi(val);
+
+        //  MPU9250 settings
+
+        } else if (strcmp(key, RTIMULIB_MPU9250_GYROACCEL_SAMPLERATE) == 0) {
+            m_MPU9250GyroAccelSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_MPU9250_COMPASS_SAMPLERATE) == 0) {
+            m_MPU9250CompassSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_MPU9250_GYRO_LPF) == 0) {
+            m_MPU9250GyroLpf = atoi(val);
+        } else if (strcmp(key, RTIMULIB_MPU9250_ACCEL_LPF) == 0) {
+            m_MPU9250AccelLpf = atoi(val);
+        } else if (strcmp(key, RTIMULIB_MPU9250_GYRO_FSR) == 0) {
+            m_MPU9250GyroFsr = atoi(val);
+        } else if (strcmp(key, RTIMULIB_MPU9250_ACCEL_FSR) == 0) {
+            m_MPU9250AccelFsr = atoi(val);
+
+        //  GD20HM303D settings
+
+        } else if (strcmp(key, RTIMULIB_GD20HM303D_GYRO_SAMPLERATE) == 0) {
+            m_GD20HM303DGyroSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303D_GYRO_FSR) == 0) {
+            m_GD20HM303DGyroFsr = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303D_GYRO_HPF) == 0) {
+            m_GD20HM303DGyroHpf = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303D_GYRO_BW) == 0) {
+            m_GD20HM303DGyroBW = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303D_ACCEL_SAMPLERATE) == 0) {
+            m_GD20HM303DAccelSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303D_ACCEL_FSR) == 0) {
+            m_GD20HM303DAccelFsr = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303D_ACCEL_LPF) == 0) {
+            m_GD20HM303DAccelLpf = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303D_COMPASS_SAMPLERATE) == 0) {
+            m_GD20HM303DCompassSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303D_COMPASS_FSR) == 0) {
+            m_GD20HM303DCompassFsr = atoi(val);
+
+        //  GD20M303DLHC settings
+
+        } else if (strcmp(key, RTIMULIB_GD20M303DLHC_GYRO_SAMPLERATE) == 0) {
+            m_GD20M303DLHCGyroSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20M303DLHC_GYRO_FSR) == 0) {
+            m_GD20M303DLHCGyroFsr = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20M303DLHC_GYRO_HPF) == 0) {
+            m_GD20M303DLHCGyroHpf = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20M303DLHC_GYRO_BW) == 0) {
+            m_GD20M303DLHCGyroBW = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20M303DLHC_ACCEL_SAMPLERATE) == 0) {
+            m_GD20M303DLHCAccelSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20M303DLHC_ACCEL_FSR) == 0) {
+            m_GD20M303DLHCAccelFsr = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20M303DLHC_COMPASS_SAMPLERATE) == 0) {
+            m_GD20M303DLHCCompassSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20M303DLHC_COMPASS_FSR) == 0) {
+            m_GD20M303DLHCCompassFsr = atoi(val);
+
+        //  GD20HM303DLHC settings
+
+         } else if (strcmp(key, RTIMULIB_GD20HM303DLHC_GYRO_SAMPLERATE) == 0) {
+            m_GD20HM303DLHCGyroSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303DLHC_GYRO_FSR) == 0) {
+            m_GD20HM303DLHCGyroFsr = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303DLHC_GYRO_HPF) == 0) {
+            m_GD20HM303DLHCGyroHpf = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303DLHC_GYRO_BW) == 0) {
+            m_GD20HM303DLHCGyroBW = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303DLHC_ACCEL_SAMPLERATE) == 0) {
+            m_GD20HM303DLHCAccelSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303DLHC_ACCEL_FSR) == 0) {
+            m_GD20HM303DLHCAccelFsr = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303DLHC_COMPASS_SAMPLERATE) == 0) {
+            m_GD20HM303DLHCCompassSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_GD20HM303DLHC_COMPASS_FSR) == 0) {
+            m_GD20HM303DLHCCompassFsr = atoi(val);
+
+        //  LSM9DS0 settings
+
+        } else if (strcmp(key, RTIMULIB_LSM9DS0_GYRO_SAMPLERATE) == 0) {
+            m_LSM9DS0GyroSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_LSM9DS0_GYRO_FSR) == 0) {
+            m_LSM9DS0GyroFsr = atoi(val);
+        } else if (strcmp(key, RTIMULIB_LSM9DS0_GYRO_HPF) == 0) {
+            m_LSM9DS0GyroHpf = atoi(val);
+        } else if (strcmp(key, RTIMULIB_LSM9DS0_GYRO_BW) == 0) {
+            m_LSM9DS0GyroBW = atoi(val);
+        } else if (strcmp(key, RTIMULIB_LSM9DS0_ACCEL_SAMPLERATE) == 0) {
+            m_LSM9DS0AccelSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_LSM9DS0_ACCEL_FSR) == 0) {
+            m_LSM9DS0AccelFsr = atoi(val);
+        } else if (strcmp(key, RTIMULIB_LSM9DS0_ACCEL_LPF) == 0) {
+            m_LSM9DS0AccelLpf = atoi(val);
+        } else if (strcmp(key, RTIMULIB_LSM9DS0_COMPASS_SAMPLERATE) == 0) {
+            m_LSM9DS0CompassSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_LSM9DS0_COMPASS_FSR) == 0) {
+            m_LSM9DS0CompassFsr = atoi(val);
+
+        //  BMX055 settings
+
+        } else if (strcmp(key, RTIMULIB_BMX055_GYRO_SAMPLERATE) == 0) {
+            m_BMX055GyroSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_BMX055_GYRO_FSR) == 0) {
+            m_BMX055GyroFsr = atoi(val);
+        } else if (strcmp(key, RTIMULIB_BMX055_ACCEL_SAMPLERATE) == 0) {
+            m_BMX055AccelSampleRate = atoi(val);
+        } else if (strcmp(key, RTIMULIB_BMX055_ACCEL_FSR) == 0) {
+            m_BMX055AccelFsr = atoi(val);
+        } else if (strcmp(key, RTIMULIB_BMX055_MAG_PRESET) == 0) {
+            m_BMX055MagPreset = atoi(val);
+
+        //  Handle unrecognized key
+
+        } else {
+            HAL_ERROR1("Unrecognized key in settings file: %s\n", buf);
+        }
+    }
+    HAL_INFO1("Settings file %s loaded\n", m_filename);
+    m_fd.close();
+    return saveSettings();                                  // make sure settings file is correct and complete
+}
+
+bool RTIMUSettings::saveSettings()
+{
+    if (!m_usingSD) {
+        RTIMULIB_CAL_DATA calData;
+
+        calData.magValid = m_compassCalValid;
+        calData.magMin[0] = m_compassCalMin.x();
+        calData.magMin[1] = m_compassCalMin.y();
+        calData.magMin[2] = m_compassCalMin.z();
+        calData.magMax[0] = m_compassCalMax.x();
+        calData.magMax[1] = m_compassCalMax.y();
+        calData.magMax[2] = m_compassCalMax.z();
+
+        EEWrite(0, &calData);
+        return true;
+    }
+
+    SD.remove(m_filename);
+
+    if (!(m_fd = SD.open(m_filename, FILE_WRITE))) {
+        HAL_ERROR("Failed to open settings file for save");
+        return false;
+    }
+
+    //  General settings
+
+    setComment("#####################################################################");
+    setComment("");
+    setComment("RTIMULib settings file");
+    setBlank();
+    setComment("General settings");
+    setComment("");
+
+    setBlank();
+    setComment("IMU type - ");
+    setComment("  0 = Auto discover");
+    setComment("  1 = Null (used when data is provided from a remote IMU");
+    setComment("  2 = InvenSense MPU-9150");
+    setComment("  3 = STM L3GD20H + LSM303D");
+    setComment("  4 = STM L3GD20 + LSM303DLHC");
+    setComment("  5 = STM LSM9DS0");
+    setComment("  6 = InvenSense MPU-9250");
+    setComment("  7 = STM L3GD20H + LSM303DLHC");
+    setValue(RTIMULIB_IMU_TYPE, m_imuType);
+
+    setBlank();
+    setComment("");
+    setComment("Fusion type type - ");
+    setComment("  0 - Null. Use if only sensor data required without fusion");
+    setComment("  1 - Kalman STATE4");
+    setComment("  2 - RTQF");
+    setValue(RTIMULIB_FUSION_TYPE, m_fusionType);
+
+    setBlank();
+    setComment("");
+    setComment("Is bus I2C: 'true' for I2C, 'false' for SPI");
+    setValue(RTIMULIB_BUS_IS_I2C, m_busIsI2C);
+
+    setBlank();
+    setComment("");
+    setComment("I2C Bus (between 0 and 7) ");
+    setValue(RTIMULIB_I2C_BUS, m_I2CBus);
+
+    setBlank();
+    setComment("");
+    setComment("SPI Bus (between 0 and 7) ");
+    setValue(RTIMULIB_SPI_BUS, m_SPIBus);
+
+    setBlank();
+    setComment("");
+    setComment("SPI select pin (default pin 9) ");
+    setValue(RTIMULIB_SPI_SELECT, m_SPISelect);
+
+    setBlank();
+    setComment("");
+    setComment("SPI Speed in Hz");
+    setValue(RTIMULIB_SPI_SPEED, (int)m_SPISpeed);
+
+    setBlank();
+    setComment("");
+    setComment("I2C slave address (filled in automatically by auto discover) ");
+    setValue(RTIMULIB_I2C_SLAVEADDRESS, m_I2CSlaveAddress);
+
+    setBlank();
+    setComment("");
+    setComment("IMU axis rotation - see RTIMU.h for details");
+    setValue(RTIMULIB_AXIS_ROTATION, m_axisRotation);
+
+    setBlank();
+    setComment("Pressure sensor type - ");
+    setComment("  0 = Auto discover");
+    setComment("  1 = Null (no hardware or don't use)");
+    setComment("  2 = BMP180");
+    setComment("  3 = LPS25H");
+    setComment("  4 = MS5611");
+    setComment("  5 = MS5637");
+
+    setValue(RTIMULIB_PRESSURE_TYPE, m_pressureType);
+
+    setBlank();
+    setComment("");
+    setComment("I2C pressure sensor address (filled in automatically by auto discover) ");
+    setValue(RTIMULIB_I2C_PRESSUREADDRESS, m_I2CPressureAddress);
+
+   //  Compass calibration settings
+
+    setBlank();
+    setComment("#####################################################################");
+    setComment("");
+
+    setBlank();
+    setComment("Compass calibration");
+    setValue(RTIMULIB_COMPASSCAL_VALID, m_compassCalValid);
+    setValue(RTIMULIB_COMPASSCAL_MINX, m_compassCalMin.x());
+    setValue(RTIMULIB_COMPASSCAL_MINY, m_compassCalMin.y());
+    setValue(RTIMULIB_COMPASSCAL_MINZ, m_compassCalMin.z());
+    setValue(RTIMULIB_COMPASSCAL_MAXX, m_compassCalMax.x());
+    setValue(RTIMULIB_COMPASSCAL_MAXY, m_compassCalMax.y());
+    setValue(RTIMULIB_COMPASSCAL_MAXZ, m_compassCalMax.z());
+
+    setBlank();
+    setComment("#####################################################################");
+    setComment("");
+
+    setBlank();
+    setComment("Compass adjustment settings");
+    setComment("Compass declination is in radians and is subtracted from calculated heading");
+    setValue(RTIMULIB_COMPASSADJ_DECLINATION, m_compassAdjDeclination);
+
+    //  Compass ellipsoid calibration settings
+
+    setBlank();
+    setComment("#####################################################################");
+    setComment("");
+
+    setBlank();
+    setComment("Compass ellipsoid calibration");
+    setValue(RTIMULIB_COMPASSCAL_ELLIPSOID_VALID, m_compassCalEllipsoidValid);
+    setValue(RTIMULIB_COMPASSCAL_OFFSET_X, m_compassCalEllipsoidOffset.x());
+    setValue(RTIMULIB_COMPASSCAL_OFFSET_Y, m_compassCalEllipsoidOffset.y());
+    setValue(RTIMULIB_COMPASSCAL_OFFSET_Z, m_compassCalEllipsoidOffset.z());
+    setValue(RTIMULIB_COMPASSCAL_CORR11, m_compassCalEllipsoidCorr[0][0]);
+    setValue(RTIMULIB_COMPASSCAL_CORR12, m_compassCalEllipsoidCorr[0][1]);
+    setValue(RTIMULIB_COMPASSCAL_CORR13, m_compassCalEllipsoidCorr[0][2]);
+    setValue(RTIMULIB_COMPASSCAL_CORR21, m_compassCalEllipsoidCorr[1][0]);
+    setValue(RTIMULIB_COMPASSCAL_CORR22, m_compassCalEllipsoidCorr[1][1]);
+    setValue(RTIMULIB_COMPASSCAL_CORR23, m_compassCalEllipsoidCorr[1][2]);
+    setValue(RTIMULIB_COMPASSCAL_CORR31, m_compassCalEllipsoidCorr[2][0]);
+    setValue(RTIMULIB_COMPASSCAL_CORR32, m_compassCalEllipsoidCorr[2][1]);
+    setValue(RTIMULIB_COMPASSCAL_CORR33, m_compassCalEllipsoidCorr[2][2]);
+
+    //  Accel calibration settings
+
+    setBlank();
+    setComment("#####################################################################");
+    setComment("");
+
+    setBlank();
+    setComment("Accel calibration");
+    setValue(RTIMULIB_ACCELCAL_VALID, m_accelCalValid);
+    setValue(RTIMULIB_ACCELCAL_MINX, m_accelCalMin.x());
+    setValue(RTIMULIB_ACCELCAL_MINY, m_accelCalMin.y());
+    setValue(RTIMULIB_ACCELCAL_MINZ, m_accelCalMin.z());
+    setValue(RTIMULIB_ACCELCAL_MAXX, m_accelCalMax.x());
+    setValue(RTIMULIB_ACCELCAL_MAXY, m_accelCalMax.y());
+    setValue(RTIMULIB_ACCELCAL_MAXZ, m_accelCalMax.z());
+
+    //  Gyro bias settings
+
+    setBlank();
+    setComment("#####################################################################");
+    setComment("");
+
+    setBlank();
+    setComment("Saved gyro bias data");
+    setValue(RTIMULIB_GYRO_BIAS_VALID, m_gyroBiasValid);
+    setValue(RTIMULIB_GYRO_BIAS_X, m_gyroBias.x());
+    setValue(RTIMULIB_GYRO_BIAS_Y, m_gyroBias.y());
+    setValue(RTIMULIB_GYRO_BIAS_Z, m_gyroBias.z());
+
+    //  MPU-9150 settings
+
+    setBlank();
+    setComment("#####################################################################");
+    setComment("");
+    setComment("MPU-9150 settings");
+    setComment("");
+
+    setBlank();
+    setComment("Gyro sample rate (between 5Hz and 1000Hz) ");
+    setValue(RTIMULIB_MPU9150_GYROACCEL_SAMPLERATE, m_MPU9150GyroAccelSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Compass sample rate (between 1Hz and 100Hz) ");
+    setValue(RTIMULIB_MPU9150_COMPASS_SAMPLERATE, m_MPU9150CompassSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro/accel low pass filter - ");
+    setComment("  0 - gyro: 256Hz, accel: 260Hz");
+    setComment("  1 - gyro: 188Hz, accel: 184Hz");
+    setComment("  2 - gyro: 98Hz, accel: 98Hz");
+    setComment("  3 - gyro: 42Hz, accel: 44Hz");
+    setComment("  4 - gyro: 20Hz, accel: 21Hz");
+    setComment("  5 - gyro: 10Hz, accel: 10Hz");
+    setComment("  6 - gyro: 5Hz, accel: 5Hz");
+    setValue(RTIMULIB_MPU9150_GYROACCEL_LPF, m_MPU9150GyroAccelLpf);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro full scale range - ");
+    setComment("  0  - +/- 250 degress per second");
+    setComment("  8  - +/- 500 degress per second");
+    setComment("  16 - +/- 1000 degress per second");
+    setComment("  24 - +/- 2000 degress per second");
+    setValue(RTIMULIB_MPU9150_GYRO_FSR, m_MPU9150GyroFsr);
+
+    setBlank();
+    setComment("");
+    setComment("Accel full scale range - ");
+    setComment("  0  - +/- 2g");
+    setComment("  8  - +/- 4g");
+    setComment("  16 - +/- 8g");
+    setComment("  24 - +/- 16g");
+    setValue(RTIMULIB_MPU9150_ACCEL_FSR, m_MPU9150AccelFsr);
+
+    //  MPU-9250 settings
+
+    setBlank();
+    setComment("#####################################################################");
+    setComment("");
+    setComment("MPU-9250 settings");
+    setComment("");
+
+    setBlank();
+    setComment("Gyro sample rate (between 5Hz and 1000Hz plus 8000Hz and 32000Hz) ");
+    setValue(RTIMULIB_MPU9250_GYROACCEL_SAMPLERATE, m_MPU9250GyroAccelSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Compass sample rate (between 1Hz and 100Hz) ");
+    setValue(RTIMULIB_MPU9250_COMPASS_SAMPLERATE, m_MPU9250CompassSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro low pass filter - ");
+    setComment("  0x11 - 8800Hz, 0.64mS delay");
+    setComment("  0x10 - 3600Hz, 0.11mS delay");
+    setComment("  0x00 - 250Hz, 0.97mS delay");
+    setComment("  0x01 - 184Hz, 2.9mS delay");
+    setComment("  0x02 - 92Hz, 3.9mS delay");
+    setComment("  0x03 - 41Hz, 5.9mS delay");
+    setComment("  0x04 - 20Hz, 9.9mS delay");
+    setComment("  0x05 - 10Hz, 17.85mS delay");
+    setComment("  0x06 - 5Hz, 33.48mS delay");
+    setValue(RTIMULIB_MPU9250_GYRO_LPF, m_MPU9250GyroLpf);
+
+    setBlank();
+    setComment("");
+    setComment("Accel low pass filter - ");
+    setComment("  0x08 - 1130Hz, 0.75mS delay");
+    setComment("  0x00 - 460Hz, 1.94mS delay");
+    setComment("  0x01 - 184Hz, 5.80mS delay");
+    setComment("  0x02 - 92Hz, 7.80mS delay");
+    setComment("  0x03 - 41Hz, 11.80mS delay");
+    setComment("  0x04 - 20Hz, 19.80mS delay");
+    setComment("  0x05 - 10Hz, 35.70mS delay");
+    setComment("  0x06 - 5Hz, 66.96mS delay");
+    setValue(RTIMULIB_MPU9250_ACCEL_LPF, m_MPU9250AccelLpf);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro full scale range - ");
+    setComment("  0  - +/- 250 degress per second");
+    setComment("  8  - +/- 500 degress per second");
+    setComment("  16 - +/- 1000 degress per second");
+    setComment("  24 - +/- 2000 degress per second");
+    setValue(RTIMULIB_MPU9250_GYRO_FSR, m_MPU9250GyroFsr);
+
+    setBlank();
+    setComment("");
+    setComment("Accel full scale range - ");
+    setComment("  0  - +/- 2g");
+    setComment("  8  - +/- 4g");
+    setComment("  16 - +/- 8g");
+    setComment("  24 - +/- 16g");
+    setValue(RTIMULIB_MPU9250_ACCEL_FSR, m_MPU9250AccelFsr);
+
+    //  GD20HM303D settings
+
+    setBlank();
+    setComment("#####################################################################");
+    setComment("");
+    setComment("L3GD20H + LSM303D settings");
+
+    setBlank();
+    setComment("");
+    setComment("Gyro sample rate - ");
+    setComment("  0 = 12.5Hz ");
+    setComment("  1 = 25Hz ");
+    setComment("  2 = 50Hz ");
+    setComment("  3 = 100Hz ");
+    setComment("  4 = 200Hz ");
+    setComment("  5 = 400Hz ");
+    setComment("  6 = 800Hz ");
+    setValue(RTIMULIB_GD20HM303D_GYRO_SAMPLERATE, m_GD20HM303DGyroSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro full scale range - ");
+    setComment("  0 = 245 degrees per second ");
+    setComment("  1 = 500 degrees per second ");
+    setComment("  2 = 2000 degrees per second ");
+    setValue(RTIMULIB_GD20HM303D_GYRO_FSR, m_GD20HM303DGyroFsr);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro high pass filter - ");
+    setComment("  0 - 9 but see the L3GD20H manual for details");
+    setValue(RTIMULIB_GD20HM303D_GYRO_HPF, m_GD20HM303DGyroHpf);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro bandwidth - ");
+    setComment("  0 - 3 but see the L3GD20H manual for details");
+    setValue(RTIMULIB_GD20HM303D_GYRO_BW, m_GD20HM303DGyroBW);
+
+    setBlank();
+    setComment("Accel sample rate - ");
+    setComment("  1 = 3.125Hz ");
+    setComment("  2 = 6.25Hz ");
+    setComment("  3 = 12.5Hz ");
+    setComment("  4 = 25Hz ");
+    setComment("  5 = 50Hz ");
+    setComment("  6 = 100Hz ");
+    setComment("  7 = 200Hz ");
+    setComment("  8 = 400Hz ");
+    setComment("  9 = 800Hz ");
+    setComment("  10 = 1600Hz ");
+    setValue(RTIMULIB_GD20HM303D_ACCEL_SAMPLERATE, m_GD20HM303DAccelSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Accel full scale range - ");
+    setComment("  0 = +/- 2g ");
+    setComment("  1 = +/- 4g ");
+    setComment("  2 = +/- 6g ");
+    setComment("  3 = +/- 8g ");
+    setComment("  4 = +/- 16g ");
+    setValue(RTIMULIB_GD20HM303D_ACCEL_FSR, m_GD20HM303DAccelFsr);
+
+    setBlank();
+    setComment("");
+    setComment("Accel low pass filter - ");
+    setComment("  0 = 773Hz");
+    setComment("  1 = 194Hz");
+    setComment("  2 = 362Hz");
+    setComment("  3 = 50Hz");
+    setValue(RTIMULIB_GD20HM303D_ACCEL_LPF, m_GD20HM303DAccelLpf);
+
+    setBlank();
+    setComment("");
+    setComment("Compass sample rate - ");
+    setComment("  0 = 3.125Hz ");
+    setComment("  1 = 6.25Hz ");
+    setComment("  2 = 12.5Hz ");
+    setComment("  3 = 25Hz ");
+    setComment("  4 = 50Hz ");
+    setComment("  5 = 100Hz ");
+    setValue(RTIMULIB_GD20HM303D_COMPASS_SAMPLERATE, m_GD20HM303DCompassSampleRate);
+
+
+    setBlank();
+    setComment("");
+    setComment("Compass full scale range - ");
+    setComment("  0 = +/- 200 uT ");
+    setComment("  1 = +/- 400 uT ");
+    setComment("  2 = +/- 800 uT ");
+    setComment("  3 = +/- 1200 uT ");
+    setValue(RTIMULIB_GD20HM303D_COMPASS_FSR, m_GD20HM303DCompassFsr);
+
+    //  GD20M303DLHC settings
+
+    setBlank();
+    setComment("#####################################################################");
+    setComment("");
+    setComment("L3GD20 + LSM303DLHC settings");
+    setComment("");
+
+    setBlank();
+    setComment("Gyro sample rate - ");
+    setComment("  0 = 95z ");
+    setComment("  1 = 190Hz ");
+    setComment("  2 = 380Hz ");
+    setComment("  3 = 760Hz ");
+    setValue(RTIMULIB_GD20M303DLHC_GYRO_SAMPLERATE, m_GD20M303DLHCGyroSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro full scale range - ");
+    setComment("  0 = 250 degrees per second ");
+    setComment("  1 = 500 degrees per second ");
+    setComment("  2 = 2000 degrees per second ");
+    setValue(RTIMULIB_GD20M303DLHC_GYRO_FSR, m_GD20M303DLHCGyroFsr);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro high pass filter - ");
+    setComment("  0 - 9 but see the L3GD20 manual for details");
+    setValue(RTIMULIB_GD20M303DLHC_GYRO_HPF, m_GD20M303DLHCGyroHpf);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro bandwidth - ");
+    setComment("  0 - 3 but see the L3GD20 manual for details");
+    setValue(RTIMULIB_GD20M303DLHC_GYRO_BW, m_GD20M303DLHCGyroBW);
+
+    setBlank();
+    setComment("Accel sample rate - ");
+    setComment("  1 = 1Hz ");
+    setComment("  2 = 10Hz ");
+    setComment("  3 = 25Hz ");
+    setComment("  4 = 50Hz ");
+    setComment("  5 = 100Hz ");
+    setComment("  6 = 200Hz ");
+    setComment("  7 = 400Hz ");
+    setValue(RTIMULIB_GD20M303DLHC_ACCEL_SAMPLERATE, m_GD20M303DLHCAccelSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Accel full scale range - ");
+    setComment("  0 = +/- 2g ");
+    setComment("  1 = +/- 4g ");
+    setComment("  2 = +/- 8g ");
+    setComment("  3 = +/- 16g ");
+    setValue(RTIMULIB_GD20M303DLHC_ACCEL_FSR, m_GD20M303DLHCAccelFsr);
+
+    setBlank();
+    setComment("");
+    setComment("Compass sample rate - ");
+    setComment("  0 = 0.75Hz ");
+    setComment("  1 = 1.5Hz ");
+    setComment("  2 = 3Hz ");
+    setComment("  3 = 7.5Hz ");
+    setComment("  4 = 15Hz ");
+    setComment("  5 = 30Hz ");
+    setComment("  6 = 75Hz ");
+    setComment("  7 = 220Hz ");
+    setValue(RTIMULIB_GD20M303DLHC_COMPASS_SAMPLERATE, m_GD20M303DLHCCompassSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Compass full scale range - ");
+    setComment("  1 = +/- 130 uT ");
+    setComment("  2 = +/- 190 uT ");
+    setComment("  3 = +/- 250 uT ");
+    setComment("  4 = +/- 400 uT ");
+    setComment("  5 = +/- 470 uT ");
+    setComment("  6 = +/- 560 uT ");
+    setComment("  7 = +/- 810 uT ");
+    setValue(RTIMULIB_GD20M303DLHC_COMPASS_FSR, m_GD20M303DLHCCompassFsr);
+
+    //  GD20HM303DLHC settings
+
+    setBlank();
+    setComment("#####################################################################");
+    setComment("");
+    setComment("L3GD20H + LSM303DLHC settings");
+    setComment("");
+
+    setBlank();
+    setComment("");
+    setComment("Gyro sample rate - ");
+    setComment("  0 = 12.5Hz ");
+    setComment("  1 = 25Hz ");
+    setComment("  2 = 50Hz ");
+    setComment("  3 = 100Hz ");
+    setComment("  4 = 200Hz ");
+    setComment("  5 = 400Hz ");
+    setComment("  6 = 800Hz ");
+    setValue(RTIMULIB_GD20HM303DLHC_GYRO_SAMPLERATE, m_GD20HM303DLHCGyroSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro full scale range - ");
+    setComment("  0 = 245 degrees per second ");
+    setComment("  1 = 500 degrees per second ");
+    setComment("  2 = 2000 degrees per second ");
+    setValue(RTIMULIB_GD20HM303DLHC_GYRO_FSR, m_GD20HM303DLHCGyroFsr);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro high pass filter - ");
+    setComment("  0 - 9 but see the L3GD20H manual for details");
+    setValue(RTIMULIB_GD20HM303DLHC_GYRO_HPF, m_GD20HM303DLHCGyroHpf);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro bandwidth - ");
+    setComment("  0 - 3 but see the L3GD20H manual for details");
+    setValue(RTIMULIB_GD20HM303DLHC_GYRO_BW, m_GD20HM303DLHCGyroBW);
+    setBlank();
+    setComment("Accel sample rate - ");
+    setComment("  1 = 1Hz ");
+    setComment("  2 = 10Hz ");
+    setComment("  3 = 25Hz ");
+    setComment("  4 = 50Hz ");
+    setComment("  5 = 100Hz ");
+    setComment("  6 = 200Hz ");
+    setComment("  7 = 400Hz ");
+    setValue(RTIMULIB_GD20HM303DLHC_ACCEL_SAMPLERATE, m_GD20HM303DLHCAccelSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Accel full scale range - ");
+    setComment("  0 = +/- 2g ");
+    setComment("  1 = +/- 4g ");
+    setComment("  2 = +/- 8g ");
+    setComment("  3 = +/- 16g ");
+    setValue(RTIMULIB_GD20HM303DLHC_ACCEL_FSR, m_GD20HM303DLHCAccelFsr);
+
+    setBlank();
+    setComment("");
+    setComment("Compass sample rate - ");
+    setComment("  0 = 0.75Hz ");
+    setComment("  1 = 1.5Hz ");
+    setComment("  2 = 3Hz ");
+    setComment("  3 = 7.5Hz ");
+    setComment("  4 = 15Hz ");
+    setComment("  5 = 30Hz ");
+    setComment("  6 = 75Hz ");
+    setComment("  7 = 220Hz ");
+    setValue(RTIMULIB_GD20HM303DLHC_COMPASS_SAMPLERATE, m_GD20HM303DLHCCompassSampleRate);
+
+
+    setBlank();
+    setComment("");
+    setComment("Compass full scale range - ");
+    setComment("  1 = +/- 130 uT ");
+    setComment("  2 = +/- 190 uT ");
+    setComment("  3 = +/- 250 uT ");
+    setComment("  4 = +/- 400 uT ");
+    setComment("  5 = +/- 470 uT ");
+    setComment("  6 = +/- 560 uT ");
+    setComment("  7 = +/- 810 uT ");
+    setValue(RTIMULIB_GD20HM303DLHC_COMPASS_FSR, m_GD20HM303DLHCCompassFsr);
+
+    //  LSM9DS0 settings
+
+    setBlank();
+    setComment("#####################################################################");
+    setComment("");
+    setComment("LSM9DS0 settings");
+    setComment("");
+
+    setBlank();
+    setComment("Gyro sample rate - ");
+    setComment("  0 = 95z ");
+    setComment("  1 = 190Hz ");
+    setComment("  2 = 380Hz ");
+    setComment("  3 = 760Hz ");
+    setValue(RTIMULIB_LSM9DS0_GYRO_SAMPLERATE, m_LSM9DS0GyroSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro full scale range - ");
+    setComment("  0 = 250 degrees per second ");
+    setComment("  1 = 500 degrees per second ");
+    setComment("  2 = 2000 degrees per second ");
+    setValue(RTIMULIB_LSM9DS0_GYRO_FSR, m_LSM9DS0GyroFsr);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro high pass filter - ");
+    setComment("  0 - 9 but see the LSM9DS0 manual for details");
+    setValue(RTIMULIB_LSM9DS0_GYRO_HPF, m_LSM9DS0GyroHpf);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro bandwidth - ");
+    setComment("  0 - 3 but see the LSM9DS0 manual for details");
+    setValue(RTIMULIB_LSM9DS0_GYRO_BW, m_LSM9DS0GyroBW);
+
+    setBlank();
+    setComment("Accel sample rate - ");
+    setComment("  1 = 3.125Hz ");
+    setComment("  2 = 6.25Hz ");
+    setComment("  3 = 12.5Hz ");
+    setComment("  4 = 25Hz ");
+    setComment("  5 = 50Hz ");
+    setComment("  6 = 100Hz ");
+    setComment("  7 = 200Hz ");
+    setComment("  8 = 400Hz ");
+    setComment("  9 = 800Hz ");
+    setComment("  10 = 1600Hz ");
+    setValue(RTIMULIB_LSM9DS0_ACCEL_SAMPLERATE, m_LSM9DS0AccelSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Accel full scale range - ");
+    setComment("  0 = +/- 2g ");
+    setComment("  1 = +/- 4g ");
+    setComment("  2 = +/- 6g ");
+    setComment("  3 = +/- 8g ");
+    setComment("  4 = +/- 16g ");
+    setValue(RTIMULIB_LSM9DS0_ACCEL_FSR, m_LSM9DS0AccelFsr);
+
+    setBlank();
+    setComment("");
+    setComment("Accel low pass filter - ");
+    setComment("  0 = 773Hz");
+    setComment("  1 = 194Hz");
+    setComment("  2 = 362Hz");
+    setComment("  3 = 50Hz");
+    setValue(RTIMULIB_LSM9DS0_ACCEL_LPF, m_LSM9DS0AccelLpf);
+
+    setBlank();
+    setComment("");
+    setComment("Compass sample rate - ");
+    setComment("  0 = 3.125Hz ");
+    setComment("  1 = 6.25Hz ");
+    setComment("  2 = 12.5Hz ");
+    setComment("  3 = 25Hz ");
+    setComment("  4 = 50Hz ");
+    setComment("  5 = 100Hz ");
+    setValue(RTIMULIB_LSM9DS0_COMPASS_SAMPLERATE, m_LSM9DS0CompassSampleRate);
+
+
+    setBlank();
+    setComment("");
+    setComment("Compass full scale range - ");
+    setComment("  0 = +/- 200 uT ");
+    setComment("  1 = +/- 400 uT ");
+    setComment("  2 = +/- 800 uT ");
+    setComment("  3 = +/- 1200 uT ");
+    setValue(RTIMULIB_LSM9DS0_COMPASS_FSR, m_LSM9DS0CompassFsr);
+
+    //  BMX055 settings
+
+    setBlank();
+    setComment("#####################################################################");
+    setComment("");
+    setComment("BMX055 settings");
+    setComment("");
+
+    setBlank();
+    setComment("");
+    setComment("Gyro sample rate - ");
+    setComment("  0 = 2000Hz (532Hz filter)");
+    setComment("  1 = 2000Hz (230Hz filter)");
+    setComment("  2 = 1000Hz (116Hz filter)");
+    setComment("  3 = 400Hz (47Hz filter)");
+    setComment("  4 = 200Hz (23Hz filter)");
+    setComment("  5 = 100Hz (12Hz filter)");
+    setComment("  6 = 200Hz (64Hz filter)");
+    setComment("  7 = 100Hz (32Hz filter)");
+    setValue(RTIMULIB_BMX055_GYRO_SAMPLERATE, m_BMX055GyroSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Gyro full scale range - ");
+    setComment("  0 = 2000 deg/s");
+    setComment("  1 = 1000 deg/s");
+    setComment("  2 = 500 deg/s");
+    setComment("  3 = 250 deg/s");
+    setComment("  4 = 125 deg/s");
+    setValue(RTIMULIB_BMX055_GYRO_FSR, m_BMX055GyroFsr);
+
+    setBlank();
+    setComment("");
+    setComment("Accel sample rate - ");
+    setComment("  0 = 15.63Hz");
+    setComment("  1 = 31.25");
+    setComment("  2 = 62.5");
+    setComment("  3 = 125");
+    setComment("  4 = 250");
+    setComment("  5 = 500");
+    setComment("  6 = 1000");
+    setComment("  7 = 2000");
+    setValue(RTIMULIB_BMX055_ACCEL_SAMPLERATE, m_BMX055AccelSampleRate);
+
+    setBlank();
+    setComment("");
+    setComment("Accel full scale range - ");
+    setComment("  0 = +/- 2g");
+    setComment("  1 = +/- 4g");
+    setComment("  2 = +/- 8g");
+    setComment("  3 = +/- 16g");
+    setValue(RTIMULIB_BMX055_ACCEL_FSR, m_BMX055AccelFsr);
+
+    setBlank();
+    setComment("");
+    setComment("Mag presets - ");
+    setComment("  0 = Low power");
+    setComment("  1 = Regular");
+    setComment("  2 = Enhanced");
+    setComment("  3 = High accuracy");
+    setValue(RTIMULIB_BMX055_MAG_PRESET, m_BMX055MagPreset);
+
+    m_fd.close();
+    return true;
+}
+
+void RTIMUSettings::setBlank()
+{
+    m_fd.println();
+}
+
+void RTIMUSettings::setComment(const char *comment)
+{
+    m_fd.print("# ");
+    m_fd.println(comment);
+}
+
+void RTIMUSettings::setValue(const char *key, const bool val)
+{
+    m_fd.print(key);
+    m_fd.print("=");
+    if (val)
+        m_fd.println("true");
+    else
+        m_fd.println("false");
+}
+
+void RTIMUSettings::setValue(const char *key, const int val)
+{
+    m_fd.print(key);
+    m_fd.print("=");
+    m_fd.println(val);
+}
+
+void RTIMUSettings::setValue(const char *key, const RTFLOAT val)
+{
+    m_fd.print(key);
+    m_fd.print("=");
+    m_fd.println(val);
+}
+
+void RTIMUSettings::EEErase(byte device)
+{
+    EEPROM.write(sizeof(RTIMULIB_CAL_DATA) * device, 0);    // just destroy the valid byte
+}
+
+void RTIMUSettings::EEWrite(byte device, RTIMULIB_CAL_DATA *calData)
+{
+    byte *ptr = (byte *)calData;
+    byte length = sizeof(RTIMULIB_CAL_DATA);
+    int eeprom = sizeof(RTIMULIB_CAL_DATA) * device;
+
+    calData->validL = RTIMULIB_CAL_DATA_VALID_LOW;
+    calData->validH = RTIMULIB_CAL_DATA_VALID_HIGH;
+
+    for (byte i = 0; i < length; i++)
+        EEPROM.write(eeprom + i, *ptr++);
+}
+
+boolean RTIMUSettings::EERead(byte device, RTIMULIB_CAL_DATA *calData)
+{
+    byte *ptr = (byte *)calData;
+    byte length = sizeof(RTIMULIB_CAL_DATA);
+    int eeprom = sizeof(RTIMULIB_CAL_DATA) * device;
+
+    calData->magValid = false;
+
+    if ((EEPROM.read(eeprom) != RTIMULIB_CAL_DATA_VALID_LOW) ||
+        (EEPROM.read(eeprom + 1) != RTIMULIB_CAL_DATA_VALID_HIGH)) {
+        return false;                                  // invalid data
+    }
+
+    for (byte i = 0; i < length; i++)
+        *ptr++ = EEPROM.read(eeprom + i);
+    return true;
+}
+
diff --git a/libraries/RTIMULib/RTIMUSettings.h b/libraries/RTIMULib/RTIMUSettings.h
new file mode 100644
index 0000000..0d3b226
--- /dev/null
+++ b/libraries/RTIMULib/RTIMUSettings.h
@@ -0,0 +1,349 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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.
+
+//  The MPU-9250 driver code is based on code generously supplied by
+//  staslock@gmail.com (www.clickdrive.io)
+
+#ifndef _RTIMUSETTINGS_H
+#define _RTIMUSETTINGS_H
+
+#include "RTMath.h"
+#include "RTIMUHal.h"
+#include 
+#include 
+#include 
+
+#define SD_CHIP_SELECT  10
+#define IMU_CHIP_SELECT  9
+
+//  Defines for EEPROM config
+
+#define RTIMULIB_CAL_DATA_VALID_LOW         0xfc            // pattern to detect valid config - low byte
+#define RTIMULIB_CAL_DATA_VALID_HIGH        0x15            // pattern to detect valid config - high byte
+
+typedef struct
+{
+    unsigned char validL;                                   // should contain the valid pattern if a good config
+    unsigned char validH;                                   // should contain the valid pattern if a good config
+    unsigned char magValid;                                 // true if data valid
+    unsigned char pad;
+    RTFLOAT magMin[3];                                      // min values
+    RTFLOAT magMax[3];                                      // max values
+} RTIMULIB_CAL_DATA;
+
+//  Settings keys for SD card based  config
+
+#define RTIMULIB_IMU_TYPE                   "IMUType"
+#define RTIMULIB_FUSION_TYPE                "FusionType"
+#define RTIMULIB_BUS_IS_I2C                 "BusIsI2C"
+#define RTIMULIB_I2C_SLAVEADDRESS           "I2CSlaveAddress"
+#define RTIMULIB_I2C_BUS                    "I2CBus"
+#define RTIMULIB_SPI_BUS                    "SPIBus"
+#define RTIMULIB_SPI_SELECT                 "SPISelect"
+#define RTIMULIB_SPI_SPEED                  "SPISpeed"
+#define RTIMULIB_AXIS_ROTATION              "AxisRotation"
+#define RTIMULIB_PRESSURE_TYPE              "PressureType"
+#define RTIMULIB_I2C_PRESSUREADDRESS        "I2CPressureAddress"
+
+//  MPU9150 settings keys
+
+#define RTIMULIB_MPU9150_GYROACCEL_SAMPLERATE "MPU9150GyroAccelSampleRate"
+#define RTIMULIB_MPU9150_COMPASS_SAMPLERATE "MPU9150CompassSampleRate"
+#define RTIMULIB_MPU9150_GYROACCEL_LPF      "MPU9150GyroAccelLpf"
+#define RTIMULIB_MPU9150_GYRO_FSR           "MPU9150GyroFSR"
+#define RTIMULIB_MPU9150_ACCEL_FSR          "MPU9150AccelFSR"
+
+//  MPU9250 settings keys
+
+#define RTIMULIB_MPU9250_GYROACCEL_SAMPLERATE "MPU9250GyroAccelSampleRate"
+#define RTIMULIB_MPU9250_COMPASS_SAMPLERATE "MPU9250CompassSampleRate"
+#define RTIMULIB_MPU9250_GYRO_LPF           "MPU9250GyroLpf"
+#define RTIMULIB_MPU9250_ACCEL_LPF          "MPU9250AccelLpf"
+#define RTIMULIB_MPU9250_GYRO_FSR           "MPU9250GyroFSR"
+#define RTIMULIB_MPU9250_ACCEL_FSR          "MPU9250AccelFSR"
+
+//  GD20HM303D settings keys
+
+#define RTIMULIB_GD20HM303D_GYRO_SAMPLERATE   "GD20HM303DGyroSampleRate"
+#define RTIMULIB_GD20HM303D_GYRO_BW           "GD20HM303DGyroBW"
+#define RTIMULIB_GD20HM303D_GYRO_HPF          "GD20HM303DGyroHpf"
+#define RTIMULIB_GD20HM303D_GYRO_FSR          "GD20HM303DGyroFsr"
+
+#define RTIMULIB_GD20HM303D_ACCEL_SAMPLERATE  "GD20HM303DAccelSampleRate"
+#define RTIMULIB_GD20HM303D_ACCEL_FSR         "GD20HM303DAccelFsr"
+#define RTIMULIB_GD20HM303D_ACCEL_LPF         "GD20HM303DAccelLpf"
+
+#define RTIMULIB_GD20HM303D_COMPASS_SAMPLERATE "GD20HM303DCompassSampleRate"
+#define RTIMULIB_GD20HM303D_COMPASS_FSR       "GD20HM303DCompassFsr"
+
+
+//  GD20M303DLHC settings keys
+
+#define RTIMULIB_GD20M303DLHC_GYRO_SAMPLERATE   "GD20M303DLHCGyroSampleRate"
+#define RTIMULIB_GD20M303DLHC_GYRO_BW           "GD20M303DLHCGyroBW"
+#define RTIMULIB_GD20M303DLHC_GYRO_HPF          "GD20M303DLHCGyroHpf"
+#define RTIMULIB_GD20M303DLHC_GYRO_FSR          "GD20M303DLHCGyroFsr"
+
+#define RTIMULIB_GD20M303DLHC_ACCEL_SAMPLERATE  "GD20M303DLHCAccelSampleRate"
+#define RTIMULIB_GD20M303DLHC_ACCEL_FSR         "GD20M303DLHCAccelFsr"
+
+#define RTIMULIB_GD20M303DLHC_COMPASS_SAMPLERATE "GD20M303DLHCCompassSampleRate"
+#define RTIMULIB_GD20M303DLHC_COMPASS_FSR       "GD20M303DLHCCompassFsr"
+
+//  GD20HM303DLHC settings keys
+
+#define RTIMULIB_GD20HM303DLHC_GYRO_SAMPLERATE  "GD20HM303DLHCGyroSampleRate"
+#define RTIMULIB_GD20HM303DLHC_GYRO_BW          "GD20HM303DLHCGyroBW"
+#define RTIMULIB_GD20HM303DLHC_GYRO_HPF         "GD20HM303DLHCGyroHpf"
+#define RTIMULIB_GD20HM303DLHC_GYRO_FSR         "GD20HM303DLHCGyroFsr"
+
+#define RTIMULIB_GD20HM303DLHC_ACCEL_SAMPLERATE "GD20HM303DLHCAccelSampleRate"
+#define RTIMULIB_GD20HM303DLHC_ACCEL_FSR        "GD20HM303DLHCAccelFsr"
+
+#define RTIMULIB_GD20HM303DLHC_COMPASS_SAMPLERATE "GD20HM303DLHCCompassSampleRate"
+#define RTIMULIB_GD20HM303DLHC_COMPASS_FSR      "GD20HM303DLHCCompassFsr"
+
+
+//  LSM9DS0 settings keys
+
+#define RTIMULIB_LSM9DS0_GYRO_SAMPLERATE   "LSM9DS0GyroSampleRate"
+#define RTIMULIB_LSM9DS0_GYRO_BW           "LSM9DS0GyroBW"
+#define RTIMULIB_LSM9DS0_GYRO_HPF          "LSM9DS0GyroHpf"
+#define RTIMULIB_LSM9DS0_GYRO_FSR          "LSM9DS0GyroFsr"
+
+#define RTIMULIB_LSM9DS0_ACCEL_SAMPLERATE  "LSM9DS0AccelSampleRate"
+#define RTIMULIB_LSM9DS0_ACCEL_FSR         "LSM9DS0AccelFsr"
+#define RTIMULIB_LSM9DS0_ACCEL_LPF         "LSM9DS0AccelLpf"
+
+#define RTIMULIB_LSM9DS0_COMPASS_SAMPLERATE "LSM9DS0CompassSampleRate"
+#define RTIMULIB_LSM9DS0_COMPASS_FSR       "LSM9DS0CompassFsr"
+
+//  BMX055 settings keys
+
+#define RTIMULIB_BMX055_GYRO_SAMPLERATE     "BMX055GyroSampleRate"
+#define RTIMULIB_BMX055_GYRO_FSR            "BMX055GyroFsr"
+
+#define RTIMULIB_BMX055_ACCEL_SAMPLERATE    "BMX055AccelSampleRate"
+#define RTIMULIB_BMX055_ACCEL_FSR           "BMX055AccelFsr"
+
+#define RTIMULIB_BMX055_MAG_PRESET          "BMX055MagPreset"
+
+//  Gyro bias keys
+
+#define RTIMULIB_GYRO_BIAS_VALID            "GyroBiasValid"
+#define RTIMULIB_GYRO_BIAS_X                "GyroBiasX"
+#define RTIMULIB_GYRO_BIAS_Y                "GyroBiasY"
+#define RTIMULIB_GYRO_BIAS_Z                "GyroBiasZ"
+
+//  Compass calibration settings keys
+
+#define RTIMULIB_COMPASSCAL_VALID           "CompassCalValid"
+#define RTIMULIB_COMPASSCAL_MINX            "CompassCalMinX"
+#define RTIMULIB_COMPASSCAL_MAXX            "CompassCalMaxX"
+#define RTIMULIB_COMPASSCAL_MINY            "CompassCalMinY"
+#define RTIMULIB_COMPASSCAL_MAXY            "CompassCalMaxY"
+#define RTIMULIB_COMPASSCAL_MINZ            "CompassCalMinZ"
+#define RTIMULIB_COMPASSCAL_MAXZ            "CompassCalMaxZ"
+
+#define RTIMULIB_COMPASSCAL_ELLIPSOID_VALID "compassCalEllipsoidValid"
+#define RTIMULIB_COMPASSCAL_OFFSET_X        "compassCalOffsetX"
+#define RTIMULIB_COMPASSCAL_OFFSET_Y        "compassCalOffsetY"
+#define RTIMULIB_COMPASSCAL_OFFSET_Z        "compassCalOffsetZ"
+#define RTIMULIB_COMPASSCAL_CORR11          "compassCalCorr11"
+#define RTIMULIB_COMPASSCAL_CORR12          "compassCalCorr12"
+#define RTIMULIB_COMPASSCAL_CORR13          "compassCalCorr13"
+#define RTIMULIB_COMPASSCAL_CORR21          "compassCalCorr21"
+#define RTIMULIB_COMPASSCAL_CORR22          "compassCalCorr22"
+#define RTIMULIB_COMPASSCAL_CORR23          "compassCalCorr23"
+#define RTIMULIB_COMPASSCAL_CORR31          "compassCalCorr31"
+#define RTIMULIB_COMPASSCAL_CORR32          "compassCalCorr32"
+#define RTIMULIB_COMPASSCAL_CORR33          "compassCalCorr33"
+
+#define RTIMULIB_COMPASSADJ_DECLINATION     "compassAdjDeclination"
+
+//  Accel calibration settings keys
+
+#define RTIMULIB_ACCELCAL_VALID             "AccelCalValid"
+#define RTIMULIB_ACCELCAL_MINX              "AccelCalMinX"
+#define RTIMULIB_ACCELCAL_MAXX              "AccelCalMaxX"
+#define RTIMULIB_ACCELCAL_MINY              "AccelCalMinY"
+#define RTIMULIB_ACCELCAL_MAXY              "AccelCalMaxY"
+#define RTIMULIB_ACCELCAL_MINZ              "AccelCalMinZ"
+#define RTIMULIB_ACCELCAL_MAXZ              "AccelCalMaxZ"
+
+
+class RTIMUSettings : public RTIMUHal
+{
+public:
+    RTIMUSettings(const char *productType = "RTIMULib");
+
+    //  This function tries to find an IMU. It stops at the first valid one
+    //  and returns true or else false
+
+    bool discoverIMU(int& imuType, bool& busIsI2C, unsigned char& slaveAddress);
+
+    //  This function tries to find a pressure sensor. It stops at the first valid one
+    //  and returns true or else false
+
+    bool discoverPressure(int& pressureType, unsigned char& pressureAddress);
+
+    //  This function sets the settings to default values.
+
+    void setDefaults();
+
+    //  This function loads the local variables from the settings file or uses defaults
+
+    virtual bool loadSettings();
+
+    //  This function saves the local variables to the settings file
+
+    virtual bool saveSettings();
+
+    //  These are the local variables
+
+    int m_imuType;                                          // type code of imu in use
+    int m_fusionType;                                       // fusion algorithm type code
+    unsigned char m_I2CSlaveAddress;                        // I2C slave address of the imu
+    int m_axisRotation;                                     // axis rotation code
+    int m_pressureType;                                     // type code of pressure sensor in use
+    unsigned char m_I2CPressureAddress;                     // I2C slave address of the pressure sensor
+
+    bool m_compassCalValid;                                 // true if there is valid compass calibration data
+    RTVector3 m_compassCalMin;                              // the minimum values
+    RTVector3 m_compassCalMax;                              // the maximum values
+
+    bool m_compassCalEllipsoidValid;                        // true if the ellipsoid calibration data is valid
+    RTVector3 m_compassCalEllipsoidOffset;                  // the ellipsoid offset
+    float m_compassCalEllipsoidCorr[3][3];                  // the correction matrix
+
+    float m_compassAdjDeclination;                          // magnetic declination adjustment - subtracted from measured
+
+    bool m_accelCalValid;                                   // true if there is valid accel calibration data
+    RTVector3 m_accelCalMin;                                // the minimum values
+    RTVector3 m_accelCalMax;                                // the maximum values
+
+    bool m_gyroBiasValid;                                   // true if the recorded gyro bias is valid
+    RTVector3 m_gyroBias;                                   // the recorded gyro bias
+
+    //  IMU-specific vars
+
+    //  MPU9150
+
+    int m_MPU9150GyroAccelSampleRate;                       // the sample rate (samples per second) for gyro and accel
+    int m_MPU9150CompassSampleRate;                         // same for the compass
+    int m_MPU9150GyroAccelLpf;                              // low pass filter code for the gyro and accel
+    int m_MPU9150GyroFsr;                                   // FSR code for the gyro
+    int m_MPU9150AccelFsr;                                  // FSR code for the accel
+
+    //  MPU9250
+
+    int m_MPU9250GyroAccelSampleRate;                       // the sample rate (samples per second) for gyro and accel
+    int m_MPU9250CompassSampleRate;                         // same for the compass
+    int m_MPU9250GyroLpf;                                   // low pass filter code for the gyro
+    int m_MPU9250AccelLpf;                                  // low pass filter code for the accel
+    int m_MPU9250GyroFsr;                                   // FSR code for the gyro
+    int m_MPU9250AccelFsr;                                  // FSR code for the accel
+
+    //  GD20HM303D
+
+    int m_GD20HM303DGyroSampleRate;                         // the gyro sample rate
+    int m_GD20HM303DGyroBW;                                 // the gyro bandwidth code
+    int m_GD20HM303DGyroHpf;                                // the gyro high pass filter cutoff code
+    int m_GD20HM303DGyroFsr;                                // the gyro full scale range
+
+    int m_GD20HM303DAccelSampleRate;                        // the accel sample rate
+    int m_GD20HM303DAccelFsr;                               // the accel full scale range
+    int m_GD20HM303DAccelLpf;                               // the accel low pass filter
+
+    int m_GD20HM303DCompassSampleRate;                      // the compass sample rate
+    int m_GD20HM303DCompassFsr;                             // the compass full scale range
+
+    //  GD20M303DLHC
+
+    int m_GD20M303DLHCGyroSampleRate;                       // the gyro sample rate
+    int m_GD20M303DLHCGyroBW;                               // the gyro bandwidth code
+    int m_GD20M303DLHCGyroHpf;                              // the gyro high pass filter cutoff code
+    int m_GD20M303DLHCGyroFsr;                              // the gyro full scale range
+
+    int m_GD20M303DLHCAccelSampleRate;                      // the accel sample rate
+    int m_GD20M303DLHCAccelFsr;                             // the accel full scale range
+
+    int m_GD20M303DLHCCompassSampleRate;                    // the compass sample rate
+    int m_GD20M303DLHCCompassFsr;                           // the compass full scale range
+
+    //  GD20HM303DLHC
+
+    int m_GD20HM303DLHCGyroSampleRate;                      // the gyro sample rate
+    int m_GD20HM303DLHCGyroBW;                              // the gyro bandwidth code
+    int m_GD20HM303DLHCGyroHpf;                             // the gyro high pass filter cutoff code
+    int m_GD20HM303DLHCGyroFsr;                             // the gyro full scale range
+
+    int m_GD20HM303DLHCAccelSampleRate;                     // the accel sample rate
+    int m_GD20HM303DLHCAccelFsr;                            // the accel full scale range
+
+    int m_GD20HM303DLHCCompassSampleRate;                   // the compass sample rate
+    int m_GD20HM303DLHCCompassFsr;                          // the compass full scale range
+
+    //  LSM9DS0
+
+    int m_LSM9DS0GyroSampleRate;                            // the gyro sample rate
+    int m_LSM9DS0GyroBW;                                    // the gyro bandwidth code
+    int m_LSM9DS0GyroHpf;                                   // the gyro high pass filter cutoff code
+    int m_LSM9DS0GyroFsr;                                   // the gyro full scale range
+
+    int m_LSM9DS0AccelSampleRate;                           // the accel sample rate
+    int m_LSM9DS0AccelFsr;                                  // the accel full scale range
+    int m_LSM9DS0AccelLpf;                                  // the accel low pass filter
+
+    int m_LSM9DS0CompassSampleRate;                         // the compass sample rate
+    int m_LSM9DS0CompassFsr;                                // the compass full scale range
+
+    //  BMX055
+
+    int m_BMX055GyroSampleRate;                             // the gyro sample rate
+    int m_BMX055GyroFsr;                                    // the gyro full scale range
+
+    int m_BMX055AccelSampleRate;                            // the accel sample rate
+    int m_BMX055AccelFsr;                                   // the accel full scale range
+
+    int m_BMX055MagPreset;                                  // the mag preset code
+
+private:
+    void setBlank();
+    void setComment(const char *comment);
+    void setValue(const char *key, const bool val);
+    void setValue(const char *key, const int val);
+    void setValue(const char *key, const RTFLOAT val);
+
+    char m_filename[256];                                    // the settings file name
+
+    File m_fd;
+    bool m_usingSD;                                          // true if using SD card
+
+    void EEErase(byte device);
+    void EEWrite(byte device, RTIMULIB_CAL_DATA * calData);
+    boolean EERead(byte device, RTIMULIB_CAL_DATA * calData);
+};
+
+#endif // _RTIMUSETTINGS_H
+
diff --git a/libraries/RTIMULib/RTMath.cpp b/libraries/RTIMULib/RTMath.cpp
new file mode 100644
index 0000000..ae0accc
--- /dev/null
+++ b/libraries/RTIMULib/RTMath.cpp
@@ -0,0 +1,620 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTMath.h"
+#include 
+
+//  Strings are put here. So the display functions are no re-entrant!
+
+char RTMath::m_string[1000];
+
+uint64_t RTMath::currentUSecsSinceEpoch()
+{
+    return micros();
+}
+
+const char *RTMath::displayRadians(const char *label, RTVector3& vec)
+{
+    sprintf(m_string, "%s: x:%f, y:%f, z:%f\n", label, vec.x(), vec.y(), vec.z());
+    return m_string;
+}
+
+const char *RTMath::displayDegrees(const char *label, RTVector3& vec)
+{
+    sprintf(m_string, "%s: roll:%f, pitch:%f, yaw:%f", label, vec.x() * RTMATH_RAD_TO_DEGREE,
+            vec.y() * RTMATH_RAD_TO_DEGREE, vec.z() * RTMATH_RAD_TO_DEGREE);
+    return m_string;
+}
+
+const char *RTMath::display(const char *label, RTQuaternion& quat)
+{
+    sprintf(m_string, "%s: scalar: %f, x:%f, y:%f, z:%f\n", label, quat.scalar(), quat.x(), quat.y(), quat.z());
+    return m_string;
+}
+
+const char *RTMath::display(const char *label, RTMatrix4x4& mat)
+{
+    sprintf(m_string, "%s(0): %f %f %f %f\n%s(1): %f %f %f %f\n%s(2): %f %f %f %f\n%s(3): %f %f %f %f\n",
+            label, mat.val(0,0), mat.val(0,1), mat.val(0,2), mat.val(0,3),
+            label, mat.val(1,0), mat.val(1,1), mat.val(1,2), mat.val(1,3),
+            label, mat.val(2,0), mat.val(2,1), mat.val(2,2), mat.val(2,3),
+            label, mat.val(3,0), mat.val(3,1), mat.val(3,2), mat.val(3,3));
+    return m_string;
+}
+
+//  convertPressureToHeight() - the conversion uses the formula:
+//
+//  h = (T0 / L0) * ((p / P0)**(-(R* * L0) / (g0 * M)) - 1)
+//
+//  where:
+//  h  = height above sea level
+//  T0 = standard temperature at sea level = 288.15
+//  L0 = standard temperatur elapse rate = -0.0065
+//  p  = measured pressure
+//  P0 = static pressure = 1013.25 (but can be overridden)
+//  g0 = gravitational acceleration = 9.80665
+//  M  = mloecular mass of earth's air = 0.0289644
+//  R* = universal gas constant = 8.31432
+//
+//  Given the constants, this works out to:
+//
+//  h = 44330.8 * (1 - (p / P0)**0.190263)
+
+RTFLOAT RTMath::convertPressureToHeight(RTFLOAT pressure, RTFLOAT staticPressure)
+{
+    return 44330.8 * (1 - pow(pressure / staticPressure, 0.190263));
+}
+
+
+RTVector3 RTMath::poseFromAccelMag(const RTVector3& accel, const RTVector3& mag)
+{
+    RTVector3 result;
+    RTQuaternion m;
+    RTQuaternion q;
+
+    accel.accelToEuler(result);
+
+//  q.fromEuler(result);
+//  since result.z() is always 0, this can be optimized a little
+
+    RTFLOAT cosX2 = cos(result.x() / 2.0f);
+    RTFLOAT sinX2 = sin(result.x() / 2.0f);
+    RTFLOAT cosY2 = cos(result.y() / 2.0f);
+    RTFLOAT sinY2 = sin(result.y() / 2.0f);
+
+    q.setScalar(cosX2 * cosY2);
+    q.setX(sinX2 * cosY2);
+    q.setY(cosX2 * sinY2);
+    q.setZ(-sinX2 * sinY2);
+//    q.normalize();
+
+    m.setScalar(0);
+    m.setX(mag.x());
+    m.setY(mag.y());
+    m.setZ(mag.z());
+
+    m = q * m * q.conjugate();
+    result.setZ(-atan2(m.y(), m.x()));
+    return result;
+}
+
+void RTMath::convertToVector(unsigned char *rawData, RTVector3& vec, RTFLOAT scale, bool bigEndian)
+{
+    if (bigEndian) {
+        vec.setX((RTFLOAT)((int16_t)(((uint16_t)rawData[0] << 8) | (uint16_t)rawData[1])) * scale);
+        vec.setY((RTFLOAT)((int16_t)(((uint16_t)rawData[2] << 8) | (uint16_t)rawData[3])) * scale);
+        vec.setZ((RTFLOAT)((int16_t)(((uint16_t)rawData[4] << 8) | (uint16_t)rawData[5])) * scale);
+    } else {
+        vec.setX((RTFLOAT)((int16_t)(((uint16_t)rawData[1] << 8) | (uint16_t)rawData[0])) * scale);
+        vec.setY((RTFLOAT)((int16_t)(((uint16_t)rawData[3] << 8) | (uint16_t)rawData[2])) * scale);
+        vec.setZ((RTFLOAT)((int16_t)(((uint16_t)rawData[5] << 8) | (uint16_t)rawData[4])) * scale);
+     }
+}
+
+
+
+//----------------------------------------------------------
+//
+//  The RTVector3 class
+
+RTVector3::RTVector3()
+{
+    zero();
+}
+
+RTVector3::RTVector3(RTFLOAT x, RTFLOAT y, RTFLOAT z)
+{
+    m_data[0] = x;
+    m_data[1] = y;
+    m_data[2] = z;
+}
+
+RTVector3& RTVector3::operator =(const RTVector3& vec)
+{
+    if (this == &vec)
+        return *this;
+
+    m_data[0] = vec.m_data[0];
+    m_data[1] = vec.m_data[1];
+    m_data[2] = vec.m_data[2];
+
+    return *this;
+}
+
+
+const RTVector3& RTVector3::operator +=(RTVector3& vec)
+{
+    for (int i = 0; i < 3; i++)
+        m_data[i] += vec.m_data[i];
+    return *this;
+}
+
+const RTVector3& RTVector3::operator -=(RTVector3& vec)
+{
+    for (int i = 0; i < 3; i++)
+        m_data[i] -= vec.m_data[i];
+    return *this;
+}
+
+void RTVector3::zero()
+{
+    for (int i = 0; i < 3; i++)
+        m_data[i] = 0;
+}
+
+
+RTFLOAT RTVector3::dotProduct(const RTVector3& a, const RTVector3& b)
+{
+    return a.x() * b.x() + a.y() * b.y() + a.z() * b.z();
+}
+
+void RTVector3::crossProduct(const RTVector3& a, const RTVector3& b, RTVector3& d)
+{
+    d.setX(a.y() * b.z() - a.z() * b.y());
+    d.setY(a.z() * b.x() - a.x() * b.z());
+    d.setZ(a.x() * b.y() - a.y() * b.x());
+}
+
+
+void RTVector3::accelToEuler(RTVector3& rollPitchYaw) const
+{
+    RTVector3 normAccel = *this;
+
+    normAccel.normalize();
+
+    rollPitchYaw.setX(atan2(normAccel.y(), normAccel.z()));
+    rollPitchYaw.setY(-atan2(normAccel.x(), sqrt(normAccel.y() * normAccel.y() + normAccel.z() * normAccel.z())));
+    rollPitchYaw.setZ(0);
+}
+
+
+void RTVector3::accelToQuaternion(RTQuaternion& qPose) const
+{
+    RTVector3 normAccel = *this;
+    RTVector3 vec;
+    RTVector3 z(0, 0, 1.0);
+
+    normAccel.normalize();
+
+    RTFLOAT angle = acos(RTVector3::dotProduct(z, normAccel));
+    RTVector3::crossProduct(normAccel, z, vec);
+    vec.normalize();
+
+    qPose.fromAngleVector(angle, vec);
+}
+
+
+void RTVector3::normalize()
+{
+    RTFLOAT length = sqrt(m_data[0] * m_data[0] + m_data[1] * m_data[1] +
+            m_data[2] * m_data[2]);
+
+    if (length == 0)
+        return;
+
+    m_data[0] /= length;
+    m_data[1] /= length;
+    m_data[2] /= length;
+}
+
+RTFLOAT RTVector3::length()
+{
+    return sqrt(m_data[0] * m_data[0] + m_data[1] * m_data[1] +
+            m_data[2] * m_data[2]);
+}
+
+//----------------------------------------------------------
+//
+//  The RTQuaternion class
+
+RTQuaternion::RTQuaternion()
+{
+    zero();
+}
+
+RTQuaternion::RTQuaternion(RTFLOAT scalar, RTFLOAT x, RTFLOAT y, RTFLOAT z)
+{
+    m_data[0] = scalar;
+    m_data[1] = x;
+    m_data[2] = y;
+    m_data[3] = z;
+}
+
+RTQuaternion& RTQuaternion::operator =(const RTQuaternion& quat)
+{
+    if (this == &quat)
+        return *this;
+
+    m_data[0] = quat.m_data[0];
+    m_data[1] = quat.m_data[1];
+    m_data[2] = quat.m_data[2];
+    m_data[3] = quat.m_data[3];
+
+    return *this;
+}
+
+
+
+RTQuaternion& RTQuaternion::operator +=(const RTQuaternion& quat)
+{
+    for (int i = 0; i < 4; i++)
+        m_data[i] += quat.m_data[i];
+    return *this;
+}
+
+RTQuaternion& RTQuaternion::operator -=(const RTQuaternion& quat)
+{
+    for (int i = 0; i < 4; i++)
+        m_data[i] -= quat.m_data[i];
+    return *this;
+}
+
+RTQuaternion& RTQuaternion::operator -=(const RTFLOAT val)
+{
+    for (int i = 0; i < 4; i++)
+        m_data[i] -= val;
+    return *this;
+}
+
+RTQuaternion& RTQuaternion::operator *=(const RTQuaternion& qb)
+{
+    RTQuaternion qa;
+
+    qa = *this;
+
+    m_data[0] = qa.scalar() * qb.scalar() - qa.x() * qb.x() - qa.y() * qb.y() - qa.z() * qb.z();
+    m_data[1] = qa.scalar() * qb.x() + qa.x() * qb.scalar() + qa.y() * qb.z() - qa.z() * qb.y();
+    m_data[2] = qa.scalar() * qb.y() - qa.x() * qb.z() + qa.y() * qb.scalar() + qa.z() * qb.x();
+    m_data[3] = qa.scalar() * qb.z() + qa.x() * qb.y() - qa.y() * qb.x() + qa.z() * qb.scalar();
+
+    return *this;
+}
+
+
+RTQuaternion& RTQuaternion::operator *=(const RTFLOAT val)
+{
+    m_data[0] *= val;
+    m_data[1] *= val;
+    m_data[2] *= val;
+    m_data[3] *= val;
+
+    return *this;
+}
+
+
+const RTQuaternion RTQuaternion::operator *(const RTQuaternion& qb) const
+{
+    RTQuaternion result = *this;
+    result *= qb;
+    return result;
+}
+
+const RTQuaternion RTQuaternion::operator *(const RTFLOAT val) const
+{
+    RTQuaternion result = *this;
+    result *= val;
+    return result;
+}
+
+
+const RTQuaternion RTQuaternion::operator -(const RTQuaternion& qb) const
+{
+    RTQuaternion result = *this;
+    result -= qb;
+    return result;
+}
+
+const RTQuaternion RTQuaternion::operator -(const RTFLOAT val) const
+{
+    RTQuaternion result = *this;
+    result -= val;
+    return result;
+}
+
+
+void RTQuaternion::zero()
+{
+    for (int i = 0; i < 4; i++)
+        m_data[i] = 0;
+}
+
+void RTQuaternion::normalize()
+{
+    RTFLOAT length = sqrt(m_data[0] * m_data[0] + m_data[1] * m_data[1] +
+            m_data[2] * m_data[2] + m_data[3] * m_data[3]);
+
+    if ((length == 0) || (length == 1))
+        return;
+
+    m_data[0] /= length;
+    m_data[1] /= length;
+    m_data[2] /= length;
+    m_data[3] /= length;
+}
+
+void RTQuaternion::toEuler(RTVector3& vec)
+{
+    vec.setX(atan2(2.0 * (m_data[2] * m_data[3] + m_data[0] * m_data[1]),
+            1 - 2.0 * (m_data[1] * m_data[1] + m_data[2] * m_data[2])));
+
+    vec.setY(asin(2.0 * (m_data[0] * m_data[2] - m_data[1] * m_data[3])));
+
+    vec.setZ(atan2(2.0 * (m_data[1] * m_data[2] + m_data[0] * m_data[3]),
+            1 - 2.0 * (m_data[2] * m_data[2] + m_data[3] * m_data[3])));
+}
+
+void RTQuaternion::fromEuler(RTVector3& vec)
+{
+    RTFLOAT cosX2 = cos(vec.x() / 2.0f);
+    RTFLOAT sinX2 = sin(vec.x() / 2.0f);
+    RTFLOAT cosY2 = cos(vec.y() / 2.0f);
+    RTFLOAT sinY2 = sin(vec.y() / 2.0f);
+    RTFLOAT cosZ2 = cos(vec.z() / 2.0f);
+    RTFLOAT sinZ2 = sin(vec.z() / 2.0f);
+
+    m_data[0] = cosX2 * cosY2 * cosZ2 + sinX2 * sinY2 * sinZ2;
+    m_data[1] = sinX2 * cosY2 * cosZ2 - cosX2 * sinY2 * sinZ2;
+    m_data[2] = cosX2 * sinY2 * cosZ2 + sinX2 * cosY2 * sinZ2;
+    m_data[3] = cosX2 * cosY2 * sinZ2 - sinX2 * sinY2 * cosZ2;
+    normalize();
+}
+
+RTQuaternion RTQuaternion::conjugate() const
+{
+    RTQuaternion q;
+    q.setScalar(m_data[0]);
+    q.setX(-m_data[1]);
+    q.setY(-m_data[2]);
+    q.setZ(-m_data[3]);
+    return q;
+}
+
+void RTQuaternion::toAngleVector(RTFLOAT& angle, RTVector3& vec)
+{
+    RTFLOAT halfTheta;
+    RTFLOAT sinHalfTheta;
+
+    halfTheta = acos(m_data[0]);
+    sinHalfTheta = sin(halfTheta);
+
+    if (sinHalfTheta == 0) {
+        vec.setX(1.0);
+        vec.setY(0);
+        vec.setZ(0);
+    } else {
+        vec.setX(m_data[1] / sinHalfTheta);
+        vec.setY(m_data[1] / sinHalfTheta);
+        vec.setZ(m_data[1] / sinHalfTheta);
+    }
+    angle = 2.0 * halfTheta;
+}
+
+void RTQuaternion::fromAngleVector(const RTFLOAT& angle, const RTVector3& vec)
+{
+    RTFLOAT sinHalfTheta = sin(angle / 2.0);
+    m_data[0] = cos(angle / 2.0);
+    m_data[1] = vec.x() * sinHalfTheta;
+    m_data[2] = vec.y() * sinHalfTheta;
+    m_data[3] = vec.z() * sinHalfTheta;
+}
+
+
+
+//----------------------------------------------------------
+//
+//  The RTMatrix4x4 class
+
+RTMatrix4x4::RTMatrix4x4()
+{
+    fill(0);
+}
+
+RTMatrix4x4& RTMatrix4x4::operator =(const RTMatrix4x4& mat)
+{
+    if (this == &mat)
+        return *this;
+
+    for (int row = 0; row < 4; row++)
+        for (int col = 0; col < 4; col++)
+            m_data[row][col] = mat.m_data[row][col];
+
+    return *this;
+}
+
+
+void RTMatrix4x4::fill(RTFLOAT val)
+{
+    for (int row = 0; row < 4; row++)
+        for (int col = 0; col < 4; col++)
+            m_data[row][col] = val;
+}
+
+
+RTMatrix4x4& RTMatrix4x4::operator +=(const RTMatrix4x4& mat)
+{
+    for (int row = 0; row < 4; row++)
+        for (int col = 0; col < 4; col++)
+            m_data[row][col] += mat.m_data[row][col];
+
+    return *this;
+}
+
+RTMatrix4x4& RTMatrix4x4::operator -=(const RTMatrix4x4& mat)
+{
+    for (int row = 0; row < 4; row++)
+        for (int col = 0; col < 4; col++)
+            m_data[row][col] -= mat.m_data[row][col];
+
+    return *this;
+}
+
+RTMatrix4x4& RTMatrix4x4::operator *=(const RTFLOAT val)
+{
+    for (int row = 0; row < 4; row++)
+        for (int col = 0; col < 4; col++)
+            m_data[row][col] *= val;
+
+    return *this;
+}
+
+const RTMatrix4x4 RTMatrix4x4::operator +(const RTMatrix4x4& mat) const
+{
+    RTMatrix4x4 result = *this;
+    result += mat;
+    return result;
+}
+
+const RTMatrix4x4 RTMatrix4x4::operator *(const RTFLOAT val) const
+{
+    RTMatrix4x4 result = *this;
+    result *= val;
+    return result;
+}
+
+
+const RTMatrix4x4 RTMatrix4x4::operator *(const RTMatrix4x4& mat) const
+{
+    RTMatrix4x4 res;
+
+    for (int row = 0; row < 4; row++)
+        for (int col = 0; col < 4; col++)
+            res.m_data[row][col] =
+                    m_data[row][0] * mat.m_data[0][col] +
+                    m_data[row][1] * mat.m_data[1][col] +
+                    m_data[row][2] * mat.m_data[2][col] +
+                    m_data[row][3] * mat.m_data[3][col];
+
+    return res;
+}
+
+
+const RTQuaternion RTMatrix4x4::operator *(const RTQuaternion& q) const
+{
+    RTQuaternion res;
+
+    res.setScalar(m_data[0][0] * q.scalar() + m_data[0][1] * q.x() + m_data[0][2] * q.y() + m_data[0][3] * q.z());
+    res.setX(m_data[1][0] * q.scalar() + m_data[1][1] * q.x() + m_data[1][2] * q.y() + m_data[1][3] * q.z());
+    res.setY(m_data[2][0] * q.scalar() + m_data[2][1] * q.x() + m_data[2][2] * q.y() + m_data[2][3] * q.z());
+    res.setZ(m_data[3][0] * q.scalar() + m_data[3][1] * q.x() + m_data[3][2] * q.y() + m_data[3][3] * q.z());
+
+    return res;
+}
+
+void RTMatrix4x4::setToIdentity()
+{
+    fill(0);
+    m_data[0][0] = 1;
+    m_data[1][1] = 1;
+    m_data[2][2] = 1;
+    m_data[3][3] = 1;
+}
+
+RTMatrix4x4 RTMatrix4x4::transposed()
+{
+    RTMatrix4x4 res;
+
+    for (int row = 0; row < 4; row++)
+        for (int col = 0; col < 4; col++)
+            res.m_data[col][row] = m_data[row][col];
+    return res;
+}
+
+//  Note:
+//  The matrix inversion code here was strongly influenced by some old code I found
+//  but I have no idea where it came from. Apologies to whoever wrote it originally!
+//  If it's you, please let me know at info@richards-tech.com so I can credit it correctly.
+
+RTMatrix4x4 RTMatrix4x4::inverted()
+{
+    RTMatrix4x4 res;
+
+    RTFLOAT det = matDet();
+
+    if (det == 0) {
+        res.setToIdentity();
+        return res;
+    }
+
+    for (int row = 0; row < 4; row++) {
+        for (int col = 0; col < 4; col++) {
+            if ((row + col) & 1)
+                res.m_data[col][row] = -matMinor(row, col) / det;
+            else
+                res.m_data[col][row] = matMinor(row, col) / det;
+        }
+    }
+
+    return res;
+}
+
+RTFLOAT RTMatrix4x4::matDet()
+{
+    RTFLOAT det = 0;
+
+    det += m_data[0][0] * matMinor(0, 0);
+    det -= m_data[0][1] * matMinor(0, 1);
+    det += m_data[0][2] * matMinor(0, 2);
+    det -= m_data[0][3] * matMinor(0, 3);
+    return det;
+}
+
+RTFLOAT RTMatrix4x4::matMinor(const int row, const int col)
+{
+    static int map[] = {1, 2, 3, 0, 2, 3, 0, 1, 3, 0, 1, 2};
+
+    int *rc;
+    int *cc;
+    RTFLOAT res = 0;
+
+    rc = map + row * 3;
+    cc = map + col * 3;
+
+    res += m_data[rc[0]][cc[0]] * m_data[rc[1]][cc[1]] * m_data[rc[2]][cc[2]];
+    res -= m_data[rc[0]][cc[0]] * m_data[rc[1]][cc[2]] * m_data[rc[2]][cc[1]];
+    res -= m_data[rc[0]][cc[1]] * m_data[rc[1]][cc[0]] * m_data[rc[2]][cc[2]];
+    res += m_data[rc[0]][cc[1]] * m_data[rc[1]][cc[2]] * m_data[rc[2]][cc[0]];
+    res += m_data[rc[0]][cc[2]] * m_data[rc[1]][cc[0]] * m_data[rc[2]][cc[1]];
+    res -= m_data[rc[0]][cc[2]] * m_data[rc[1]][cc[1]] * m_data[rc[2]][cc[0]];
+    return res;
+}
+
diff --git a/libraries/RTIMULib/RTMath.h b/libraries/RTIMULib/RTMath.h
new file mode 100644
index 0000000..a2a2c7f
--- /dev/null
+++ b/libraries/RTIMULib/RTMath.h
@@ -0,0 +1,191 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib-Teensy
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTMATH_H_
+#define _RTMATH_H_
+
+#include "RTIMUHal.h"
+
+//  The fundamental float type
+
+#ifdef RTMATH_USE_DOUBLE
+typedef double RTFLOAT;
+#else
+typedef float RTFLOAT;
+#endif
+
+//  Useful constants
+
+#define	RTMATH_PI					3.1415926535
+#define	RTMATH_DEGREE_TO_RAD		(RTMATH_PI / 180.0)
+#define	RTMATH_RAD_TO_DEGREE		(180.0 / RTMATH_PI)
+
+class RTVector3;
+class RTMatrix4x4;
+class RTQuaternion;
+
+class RTMath
+{
+public:
+    // convenient display routines
+
+    static const char *displayRadians(const char *label, RTVector3& vec);
+    static const char *displayDegrees(const char *label, RTVector3& vec);
+    static const char *display(const char *label, RTQuaternion& quat);
+    static const char *display(const char *label, RTMatrix4x4& mat);
+
+    //  currentUSecsSinceEpoch() is the source of all timestamps and
+    //  is the number of uS sonce the standard epoch
+
+    static uint64_t currentUSecsSinceEpoch();
+
+    //  poseFromAccelMag generates pose Euler angles from measured settings
+
+    static RTVector3 poseFromAccelMag(const RTVector3& accel, const RTVector3& mag);
+
+    //  Takes signed 16 bit data from a char array and converts it to a vector of scaled RTFLOATs
+
+    static void convertToVector(unsigned char *rawData, RTVector3& vec, RTFLOAT scale, bool bigEndian);
+
+    //  Takes a pressure in hPa and returns height above sea level in meters
+
+    static RTFLOAT convertPressureToHeight(RTFLOAT pressure, RTFLOAT staticPressure = 1013.25);
+
+private:
+    static char m_string[1000];                             // for the display routines
+};
+
+
+class RTVector3
+{
+public:
+    RTVector3();
+    RTVector3(RTFLOAT x, RTFLOAT y, RTFLOAT z);
+
+    const RTVector3&  operator +=(RTVector3& vec);
+    const RTVector3&  operator -=(RTVector3& vec);
+
+    RTVector3& operator =(const RTVector3& vec);
+
+    RTFLOAT length();
+    void normalize();
+    void zero();
+    const char *display();
+    const char *displayDegrees();
+
+    static float dotProduct(const RTVector3& a, const RTVector3& b);
+    static void crossProduct(const RTVector3& a, const RTVector3& b, RTVector3& d);
+
+    void accelToEuler(RTVector3& rollPitchYaw) const;
+    void accelToQuaternion(RTQuaternion& qPose) const;
+
+    inline RTFLOAT x() const { return m_data[0]; }
+    inline RTFLOAT y() const { return m_data[1]; }
+    inline RTFLOAT z() const { return m_data[2]; }
+    inline RTFLOAT data(const int i) const { return m_data[i]; }
+
+    inline void setX(const RTFLOAT val) { m_data[0] = val; }
+    inline void setY(const RTFLOAT val) { m_data[1] = val; }
+    inline void setZ(const RTFLOAT val) { m_data[2] = val; }
+    inline void setData(const int i, RTFLOAT val) { m_data[i] = val; }
+
+private:
+    RTFLOAT m_data[3];
+};
+
+
+class RTQuaternion
+{
+public:
+    RTQuaternion();
+    RTQuaternion(RTFLOAT scalar, RTFLOAT x, RTFLOAT y, RTFLOAT z);
+
+    RTQuaternion& operator +=(const RTQuaternion& quat);
+    RTQuaternion& operator -=(const RTQuaternion& quat);
+    RTQuaternion& operator *=(const RTQuaternion& qb);
+    RTQuaternion& operator *=(const RTFLOAT val);
+    RTQuaternion& operator -=(const RTFLOAT val);
+
+    RTQuaternion& operator =(const RTQuaternion& quat);
+    const RTQuaternion operator *(const RTQuaternion& qb) const;
+    const RTQuaternion operator *(const RTFLOAT val) const;
+    const RTQuaternion operator -(const RTQuaternion& qb) const;
+    const RTQuaternion operator -(const RTFLOAT val) const;
+
+    void normalize();
+    void toEuler(RTVector3& vec);
+    void fromEuler(RTVector3& vec);
+    RTQuaternion conjugate() const;
+    void toAngleVector(RTFLOAT& angle, RTVector3& vec);
+    void fromAngleVector(const RTFLOAT& angle, const RTVector3& vec);
+
+    void zero();
+    const char *display();
+
+    inline RTFLOAT scalar() const { return m_data[0]; }
+    inline RTFLOAT x() const { return m_data[1]; }
+    inline RTFLOAT y() const { return m_data[2]; }
+    inline RTFLOAT z() const { return m_data[3]; }
+    inline RTFLOAT data(const int i) const { return m_data[i]; }
+
+    inline void setScalar(const RTFLOAT val) { m_data[0] = val; }
+    inline void setX(const RTFLOAT val) { m_data[1] = val; }
+    inline void setY(const RTFLOAT val) { m_data[2] = val; }
+    inline void setZ(const RTFLOAT val) { m_data[3] = val; }
+    inline void setData(const int i, RTFLOAT val) { m_data[i] = val; }
+
+private:
+    RTFLOAT m_data[4];
+};
+
+class RTMatrix4x4
+{
+public:
+    RTMatrix4x4();
+
+    RTMatrix4x4& operator +=(const RTMatrix4x4& mat);
+    RTMatrix4x4& operator -=(const RTMatrix4x4& mat);
+    RTMatrix4x4& operator *=(const RTFLOAT val);
+
+    RTMatrix4x4& operator =(const RTMatrix4x4& vec);
+    const RTQuaternion operator *(const RTQuaternion& q) const;
+    const RTMatrix4x4 operator *(const RTFLOAT val) const;
+    const RTMatrix4x4 operator *(const RTMatrix4x4& mat) const;
+    const RTMatrix4x4 operator +(const RTMatrix4x4& mat) const;
+
+    inline RTFLOAT val(int row, int col) const { return m_data[row][col]; }
+    inline void setVal(int row, int col, RTFLOAT val) { m_data[row][col] = val; }
+    void fill(RTFLOAT val);
+    void setToIdentity();
+
+    RTMatrix4x4 inverted();
+    RTMatrix4x4 transposed();
+
+private:
+    RTFLOAT m_data[4][4];                                   // row, column
+
+    RTFLOAT matDet();
+    RTFLOAT matMinor(const int row, const int col);
+};
+
+#endif /* _RTMATH_H_ */
diff --git a/libraries/RTIMULib/utility/RTIMU.cpp b/libraries/RTIMULib/utility/RTIMU.cpp
new file mode 100644
index 0000000..4a900cc
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMU.cpp
@@ -0,0 +1,475 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTIMU.h"
+#include "RTFusionKalman4.h"
+#include "RTFusionRTQF.h"
+
+#include "RTIMUNull.h"
+#include "RTIMUMPU9150.h"
+#include "RTIMUMPU9250.h"
+#include "RTIMUGD20HM303D.h"
+#include "RTIMUGD20M303DLHC.h"
+#include "RTIMUGD20HM303DLHC.h"
+#include "RTIMULSM9DS0.h"
+#include "RTIMUBMX055.h"
+#include "RTIMUBNO055.h"
+
+//  this sets the learning rate for compass running average calculation
+
+#define COMPASS_ALPHA 0.2f
+
+//  this sets the min range (max - min) of values to trigger runtime mag calibration
+
+#define RTIMU_RUNTIME_MAGCAL_RANGE  30
+
+//  this defines the accelerometer noise level
+
+#define RTIMU_FUZZY_GYRO_ZERO      0.20
+
+//  this defines the accelerometer noise level
+
+#define RTIMU_FUZZY_ACCEL_ZERO      0.05
+
+//  Axis rotation arrays
+
+float RTIMU::m_axisRotation[RTIMU_AXIS_ROTATION_COUNT][9] = {
+    {1, 0, 0, 0, 1, 0, 0, 0, 1},                    // RTIMU_XNORTH_YEAST
+    {0, -1, 0, 1, 0, 0, 0, 0, 1},                   // RTIMU_XEAST_YSOUTH
+    {-1, 0, 0, 0, -1, 0, 0, 0, 1},                  // RTIMU_XSOUTH_YWEST
+    {0, 1, 0, -1, 0, 0, 0, 0, 1},                   // RTIMU_XWEST_YNORTH
+
+    {1, 0, 0, 0, -1, 0, 0, 0, -1},                  // RTIMU_XNORTH_YWEST
+    {0, 1, 0, 1, 0, 0, 0, 0, -1},                   // RTIMU_XEAST_YNORTH
+    {-1, 0, 0, 0, 1, 0, 0, 0, -1},                  // RTIMU_XSOUTH_YEAST
+    {0, -1, 0, -1, 0, 0, 0, 0, -1},                 // RTIMU_XWEST_YSOUTH
+
+    {0, 1, 0, 0, 0, -1, -1, 0, 0},                  // RTIMU_XUP_YNORTH
+    {0, 0, 1, 0, 1, 0, -1, 0, 0},                   // RTIMU_XUP_YEAST
+    {0, -1, 0, 0, 0, 1, -1, 0, 0},                  // RTIMU_XUP_YSOUTH
+    {0, 0, -1, 0, -1, 0, -1, 0, 0},                 // RTIMU_XUP_YWEST
+
+    {0, 1, 0, 0, 0, 1, 1, 0, 0},                    // RTIMU_XDOWN_YNORTH
+    {0, 0, -1, 0, 1, 0, 1, 0, 0},                   // RTIMU_XDOWN_YEAST
+    {0, -1, 0, 0, 0, -1, 1, 0, 0},                  // RTIMU_XDOWN_YSOUTH
+    {0, 0, 1, 0, -1, 0, 1, 0, 0},                   // RTIMU_XDOWN_YWEST
+
+    {1, 0, 0, 0, 0, 1, 0, -1, 0},                   // RTIMU_XNORTH_YUP
+    {0, 0, -1, 1, 0, 0, 0, -1, 0},                  // RTIMU_XEAST_YUP
+    {-1, 0, 0, 0, 0, -1, 0, -1, 0},                 // RTIMU_XSOUTH_YUP
+    {0, 0, 1, -1, 0, 0, 0, -1, 0},                  // RTIMU_XWEST_YUP
+
+    {1, 0, 0, 0, 0, -1, 0, 1, 0},                   // RTIMU_XNORTH_YDOWN
+    {0, 0, 1, 1, 0, 0, 0, 1, 0},                    // RTIMU_XEAST_YDOWN
+    {-1, 0, 0, 0, 0, 1, 0, 1, 0},                   // RTIMU_XSOUTH_YDOWN
+    {0, 0, -1, -1, 0, 0, 0, 1, 0}                   // RTIMU_XWEST_YDOWN
+};
+
+RTIMU *RTIMU::createIMU(RTIMUSettings *settings)
+{
+    switch (settings->m_imuType) {
+    case RTIMU_TYPE_MPU9150:
+        return new RTIMUMPU9150(settings);
+
+    case RTIMU_TYPE_GD20HM303D:
+        return new RTIMUGD20HM303D(settings);
+
+    case RTIMU_TYPE_GD20M303DLHC:
+        return new RTIMUGD20M303DLHC(settings);
+
+    case RTIMU_TYPE_LSM9DS0:
+        return new RTIMULSM9DS0(settings);
+
+    case RTIMU_TYPE_MPU9250:
+        return new RTIMUMPU9250(settings);
+
+    case RTIMU_TYPE_GD20HM303DLHC:
+        return new RTIMUGD20HM303DLHC(settings);
+
+    case RTIMU_TYPE_BMX055:
+        return new RTIMUBMX055(settings);
+
+    case RTIMU_TYPE_BNO055:
+        return new RTIMUBNO055(settings);
+
+    case RTIMU_TYPE_AUTODISCOVER:
+        if (settings->discoverIMU(settings->m_imuType, settings->m_busIsI2C, settings->m_I2CSlaveAddress)) {
+            settings->saveSettings();
+            return RTIMU::createIMU(settings);
+        }
+        return new RTIMUNull(settings);
+
+    case RTIMU_TYPE_NULL:
+        return new RTIMUNull(settings);
+
+    default:
+        return NULL;
+    }
+}
+
+
+RTIMU::RTIMU(RTIMUSettings *settings)
+{
+    m_settings = settings;
+
+    m_compassCalibrationMode = false;
+    m_accelCalibrationMode = false;
+
+    m_runtimeMagCalValid = false;
+
+    for (int i = 0; i < 3; i++) {
+        m_runtimeMagCalMax[i] = -1000;
+        m_runtimeMagCalMin[i] = 1000;
+    }
+
+    switch (m_settings->m_fusionType) {
+    case RTFUSION_TYPE_KALMANSTATE4:
+        m_fusion = new RTFusionKalman4();
+        break;
+
+    case RTFUSION_TYPE_RTQF:
+        m_fusion = new RTFusionRTQF();
+        break;
+
+    default:
+        m_fusion = new RTFusion();
+        break;
+    }
+    HAL_INFO1("Using fusion algorithm %s\n", RTFusion::fusionName(m_settings->m_fusionType));
+}
+
+RTIMU::~RTIMU()
+{
+    delete m_fusion;
+    m_fusion = NULL;
+}
+
+void RTIMU::setCalibrationData()
+{
+    float maxDelta = -1;
+    float delta;
+
+    if (m_settings->m_compassCalValid) {
+        //  find biggest range
+
+        for (int i = 0; i < 3; i++) {
+            if ((m_settings->m_compassCalMax.data(i) - m_settings->m_compassCalMin.data(i)) > maxDelta)
+                maxDelta = m_settings->m_compassCalMax.data(i) - m_settings->m_compassCalMin.data(i);
+        }
+        if (maxDelta < 0) {
+            HAL_ERROR("Error in compass calibration data\n");
+            return;
+        }
+        maxDelta /= 2.0f;                                       // this is the max +/- range
+
+        for (int i = 0; i < 3; i++) {
+            delta = (m_settings->m_compassCalMax.data(i) - m_settings->m_compassCalMin.data(i)) / 2.0f;
+            m_compassCalScale[i] = maxDelta / delta;            // makes everything the same range
+            m_compassCalOffset[i] = (m_settings->m_compassCalMax.data(i) + m_settings->m_compassCalMin.data(i)) / 2.0f;
+        }
+    }
+
+    if (m_settings->m_compassCalValid) {
+        HAL_INFO("Using min/max compass calibration\n");
+    } else {
+        HAL_INFO("min/max compass calibration not in use\n");
+    }
+
+    if (m_settings->m_compassCalEllipsoidValid) {
+        HAL_INFO("Using ellipsoid compass calibration\n");
+    } else {
+        HAL_INFO("Ellipsoid compass calibration not in use\n");
+    }
+
+    if (m_settings->m_accelCalValid) {
+        HAL_INFO("Using accel calibration\n");
+    } else {
+        HAL_INFO("Accel calibration not in use\n");
+    }
+}
+
+bool RTIMU::setGyroContinuousLearningAlpha(RTFLOAT alpha)
+{
+    if ((alpha < 0.0) || (alpha >= 1.0))
+        return false;
+
+    m_gyroContinuousAlpha = alpha;
+    return true;
+}
+
+
+void RTIMU::gyroBiasInit()
+{
+    m_gyroLearningAlpha = 2.0f / m_sampleRate;
+    m_gyroContinuousAlpha = 0.01f / m_sampleRate;
+    m_gyroSampleCount = 0;
+}
+
+//  Note - code assumes that this is the first thing called after axis swapping
+//  for each specific IMU chip has occurred.
+
+void RTIMU::handleGyroBias()
+{
+    // do axis rotation
+
+    if ((m_settings->m_axisRotation > 0) && (m_settings->m_axisRotation < RTIMU_AXIS_ROTATION_COUNT)) {
+        // need to do an axis rotation
+        float *matrix = m_axisRotation[m_settings->m_axisRotation];
+        RTIMU_DATA tempIMU = m_imuData;
+
+        // do new x value
+        if (matrix[0] != 0) {
+            m_imuData.gyro.setX(tempIMU.gyro.x() * matrix[0]);
+            m_imuData.accel.setX(tempIMU.accel.x() * matrix[0]);
+            m_imuData.compass.setX(tempIMU.compass.x() * matrix[0]);
+        } else if (matrix[1] != 0) {
+            m_imuData.gyro.setX(tempIMU.gyro.y() * matrix[1]);
+            m_imuData.accel.setX(tempIMU.accel.y() * matrix[1]);
+            m_imuData.compass.setX(tempIMU.compass.y() * matrix[1]);
+        } else if (matrix[2] != 0) {
+            m_imuData.gyro.setX(tempIMU.gyro.z() * matrix[2]);
+            m_imuData.accel.setX(tempIMU.accel.z() * matrix[2]);
+            m_imuData.compass.setX(tempIMU.compass.z() * matrix[2]);
+        }
+
+        // do new y value
+        if (matrix[3] != 0) {
+            m_imuData.gyro.setY(tempIMU.gyro.x() * matrix[3]);
+            m_imuData.accel.setY(tempIMU.accel.x() * matrix[3]);
+            m_imuData.compass.setY(tempIMU.compass.x() * matrix[3]);
+        } else if (matrix[4] != 0) {
+            m_imuData.gyro.setY(tempIMU.gyro.y() * matrix[4]);
+            m_imuData.accel.setY(tempIMU.accel.y() * matrix[4]);
+            m_imuData.compass.setY(tempIMU.compass.y() * matrix[4]);
+        } else if (matrix[5] != 0) {
+            m_imuData.gyro.setY(tempIMU.gyro.z() * matrix[5]);
+            m_imuData.accel.setY(tempIMU.accel.z() * matrix[5]);
+            m_imuData.compass.setY(tempIMU.compass.z() * matrix[5]);
+        }
+
+        // do new z value
+        if (matrix[6] != 0) {
+            m_imuData.gyro.setZ(tempIMU.gyro.x() * matrix[6]);
+            m_imuData.accel.setZ(tempIMU.accel.x() * matrix[6]);
+            m_imuData.compass.setZ(tempIMU.compass.x() * matrix[6]);
+        } else if (matrix[7] != 0) {
+            m_imuData.gyro.setZ(tempIMU.gyro.y() * matrix[7]);
+            m_imuData.accel.setZ(tempIMU.accel.y() * matrix[7]);
+            m_imuData.compass.setZ(tempIMU.compass.y() * matrix[7]);
+        } else if (matrix[8] != 0) {
+            m_imuData.gyro.setZ(tempIMU.gyro.z() * matrix[8]);
+            m_imuData.accel.setZ(tempIMU.accel.z() * matrix[8]);
+            m_imuData.compass.setZ(tempIMU.compass.z() * matrix[8]);
+        }
+    }
+
+    RTVector3 deltaAccel = m_previousAccel;
+    deltaAccel -= m_imuData.accel;   // compute difference
+    m_previousAccel = m_imuData.accel;
+
+    if ((deltaAccel.length() < RTIMU_FUZZY_ACCEL_ZERO) && (m_imuData.gyro.length() < RTIMU_FUZZY_GYRO_ZERO)) {
+        // what we are seeing on the gyros should be bias only so learn from this
+
+        if (m_gyroSampleCount < (5 * m_sampleRate)) {
+            m_settings->m_gyroBias.setX((1.0 - m_gyroLearningAlpha) * m_settings->m_gyroBias.x() + m_gyroLearningAlpha * m_imuData.gyro.x());
+            m_settings->m_gyroBias.setY((1.0 - m_gyroLearningAlpha) * m_settings->m_gyroBias.y() + m_gyroLearningAlpha * m_imuData.gyro.y());
+            m_settings->m_gyroBias.setZ((1.0 - m_gyroLearningAlpha) * m_settings->m_gyroBias.z() + m_gyroLearningAlpha * m_imuData.gyro.z());
+
+            m_gyroSampleCount++;
+
+            if (m_gyroSampleCount == (5 * m_sampleRate)) {
+                // this could have been true already of course
+                m_settings->m_gyroBiasValid = true;
+                m_settings->saveSettings();
+            }
+        } else {
+            m_settings->m_gyroBias.setX((1.0 - m_gyroContinuousAlpha) * m_settings->m_gyroBias.x() + m_gyroContinuousAlpha * m_imuData.gyro.x());
+            m_settings->m_gyroBias.setY((1.0 - m_gyroContinuousAlpha) * m_settings->m_gyroBias.y() + m_gyroContinuousAlpha * m_imuData.gyro.y());
+            m_settings->m_gyroBias.setZ((1.0 - m_gyroContinuousAlpha) * m_settings->m_gyroBias.z() + m_gyroContinuousAlpha * m_imuData.gyro.z());
+        }
+    }
+
+    m_imuData.gyro -= m_settings->m_gyroBias;
+}
+
+void RTIMU::calibrateAverageCompass()
+{
+    //  see if need to do runtime mag calibration (i.e. no stored calibration data)
+
+    if (!m_compassCalibrationMode && !m_settings->m_compassCalValid) {
+        // try runtime calibration
+        bool changed = false;
+
+        // see if there is a new max or min
+
+        if (m_runtimeMagCalMax[0] < m_imuData.compass.x()) {
+            m_runtimeMagCalMax[0] = m_imuData.compass.x();
+            changed = true;
+        }
+        if (m_runtimeMagCalMax[1] < m_imuData.compass.y()) {
+            m_runtimeMagCalMax[1] = m_imuData.compass.y();
+            changed = true;
+        }
+        if (m_runtimeMagCalMax[2] < m_imuData.compass.z()) {
+            m_runtimeMagCalMax[2] = m_imuData.compass.z();
+            changed = true;
+        }
+
+        if (m_runtimeMagCalMin[0] > m_imuData.compass.x()) {
+            m_runtimeMagCalMin[0] = m_imuData.compass.x();
+            changed = true;
+        }
+        if (m_runtimeMagCalMin[1] > m_imuData.compass.y()) {
+            m_runtimeMagCalMin[1] = m_imuData.compass.y();
+            changed = true;
+        }
+        if (m_runtimeMagCalMin[2] > m_imuData.compass.z()) {
+            m_runtimeMagCalMin[2] = m_imuData.compass.z();
+            changed = true;
+        }
+
+        //  now see if ranges are sufficient
+
+        if (changed) {
+
+            float delta;
+
+            if (!m_runtimeMagCalValid) {
+                m_runtimeMagCalValid = true;
+
+                for (int i = 0; i < 3; i++)
+                {
+                    delta = m_runtimeMagCalMax[i] - m_runtimeMagCalMin[i];
+                    if ((delta < RTIMU_RUNTIME_MAGCAL_RANGE) || (m_runtimeMagCalMin[i] > 0) || (m_runtimeMagCalMax[i] < 0))
+                    {
+                        m_runtimeMagCalValid = false;
+                        break;
+                    }
+                }
+            }
+
+            //  find biggest range and scale to that
+
+            if (m_runtimeMagCalValid) {
+                float magMaxDelta = -1;
+
+                for (int i = 0; i < 3; i++) {
+                    if ((m_runtimeMagCalMax[i] - m_runtimeMagCalMin[i]) > magMaxDelta)
+                    {
+                        magMaxDelta = m_runtimeMagCalMax[i] - m_runtimeMagCalMin[i];
+                    }
+                }
+
+                // adjust for + and - range
+
+                magMaxDelta /= 2.0;
+
+                for (int i = 0; i < 3; i++)
+                {
+                    delta = (m_runtimeMagCalMax[i] - m_runtimeMagCalMin[i]) / 2.0;
+                    m_compassCalScale[i] = magMaxDelta / delta;
+                    m_compassCalOffset[i] = (m_runtimeMagCalMax[i] + m_runtimeMagCalMin[i]) / 2.0;
+                }
+            }
+        }
+    }
+
+    if (getCompassCalibrationValid() || getRuntimeCompassCalibrationValid()) {
+        m_imuData.compass.setX((m_imuData.compass.x() - m_compassCalOffset[0]) * m_compassCalScale[0]);
+        m_imuData.compass.setY((m_imuData.compass.y() - m_compassCalOffset[1]) * m_compassCalScale[1]);
+        m_imuData.compass.setZ((m_imuData.compass.z() - m_compassCalOffset[2]) * m_compassCalScale[2]);
+
+        if (m_settings->m_compassCalEllipsoidValid) {
+            RTVector3 ev = m_imuData.compass;
+            ev -= m_settings->m_compassCalEllipsoidOffset;
+
+            m_imuData.compass.setX(ev.x() * m_settings->m_compassCalEllipsoidCorr[0][0] +
+                ev.y() * m_settings->m_compassCalEllipsoidCorr[0][1] +
+                ev.z() * m_settings->m_compassCalEllipsoidCorr[0][2]);
+
+            m_imuData.compass.setY(ev.x() * m_settings->m_compassCalEllipsoidCorr[1][0] +
+                ev.y() * m_settings->m_compassCalEllipsoidCorr[1][1] +
+                ev.z() * m_settings->m_compassCalEllipsoidCorr[1][2]);
+
+            m_imuData.compass.setZ(ev.x() * m_settings->m_compassCalEllipsoidCorr[2][0] +
+                ev.y() * m_settings->m_compassCalEllipsoidCorr[2][1] +
+                ev.z() * m_settings->m_compassCalEllipsoidCorr[2][2]);
+        }
+    }
+
+    //  update running average
+
+    m_compassAverage.setX(m_imuData.compass.x() * COMPASS_ALPHA + m_compassAverage.x() * (1.0 - COMPASS_ALPHA));
+    m_compassAverage.setY(m_imuData.compass.y() * COMPASS_ALPHA + m_compassAverage.y() * (1.0 - COMPASS_ALPHA));
+    m_compassAverage.setZ(m_imuData.compass.z() * COMPASS_ALPHA + m_compassAverage.z() * (1.0 - COMPASS_ALPHA));
+
+    m_imuData.compass = m_compassAverage;
+}
+
+void RTIMU::calibrateAccel()
+{
+    if (!getAccelCalibrationValid())
+        return;
+
+    if (m_imuData.accel.x() >= 0)
+        m_imuData.accel.setX(m_imuData.accel.x() / m_settings->m_accelCalMax.x());
+    else
+        m_imuData.accel.setX(m_imuData.accel.x() / -m_settings->m_accelCalMin.x());
+
+    if (m_imuData.accel.y() >= 0)
+        m_imuData.accel.setY(m_imuData.accel.y() / m_settings->m_accelCalMax.y());
+    else
+        m_imuData.accel.setY(m_imuData.accel.y() / -m_settings->m_accelCalMin.y());
+
+    if (m_imuData.accel.z() >= 0)
+        m_imuData.accel.setZ(m_imuData.accel.z() / m_settings->m_accelCalMax.z());
+    else
+        m_imuData.accel.setZ(m_imuData.accel.z() / -m_settings->m_accelCalMin.z());
+}
+
+void RTIMU::updateFusion()
+{
+    m_fusion->newIMUData(m_imuData, m_settings);
+}
+
+bool RTIMU::IMUGyroBiasValid()
+{
+    return m_settings->m_gyroBiasValid;
+}
+
+ void RTIMU::setExtIMUData(RTFLOAT gx, RTFLOAT gy, RTFLOAT gz, RTFLOAT ax, RTFLOAT ay, RTFLOAT az,
+        RTFLOAT mx, RTFLOAT my, RTFLOAT mz, uint64_t timestamp)
+ {
+     m_imuData.gyro.setX(gx);
+     m_imuData.gyro.setY(gy);
+     m_imuData.gyro.setZ(gz);
+     m_imuData.accel.setX(ax);
+     m_imuData.accel.setY(ay);
+     m_imuData.accel.setZ(az);
+     m_imuData.compass.setX(mx);
+     m_imuData.compass.setY(my);
+     m_imuData.compass.setZ(mz);
+     m_imuData.timestamp = timestamp;
+     updateFusion();
+}
diff --git a/libraries/RTIMULib/utility/RTIMU.h b/libraries/RTIMULib/utility/RTIMU.h
new file mode 100644
index 0000000..8475f4b
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMU.h
@@ -0,0 +1,200 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTIMU_H
+#define	_RTIMU_H
+
+#include "RTMath.h"
+#include "RTFusion.h"
+#include "RTIMULibDefs.h"
+#include "RTIMUSettings.h"
+
+//  Axis rotation defs
+//
+//  These allow the IMU to be virtually repositioned if it is in a non-standard configuration
+//  Standard configuration is X pointing at north, Y pointing east and Z pointing down
+//  with the IMU horizontal. There are 24 different possible orientations as defined
+//  below. Setting the axis rotation code to non-zero values performs the repositioning.
+
+#define RTIMU_XNORTH_YEAST              0                   // this is the default identity matrix
+#define RTIMU_XEAST_YSOUTH              1
+#define RTIMU_XSOUTH_YWEST              2
+#define RTIMU_XWEST_YNORTH              3
+#define RTIMU_XNORTH_YWEST              4
+#define RTIMU_XEAST_YNORTH              5
+#define RTIMU_XSOUTH_YEAST              6
+#define RTIMU_XWEST_YSOUTH              7
+#define RTIMU_XUP_YNORTH                8
+#define RTIMU_XUP_YEAST                 9
+#define RTIMU_XUP_YSOUTH                10
+#define RTIMU_XUP_YWEST                 11
+#define RTIMU_XDOWN_YNORTH              12
+#define RTIMU_XDOWN_YEAST               13
+#define RTIMU_XDOWN_YSOUTH              14
+#define RTIMU_XDOWN_YWEST               15
+#define RTIMU_XNORTH_YUP                16
+#define RTIMU_XEAST_YUP                 17
+#define RTIMU_XSOUTH_YUP                18
+#define RTIMU_XWEST_YUP                 19
+#define RTIMU_XNORTH_YDOWN              20
+#define RTIMU_XEAST_YDOWN               21
+#define RTIMU_XSOUTH_YDOWN              22
+#define RTIMU_XWEST_YDOWN               23
+
+#define RTIMU_AXIS_ROTATION_COUNT       24
+
+class RTIMU
+{
+public:
+    //  IMUs should always be created with the following call
+
+    static RTIMU *createIMU(RTIMUSettings *settings);
+
+    //  Constructor/destructor
+
+    RTIMU(RTIMUSettings *settings);
+    virtual ~RTIMU();
+
+    //  These functions must be provided by sub classes
+
+    virtual const char *IMUName() = 0;                      // the name of the IMU
+    virtual int IMUType() = 0;                              // the type code of the IMU
+    virtual bool IMUInit() = 0;                             // set up the IMU
+    virtual int IMUGetPollInterval() = 0;                   // returns the recommended poll interval in mS
+    virtual bool IMURead() = 0;                             // get a sample
+
+    // setGyroContinuousALearninglpha allows the continuous learning rate to be over-ridden
+    // The value must be between 0.0 and 1.0 and will generally be close to 0
+
+    bool setGyroContinuousLearningAlpha(RTFLOAT alpha);
+
+    // returns true if enough samples for valid data
+
+    virtual bool IMUGyroBiasValid();
+
+    //  the following function can be called to set the SLERP power
+
+    void setSlerpPower(RTFLOAT power) { m_fusion->setSlerpPower(power); }
+
+    //  call the following to reset the fusion algorithm
+
+    void resetFusion() { m_fusion->reset(); }
+
+    //  the following three functions control the influence of the gyro, accel and compass sensors
+
+    void setGyroEnable(bool enable) { m_fusion->setGyroEnable(enable);}
+    void setAccelEnable(bool enable) { m_fusion->setAccelEnable(enable);}
+    void setCompassEnable(bool enable) { m_fusion->setCompassEnable(enable);}
+
+    //  call the following to enable debug messages
+
+    void setDebugEnable(bool enable) { m_fusion->setDebugEnable(enable); }
+
+    //  getIMUData returns the standard outputs of the IMU and fusion filter
+
+    const RTIMU_DATA& getIMUData() { return m_imuData; }
+
+    //  setExtIMUData allows data from some external IMU to be injected to the fusion algorithm
+
+    void setExtIMUData(RTFLOAT gx, RTFLOAT gy, RTFLOAT gz, RTFLOAT ax, RTFLOAT ay, RTFLOAT az,
+        RTFLOAT mx, RTFLOAT my, RTFLOAT mz, uint64_t timestamp);
+
+    //  the following two functions get access to the measured pose (accel and compass)
+
+    const RTVector3& getMeasuredPose() { return m_fusion->getMeasuredPose(); }
+    const RTQuaternion& getMeasuredQPose() { return m_fusion->getMeasuredQPose(); }
+
+    //  setCompassCalibrationMode() turns off use of cal data so that raw data can be accumulated
+    //  to derive calibration data
+
+    void setCompassCalibrationMode(bool enable) { m_compassCalibrationMode = enable; }
+
+    //  setAccelCalibrationMode() turns off use of cal data so that raw data can be accumulated
+    //  to derive calibration data
+
+    void setAccelCalibrationMode(bool enable) { m_accelCalibrationMode = enable; }
+
+    //  setCalibrationData configures the cal data from settings and also enables use if valid
+
+    void setCalibrationData();
+
+    //  getCompassCalibrationValid() returns true if the compass min/max calibration data is being used
+
+    bool getCompassCalibrationValid() { return !m_compassCalibrationMode && m_settings->m_compassCalValid; }
+
+    //  getRuntimeCompassCalibrationValid() returns true if the runtime compass min/max calibration data is being used
+
+    bool getRuntimeCompassCalibrationValid() { return !m_compassCalibrationMode && m_runtimeMagCalValid; }
+
+    //  getCompassCalibrationEllipsoidValid() returns true if the compass ellipsoid calibration data is being used
+
+    bool getCompassCalibrationEllipsoidValid() { return !m_compassCalibrationMode && m_settings->m_compassCalEllipsoidValid; }
+
+    //  getAccelCalibrationValid() returns true if the accel calibration data is being used
+
+    bool getAccelCalibrationValid() { return !m_accelCalibrationMode && m_settings->m_accelCalValid; }
+
+    const RTVector3& getGyro() { return m_imuData.gyro; }   // gets gyro rates in radians/sec
+    const RTVector3& getAccel() { return m_imuData.accel; } // get accel data in gs
+    const RTVector3& getCompass() { return m_imuData.compass; } // gets compass data in uT
+
+    RTVector3 getAccelResiduals() { return m_fusion->getAccelResiduals(); }
+
+protected:
+    void gyroBiasInit();                                    // sets up gyro bias calculation
+    void handleGyroBias();                                  // adjust gyro for bias
+    void calibrateAverageCompass();                         // calibrate and smooth compass
+    void calibrateAccel();                                  // calibrate the accelerometers
+    void updateFusion();                                    // call when new data to update fusion state
+
+    bool m_compassCalibrationMode;                          // true if cal mode so don't use cal data!
+    bool m_accelCalibrationMode;                            // true if cal mode so don't use cal data!
+
+    RTIMU_DATA m_imuData;                                   // the data from the IMU
+
+    RTIMUSettings *m_settings;                              // the settings object pointer
+
+    RTFusion *m_fusion;                                     // the fusion algorithm
+
+    int m_sampleRate;                                       // samples per second
+    uint64_t m_sampleInterval;                              // interval between samples in microseonds
+
+    RTFLOAT m_gyroLearningAlpha;                            // gyro bias rapid learning rate
+    RTFLOAT m_gyroContinuousAlpha;                          // gyro bias continuous (slow) learning rate
+    int m_gyroSampleCount;                                  // number of gyro samples used
+
+    RTVector3 m_previousAccel;                              // previous step accel for gyro learning
+
+    float m_compassCalOffset[3];
+    float m_compassCalScale[3];
+    RTVector3 m_compassAverage;                             // a running average to smooth the mag outputs
+
+    bool m_runtimeMagCalValid;                              // true if the runtime mag calibration has valid data
+    float m_runtimeMagCalMax[3];                            // runtime max mag values seen
+    float m_runtimeMagCalMin[3];                            // runtime min mag values seen
+
+    static float m_axisRotation[RTIMU_AXIS_ROTATION_COUNT][9];    // array of rotation matrices
+
+ };
+
+#endif // _RTIMU_H
diff --git a/libraries/RTIMULib/utility/RTIMUBMX055.cpp b/libraries/RTIMULib/utility/RTIMUBMX055.cpp
new file mode 100644
index 0000000..97d2792
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUBMX055.cpp
@@ -0,0 +1,906 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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.
+
+//  Some code from Bosch BMM150 API driver:
+
+/*
+****************************************************************************
+* Copyright (C) 2011 - 2014 Bosch Sensortec GmbH
+*
+* bmm050.c
+* Date: 2014/12/12
+* Revision: 2.0.3 $
+*
+* Usage: Sensor Driver for  BMM050 and BMM150 sensor
+*
+****************************************************************************
+* License:
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions are met:
+*
+*   Redistributions of source code must retain the above copyright
+*   notice, this list of conditions and the following disclaimer.
+*
+*   Redistributions in binary form must reproduce the above copyright
+*   notice, this list of conditions and the following disclaimer in the
+*   documentation and/or other materials provided with the distribution.
+*
+*   Neither the name of the copyright holder nor the names of the
+*   contributors may be used to endorse or promote products derived from
+*   this software without specific prior written permission.
+*
+* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND
+* CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
+* IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+* WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+* DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER
+* OR CONTRIBUTORS BE LIABLE FOR ANY
+* DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY,
+* OR CONSEQUENTIAL DAMAGES(INCLUDING, BUT NOT LIMITED TO,
+* PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+* HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY,
+* WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+* (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+* ANY WAY OUT OF THE USE OF THIS
+* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE
+*
+* The information provided is believed to be accurate and reliable.
+* The copyright holder assumes no responsibility
+* for the consequences of use
+* of such information nor for any infringement of patents or
+* other rights of third parties which may result from its use.
+* No license is granted by implication or otherwise under any patent or
+* patent rights of the copyright holder.
+**************************************************************************/
+/****************************************************************************/
+
+#include "RTIMUBMX055.h"
+#include "RTIMUSettings.h"
+
+//  this sets the learning rate for compass running average calculation
+
+#define COMPASS_ALPHA 0.2f
+
+RTIMUBMX055::RTIMUBMX055(RTIMUSettings *settings) : RTIMU(settings)
+{
+    m_sampleRate = 100;
+    m_sampleInterval = (uint64_t)1000000 / m_sampleRate;
+}
+
+RTIMUBMX055::~RTIMUBMX055()
+{
+}
+
+bool RTIMUBMX055::IMUInit()
+{
+    unsigned char result;
+
+    m_firstTime = true;
+
+    // set validity flags
+
+    m_imuData.fusionPoseValid = false;
+    m_imuData.fusionQPoseValid = false;
+    m_imuData.gyroValid = true;
+    m_imuData.accelValid = true;
+    m_imuData.compassValid = true;
+    m_imuData.pressureValid = false;
+    m_imuData.temperatureValid = false;
+    m_imuData.humidityValid = false;
+
+    //  configure IMU
+
+    m_gyroSlaveAddr = m_settings->m_I2CSlaveAddress;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, BMX055_GYRO_WHO_AM_I, 1, &result, "Failed to read BMX055 gyro id"))
+        return false;
+
+    if (result !=  BMX055_GYRO_ID) {
+        HAL_ERROR1("Incorrect BMX055 id %d\n", result);
+        return false;
+    }
+
+    // work out accel address
+
+    if (m_settings->HALRead(BMX055_ACCEL_ADDRESS0, BMX055_ACCEL_WHO_AM_I, 1, &result, "")) {
+        if (result == BMX055_ACCEL_ID) {
+            m_accelSlaveAddr = BMX055_ACCEL_ADDRESS0;
+        } else {
+            m_accelSlaveAddr = BMX055_ACCEL_ADDRESS1;
+        }
+    }
+
+    // work out mag address
+
+    int magAddr;
+
+    for (magAddr = BMX055_MAG_ADDRESS0; magAddr <= BMX055_MAG_ADDRESS3; magAddr++) {
+
+        // have to enable chip to get id...
+
+        m_settings->HALWrite(magAddr, BMX055_MAG_POWER, 1, "");
+
+        m_settings->delayMs(50);
+
+        if (m_settings->HALRead(magAddr, BMX055_MAG_WHO_AM_I, 1, &result, "")) {
+            if (result == BMX055_MAG_ID) {
+                m_magSlaveAddr = magAddr;
+                break;
+            }
+        }
+    }
+
+    if (magAddr > BMX055_MAG_ADDRESS3) {
+        HAL_ERROR("Failed to find BMX055 mag\n");
+        return false;
+    }
+
+    setCalibrationData();
+
+    //  enable the I2C bus
+
+    if (!m_settings->HALOpen())
+        return false;
+
+    //  Set up the gyro
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, BMX055_GYRO_FIFO_CONFIG_1, 0x40, "Failed to set BMX055 FIFO config"))
+        return false;
+
+    if (!setGyroSampleRate())
+            return false;
+
+    if (!setGyroFSR())
+            return false;
+
+    gyroBiasInit();
+
+    //  set up the accel
+
+    if (!setAccelSampleRate())
+            return false;
+
+    if (!setAccelFSR())
+            return false;
+
+
+    //  set up the mag
+
+    magInitTrimRegisters();
+    setMagPreset();
+
+    HAL_INFO("BMX055 init complete\n");
+    return true;
+}
+
+bool RTIMUBMX055::setGyroSampleRate()
+{
+    unsigned char bw;
+
+    switch (m_settings->m_BMX055GyroSampleRate) {
+    case BMX055_GYRO_SAMPLERATE_2000_523:
+        bw = 0;
+        m_sampleRate = 2000;
+        break;
+
+    case BMX055_GYRO_SAMPLERATE_2000_230:
+        bw = 1;
+        m_sampleRate = 2000;
+        break;
+
+    case BMX055_GYRO_SAMPLERATE_1000_116:
+        bw = 2;
+        m_sampleRate = 1000;
+        break;
+
+    case BMX055_GYRO_SAMPLERATE_400_47:
+        bw = 3;
+        m_sampleRate = 400;
+        break;
+
+    case BMX055_GYRO_SAMPLERATE_200_23:
+        bw = 4;
+        m_sampleRate = 200;
+        break;
+
+    case BMX055_GYRO_SAMPLERATE_100_12:
+        bw = 5;
+        m_sampleRate = 100;
+        break;
+
+    case BMX055_GYRO_SAMPLERATE_200_64:
+        bw = 6;
+        m_sampleRate = 200;
+        break;
+
+    case BMX055_GYRO_SAMPLERATE_100_32:
+        bw = 7;
+        m_sampleRate = 100;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal BMX055 gyro sample rate code %d\n", m_settings->m_BMX055GyroSampleRate);
+        return false;
+    }
+
+    m_sampleInterval = (uint64_t)1000000 / m_sampleRate;
+    return (m_settings->HALWrite(m_gyroSlaveAddr, BMX055_GYRO_BW, bw, "Failed to set BMX055 gyro rate"));
+}
+
+bool RTIMUBMX055::setGyroFSR()
+{
+    switch(m_settings->m_BMX055GyroFsr) {
+    case BMX055_GYRO_FSR_2000:
+        m_gyroScale = 0.061 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    case BMX055_GYRO_FSR_1000:
+        m_gyroScale = 0.0305 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    case BMX055_GYRO_FSR_500:
+        m_gyroScale = 0.0153 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    case BMX055_GYRO_FSR_250:
+        m_gyroScale = 0.0076 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    case BMX055_GYRO_FSR_125:
+        m_gyroScale = 0.0038 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal BMX055 gyro FSR code %d\n", m_settings->m_BMX055GyroFsr);
+        return false;
+
+    }
+    return (m_settings->HALWrite(m_gyroSlaveAddr, BMX055_GYRO_RANGE, m_settings->m_BMX055GyroFsr, "Failed to set BMX055 gyro rate"));
+}
+
+
+bool RTIMUBMX055::setAccelSampleRate()
+{
+    unsigned char reg;
+
+    switch(m_settings->m_BMX055AccelSampleRate) {
+    case BMX055_ACCEL_SAMPLERATE_15:
+        reg = 0x08;
+        break;
+
+    case BMX055_ACCEL_SAMPLERATE_31:
+        reg = 0x09;
+        break;
+
+    case BMX055_ACCEL_SAMPLERATE_62:
+        reg = 0x0a;
+        break;
+
+    case BMX055_ACCEL_SAMPLERATE_125:
+        reg = 0x0b;
+        break;
+
+    case BMX055_ACCEL_SAMPLERATE_250:
+        reg = 0x0c;
+        break;
+
+    case BMX055_ACCEL_SAMPLERATE_500:
+        reg = 0x0d;
+        break;
+
+    case BMX055_ACCEL_SAMPLERATE_1000:
+        reg = 0x0e;
+        break;
+
+    case BMX055_ACCEL_SAMPLERATE_2000:
+        reg = 0x0f;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal BMX055 accel FSR code %d\n", m_settings->m_BMX055AccelSampleRate);
+        return false;
+    }
+    return (m_settings->HALWrite(m_accelSlaveAddr, BMX055_ACCEL_PMU_BW, reg, "Failed to set BMX055 accel rate"));
+}
+
+bool RTIMUBMX055::setAccelFSR()
+{
+    unsigned char reg;
+
+    switch(m_settings->m_BMX055AccelFsr) {
+    case BMX055_ACCEL_FSR_2:
+        reg = 0x03;
+        m_accelScale = 0.00098 / 16.0;
+        break;
+
+    case BMX055_ACCEL_FSR_4:
+        reg = 0x05;
+        m_accelScale = 0.00195 / 16.0;
+        break;
+
+    case BMX055_ACCEL_FSR_8:
+        reg = 0x08;
+        m_accelScale = 0.00391 / 16.0;
+        break;
+
+    case BMX055_ACCEL_FSR_16:
+        reg = 0x0c;
+        m_accelScale = 0.00781 / 16.0;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal BMX055 accel FSR code %d\n", m_settings->m_BMX055AccelFsr);
+        return false;
+    }
+    return (m_settings->HALWrite(m_accelSlaveAddr, BMX055_ACCEL_PMU_RANGE, reg, "Failed to set BMX055 accel rate"));
+}
+
+bool RTIMUBMX055::setMagPreset()
+{
+    unsigned char mode, repXY, repZ;
+
+    switch (m_settings->m_BMX055MagPreset) {
+    case BMX055_MAG_LOW_POWER:                              // ODR=10, RepXY=3, RepZ=3
+        mode = 0;
+        repXY = 1;
+        repZ = 2;
+        break;
+
+    case BMX055_MAG_REGULAR:                                // ODR=10, RepXY=9, RepZ=15
+        mode = 0;
+        repXY = 4;
+        repZ = 14;
+        break;
+
+    case BMX055_MAG_ENHANCED:                               // ODR=10, RepXY=15, RepZ=27
+        mode = 0;
+        repXY = 7;
+        repZ = 26;
+        break;
+
+    case BMX055_MAG_HIGH_ACCURACY:                          // ODR=10, RepXY=47, RepZ=83
+        mode = 0;
+        repXY = 23;
+        repZ = 82;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal BMX055 mag preset code %d\n", m_settings->m_BMX055MagPreset);
+        return false;
+    }
+
+    if (!m_settings->HALWrite(m_magSlaveAddr, BMX055_MAG_MODE, mode, "Failed to set BMX055 mag mode"))
+        return false;
+    if (!m_settings->HALWrite(m_magSlaveAddr, BMX055_MAG_REPXY, repXY, "Failed to set BMX055 mag repXY"))
+        return false;
+    if (!m_settings->HALWrite(m_magSlaveAddr, BMX055_MAG_REPZ, repZ, "Failed to set BMX055 mag repZ"))
+        return false;
+    return true;
+}
+
+int RTIMUBMX055::IMUGetPollInterval()
+{
+    if (m_sampleRate > 400)
+        return 1;
+    else
+        return (400 / m_sampleRate);
+}
+
+bool RTIMUBMX055::IMURead()
+{
+    unsigned char status;
+    unsigned char gyroData[6];
+    unsigned char accelData[6];
+    unsigned char magData[8];
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, BMX055_GYRO_FIFO_STATUS, 1, &status, "Failed to read BMX055 gyro fifo status"))
+        return false;
+
+    if (status & 0x80) {
+        // fifo overflowed
+        HAL_ERROR("BMX055 fifo overflow\n");
+
+        // this should clear it
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, BMX055_GYRO_FIFO_CONFIG_1, 0x40, "Failed to set BMX055 FIFO config"))
+            return false;
+
+        m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();  // try to fix timestamp
+        return false;
+    }
+
+    if (status == 0)
+        return false;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, BMX055_GYRO_FIFO_DATA, 6, gyroData, "Failed to read BMX055 gyro data"))
+            return false;
+
+    if (!m_settings->HALRead(m_accelSlaveAddr, BMX055_ACCEL_X_LSB, 6, accelData, "Failed to read BMX055 accel data"))
+        return false;
+
+    if (!m_settings->HALRead(m_magSlaveAddr, BMX055_MAG_X_LSB, 8, magData, "Failed to read BMX055 mag data"))
+        return false;
+
+    RTMath::convertToVector(gyroData, m_imuData.gyro, m_gyroScale, false);
+
+    //  need to prepare accel data
+
+    accelData[0] &= 0xf0;
+    accelData[2] &= 0xf0;
+    accelData[4] &= 0xf0;
+
+    RTMath::convertToVector(accelData, m_imuData.accel, m_accelScale, false);
+
+    float mx, my, mz;
+
+    processMagData(magData, mx, my, mz);
+    m_imuData.compass.setX(mx);
+    m_imuData.compass.setY(my);
+    m_imuData.compass.setZ(mz);
+
+    //  sort out gyro axes
+
+    m_imuData.gyro.setY(-m_imuData.gyro.y());
+    m_imuData.gyro.setZ(-m_imuData.gyro.z());
+
+    //  sort out accel axes
+
+    m_imuData.accel.setX(-m_imuData.accel.x());
+
+    //  sort out mag axes
+
+    m_imuData.compass.setY(-m_imuData.compass.y());
+    m_imuData.compass.setZ(-m_imuData.compass.z());
+
+    //  now do standard processing
+
+    handleGyroBias();
+    calibrateAverageCompass();
+    calibrateAccel();
+
+    if (m_firstTime)
+        m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+    else
+        m_imuData.timestamp += m_sampleInterval;
+
+    m_firstTime = false;
+
+    //  now update the filter
+
+    updateFusion();
+
+    return true;
+}
+
+/*!
+ *	@brief This API reads remapped compensated Magnetometer
+ *	data of X,Y,Z values
+ *	@note The output value of compensated X, Y, Z as float
+ *
+ *	@note In this function X and Y axis is remapped
+ *	@note X is read from the address 0x44 & 0x45
+ *	@note Y is read from the address 0x42 & 0x43
+ *	@note this API is only applicable for BMX055 sensor
+ * *
+ *
+*/
+
+/****************************************************/
+/**\name	ARRAY PARAMETERS      */
+/***************************************************/
+#define LSB_ZERO	0
+#define MSB_ONE		1
+#define LSB_TWO		2
+#define MSB_THREE	3
+#define LSB_FOUR	4
+#define MSB_FIVE	5
+#define LSB_SIX		6
+#define MSB_SEVEN	7
+
+/********************************************/
+/**\name BIT MASK, LENGTH AND POSITION OF REMAPPED DATA REGISTERS   */
+/********************************************/
+/* Data X LSB Remapped Register only applicable for BMX055 */
+#define BMM050_BMX055_REMAPPED_DATAX_LSB_VALUEX__POS        3
+#define BMM050_BMX055_REMAPPED_DATAX_LSB_VALUEX__LEN        5
+#define BMM050_BMX055_REMAPPED_DATAX_LSB_VALUEX__MSK        0xF8
+#define BMM050_BMX055_REMAPPED_DATAX_LSB_VALUEX__REG\
+BMM050_BMX055_REMAPPED_DATAX_LSB
+
+/* Data Y LSB Remapped Register only applicable for BMX055  */
+#define BMM050_BMX055_REMAPPED_DATAY_LSB_VALUEY__POS        3
+#define BMM050_BMX055_REMAPPED_DATAY_LSB_VALUEY__LEN        5
+#define BMM050_BMX055_REMAPPED_DATAY_LSB_VALUEY__MSK        0xF8
+#define BMM050_BMX055_REMAPPED_DATAY_LSB_VALUEY__REG\
+BMM050_BMX055_REMAPPED_DATAY_LSB
+
+/********************************************/
+/**\name BIT MASK, LENGTH AND POSITION OF DATA REGISTERS   */
+/********************************************/
+/* Data X LSB Register */
+#define BMM050_DATAX_LSB_VALUEX__POS        3
+#define BMM050_DATAX_LSB_VALUEX__LEN        5
+#define BMM050_DATAX_LSB_VALUEX__MSK        0xF8
+#define BMM050_DATAX_LSB_VALUEX__REG        BMM050_DATAX_LSB
+
+/* Data X SelfTest Register */
+#define BMM050_DATAX_LSB_TESTX__POS         0
+#define BMM050_DATAX_LSB_TESTX__LEN         1
+#define BMM050_DATAX_LSB_TESTX__MSK         0x01
+#define BMM050_DATAX_LSB_TESTX__REG         BMM050_DATAX_LSB
+
+/* Data Y LSB Register */
+#define BMM050_DATAY_LSB_VALUEY__POS        3
+#define BMM050_DATAY_LSB_VALUEY__LEN        5
+#define BMM050_DATAY_LSB_VALUEY__MSK        0xF8
+#define BMM050_DATAY_LSB_VALUEY__REG        BMM050_DATAY_LSB
+
+/* Data Y SelfTest Register */
+#define BMM050_DATAY_LSB_TESTY__POS         0
+#define BMM050_DATAY_LSB_TESTY__LEN         1
+#define BMM050_DATAY_LSB_TESTY__MSK         0x01
+#define BMM050_DATAY_LSB_TESTY__REG         BMM050_DATAY_LSB
+
+/* Data Z LSB Register */
+#define BMM050_DATAZ_LSB_VALUEZ__POS        1
+#define BMM050_DATAZ_LSB_VALUEZ__LEN        7
+#define BMM050_DATAZ_LSB_VALUEZ__MSK        0xFE
+#define BMM050_DATAZ_LSB_VALUEZ__REG        BMM050_DATAZ_LSB
+
+/* Data Z SelfTest Register */
+#define BMM050_DATAZ_LSB_TESTZ__POS         0
+#define BMM050_DATAZ_LSB_TESTZ__LEN         1
+#define BMM050_DATAZ_LSB_TESTZ__MSK         0x01
+#define BMM050_DATAZ_LSB_TESTZ__REG         BMM050_DATAZ_LSB
+
+/* Hall Resistance LSB Register */
+#define BMM050_R_LSB_VALUE__POS             2
+#define BMM050_R_LSB_VALUE__LEN             6
+#define BMM050_R_LSB_VALUE__MSK             0xFC
+#define BMM050_R_LSB_VALUE__REG             BMM050_R_LSB
+
+#define BMM050_DATA_RDYSTAT__POS            0
+#define BMM050_DATA_RDYSTAT__LEN            1
+#define BMM050_DATA_RDYSTAT__MSK            0x01
+#define BMM050_DATA_RDYSTAT__REG            BMM050_R_LSB
+
+/********************************************/
+/**\name GET AND SET BITSLICE FUNCTIONS  */
+/********************************************/
+/* get bit slice  */
+#define BMM050_GET_BITSLICE(regvar, bitname)\
+    ((regvar & bitname##__MSK) >> bitname##__POS)
+
+/* Set bit slice */
+#define BMM050_SET_BITSLICE(regvar, bitname, val)\
+    ((regvar & ~bitname##__MSK) | ((val<resistance = raw_data_xyz_t.raw_data_r;
+
+}
+
+float RTIMUBMX055::bmm050_compensate_X_float(int16_t mag_data_x, uint16_t data_r)
+{
+    float inter_retval = BMM050_ZERO_U8X;
+    if (mag_data_x != BMM050_FLIP_OVERFLOW_ADCVAL	/* no overflow */
+       ) {
+        if (data_r != C_BMM050_ZERO_U8X) {
+            inter_retval = ((((float)m_dig_xyz1)
+            * BMM050_FLOAT_ONE_SIX_THREE_EIGHT_FOUR
+                /data_r)
+                - BMM050_FLOAT_ONE_SIX_THREE_EIGHT_FOUR);
+        } else {
+            inter_retval = BMM050_OVERFLOW_OUTPUT_FLOAT;
+            return inter_retval;
+        }
+        inter_retval = (((mag_data_x * ((((((float)m_dig_xy2) *
+            (inter_retval*inter_retval /
+            BMM050_FLOAT_2_6_8_4_3_5_4_5_6_DATA) +
+            inter_retval * ((float)m_dig_xy1)
+            / BMM050_FLOAT_1_6_3_8_4_DATA))
+            + BMM050_FLOAT_2_5_6_DATA) *
+            (((float)m_dig_x2) + BMM050_FLOAT_1_6_0_DATA)))
+            / BMM050_FLOAT_8_1_9_2_DATA)
+            + (((float)m_dig_x1) *
+            BMM050_FLOAT_EIGHT_DATA))/
+            BMM050_FLOAT_SIXTEEN_DATA;
+    } else {
+        inter_retval = BMM050_OVERFLOW_OUTPUT_FLOAT;
+    }
+    return inter_retval;
+}
+
+float RTIMUBMX055::bmm050_compensate_Y_float(int16_t mag_data_y, uint16_t data_r)
+{
+    float inter_retval = BMM050_ZERO_U8X;
+    if (mag_data_y != BMM050_FLIP_OVERFLOW_ADCVAL /* no overflow */
+       ) {
+        if (data_r != C_BMM050_ZERO_U8X) {
+            inter_retval = ((((float)m_dig_xyz1)
+            * BMM050_FLOAT_ONE_SIX_THREE_EIGHT_FOUR
+            /data_r) - BMM050_FLOAT_ONE_SIX_THREE_EIGHT_FOUR);
+        } else {
+            inter_retval = BMM050_OVERFLOW_OUTPUT_FLOAT;
+            return inter_retval;
+        }
+        inter_retval = (((mag_data_y * ((((((float)m_dig_xy2) *
+            (inter_retval*inter_retval
+            / BMM050_FLOAT_2_6_8_4_3_5_4_5_6_DATA) +
+            inter_retval * ((float)m_dig_xy1)
+            / BMM050_FLOAT_1_6_3_8_4_DATA)) +
+            BMM050_FLOAT_2_5_6_DATA) *
+            (((float)m_dig_y2) + BMM050_FLOAT_1_6_0_DATA)))
+            / BMM050_FLOAT_8_1_9_2_DATA) +
+            (((float)m_dig_y1) * BMM050_FLOAT_EIGHT_DATA))
+            / BMM050_FLOAT_SIXTEEN_DATA;
+    } else {
+        /* overflow, set output to 0.0f */
+        inter_retval = BMM050_OVERFLOW_OUTPUT_FLOAT;
+    }
+    return inter_retval;
+}
+
+float RTIMUBMX055::bmm050_compensate_Z_float (int16_t mag_data_z, uint16_t data_r)
+{
+    float inter_retval = BMM050_ZERO_U8X;
+     /* no overflow */
+    if (mag_data_z != BMM050_HALL_OVERFLOW_ADCVAL) {
+        if ((m_dig_z2 != BMM050_ZERO_U8X)
+        && (m_dig_z1 != BMM050_ZERO_U8X)
+        && (data_r != BMM050_ZERO_U8X)) {
+            inter_retval = ((((((float)mag_data_z)-
+            ((float)m_dig_z4))*
+            BMM050_FLOAT_1_3_1_0_7_2_DATA)-
+            (((float)m_dig_z3)*(((float)data_r)
+            -((float)m_dig_xyz1))))
+            /((((float)m_dig_z2)+
+            ((float)m_dig_z1)*((float)data_r) /
+            BMM050_FLOAT_3_2_7_6_8_DATA)
+            * BMM050_FLOAT_4_DATA))
+            / BMM050_FLOAT_SIXTEEN_DATA;
+        }
+    } else {
+        /* overflow, set output to 0.0f */
+        inter_retval = BMM050_OVERFLOW_OUTPUT_FLOAT;
+    }
+    return inter_retval;
+}
+
+bool RTIMUBMX055::magInitTrimRegisters()
+{
+    unsigned char data[2];
+    data[0] = 0;
+    data[1] = 0;
+
+    if (!m_settings->HALRead(m_magSlaveAddr, BMX055_MAG_DIG_X1, 1, (uint8_t *)&m_dig_x1, "Failed to read BMX055 mag trim x1"))
+        return false;
+
+    if (!m_settings->HALRead(m_magSlaveAddr, BMX055_MAG_DIG_Y1, 1, (uint8_t *)&m_dig_y1, "Failed to read BMX055 mag trim y1"))
+        return false;
+
+    if (!m_settings->HALRead(m_magSlaveAddr, BMX055_MAG_DIG_X2, 1, (uint8_t *)&m_dig_x2, "Failed to read BMX055 mag trim x2"))
+        return false;
+
+    if (!m_settings->HALRead(m_magSlaveAddr, BMX055_MAG_DIG_Y2, 1, (uint8_t *)&m_dig_y2, "Failed to read BMX055 mag trim y2"))
+        return false;
+
+    if (!m_settings->HALRead(m_magSlaveAddr, BMX055_MAG_DIG_XY1, 1, &m_dig_xy1, "Failed to read BMX055 mag trim xy1"))
+        return false;
+
+    if (!m_settings->HALRead(m_magSlaveAddr, BMX055_MAG_DIG_XY2, 1, (uint8_t *)&m_dig_xy2, "Failed to read BMX055 mag trim xy2"))
+        return false;
+
+    /* shorts can not be recast into (uint8_t*)
+    * due to possible mix up between trim data
+    * arrangement and memory arrangement */
+
+    if (!m_settings->HALRead(m_magSlaveAddr, BMX055_MAG_DIG_Z1_LSB, 2, data, "Failed to read BMX055 mag trim z1"))
+        return false;
+
+    m_dig_z1 = (uint16_t)((((uint32_t)((uint8_t)
+    data[MSB_ONE])) <<
+    SHIFT_LEFT_8_POSITION) | data[LSB_ZERO]);
+
+    if (!m_settings->HALRead(m_magSlaveAddr, BMX055_MAG_DIG_Z2_LSB, 2, data, "Failed to read BMX055 mag trim z2"))
+        return false;
+
+    m_dig_z2 = (int16_t)((((int32_t)(
+    (int8_t)data[MSB_ONE])) <<
+    SHIFT_LEFT_8_POSITION) | data[LSB_ZERO]);
+
+    if (!m_settings->HALRead(m_magSlaveAddr, BMX055_MAG_DIG_Z3_LSB, 2, data, "Failed to read BMX055 mag trim z3"))
+        return false;
+
+    m_dig_z3 = (int16_t)((((int32_t)(
+    (int8_t)data[MSB_ONE])) <<
+    SHIFT_LEFT_8_POSITION) | data[LSB_ZERO]);
+
+    if (!m_settings->HALRead(m_magSlaveAddr, BMX055_MAG_DIG_Z4_LSB, 2, data, "Failed to read BMX055 mag trim z4"))
+        return false;
+
+    m_dig_z4 = (int16_t)((((int32_t)(
+    (int8_t)data[MSB_ONE])) <<
+    SHIFT_LEFT_8_POSITION) | data[LSB_ZERO]);
+
+    if (!m_settings->HALRead(m_magSlaveAddr, BMX055_MAG_DIG_XYZ1_LSB, 2, data, "Failed to read BMX055 mag trim xyz1"))
+        return false;
+
+    data[MSB_ONE] = BMM050_GET_BITSLICE(data[MSB_ONE],
+    BMM050_DIG_XYZ1_MSB);
+    m_dig_xyz1 = (uint16_t)((((uint32_t)
+    ((uint8_t)data[MSB_ONE])) <<
+    SHIFT_LEFT_8_POSITION) | data[LSB_ZERO]);
+
+    return true;
+}
diff --git a/libraries/RTIMULib/utility/RTIMUBMX055.h b/libraries/RTIMULib/utility/RTIMUBMX055.h
new file mode 100644
index 0000000..a690f1a
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUBMX055.h
@@ -0,0 +1,80 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTIMUBMX055_H
+#define	_RTIMUBMX055_H
+
+#include "RTIMU.h"
+
+class RTIMUBMX055 : public RTIMU
+{
+public:
+    RTIMUBMX055(RTIMUSettings *settings);
+    ~RTIMUBMX055();
+
+    virtual const char *IMUName() { return "BMX055"; }
+    virtual int IMUType() { return RTIMU_TYPE_BMX055; }
+    virtual bool IMUInit();
+    virtual int IMUGetPollInterval();
+    virtual bool IMURead();
+
+private:
+    bool setGyroSampleRate();
+    bool setGyroFSR();
+    bool setAccelSampleRate();
+    bool setAccelFSR();
+    bool magInitTrimRegisters();
+    bool setMagPreset();
+    void processMagData(unsigned char *v_data_uint8_t, float& magX, float& magY, float& magZ);
+    float bmm050_compensate_X_float(int16_t mag_data_x, uint16_t data_r);
+    float bmm050_compensate_Y_float(int16_t mag_data_y, uint16_t data_r);
+    float bmm050_compensate_Z_float(int16_t mag_data_z, uint16_t data_r);
+
+    unsigned char m_gyroSlaveAddr;                          // I2C address of gyro
+    unsigned char m_accelSlaveAddr;                         // I2C address of accel
+    unsigned char m_magSlaveAddr;                           // I2C address of mag
+
+    bool m_firstTime;                                       // if first sample
+
+    RTFLOAT m_gyroScale;
+    RTFLOAT m_accelScale;
+
+    int8_t m_dig_x1;/**< trim x1 data */
+    int8_t m_dig_y1;/**< trim y1 data */
+
+    int8_t m_dig_x2;/**< trim x2 data */
+    int8_t m_dig_y2;/**< trim y2 data */
+
+    uint16_t m_dig_z1;/**< trim z1 data */
+    int16_t m_dig_z2;/**< trim z2 data */
+    int16_t m_dig_z3;/**< trim z3 data */
+    int16_t m_dig_z4;/**< trim z4 data */
+
+    uint8_t m_dig_xy1;/**< trim xy1 data */
+    int8_t m_dig_xy2;/**< trim xy2 data */
+
+    uint16_t m_dig_xyz1;/**< trim xyz1 data */
+};
+
+#endif // _RTIMUBMX055_H
diff --git a/libraries/RTIMULib/utility/RTIMUBNO055.cpp b/libraries/RTIMULib/utility/RTIMUBNO055.cpp
new file mode 100644
index 0000000..f5340d0
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUBNO055.cpp
@@ -0,0 +1,191 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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.
+
+//  Based on the Adafruit BNO055 driver:
+
+/***************************************************************************
+  This is a library for the BNO055 orientation sensor
+  Designed specifically to work with the Adafruit BNO055 Breakout.
+  Pick one up today in the adafruit shop!
+  ------> http://www.adafruit.com/products
+  These sensors use I2C to communicate, 2 pins are required to interface.
+  Adafruit invests time and resources providing this open source code,
+  please support Adafruit andopen-source hardware by purchasing products
+  from Adafruit!
+  Written by KTOWN for Adafruit Industries.
+  MIT license, all text above must be included in any redistribution
+ ***************************************************************************/
+
+#include "RTIMUBNO055.h"
+#include "RTIMUSettings.h"
+
+RTIMUBNO055::RTIMUBNO055(RTIMUSettings *settings) : RTIMU(settings)
+{
+    m_sampleRate = 100;
+    m_sampleInterval = (uint64_t)1000000 / m_sampleRate;
+}
+
+RTIMUBNO055::~RTIMUBNO055()
+{
+}
+
+bool RTIMUBNO055::IMUInit()
+{
+    unsigned char result;
+
+    m_slaveAddr = m_settings->m_I2CSlaveAddress;
+    m_lastReadTime = RTMath::currentUSecsSinceEpoch();
+
+    // set validity flags
+
+    m_imuData.fusionPoseValid = true;
+    m_imuData.fusionQPoseValid = true;
+    m_imuData.gyroValid = true;
+    m_imuData.accelValid = true;
+    m_imuData.compassValid = true;
+    m_imuData.pressureValid = false;
+    m_imuData.temperatureValid = false;
+    m_imuData.humidityValid = false;
+
+    if (!m_settings->HALRead(m_slaveAddr, BNO055_WHO_AM_I, 1, &result, "Failed to read BNO055 id"))
+        return false;
+
+    if (result != BNO055_ID) {
+        HAL_ERROR1("Incorrect IMU id %d", result);
+        return false;
+    }
+
+    if (!m_settings->HALWrite(m_slaveAddr, BNO055_OPER_MODE, BNO055_OPER_MODE_CONFIG, "Failed to set BNO055 into config mode"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    if (!m_settings->HALWrite(m_slaveAddr, BNO055_SYS_TRIGGER, 0x20, "Failed to reset BNO055"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    while (1) {
+        if (!m_settings->HALRead(m_slaveAddr, BNO055_WHO_AM_I, 1, &result, ""))
+            continue;
+        if (result == BNO055_ID)
+            break;
+        m_settings->delayMs(50);
+    }
+
+    m_settings->delayMs(50);
+
+    if (!m_settings->HALWrite(m_slaveAddr, BNO055_PWR_MODE, BNO055_PWR_MODE_NORMAL, "Failed to set BNO055 normal power mode"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    if (!m_settings->HALWrite(m_slaveAddr, BNO055_PAGE_ID, 0, "Failed to set BNO055 page 0"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    if (!m_settings->HALWrite(m_slaveAddr, BNO055_SYS_TRIGGER, 0x00, "Failed to start BNO055"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    if (!m_settings->HALWrite(m_slaveAddr, BNO055_UNIT_SEL, 0x87, "Failed to set BNO055 units"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    if (!m_settings->HALWrite(m_slaveAddr, BNO055_OPER_MODE, BNO055_OPER_MODE_NDOF, "Failed to set BNO055 into 9-dof mode"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    HAL_INFO("BNO055 init complete\n");
+    return true;
+}
+
+int RTIMUBNO055::IMUGetPollInterval()
+{
+    return (7);
+}
+
+bool RTIMUBNO055::IMURead()
+{
+    unsigned char buffer[24];
+
+    if ((RTMath::currentUSecsSinceEpoch() - m_lastReadTime) < m_sampleInterval)
+        return false;                                       // too soon
+
+    m_lastReadTime = RTMath::currentUSecsSinceEpoch();
+    if (!m_settings->HALRead(m_slaveAddr, BNO055_ACCEL_DATA, 24, buffer, "Failed to read BNO055 data"))
+        return false;
+
+    int16_t x, y, z;
+
+    // process accel data
+
+    x = (((uint16_t)buffer[1]) << 8) | ((uint16_t)buffer[0]);
+    y = (((uint16_t)buffer[3]) << 8) | ((uint16_t)buffer[2]);
+    z = (((uint16_t)buffer[5]) << 8) | ((uint16_t)buffer[4]);
+
+    m_imuData.accel.setX((RTFLOAT)y / 1000.0);
+    m_imuData.accel.setY((RTFLOAT)x / 1000.0);
+    m_imuData.accel.setZ((RTFLOAT)z / 1000.0);
+
+    // process mag data
+
+    x = (((uint16_t)buffer[7]) << 8) | ((uint16_t)buffer[6]);
+    y = (((uint16_t)buffer[9]) << 8) | ((uint16_t)buffer[8]);
+    z = (((uint16_t)buffer[11]) << 8) | ((uint16_t)buffer[10]);
+
+    m_imuData.compass.setX(-(RTFLOAT)y / 16.0);
+    m_imuData.compass.setY(-(RTFLOAT)x / 16.0);
+    m_imuData.compass.setZ(-(RTFLOAT)z / 16.0);
+
+    // process gyro data
+
+    x = (((uint16_t)buffer[13]) << 8) | ((uint16_t)buffer[12]);
+    y = (((uint16_t)buffer[15]) << 8) | ((uint16_t)buffer[14]);
+    z = (((uint16_t)buffer[17]) << 8) | ((uint16_t)buffer[16]);
+
+    m_imuData.gyro.setX(-(RTFLOAT)y / 900.0);
+    m_imuData.gyro.setY(-(RTFLOAT)x / 900.0);
+    m_imuData.gyro.setZ(-(RTFLOAT)z / 900.0);
+
+    // process euler angles
+
+    x = (((uint16_t)buffer[19]) << 8) | ((uint16_t)buffer[18]);
+    y = (((uint16_t)buffer[21]) << 8) | ((uint16_t)buffer[20]);
+    z = (((uint16_t)buffer[23]) << 8) | ((uint16_t)buffer[22]);
+
+    //  put in structure and do axis remap
+
+    m_imuData.fusionPose.setX((RTFLOAT)y / 900.0);
+    m_imuData.fusionPose.setY((RTFLOAT)z / 900.0);
+    m_imuData.fusionPose.setZ((RTFLOAT)x / 900.0);
+
+    m_imuData.fusionQPose.fromEuler(m_imuData.fusionPose);
+
+    m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+    return true;
+}
diff --git a/libraries/RTIMULib/utility/RTIMUBNO055.h b/libraries/RTIMULib/utility/RTIMUBNO055.h
new file mode 100644
index 0000000..7ff9c3e
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUBNO055.h
@@ -0,0 +1,48 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTIMUBNO055_H
+#define	_RTIMUBNO055_H
+
+#include "RTIMU.h"
+
+class RTIMUBNO055 : public RTIMU
+{
+public:
+    RTIMUBNO055(RTIMUSettings *settings);
+    ~RTIMUBNO055();
+
+    virtual const char *IMUName() { return "BNO055"; }
+    virtual int IMUType() { return RTIMU_TYPE_BNO055; }
+    virtual bool IMUInit();
+    virtual int IMUGetPollInterval();
+    virtual bool IMURead();
+
+private:
+    unsigned char m_slaveAddr;                              // I2C address of BNO055
+
+    uint64_t m_lastReadTime;
+};
+
+#endif // _RTIMUBNO055_H
diff --git a/libraries/RTIMULib/utility/RTIMUDefs.h b/libraries/RTIMULib/utility/RTIMUDefs.h
new file mode 100644
index 0000000..19905f9
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUDefs.h
@@ -0,0 +1,945 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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.
+
+//  The MPU-9250 and SPI driver code is based on code generously supplied by
+//  staslock@gmail.com (www.clickdrive.io)
+
+
+#ifndef _RTIMUDEFS_H
+#define	_RTIMUDEFS_H
+
+//  IMU type codes
+
+#define RTIMU_TYPE_AUTODISCOVER             0                   // audodiscover the IMU
+#define RTIMU_TYPE_NULL                     1                   // if no physical hardware
+#define RTIMU_TYPE_MPU9150                  2                   // InvenSense MPU9150
+#define RTIMU_TYPE_GD20HM303D               3                   // STM L3GD20H/LSM303D (Pololu Altimu)
+#define RTIMU_TYPE_GD20M303DLHC             4                   // STM L3GD20/LSM303DHLC (old Adafruit IMU)
+#define RTIMU_TYPE_LSM9DS0                  5                   // STM LSM9DS0 (eg Sparkfun IMU)
+#define RTIMU_TYPE_MPU9250                  6                   // InvenSense MPU9250
+#define RTIMU_TYPE_GD20HM303DLHC            7                   // STM L3GD20H/LSM303DHLC (new Adafruit IMU)
+#define RTIMU_TYPE_BMX055                   8                   // Bosch BMX055
+#define RTIMU_TYPE_BNO055                   9                   // Bosch BNO055
+
+//----------------------------------------------------------
+//
+//  MPU-9150
+
+//  MPU9150 I2C Slave Addresses
+
+#define MPU9150_ADDRESS0            0x68
+#define MPU9150_ADDRESS1            0x69
+#define MPU9150_ID                  0x68
+
+//  thes magnetometers are on aux bus
+
+#define AK8975_ADDRESS              0x0c
+#define HMC5883_ADDRESS             0x1e
+
+//  Register map
+
+#define MPU9150_YG_OFFS_TC          0x01
+#define MPU9150_SMPRT_DIV           0x19
+#define MPU9150_LPF_CONFIG          0x1a
+#define MPU9150_GYRO_CONFIG         0x1b
+#define MPU9150_ACCEL_CONFIG        0x1c
+#define MPU9150_FIFO_EN             0x23
+#define MPU9150_I2C_MST_CTRL        0x24
+#define MPU9150_I2C_SLV0_ADDR       0x25
+#define MPU9150_I2C_SLV0_REG        0x26
+#define MPU9150_I2C_SLV0_CTRL       0x27
+#define MPU9150_I2C_SLV1_ADDR       0x28
+#define MPU9150_I2C_SLV1_REG        0x29
+#define MPU9150_I2C_SLV1_CTRL       0x2a
+#define MPU9150_I2C_SLV4_CTRL       0x34
+#define MPU9150_INT_PIN_CFG         0x37
+#define MPU9150_INT_ENABLE          0x38
+#define MPU9150_INT_STATUS          0x3a
+#define MPU9150_ACCEL_XOUT_H        0x3b
+#define MPU9150_GYRO_XOUT_H         0x43
+#define MPU9150_EXT_SENS_DATA_00    0x49
+#define MPU9150_I2C_SLV1_DO         0x64
+#define MPU9150_I2C_MST_DELAY_CTRL  0x67
+#define MPU9150_USER_CTRL           0x6a
+#define MPU9150_PWR_MGMT_1          0x6b
+#define MPU9150_PWR_MGMT_2          0x6c
+#define MPU9150_FIFO_COUNT_H        0x72
+#define MPU9150_FIFO_R_W            0x74
+#define MPU9150_WHO_AM_I            0x75
+
+//  sample rate defines (applies to gyros and accels, not mags)
+
+#define MPU9150_SAMPLERATE_MIN      5                      // 5 samples per second is the lowest
+#define MPU9150_SAMPLERATE_MAX      1000                   // 1000 samples per second is the absolute maximum
+
+//  compass rate defines
+
+#define MPU9150_COMPASSRATE_MIN     1                      // 1 samples per second is the lowest
+#define MPU9150_COMPASSRATE_MAX     100                    // 100 samples per second is maximum
+
+//  LPF options (gyros and accels)
+
+#define MPU9150_LPF_256             0                       // gyro: 256Hz, accel: 260Hz
+#define MPU9150_LPF_188             1                       // gyro: 188Hz, accel: 184Hz
+#define MPU9150_LPF_98              2                       // gyro: 98Hz, accel: 98Hz
+#define MPU9150_LPF_42              3                       // gyro: 42Hz, accel: 44Hz
+#define MPU9150_LPF_20              4                       // gyro: 20Hz, accel: 21Hz
+#define MPU9150_LPF_10              5                       // gyro: 10Hz, accel: 10Hz
+#define MPU9150_LPF_5               6                       // gyro: 5Hz, accel: 5Hz
+
+//  Gyro FSR options
+
+#define MPU9150_GYROFSR_250         0                       // +/- 250 degrees per second
+#define MPU9150_GYROFSR_500         8                       // +/- 500 degrees per second
+#define MPU9150_GYROFSR_1000        0x10                    // +/- 1000 degrees per second
+#define MPU9150_GYROFSR_2000        0x18                    // +/- 2000 degrees per second
+
+//  Accel FSR options
+
+#define MPU9150_ACCELFSR_2          0                       // +/- 2g
+#define MPU9150_ACCELFSR_4          8                       // +/- 4g
+#define MPU9150_ACCELFSR_8          0x10                    // +/- 8g
+#define MPU9150_ACCELFSR_16         0x18                    // +/- 16g
+
+
+//  AK8975 compass registers
+
+#define AK8975_DEVICEID             0x0                     // the device ID
+#define AK8975_ST1                  0x02                    // status 1
+#define AK8975_CNTL                 0x0a                    // control reg
+#define AK8975_ASAX                 0x10                    // start of the fuse ROM data
+
+//  HMC5883 compass registers
+
+#define HMC5883_CONFIG_A            0x00                    // configuration A
+#define HMC5883_CONFIG_B            0x01                    // configuration B
+#define HMC5883_MODE                0x02                    // mode
+#define HMC5883_DATA_X_HI           0x03                    // data x msb
+#define HMC5883_STATUS              0x09                    // status
+#define HMC5883_ID                  0x0a                    // id
+
+
+//----------------------------------------------------------
+//
+//  MPU-9250
+
+//  MPU9250 I2C Slave Addresses
+
+#define MPU9250_ADDRESS0            0x68
+#define MPU9250_ADDRESS1            0x69
+#define MPU9250_ID                  0x71
+
+#define AK8963_ADDRESS              0x0c
+
+//  Register map
+
+#define MPU9250_SMPRT_DIV           0x19
+#define MPU9250_GYRO_LPF            0x1a
+#define MPU9250_GYRO_CONFIG         0x1b
+#define MPU9250_ACCEL_CONFIG        0x1c
+#define MPU9250_ACCEL_LPF           0x1d
+#define MPU9250_FIFO_EN             0x23
+#define MPU9250_I2C_MST_CTRL        0x24
+#define MPU9250_I2C_SLV0_ADDR       0x25
+#define MPU9250_I2C_SLV0_REG        0x26
+#define MPU9250_I2C_SLV0_CTRL       0x27
+#define MPU9250_I2C_SLV1_ADDR       0x28
+#define MPU9250_I2C_SLV1_REG        0x29
+#define MPU9250_I2C_SLV1_CTRL       0x2a
+#define MPU9250_I2C_SLV2_ADDR       0x2b
+#define MPU9250_I2C_SLV2_REG        0x2c
+#define MPU9250_I2C_SLV2_CTRL       0x2d
+#define MPU9250_I2C_SLV4_CTRL       0x34
+#define MPU9250_INT_PIN_CFG         0x37
+#define MPU9250_INT_ENABLE          0x38
+#define MPU9250_INT_STATUS          0x3a
+#define MPU9250_ACCEL_XOUT_H        0x3b
+#define MPU9250_GYRO_XOUT_H         0x43
+#define MPU9250_EXT_SENS_DATA_00    0x49
+#define MPU9250_I2C_SLV1_DO         0x64
+#define MPU9250_I2C_MST_DELAY_CTRL  0x67
+#define MPU9250_USER_CTRL           0x6a
+#define MPU9250_PWR_MGMT_1          0x6b
+#define MPU9250_PWR_MGMT_2          0x6c
+#define MPU9250_FIFO_COUNT_H        0x72
+#define MPU9250_FIFO_R_W            0x74
+#define MPU9250_WHO_AM_I            0x75
+
+//  sample rate defines (applies to gyros and accels, not mags)
+
+#define MPU9250_SAMPLERATE_MIN      5                       // 5 samples per second is the lowest
+#define MPU9250_SAMPLERATE_MAX      32000                   // 32000 samples per second is the absolute maximum
+
+//  compass rate defines
+
+#define MPU9250_COMPASSRATE_MIN     1                       // 1 samples per second is the lowest
+#define MPU9250_COMPASSRATE_MAX     100                     // 100 samples per second is maximum
+
+//  Gyro LPF options
+
+#define MPU9250_GYRO_LPF_8800       0x11                    // 8800Hz, 0.64mS delay
+#define MPU9250_GYRO_LPF_3600       0x10                    // 3600Hz, 0.11mS delay
+#define MPU9250_GYRO_LPF_250        0x00                    // 250Hz, 0.97mS delay
+#define MPU9250_GYRO_LPF_184        0x01                    // 184Hz, 2.9mS delay
+#define MPU9250_GYRO_LPF_92         0x02                    // 92Hz, 3.9mS delay
+#define MPU9250_GYRO_LPF_41         0x03                    // 41Hz, 5.9mS delay
+#define MPU9250_GYRO_LPF_20         0x04                    // 20Hz, 9.9mS delay
+#define MPU9250_GYRO_LPF_10         0x05                    // 10Hz, 17.85mS delay
+#define MPU9250_GYRO_LPF_5          0x06                    // 5Hz, 33.48mS delay
+
+//  Gyro FSR options
+
+#define MPU9250_GYROFSR_250         0                       // +/- 250 degrees per second
+#define MPU9250_GYROFSR_500         8                       // +/- 500 degrees per second
+#define MPU9250_GYROFSR_1000        0x10                    // +/- 1000 degrees per second
+#define MPU9250_GYROFSR_2000        0x18                    // +/- 2000 degrees per second
+
+//  Accel FSR options
+
+#define MPU9250_ACCELFSR_2          0                       // +/- 2g
+#define MPU9250_ACCELFSR_4          8                       // +/- 4g
+#define MPU9250_ACCELFSR_8          0x10                    // +/- 8g
+#define MPU9250_ACCELFSR_16         0x18                    // +/- 16g
+
+//  Accel LPF options
+
+#define MPU9250_ACCEL_LPF_1130      0x08                    // 1130Hz, 0.75mS delay
+#define MPU9250_ACCEL_LPF_460       0x00                    // 460Hz, 1.94mS delay
+#define MPU9250_ACCEL_LPF_184       0x01                    // 184Hz, 5.80mS delay
+#define MPU9250_ACCEL_LPF_92        0x02                    // 92Hz, 7.80mS delay
+#define MPU9250_ACCEL_LPF_41        0x03                    // 41Hz, 11.80mS delay
+#define MPU9250_ACCEL_LPF_20        0x04                    // 20Hz, 19.80mS delay
+#define MPU9250_ACCEL_LPF_10        0x05                    // 10Hz, 35.70mS delay
+#define MPU9250_ACCEL_LPF_5         0x06                    // 5Hz, 66.96mS delay
+
+//  AK8963 compass registers
+
+#define AK8963_DEVICEID             0x48                    // the device ID
+#define AK8963_ST1                  0x02                    // status 1
+#define AK8963_CNTL                 0x0a                    // control reg
+#define AK8963_ASAX                 0x10                    // start of the fuse ROM data
+
+//----------------------------------------------------------
+//
+//  L3GD20
+
+//  I2C Slave Addresses
+
+#define L3GD20_ADDRESS0             0x6a
+#define L3GD20_ADDRESS1             0x6b
+#define L3GD20_ID                   0xd4
+
+//  L3GD20 Register map
+
+#define L3GD20_WHO_AM_I        0x0f
+#define L3GD20_CTRL1           0x20
+#define L3GD20_CTRL2           0x21
+#define L3GD20_CTRL3           0x22
+#define L3GD20_CTRL4           0x23
+#define L3GD20_CTRL5           0x24
+#define L3GD20_OUT_TEMP        0x26
+#define L3GD20_STATUS          0x27
+#define L3GD20_OUT_X_L         0x28
+#define L3GD20_OUT_X_H         0x29
+#define L3GD20_OUT_Y_L         0x2a
+#define L3GD20_OUT_Y_H         0x2b
+#define L3GD20_OUT_Z_L         0x2c
+#define L3GD20_OUT_Z_H         0x2d
+#define L3GD20_FIFO_CTRL       0x2e
+#define L3GD20_FIFO_SRC        0x2f
+#define L3GD20_IG_CFG          0x30
+#define L3GD20_IG_SRC          0x31
+#define L3GD20_IG_THS_XH       0x32
+#define L3GD20_IG_THS_XL       0x33
+#define L3GD20_IG_THS_YH       0x34
+#define L3GD20_IG_THS_YL       0x35
+#define L3GD20_IG_THS_ZH       0x36
+#define L3GD20_IG_THS_ZL       0x37
+#define L3GD20_IG_DURATION     0x38
+
+//  Gyro sample rate defines
+
+#define L3GD20_SAMPLERATE_95    0
+#define L3GD20_SAMPLERATE_190   1
+#define L3GD20_SAMPLERATE_380   2
+#define L3GD20_SAMPLERATE_760   3
+
+//  Gyro banwidth defines
+
+#define L3GD20_BANDWIDTH_0     0
+#define L3GD20_BANDWIDTH_1     1
+#define L3GD20_BANDWIDTH_2     2
+#define L3GD20_BANDWIDTH_3     3
+
+//  Gyro FSR defines
+
+#define L3GD20_FSR_250         0
+#define L3GD20_FSR_500         1
+#define L3GD20_FSR_2000        2
+
+//  Gyro high pass filter defines
+
+#define L3GD20_HPF_0           0
+#define L3GD20_HPF_1           1
+#define L3GD20_HPF_2           2
+#define L3GD20_HPF_3           3
+#define L3GD20_HPF_4           4
+#define L3GD20_HPF_5           5
+#define L3GD20_HPF_6           6
+#define L3GD20_HPF_7           7
+#define L3GD20_HPF_8           8
+#define L3GD20_HPF_9           9
+
+//----------------------------------------------------------
+//
+//  L3GD20H
+
+//  I2C Slave Addresses
+
+#define L3GD20H_ADDRESS0        0x6a
+#define L3GD20H_ADDRESS1        0x6b
+#define L3GD20H_ID              0xd7
+
+//  L3GD20H Register map
+
+#define L3GD20H_WHO_AM_I        0x0f
+#define L3GD20H_CTRL1           0x20
+#define L3GD20H_CTRL2           0x21
+#define L3GD20H_CTRL3           0x22
+#define L3GD20H_CTRL4           0x23
+#define L3GD20H_CTRL5           0x24
+#define L3GD20H_OUT_TEMP        0x26
+#define L3GD20H_STATUS          0x27
+#define L3GD20H_OUT_X_L         0x28
+#define L3GD20H_OUT_X_H         0x29
+#define L3GD20H_OUT_Y_L         0x2a
+#define L3GD20H_OUT_Y_H         0x2b
+#define L3GD20H_OUT_Z_L         0x2c
+#define L3GD20H_OUT_Z_H         0x2d
+#define L3GD20H_FIFO_CTRL       0x2e
+#define L3GD20H_FIFO_SRC        0x2f
+#define L3GD20H_IG_CFG          0x30
+#define L3GD20H_IG_SRC          0x31
+#define L3GD20H_IG_THS_XH       0x32
+#define L3GD20H_IG_THS_XL       0x33
+#define L3GD20H_IG_THS_YH       0x34
+#define L3GD20H_IG_THS_YL       0x35
+#define L3GD20H_IG_THS_ZH       0x36
+#define L3GD20H_IG_THS_ZL       0x37
+#define L3GD20H_IG_DURATION     0x38
+#define L3GD20H_LOW_ODR         0x39
+
+//  Gyro sample rate defines
+
+#define L3GD20H_SAMPLERATE_12_5 0
+#define L3GD20H_SAMPLERATE_25   1
+#define L3GD20H_SAMPLERATE_50   2
+#define L3GD20H_SAMPLERATE_100  3
+#define L3GD20H_SAMPLERATE_200  4
+#define L3GD20H_SAMPLERATE_400  5
+#define L3GD20H_SAMPLERATE_800  6
+
+//  Gyro banwidth defines
+
+#define L3GD20H_BANDWIDTH_0     0
+#define L3GD20H_BANDWIDTH_1     1
+#define L3GD20H_BANDWIDTH_2     2
+#define L3GD20H_BANDWIDTH_3     3
+
+//  Gyro FSR defines
+
+#define L3GD20H_FSR_245         0
+#define L3GD20H_FSR_500         1
+#define L3GD20H_FSR_2000        2
+
+//  Gyro high pass filter defines
+
+#define L3GD20H_HPF_0           0
+#define L3GD20H_HPF_1           1
+#define L3GD20H_HPF_2           2
+#define L3GD20H_HPF_3           3
+#define L3GD20H_HPF_4           4
+#define L3GD20H_HPF_5           5
+#define L3GD20H_HPF_6           6
+#define L3GD20H_HPF_7           7
+#define L3GD20H_HPF_8           8
+#define L3GD20H_HPF_9           9
+
+//----------------------------------------------------------
+//
+//  LSM303D
+
+#define LSM303D_ADDRESS0        0x1e
+#define LSM303D_ADDRESS1        0x1d
+#define LSM303D_ID              0x49
+
+//  LSM303D Register Map
+
+#define LSM303D_TEMP_OUT_L      0x05
+#define LSM303D_TEMP_OUT_H      0x06
+#define LSM303D_STATUS_M        0x07
+#define LSM303D_OUT_X_L_M       0x08
+#define LSM303D_OUT_X_H_M       0x09
+#define LSM303D_OUT_Y_L_M       0x0a
+#define LSM303D_OUT_Y_H_M       0x0b
+#define LSM303D_OUT_Z_L_M       0x0c
+#define LSM303D_OUT_Z_H_M       0x0d
+#define LSM303D_WHO_AM_I        0x0f
+#define LSM303D_INT_CTRL_M      0x12
+#define LSM303D_INT_SRC_M       0x13
+#define LSM303D_INT_THS_L_M     0x14
+#define LSM303D_INT_THS_H_M     0x15
+#define LSM303D_OFFSET_X_L_M    0x16
+#define LSM303D_OFFSET_X_H_M    0x17
+#define LSM303D_OFFSET_Y_L_M    0x18
+#define LSM303D_OFFSET_Y_H_M    0x19
+#define LSM303D_OFFSET_Z_L_M    0x1a
+#define LSM303D_OFFSET_Z_H_M    0x1b
+#define LSM303D_REFERENCE_X     0x1c
+#define LSM303D_REFERENCE_Y     0x1d
+#define LSM303D_REFERENCE_Z     0x1e
+#define LSM303D_CTRL0           0x1f
+#define LSM303D_CTRL1           0x20
+#define LSM303D_CTRL2           0x21
+#define LSM303D_CTRL3           0x22
+#define LSM303D_CTRL4           0x23
+#define LSM303D_CTRL5           0x24
+#define LSM303D_CTRL6           0x25
+#define LSM303D_CTRL7           0x26
+#define LSM303D_STATUS_A        0x27
+#define LSM303D_OUT_X_L_A       0x28
+#define LSM303D_OUT_X_H_A       0x29
+#define LSM303D_OUT_Y_L_A       0x2a
+#define LSM303D_OUT_Y_H_A       0x2b
+#define LSM303D_OUT_Z_L_A       0x2c
+#define LSM303D_OUT_Z_H_A       0x2d
+#define LSM303D_FIFO_CTRL       0x2e
+#define LSM303D_FIFO_SRC        0x2f
+#define LSM303D_IG_CFG1         0x30
+#define LSM303D_IG_SRC1         0x31
+#define LSM303D_IG_THS1         0x32
+#define LSM303D_IG_DUR1         0x33
+#define LSM303D_IG_CFG2         0x34
+#define LSM303D_IG_SRC2         0x35
+#define LSM303D_IG_THS2         0x36
+#define LSM303D_IG_DUR2         0x37
+#define LSM303D_CLICK_CFG       0x38
+#define LSM303D_CLICK_SRC       0x39
+#define LSM303D_CLICK_THS       0x3a
+#define LSM303D_TIME_LIMIT      0x3b
+#define LSM303D_TIME_LATENCY    0x3c
+#define LSM303D_TIME_WINDOW     0x3d
+#define LSM303D_ACT_THIS        0x3e
+#define LSM303D_ACT_DUR         0x3f
+
+//  Accel sample rate defines
+
+#define LSM303D_ACCEL_SAMPLERATE_3_125 1
+#define LSM303D_ACCEL_SAMPLERATE_6_25 2
+#define LSM303D_ACCEL_SAMPLERATE_12_5 3
+#define LSM303D_ACCEL_SAMPLERATE_25   4
+#define LSM303D_ACCEL_SAMPLERATE_50   5
+#define LSM303D_ACCEL_SAMPLERATE_100  6
+#define LSM303D_ACCEL_SAMPLERATE_200  7
+#define LSM303D_ACCEL_SAMPLERATE_400  8
+#define LSM303D_ACCEL_SAMPLERATE_800  9
+#define LSM303D_ACCEL_SAMPLERATE_1600 10
+
+//  Accel FSR
+
+#define LSM303D_ACCEL_FSR_2     0
+#define LSM303D_ACCEL_FSR_4     1
+#define LSM303D_ACCEL_FSR_6     2
+#define LSM303D_ACCEL_FSR_8     3
+#define LSM303D_ACCEL_FSR_16    4
+
+//  Accel filter bandwidth
+
+#define LSM303D_ACCEL_LPF_773   0
+#define LSM303D_ACCEL_LPF_194   1
+#define LSM303D_ACCEL_LPF_362   2
+#define LSM303D_ACCEL_LPF_50    3
+
+//  Compass sample rate defines
+
+#define LSM303D_COMPASS_SAMPLERATE_3_125    0
+#define LSM303D_COMPASS_SAMPLERATE_6_25     1
+#define LSM303D_COMPASS_SAMPLERATE_12_5     2
+#define LSM303D_COMPASS_SAMPLERATE_25       3
+#define LSM303D_COMPASS_SAMPLERATE_50       4
+#define LSM303D_COMPASS_SAMPLERATE_100      5
+
+//  Compass FSR
+
+#define LSM303D_COMPASS_FSR_2   0
+#define LSM303D_COMPASS_FSR_4   1
+#define LSM303D_COMPASS_FSR_8   2
+#define LSM303D_COMPASS_FSR_12  3
+
+//----------------------------------------------------------
+//
+//  LSM303DLHC
+
+#define LSM303DLHC_ACCEL_ADDRESS    0x19
+#define LSM303DLHC_COMPASS_ADDRESS  0x1e
+
+//  LSM303DLHC Accel Register Map
+
+#define LSM303DLHC_CTRL1_A         0x20
+#define LSM303DLHC_CTRL2_A         0x21
+#define LSM303DLHC_CTRL3_A         0x22
+#define LSM303DLHC_CTRL4_A         0x23
+#define LSM303DLHC_CTRL5_A         0x24
+#define LSM303DLHC_CTRL6_A         0x25
+#define LSM303DLHC_REF_A           0x26
+#define LSM303DLHC_STATUS_A        0x27
+#define LSM303DLHC_OUT_X_L_A       0x28
+#define LSM303DLHC_OUT_X_H_A       0x29
+#define LSM303DLHC_OUT_Y_L_A       0x2a
+#define LSM303DLHC_OUT_Y_H_A       0x2b
+#define LSM303DLHC_OUT_Z_L_A       0x2c
+#define LSM303DLHC_OUT_Z_H_A       0x2d
+#define LSM303DLHC_FIFO_CTRL_A     0x2e
+#define LSM303DLHC_FIFO_SRC_A      0x2f
+
+//  LSM303DLHC Compass Register Map
+
+#define LSM303DLHC_CRA_M            0x00
+#define LSM303DLHC_CRB_M            0x01
+#define LSM303DLHC_CRM_M            0x02
+#define LSM303DLHC_OUT_X_H_M        0x03
+#define LSM303DLHC_OUT_X_L_M        0x04
+#define LSM303DLHC_OUT_Y_H_M        0x05
+#define LSM303DLHC_OUT_Y_L_M        0x06
+#define LSM303DLHC_OUT_Z_H_M        0x07
+#define LSM303DLHC_OUT_Z_L_M        0x08
+#define LSM303DLHC_STATUS_M         0x09
+#define LSM303DLHC_TEMP_OUT_L_M     0x31
+#define LSM303DLHC_TEMP_OUT_H_M     0x32
+
+//  Accel sample rate defines
+
+#define LSM303DLHC_ACCEL_SAMPLERATE_1       1
+#define LSM303DLHC_ACCEL_SAMPLERATE_10      2
+#define LSM303DLHC_ACCEL_SAMPLERATE_25      3
+#define LSM303DLHC_ACCEL_SAMPLERATE_50      4
+#define LSM303DLHC_ACCEL_SAMPLERATE_100     5
+#define LSM303DLHC_ACCEL_SAMPLERATE_200     6
+#define LSM303DLHC_ACCEL_SAMPLERATE_400     7
+
+//  Accel FSR
+
+#define LSM303DLHC_ACCEL_FSR_2     0
+#define LSM303DLHC_ACCEL_FSR_4     1
+#define LSM303DLHC_ACCEL_FSR_8     2
+#define LSM303DLHC_ACCEL_FSR_16    3
+
+//  Compass sample rate defines
+
+#define LSM303DLHC_COMPASS_SAMPLERATE_0_75      0
+#define LSM303DLHC_COMPASS_SAMPLERATE_1_5       1
+#define LSM303DLHC_COMPASS_SAMPLERATE_3         2
+#define LSM303DLHC_COMPASS_SAMPLERATE_7_5       3
+#define LSM303DLHC_COMPASS_SAMPLERATE_15        4
+#define LSM303DLHC_COMPASS_SAMPLERATE_30        5
+#define LSM303DLHC_COMPASS_SAMPLERATE_75        6
+#define LSM303DLHC_COMPASS_SAMPLERATE_220       7
+
+//  Compass FSR
+
+#define LSM303DLHC_COMPASS_FSR_1_3      1
+#define LSM303DLHC_COMPASS_FSR_1_9      2
+#define LSM303DLHC_COMPASS_FSR_2_5      3
+#define LSM303DLHC_COMPASS_FSR_4        4
+#define LSM303DLHC_COMPASS_FSR_4_7      5
+#define LSM303DLHC_COMPASS_FSR_5_6      6
+#define LSM303DLHC_COMPASS_FSR_8_1      7
+
+//----------------------------------------------------------
+//
+//  LSM9DS0
+
+//  I2C Slave Addresses
+
+#define LSM9DS0_GYRO_ADDRESS0       0x6a
+#define LSM9DS0_GYRO_ADDRESS1       0x6b
+#define LSM9DS0_GYRO_ID             0xd4
+
+#define LSM9DS0_ACCELMAG_ADDRESS0   0x1e
+#define LSM9DS0_ACCELMAG_ADDRESS1   0x1d
+#define LSM9DS0_ACCELMAG_ID         0x49
+
+//  L3GD20 Register map
+
+#define LSM9DS0_GYRO_WHO_AM_I       0x0f
+#define LSM9DS0_GYRO_CTRL1          0x20
+#define LSM9DS0_GYRO_CTRL2          0x21
+#define LSM9DS0_GYRO_CTRL3          0x22
+#define LSM9DS0_GYRO_CTRL4          0x23
+#define LSM9DS0_GYRO_CTRL5          0x24
+#define LSM9DS0_GYRO_OUT_TEMP       0x26
+#define LSM9DS0_GYRO_STATUS         0x27
+#define LSM9DS0_GYRO_OUT_X_L        0x28
+#define LSM9DS0_GYRO_OUT_X_H        0x29
+#define LSM9DS0_GYRO_OUT_Y_L        0x2a
+#define LSM9DS0_GYRO_OUT_Y_H        0x2b
+#define LSM9DS0_GYRO_OUT_Z_L        0x2c
+#define LSM9DS0_GYRO_OUT_Z_H        0x2d
+#define LSM9DS0_GYRO_FIFO_CTRL      0x2e
+#define LSM9DS0_GYRO_FIFO_SRC       0x2f
+#define LSM9DS0_GYRO_IG_CFG         0x30
+#define LSM9DS0_GYRO_IG_SRC         0x31
+#define LSM9DS0_GYRO_IG_THS_XH      0x32
+#define LSM9DS0_GYRO_IG_THS_XL      0x33
+#define LSM9DS0_GYRO_IG_THS_YH      0x34
+#define LSM9DS0_GYRO_IG_THS_YL      0x35
+#define LSM9DS0_GYRO_IG_THS_ZH      0x36
+#define LSM9DS0_GYRO_IG_THS_ZL      0x37
+#define LSM9DS0_GYRO_IG_DURATION    0x38
+
+//  Gyro sample rate defines
+
+#define LSM9DS0_GYRO_SAMPLERATE_95  0
+#define LSM9DS0_GYRO_SAMPLERATE_190 1
+#define LSM9DS0_GYRO_SAMPLERATE_380 2
+#define LSM9DS0_GYRO_SAMPLERATE_760 3
+
+//  Gyro banwidth defines
+
+#define LSM9DS0_GYRO_BANDWIDTH_0    0
+#define LSM9DS0_GYRO_BANDWIDTH_1    1
+#define LSM9DS0_GYRO_BANDWIDTH_2    2
+#define LSM9DS0_GYRO_BANDWIDTH_3    3
+
+//  Gyro FSR defines
+
+#define LSM9DS0_GYRO_FSR_250        0
+#define LSM9DS0_GYRO_FSR_500        1
+#define LSM9DS0_GYRO_FSR_2000       2
+
+//  Gyro high pass filter defines
+
+#define LSM9DS0_GYRO_HPF_0          0
+#define LSM9DS0_GYRO_HPF_1          1
+#define LSM9DS0_GYRO_HPF_2          2
+#define LSM9DS0_GYRO_HPF_3          3
+#define LSM9DS0_GYRO_HPF_4          4
+#define LSM9DS0_GYRO_HPF_5          5
+#define LSM9DS0_GYRO_HPF_6          6
+#define LSM9DS0_GYRO_HPF_7          7
+#define LSM9DS0_GYRO_HPF_8          8
+#define LSM9DS0_GYRO_HPF_9          9
+
+//  Accel/Mag Register Map
+
+#define LSM9DS0_TEMP_OUT_L      0x05
+#define LSM9DS0_TEMP_OUT_H      0x06
+#define LSM9DS0_STATUS_M        0x07
+#define LSM9DS0_OUT_X_L_M       0x08
+#define LSM9DS0_OUT_X_H_M       0x09
+#define LSM9DS0_OUT_Y_L_M       0x0a
+#define LSM9DS0_OUT_Y_H_M       0x0b
+#define LSM9DS0_OUT_Z_L_M       0x0c
+#define LSM9DS0_OUT_Z_H_M       0x0d
+#define LSM9DS0_WHO_AM_I        0x0f
+#define LSM9DS0_INT_CTRL_M      0x12
+#define LSM9DS0_INT_SRC_M       0x13
+#define LSM9DS0_INT_THS_L_M     0x14
+#define LSM9DS0_INT_THS_H_M     0x15
+#define LSM9DS0_OFFSET_X_L_M    0x16
+#define LSM9DS0_OFFSET_X_H_M    0x17
+#define LSM9DS0_OFFSET_Y_L_M    0x18
+#define LSM9DS0_OFFSET_Y_H_M    0x19
+#define LSM9DS0_OFFSET_Z_L_M    0x1a
+#define LSM9DS0_OFFSET_Z_H_M    0x1b
+#define LSM9DS0_REFERENCE_X     0x1c
+#define LSM9DS0_REFERENCE_Y     0x1d
+#define LSM9DS0_REFERENCE_Z     0x1e
+#define LSM9DS0_CTRL0           0x1f
+#define LSM9DS0_CTRL1           0x20
+#define LSM9DS0_CTRL2           0x21
+#define LSM9DS0_CTRL3           0x22
+#define LSM9DS0_CTRL4           0x23
+#define LSM9DS0_CTRL5           0x24
+#define LSM9DS0_CTRL6           0x25
+#define LSM9DS0_CTRL7           0x26
+#define LSM9DS0_STATUS_A        0x27
+#define LSM9DS0_OUT_X_L_A       0x28
+#define LSM9DS0_OUT_X_H_A       0x29
+#define LSM9DS0_OUT_Y_L_A       0x2a
+#define LSM9DS0_OUT_Y_H_A       0x2b
+#define LSM9DS0_OUT_Z_L_A       0x2c
+#define LSM9DS0_OUT_Z_H_A       0x2d
+#define LSM9DS0_FIFO_CTRL       0x2e
+#define LSM9DS0_FIFO_SRC        0x2f
+#define LSM9DS0_IG_CFG1         0x30
+#define LSM9DS0_IG_SRC1         0x31
+#define LSM9DS0_IG_THS1         0x32
+#define LSM9DS0_IG_DUR1         0x33
+#define LSM9DS0_IG_CFG2         0x34
+#define LSM9DS0_IG_SRC2         0x35
+#define LSM9DS0_IG_THS2         0x36
+#define LSM9DS0_IG_DUR2         0x37
+#define LSM9DS0_CLICK_CFG       0x38
+#define LSM9DS0_CLICK_SRC       0x39
+#define LSM9DS0_CLICK_THS       0x3a
+#define LSM9DS0_TIME_LIMIT      0x3b
+#define LSM9DS0_TIME_LATENCY    0x3c
+#define LSM9DS0_TIME_WINDOW     0x3d
+#define LSM9DS0_ACT_THIS        0x3e
+#define LSM9DS0_ACT_DUR         0x3f
+
+//  Accel sample rate defines
+
+#define LSM9DS0_ACCEL_SAMPLERATE_3_125 1
+#define LSM9DS0_ACCEL_SAMPLERATE_6_25 2
+#define LSM9DS0_ACCEL_SAMPLERATE_12_5 3
+#define LSM9DS0_ACCEL_SAMPLERATE_25   4
+#define LSM9DS0_ACCEL_SAMPLERATE_50   5
+#define LSM9DS0_ACCEL_SAMPLERATE_100  6
+#define LSM9DS0_ACCEL_SAMPLERATE_200  7
+#define LSM9DS0_ACCEL_SAMPLERATE_400  8
+#define LSM9DS0_ACCEL_SAMPLERATE_800  9
+#define LSM9DS0_ACCEL_SAMPLERATE_1600 10
+
+//  Accel FSR
+
+#define LSM9DS0_ACCEL_FSR_2     0
+#define LSM9DS0_ACCEL_FSR_4     1
+#define LSM9DS0_ACCEL_FSR_6     2
+#define LSM9DS0_ACCEL_FSR_8     3
+#define LSM9DS0_ACCEL_FSR_16    4
+
+//  Accel filter bandwidth
+
+#define LSM9DS0_ACCEL_LPF_773   0
+#define LSM9DS0_ACCEL_LPF_194   1
+#define LSM9DS0_ACCEL_LPF_362   2
+#define LSM9DS0_ACCEL_LPF_50    3
+
+//  Compass sample rate defines
+
+#define LSM9DS0_COMPASS_SAMPLERATE_3_125    0
+#define LSM9DS0_COMPASS_SAMPLERATE_6_25     1
+#define LSM9DS0_COMPASS_SAMPLERATE_12_5     2
+#define LSM9DS0_COMPASS_SAMPLERATE_25       3
+#define LSM9DS0_COMPASS_SAMPLERATE_50       4
+#define LSM9DS0_COMPASS_SAMPLERATE_100      5
+
+//  Compass FSR
+
+#define LSM9DS0_COMPASS_FSR_2   0
+#define LSM9DS0_COMPASS_FSR_4   1
+#define LSM9DS0_COMPASS_FSR_8   2
+#define LSM9DS0_COMPASS_FSR_12  3
+
+//----------------------------------------------------------
+//
+//  BMX055
+
+//  I2C Slave Addresses
+
+#define BMX055_GYRO_ADDRESS0        0x68
+#define BMX055_GYRO_ADDRESS1        0x69
+#define BMX055_GYRO_ID              0x0f
+
+#define BMX055_ACCEL_ADDRESS0       0x18
+#define BMX055_ACCEL_ADDRESS1       0x19
+#define BMX055_ACCEL_ID             0xfa
+
+#define BMX055_MAG_ADDRESS0         0x10
+#define BMX055_MAG_ADDRESS1         0x11
+#define BMX055_MAG_ADDRESS2         0x12
+#define BMX055_MAG_ADDRESS3         0x13
+
+#define BMX055_MAG_ID               0x32
+
+//  BMX055 Register map
+
+#define BMX055_GYRO_WHO_AM_I        0x00
+#define BMX055_GYRO_X_LSB           0x02
+#define BMX055_GYRO_X_MSB           0x03
+#define BMX055_GYRO_Y_LSB           0x04
+#define BMX055_GYRO_Y_MSB           0x05
+#define BMX055_GYRO_Z_LSB           0x06
+#define BMX055_GYRO_Z_MSB           0x07
+#define BMX055_GYRO_INT_STATUS_0    0x09
+#define BMX055_GYRO_INT_STATUS_1    0x0a
+#define BMX055_GYRO_INT_STATUS_2    0x0b
+#define BMX055_GYRO_INT_STATUS_3    0x0c
+#define BMX055_GYRO_FIFO_STATUS     0x0e
+#define BMX055_GYRO_RANGE           0x0f
+#define BMX055_GYRO_BW              0x10
+#define BMX055_GYRO_LPM1            0x11
+#define BMX055_GYRO_LPM2            0x12
+#define BMX055_GYRO_RATE_HBW        0x13
+#define BMX055_GYRO_SOFT_RESET      0x14
+#define BMX055_GYRO_INT_EN_0        0x15
+#define BMX055_GYRO_1A              0x1a
+#define BMX055_GYRO_1B              0x1b
+#define BMX055_GYRO_SOC             0x31
+#define BMX055_GYRO_FOC             0x32
+#define BMX055_GYRO_FIFO_CONFIG_0   0x3d
+#define BMX055_GYRO_FIFO_CONFIG_1   0x3e
+#define BMX055_GYRO_FIFO_DATA       0x3f
+
+#define BMX055_ACCEL_WHO_AM_I       0x00
+#define BMX055_ACCEL_X_LSB          0x02
+#define BMX055_ACCEL_X_MSB          0x03
+#define BMX055_ACCEL_Y_LSB          0x04
+#define BMX055_ACCEL_Y_MSB          0x05
+#define BMX055_ACCEL_Z_LSB          0x06
+#define BMX055_ACCEL_Z_MSB          0x07
+#define BMX055_ACCEL_TEMP           0x08
+#define BMX055_ACCEL_INT_STATUS_0   0x09
+#define BMX055_ACCEL_INT_STATUS_1   0x0a
+#define BMX055_ACCEL_INT_STATUS_2   0x0b
+#define BMX055_ACCEL_INT_STATUS_3   0x0c
+#define BMX055_ACCEL_FIFO_STATUS    0x0e
+#define BMX055_ACCEL_PMU_RANGE      0x0f
+#define BMX055_ACCEL_PMU_BW         0x10
+#define BMX055_ACCEL_PMU_LPW        0x11
+#define BMX055_ACCEL_PMU_LOW_POWER  0x12
+#define BMX055_ACCEL_HBW            0x13
+#define BMX055_ACCEL_SOFT_RESET     0x14
+#define BMX055_ACCEL_FIFO_CONFIG_0  0x30
+#define BMX055_ACCEL_OFC_CTRL       0x36
+#define BMX055_ACCEL_OFC_SETTING    0x37
+#define BMX055_ACCEL_FIFO_CONFIG_1  0x3e
+#define BMX055_ACCEL_FIFO_DATA      0x3f
+
+#define BMX055_MAG_WHO_AM_I         0x40
+#define BMX055_MAG_X_LSB            0x42
+#define BMX055_MAG_X_MSB            0x43
+#define BMX055_MAG_Y_LSB            0x44
+#define BMX055_MAG_Y_MSB            0x45
+#define BMX055_MAG_Z_LSB            0x46
+#define BMX055_MAG_Z_MSB            0x47
+#define BMX055_MAG_RHALL_LSB        0x48
+#define BMX055_MAG_RHALL_MSB        0x49
+#define BMX055_MAG_INT_STAT         0x4a
+#define BMX055_MAG_POWER            0x4b
+#define BMX055_MAG_MODE             0x4c
+#define BMX055_MAG_INT_ENABLE       0x4d
+#define BMX055_MAG_AXIS_ENABLE      0x4e
+#define BMX055_MAG_REPXY            0x51
+#define BMX055_MAG_REPZ             0x52
+
+#define BMX055_MAG_DIG_X1               0x5D
+#define BMX055_MAG_DIG_Y1               0x5E
+#define BMX055_MAG_DIG_Z4_LSB           0x62
+#define BMX055_MAG_DIG_Z4_MSB           0x63
+#define BMX055_MAG_DIG_X2               0x64
+#define BMX055_MAG_DIG_Y2               0x65
+#define BMX055_MAG_DIG_Z2_LSB           0x68
+#define BMX055_MAG_DIG_Z2_MSB           0x69
+#define BMX055_MAG_DIG_Z1_LSB           0x6A
+#define BMX055_MAG_DIG_Z1_MSB           0x6B
+#define BMX055_MAG_DIG_XYZ1_LSB         0x6C
+#define BMX055_MAG_DIG_XYZ1_MSB         0x6D
+#define BMX055_MAG_DIG_Z3_LSB           0x6E
+#define BMX055_MAG_DIG_Z3_MSB           0x6F
+#define BMX055_MAG_DIG_XY2              0x70
+#define BMX055_MAG_DIG_XY1              0x71
+
+//  Gyro sample rate defines
+
+#define BMX055_GYRO_SAMPLERATE_100_32  0x07
+#define BMX055_GYRO_SAMPLERATE_200_64  0x06
+#define BMX055_GYRO_SAMPLERATE_100_12  0x05
+#define BMX055_GYRO_SAMPLERATE_200_23  0x04
+#define BMX055_GYRO_SAMPLERATE_400_47  0x03
+#define BMX055_GYRO_SAMPLERATE_1000_116  0x02
+#define BMX055_GYRO_SAMPLERATE_2000_230  0x01
+#define BMX055_GYRO_SAMPLERATE_2000_523  0x00
+
+//  Gyro FSR defines
+
+#define BMX055_GYRO_FSR_2000        0x00
+#define BMX055_GYRO_FSR_1000        0x01
+#define BMX055_GYRO_FSR_500         0x02
+#define BMX055_GYRO_FSR_250         0x03
+#define BMX055_GYRO_FSR_125         0x04
+
+//  Accel sample rate defines
+
+#define BMX055_ACCEL_SAMPLERATE_15  0X00
+#define BMX055_ACCEL_SAMPLERATE_31  0X01
+#define BMX055_ACCEL_SAMPLERATE_62  0X02
+#define BMX055_ACCEL_SAMPLERATE_125  0X03
+#define BMX055_ACCEL_SAMPLERATE_250  0X04
+#define BMX055_ACCEL_SAMPLERATE_500  0X05
+#define BMX055_ACCEL_SAMPLERATE_1000  0X06
+#define BMX055_ACCEL_SAMPLERATE_2000  0X07
+
+//  Accel FSR defines
+
+#define BMX055_ACCEL_FSR_2          0x00
+#define BMX055_ACCEL_FSR_4          0x01
+#define BMX055_ACCEL_FSR_8          0x02
+#define BMX055_ACCEL_FSR_16         0x03
+
+
+//  Mag preset defines
+
+#define BMX055_MAG_LOW_POWER        0x00
+#define BMX055_MAG_REGULAR          0x01
+#define BMX055_MAG_ENHANCED         0x02
+#define BMX055_MAG_HIGH_ACCURACY    0x03
+
+//----------------------------------------------------------
+//
+//  BNO055
+
+//  I2C Slave Addresses
+
+#define BNO055_ADDRESS0             0x28
+#define BNO055_ADDRESS1             0x29
+#define BNO055_ID                   0xa0
+
+//  Register map
+
+#define BNO055_WHO_AM_I             0x00
+#define BNO055_PAGE_ID              0x07
+#define BNO055_ACCEL_DATA           0x08
+#define BNO055_MAG_DATA             0x0e
+#define BNO055_GYRO_DATA            0x14
+#define BNO055_FUSED_EULER          0x1a
+#define BNO055_FUSED_QUAT           0x20
+#define BNO055_UNIT_SEL             0x3b
+#define BNO055_OPER_MODE            0x3d
+#define BNO055_PWR_MODE             0x3e
+#define BNO055_SYS_TRIGGER          0x3f
+#define BNO055_AXIS_MAP_CONFIG      0x41
+#define BNO055_AXIS_MAP_SIGN        0x42
+
+//  Operation modes
+
+#define BNO055_OPER_MODE_CONFIG     0x00
+#define BNO055_OPER_MODE_NDOF       0x0c
+
+//  Power modes
+
+#define BNO055_PWR_MODE_NORMAL      0x00
+
+#endif // _RTIMUDEFS_H
diff --git a/libraries/RTIMULib/utility/RTIMUGD20HM303D.cpp b/libraries/RTIMULib/utility/RTIMUGD20HM303D.cpp
new file mode 100644
index 0000000..14f02c1
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUGD20HM303D.cpp
@@ -0,0 +1,563 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTIMUGD20HM303D.h"
+#include "RTIMUSettings.h"
+
+//  this sets the learning rate for compass running average calculation
+
+#define COMPASS_ALPHA 0.2f
+
+RTIMUGD20HM303D::RTIMUGD20HM303D(RTIMUSettings *settings) : RTIMU(settings)
+{
+    m_sampleRate = 100;
+}
+
+RTIMUGD20HM303D::~RTIMUGD20HM303D()
+{
+}
+
+bool RTIMUGD20HM303D::IMUInit()
+{
+    unsigned char result;
+
+#ifdef GD20HM303D_CACHE_MODE
+    m_firstTime = true;
+    m_cacheIn = m_cacheOut = m_cacheCount = 0;
+#endif
+    // set validity flags
+
+    m_imuData.fusionPoseValid = false;
+    m_imuData.fusionQPoseValid = false;
+    m_imuData.gyroValid = true;
+    m_imuData.accelValid = true;
+    m_imuData.compassValid = true;
+    m_imuData.pressureValid = false;
+    m_imuData.temperatureValid = false;
+    m_imuData.humidityValid = false;
+
+    //  configure IMU
+
+    m_gyroSlaveAddr = m_settings->m_I2CSlaveAddress;
+
+    // work out accel/mag address
+
+    if (m_settings->HALRead(LSM303D_ADDRESS0, LSM303D_WHO_AM_I, 1, &result, "")) {
+        if (result == LSM303D_ID) {
+            m_accelCompassSlaveAddr = LSM303D_ADDRESS0;
+        }
+    } else {
+        m_accelCompassSlaveAddr = LSM303D_ADDRESS1;
+    }
+
+    setCalibrationData();
+
+    //  enable the I2C bus
+
+    if (!m_settings->HALOpen())
+        return false;
+
+    //  Set up the gyro
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_LOW_ODR, 0x04, "Failed to reset L3GD20H"))
+        return false;
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_CTRL5, 0x80, "Failed to boot L3GD20H"))
+        return false;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, L3GD20H_WHO_AM_I, 1, &result, "Failed to read L3GD20H id"))
+        return false;
+
+    if (result != L3GD20H_ID) {
+        HAL_ERROR1("Incorrect L3GD20H id %d\n", result);
+        return false;
+    }
+
+    if (!setGyroSampleRate())
+            return false;
+
+    if (!setGyroCTRL2())
+            return false;
+
+    if (!setGyroCTRL4())
+            return false;
+
+    //  Set up the accel/compass
+
+    if (!m_settings->HALRead(m_accelCompassSlaveAddr, LSM303D_WHO_AM_I, 1, &result, "Failed to read LSM303D id"))
+        return false;
+
+    if (result != LSM303D_ID) {
+        HAL_ERROR1("Incorrect LSM303D id %d\n", result);
+        return false;
+    }
+
+    if (!setAccelCTRL1())
+        return false;
+
+    if (!setAccelCTRL2())
+        return false;
+
+    if (!setCompassCTRL5())
+        return false;
+
+    if (!setCompassCTRL6())
+        return false;
+
+    if (!setCompassCTRL7())
+        return false;
+
+#ifdef GD20HM303D_CACHE_MODE
+
+    //  turn on gyro fifo
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_FIFO_CTRL, 0x3f, "Failed to set L3GD20H FIFO mode"))
+        return false;
+#endif
+
+    if (!setGyroCTRL5())
+            return false;
+
+    gyroBiasInit();
+
+    HAL_INFO("GD20HM303D init complete\n");
+    return true;
+}
+
+bool RTIMUGD20HM303D::setGyroSampleRate()
+{
+    unsigned char ctrl1;
+    unsigned char lowOdr = 0;
+
+    switch (m_settings->m_GD20HM303DGyroSampleRate) {
+    case L3GD20H_SAMPLERATE_12_5:
+        ctrl1 = 0x0f;
+        lowOdr = 1;
+        m_sampleRate = 13;
+        break;
+
+    case L3GD20H_SAMPLERATE_25:
+        ctrl1 = 0x4f;
+        lowOdr = 1;
+        m_sampleRate = 25;
+        break;
+
+    case L3GD20H_SAMPLERATE_50:
+        ctrl1 = 0x8f;
+        lowOdr = 1;
+        m_sampleRate = 50;
+        break;
+
+    case L3GD20H_SAMPLERATE_100:
+        ctrl1 = 0x0f;
+        m_sampleRate = 100;
+        break;
+
+    case L3GD20H_SAMPLERATE_200:
+        ctrl1 = 0x4f;
+        m_sampleRate = 200;
+        break;
+
+    case L3GD20H_SAMPLERATE_400:
+        ctrl1 = 0x8f;
+        m_sampleRate = 400;
+        break;
+
+    case L3GD20H_SAMPLERATE_800:
+        ctrl1 = 0xcf;
+        m_sampleRate = 800;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal L3GD20H sample rate code %d\n", m_settings->m_GD20HM303DGyroSampleRate);
+        return false;
+    }
+
+    m_sampleInterval = (uint64_t)1000000 / m_sampleRate;
+
+    switch (m_settings->m_GD20HM303DGyroBW) {
+    case L3GD20H_BANDWIDTH_0:
+        ctrl1 |= 0x00;
+        break;
+
+    case L3GD20H_BANDWIDTH_1:
+        ctrl1 |= 0x10;
+        break;
+
+    case L3GD20H_BANDWIDTH_2:
+        ctrl1 |= 0x20;
+        break;
+
+    case L3GD20H_BANDWIDTH_3:
+        ctrl1 |= 0x30;
+        break;
+
+    }
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_LOW_ODR, lowOdr, "Failed to set L3GD20H LOW_ODR"))
+        return false;
+
+    return (m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_CTRL1, ctrl1, "Failed to set L3GD20H CTRL1"));
+}
+
+bool RTIMUGD20HM303D::setGyroCTRL2()
+{
+    if ((m_settings->m_GD20HM303DGyroHpf < L3GD20H_HPF_0) || (m_settings->m_GD20HM303DGyroHpf > L3GD20H_HPF_9)) {
+        HAL_ERROR1("Illegal L3GD20H high pass filter code %d\n", m_settings->m_GD20HM303DGyroHpf);
+        return false;
+    }
+    return m_settings->HALWrite(m_gyroSlaveAddr,  L3GD20H_CTRL2, m_settings->m_GD20HM303DGyroHpf, "Failed to set L3GD20H CTRL2");
+}
+
+bool RTIMUGD20HM303D::setGyroCTRL4()
+{
+    unsigned char ctrl4;
+
+    switch (m_settings->m_GD20HM303DGyroFsr) {
+    case L3GD20H_FSR_245:
+        ctrl4 = 0x00;
+        m_gyroScale = (RTFLOAT)0.00875 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    case L3GD20H_FSR_500:
+        ctrl4 = 0x10;
+        m_gyroScale = (RTFLOAT)0.0175 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    case L3GD20H_FSR_2000:
+        ctrl4 = 0x20;
+        m_gyroScale = (RTFLOAT)0.07 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal L3GD20H FSR code %d\n", m_settings->m_GD20HM303DGyroFsr);
+        return false;
+    }
+
+    return m_settings->HALWrite(m_gyroSlaveAddr,  L3GD20H_CTRL4, ctrl4, "Failed to set L3GD20H CTRL4");
+}
+
+
+bool RTIMUGD20HM303D::setGyroCTRL5()
+{
+    unsigned char ctrl5;
+
+    //  Turn on hpf
+
+    ctrl5 = 0x10;
+
+#ifdef GD20HM303D_CACHE_MODE
+    //  turn on fifo
+
+    ctrl5 |= 0x40;
+#endif
+
+    return m_settings->HALWrite(m_gyroSlaveAddr,  L3GD20H_CTRL5, ctrl5, "Failed to set L3GD20H CTRL5");
+}
+
+
+bool RTIMUGD20HM303D::setAccelCTRL1()
+{
+    unsigned char ctrl1;
+
+    if ((m_settings->m_GD20HM303DAccelSampleRate < 0) || (m_settings->m_GD20HM303DAccelSampleRate > 10)) {
+        HAL_ERROR1("Illegal LSM303D accel sample rate code %d\n", m_settings->m_GD20HM303DAccelSampleRate);
+        return false;
+    }
+
+    ctrl1 = (m_settings->m_GD20HM303DAccelSampleRate << 4) | 0x07;
+
+    return m_settings->HALWrite(m_accelCompassSlaveAddr,  LSM303D_CTRL1, ctrl1, "Failed to set LSM303D CTRL1");
+}
+
+bool RTIMUGD20HM303D::setAccelCTRL2()
+{
+    unsigned char ctrl2;
+
+    if ((m_settings->m_GD20HM303DAccelLpf < 0) || (m_settings->m_GD20HM303DAccelLpf > 3)) {
+        HAL_ERROR1("Illegal LSM303D accel low pass fiter code %d\n", m_settings->m_GD20HM303DAccelLpf);
+        return false;
+    }
+
+    switch (m_settings->m_GD20HM303DAccelFsr) {
+    case LSM303D_ACCEL_FSR_2:
+        m_accelScale = (RTFLOAT)0.000061;
+        break;
+
+    case LSM303D_ACCEL_FSR_4:
+        m_accelScale = (RTFLOAT)0.000122;
+        break;
+
+    case LSM303D_ACCEL_FSR_6:
+        m_accelScale = (RTFLOAT)0.000183;
+        break;
+
+    case LSM303D_ACCEL_FSR_8:
+        m_accelScale = (RTFLOAT)0.000244;
+        break;
+
+    case LSM303D_ACCEL_FSR_16:
+        m_accelScale = (RTFLOAT)0.000732;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal LSM303D accel FSR code %d\n", m_settings->m_GD20HM303DAccelFsr);
+        return false;
+    }
+
+    ctrl2 = (m_settings->m_GD20HM303DAccelLpf << 6) | (m_settings->m_GD20HM303DAccelFsr << 3);
+
+    return m_settings->HALWrite(m_accelCompassSlaveAddr,  LSM303D_CTRL2, ctrl2, "Failed to set LSM303D CTRL2");
+}
+
+
+bool RTIMUGD20HM303D::setCompassCTRL5()
+{
+    unsigned char ctrl5;
+
+    if ((m_settings->m_GD20HM303DCompassSampleRate < 0) || (m_settings->m_GD20HM303DCompassSampleRate > 5)) {
+        HAL_ERROR1("Illegal LSM303D compass sample rate code %d\n", m_settings->m_GD20HM303DCompassSampleRate);
+        return false;
+    }
+
+    ctrl5 = (m_settings->m_GD20HM303DCompassSampleRate << 2);
+
+#ifdef GD20HM303D_CACHE_MODE
+    //  enable fifo
+
+    ctrl5 |= 0x40;
+#endif
+
+    return m_settings->HALWrite(m_accelCompassSlaveAddr,  LSM303D_CTRL5, ctrl5, "Failed to set LSM303D CTRL5");
+}
+
+bool RTIMUGD20HM303D::setCompassCTRL6()
+{
+    unsigned char ctrl6;
+
+    //  convert FSR to uT
+
+    switch (m_settings->m_GD20HM303DCompassFsr) {
+    case LSM303D_COMPASS_FSR_2:
+        ctrl6 = 0;
+        m_compassScale = (RTFLOAT)0.008;
+        break;
+
+    case LSM303D_COMPASS_FSR_4:
+        ctrl6 = 0x20;
+        m_compassScale = (RTFLOAT)0.016;
+        break;
+
+    case LSM303D_COMPASS_FSR_8:
+        ctrl6 = 0x40;
+        m_compassScale = (RTFLOAT)0.032;
+        break;
+
+    case LSM303D_COMPASS_FSR_12:
+        ctrl6 = 0x60;
+        m_compassScale = (RTFLOAT)0.0479;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal LSM303D compass FSR code %d\n", m_settings->m_GD20HM303DCompassFsr);
+        return false;
+    }
+
+    return m_settings->HALWrite(m_accelCompassSlaveAddr,  LSM303D_CTRL6, ctrl6, "Failed to set LSM303D CTRL6");
+}
+
+bool RTIMUGD20HM303D::setCompassCTRL7()
+{
+     return m_settings->HALWrite(m_accelCompassSlaveAddr,  LSM303D_CTRL7, 0x60, "Failed to set LSM303D CTRL7");
+}
+
+
+int RTIMUGD20HM303D::IMUGetPollInterval()
+{
+    return (400 / m_sampleRate);
+}
+
+bool RTIMUGD20HM303D::IMURead()
+{
+    unsigned char status;
+    unsigned char gyroData[6];
+    unsigned char accelData[6];
+    unsigned char compassData[6];
+
+
+#ifdef GD20HM303D_CACHE_MODE
+    int count;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, L3GD20H_FIFO_SRC, 1, &status, "Failed to read L3GD20H fifo status"))
+        return false;
+
+    if ((status & 0x40) != 0) {
+        HAL_INFO("L3GD20H fifo overrun\n");
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_CTRL5, 0x10, "Failed to set L3GD20H CTRL5"))
+            return false;
+
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_FIFO_CTRL, 0x0, "Failed to set L3GD20H FIFO mode"))
+            return false;
+
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_FIFO_CTRL, 0x3f, "Failed to set L3GD20H FIFO mode"))
+            return false;
+
+        if (!setGyroCTRL5())
+            return false;
+
+        m_imuData.timestamp += m_sampleInterval * 32;
+        return false;
+    }
+
+    // get count of samples in fifo
+    count = status & 0x1f;
+
+    if ((m_cacheCount == 0) && (count > 0) && (count < GD20HM303D_FIFO_THRESH)) {
+        // special case of a small fifo and nothing cached - just handle as simple read
+
+        if (!m_settings->HALRead(m_gyroSlaveAddr, 0x80 | L3GD20H_OUT_X_L, 6, gyroData, "Failed to read L3GD20H data"))
+            return false;
+
+        if (!m_settings->HALRead(m_accelCompassSlaveAddr, 0x80 | LSM303D_OUT_X_L_A, 6, accelData, "Failed to read LSM303D accel data"))
+            return false;
+
+        if (!m_settings->HALRead(m_accelCompassSlaveAddr, 0x80 | LSM303D_OUT_X_L_M, 6, compassData, "Failed to read LSM303D compass data"))
+            return false;
+
+        if (m_firstTime)
+            m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+        else
+            m_imuData.timestamp += m_sampleInterval;
+
+        m_firstTime = false;
+    } else {
+        if (count >=  GD20HM303D_FIFO_THRESH) {
+            // need to create a cache block
+
+            if (m_cacheCount == GD20HM303D_CACHE_BLOCK_COUNT) {
+                // all cache blocks are full - discard oldest and update timestamp to account for lost samples
+                m_imuData.timestamp += m_sampleInterval * m_cache[m_cacheOut].count;
+                if (++m_cacheOut == GD20HM303D_CACHE_BLOCK_COUNT)
+                    m_cacheOut = 0;
+                m_cacheCount--;
+            }
+
+            if (!m_settings->HALRead(m_gyroSlaveAddr, 0x80 | L3GD20H_OUT_X_L, GD20HM303D_FIFO_CHUNK_SIZE * GD20HM303D_FIFO_THRESH,
+                         m_cache[m_cacheIn].data, "Failed to read L3GD20H fifo data"))
+                return false;
+
+            if (!m_settings->HALRead(m_accelCompassSlaveAddr, 0x80 | LSM303D_OUT_X_L_A, 6,
+                         m_cache[m_cacheIn].accel, "Failed to read LSM303D accel data"))
+                return false;
+
+            if (!m_settings->HALRead(m_accelCompassSlaveAddr, 0x80 | LSM303D_OUT_X_L_M, 6,
+                         m_cache[m_cacheIn].compass, "Failed to read LSM303D compass data"))
+                return false;
+
+            m_cache[m_cacheIn].count = GD20HM303D_FIFO_THRESH;
+            m_cache[m_cacheIn].index = 0;
+
+            m_cacheCount++;
+            if (++m_cacheIn == GD20HM303D_CACHE_BLOCK_COUNT)
+                m_cacheIn = 0;
+
+        }
+
+        //  now fifo has been read if necessary, get something to process
+
+        if (m_cacheCount == 0)
+            return false;
+
+        memcpy(gyroData, m_cache[m_cacheOut].data + m_cache[m_cacheOut].index, GD20HM303D_FIFO_CHUNK_SIZE);
+        memcpy(accelData, m_cache[m_cacheOut].accel, 6);
+        memcpy(compassData, m_cache[m_cacheOut].compass, 6);
+
+        m_cache[m_cacheOut].index += GD20HM303D_FIFO_CHUNK_SIZE;
+
+        if (--m_cache[m_cacheOut].count == 0) {
+            //  this cache block is now empty
+
+            if (++m_cacheOut == GD20HM303D_CACHE_BLOCK_COUNT)
+                m_cacheOut = 0;
+            m_cacheCount--;
+        }
+        if (m_firstTime)
+            m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+        else
+            m_imuData.timestamp += m_sampleInterval;
+
+        m_firstTime = false;
+    }
+
+#else
+    if (!m_settings->HALRead(m_gyroSlaveAddr, L3GD20H_STATUS, 1, &status, "Failed to read L3GD20H status"))
+        return false;
+
+    if ((status & 0x8) == 0)
+        return false;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, 0x80 | L3GD20H_OUT_X_L, 6, gyroData, "Failed to read L3GD20H data"))
+        return false;
+
+    m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+
+    if (!m_settings->HALRead(m_accelCompassSlaveAddr, 0x80 | LSM303D_OUT_X_L_A, 6, accelData, "Failed to read LSM303D accel data"))
+        return false;
+
+    if (!m_settings->HALRead(m_accelCompassSlaveAddr, 0x80 | LSM303D_OUT_X_L_M, 6, compassData, "Failed to read LSM303D compass data"))
+        return false;
+
+#endif
+
+    RTMath::convertToVector(gyroData, m_imuData.gyro, m_gyroScale, false);
+    RTMath::convertToVector(accelData, m_imuData.accel, m_accelScale, false);
+    RTMath::convertToVector(compassData, m_imuData.compass, m_compassScale, false);
+
+    //  sort out gyro axes
+
+    m_imuData.gyro.setX(m_imuData.gyro.x());
+    m_imuData.gyro.setY(-m_imuData.gyro.y());
+    m_imuData.gyro.setZ(-m_imuData.gyro.z());
+
+    //  sort out accel data;
+
+    m_imuData.accel.setX(-m_imuData.accel.x());
+
+    //  sort out compass axes
+
+    m_imuData.compass.setY(-m_imuData.compass.y());
+    m_imuData.compass.setZ(-m_imuData.compass.z());
+
+    //  now do standard processing
+
+    handleGyroBias();
+    calibrateAverageCompass();
+    calibrateAccel();
+
+    //  now update the filter
+
+    updateFusion();
+
+    return true;
+}
diff --git a/libraries/RTIMULib/utility/RTIMUGD20HM303D.h b/libraries/RTIMULib/utility/RTIMUGD20HM303D.h
new file mode 100644
index 0000000..bd7de2f
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUGD20HM303D.h
@@ -0,0 +1,95 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTIMUGD20HM303D_H
+#define	_RTIMUGD20HM303D_H
+
+#include "RTIMU.h"
+
+//  Define this symbol to use cache mode
+
+//#define GD20HM303D_CACHE_MODE   // not reliable at the moment
+
+#ifdef GD20HM303D_CACHE_MODE
+
+//  Cache defs
+
+#define GD20HM303D_FIFO_CHUNK_SIZE    6                       // 6 bytes of gyro data
+#define GD20HM303D_FIFO_THRESH        16                      // threshold point in fifo
+#define GD20HM303D_CACHE_BLOCK_COUNT  16                      // number of cache blocks
+
+typedef struct
+{
+    unsigned char data[GD20HM303D_FIFO_THRESH * GD20HM303D_FIFO_CHUNK_SIZE];
+    int count;                                              // number of chunks in the cache block
+    int index;                                              // current index into the cache
+    unsigned char accel[6];                                 // the raw accel readings for the block
+    unsigned char compass[6];                               // the raw compass readings for the block
+
+} GD20HM303D_CACHE_BLOCK;
+
+#endif
+
+class RTIMUGD20HM303D : public RTIMU
+{
+public:
+    RTIMUGD20HM303D(RTIMUSettings *settings);
+    ~RTIMUGD20HM303D();
+
+    virtual const char *IMUName() { return "L3GD20H + LSM303D"; }
+    virtual int IMUType() { return RTIMU_TYPE_GD20HM303D; }
+    virtual bool IMUInit();
+    virtual int IMUGetPollInterval();
+    virtual bool IMURead();
+
+private:
+    bool setGyroSampleRate();
+    bool setGyroCTRL2();
+    bool setGyroCTRL4();
+    bool setGyroCTRL5();
+    bool setAccelCTRL1();
+    bool setAccelCTRL2();
+    bool setCompassCTRL5();
+    bool setCompassCTRL6();
+    bool setCompassCTRL7();
+
+    unsigned char m_gyroSlaveAddr;                          // I2C address of L3GD20H
+    unsigned char m_accelCompassSlaveAddr;                  // I2C address of LSM303D
+
+    RTFLOAT m_gyroScale;
+    RTFLOAT m_accelScale;
+    RTFLOAT m_compassScale;
+
+#ifdef GD20HM303D_CACHE_MODE
+    bool m_firstTime;                                       // if first sample
+
+    GD20HM303D_CACHE_BLOCK m_cache[GD20HM303D_CACHE_BLOCK_COUNT]; // the cache itself
+    int m_cacheIn;                                          // the in index
+    int m_cacheOut;                                         // the out index
+    int m_cacheCount;                                       // number of used cache blocks
+
+#endif
+};
+
+#endif // _RTIMUGD20HM303D_H
diff --git a/libraries/RTIMULib/utility/RTIMUGD20HM303DLHC.cpp b/libraries/RTIMULib/utility/RTIMUGD20HM303DLHC.cpp
new file mode 100644
index 0000000..c4f6ab4
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUGD20HM303DLHC.cpp
@@ -0,0 +1,562 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTIMUGD20HM303DLHC.h"
+#include "RTIMUSettings.h"
+
+//  this sets the learning rate for compass running average calculation
+
+#define COMPASS_ALPHA 0.2f
+
+RTIMUGD20HM303DLHC::RTIMUGD20HM303DLHC(RTIMUSettings *settings) : RTIMU(settings)
+{
+    m_sampleRate = 100;
+}
+
+RTIMUGD20HM303DLHC::~RTIMUGD20HM303DLHC()
+{
+}
+
+bool RTIMUGD20HM303DLHC::IMUInit()
+{
+    unsigned char result;
+
+#ifdef GD20HM303DLHC_CACHE_MODE
+    m_firstTime = true;
+    m_cacheIn = m_cacheOut = m_cacheCount = 0;
+#endif
+    // set validity flags
+
+    m_imuData.fusionPoseValid = false;
+    m_imuData.fusionQPoseValid = false;
+    m_imuData.gyroValid = true;
+    m_imuData.accelValid = true;
+    m_imuData.compassValid = true;
+    m_imuData.pressureValid = false;
+    m_imuData.temperatureValid = false;
+    m_imuData.humidityValid = false;
+
+    //  configure IMU
+
+    m_gyroSlaveAddr = m_settings->m_I2CSlaveAddress;
+    m_accelSlaveAddr = LSM303DLHC_ACCEL_ADDRESS;
+    m_compassSlaveAddr = LSM303DLHC_COMPASS_ADDRESS;
+
+    setCalibrationData();
+
+    //  enable the I2C bus
+
+    if (!m_settings->HALOpen())
+        return false;
+
+    //  Set up the gyro
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_LOW_ODR, 0x04, "Failed to reset L3GD20H"))
+        return false;
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_CTRL5, 0x80, "Failed to boot L3GD20H"))
+        return false;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, L3GD20H_WHO_AM_I, 1, &result, "Failed to read L3GD20H id"))
+        return false;
+
+    if (result != L3GD20H_ID) {
+        HAL_ERROR1("Incorrect L3GD20H id %d\n", result);
+        return false;
+    }
+
+    if (!setGyroSampleRate())
+            return false;
+
+    if (!setGyroCTRL2())
+            return false;
+
+    if (!setGyroCTRL4())
+            return false;
+
+    //  Set up the accel
+
+    if (!setAccelCTRL1())
+        return false;
+
+    if (!setAccelCTRL4())
+        return false;
+
+    //  Set up the compass
+
+    if (!setCompassCRA())
+        return false;
+
+    if (!setCompassCRB())
+        return false;
+
+    if (!setCompassCRM())
+        return false;
+
+#ifdef GD20HM303DLHC_CACHE_MODE
+
+    //  turn on gyro fifo
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20_FIFO_CTRL, 0x3f, "Failed to set L3GD20 FIFO mode"))
+        return false;
+#endif
+
+    if (!setGyroCTRL5())
+            return false;
+
+    gyroBiasInit();
+
+    HAL_INFO("GD20HM303DLHC init complete\n");
+    return true;
+}
+
+bool RTIMUGD20HM303DLHC::setGyroSampleRate()
+{
+    unsigned char ctrl1;
+    unsigned char lowOdr = 0;
+
+    switch (m_settings->m_GD20HM303DLHCGyroSampleRate) {
+    case L3GD20H_SAMPLERATE_12_5:
+        ctrl1 = 0x0f;
+        lowOdr = 1;
+        m_sampleRate = 13;
+        break;
+
+    case L3GD20H_SAMPLERATE_25:
+        ctrl1 = 0x4f;
+        lowOdr = 1;
+        m_sampleRate = 25;
+        break;
+
+    case L3GD20H_SAMPLERATE_50:
+        ctrl1 = 0x8f;
+        lowOdr = 1;
+        m_sampleRate = 50;
+        break;
+
+    case L3GD20H_SAMPLERATE_100:
+        ctrl1 = 0x0f;
+        m_sampleRate = 100;
+        break;
+
+    case L3GD20H_SAMPLERATE_200:
+        ctrl1 = 0x4f;
+        m_sampleRate = 200;
+        break;
+
+    case L3GD20H_SAMPLERATE_400:
+        ctrl1 = 0x8f;
+        m_sampleRate = 400;
+        break;
+
+    case L3GD20H_SAMPLERATE_800:
+        ctrl1 = 0xcf;
+        m_sampleRate = 800;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal L3GD20H sample rate code %d\n", m_settings->m_GD20HM303DLHCGyroSampleRate);
+        return false;
+    }
+
+    m_sampleInterval = (uint64_t)1000000 / m_sampleRate;
+
+    switch (m_settings->m_GD20HM303DLHCGyroBW) {
+    case L3GD20H_BANDWIDTH_0:
+        ctrl1 |= 0x00;
+        break;
+
+    case L3GD20H_BANDWIDTH_1:
+        ctrl1 |= 0x10;
+        break;
+
+    case L3GD20H_BANDWIDTH_2:
+        ctrl1 |= 0x20;
+        break;
+
+    case L3GD20H_BANDWIDTH_3:
+        ctrl1 |= 0x30;
+        break;
+
+    }
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_LOW_ODR, lowOdr, "Failed to set L3GD20H LOW_ODR"))
+        return false;
+
+    return (m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_CTRL1, ctrl1, "Failed to set L3GD20H CTRL1"));
+}
+
+bool RTIMUGD20HM303DLHC::setGyroCTRL2()
+{
+    if ((m_settings->m_GD20HM303DLHCGyroHpf < L3GD20H_HPF_0) || (m_settings->m_GD20HM303DLHCGyroHpf > L3GD20H_HPF_9)) {
+        HAL_ERROR1("Illegal L3GD20H high pass filter code %d\n", m_settings->m_GD20HM303DLHCGyroHpf);
+        return false;
+    }
+    return m_settings->HALWrite(m_gyroSlaveAddr,  L3GD20H_CTRL2, m_settings->m_GD20HM303DLHCGyroHpf, "Failed to set L3GD20H CTRL2");
+}
+
+bool RTIMUGD20HM303DLHC::setGyroCTRL4()
+{
+    unsigned char ctrl4;
+
+    switch (m_settings->m_GD20HM303DLHCGyroFsr) {
+    case L3GD20H_FSR_245:
+        ctrl4 = 0x00;
+        m_gyroScale = (RTFLOAT)0.00875 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    case L3GD20H_FSR_500:
+        ctrl4 = 0x10;
+        m_gyroScale = (RTFLOAT)0.0175 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    case L3GD20H_FSR_2000:
+        ctrl4 = 0x20;
+        m_gyroScale = (RTFLOAT)0.07 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal L3GD20H FSR code %d\n", m_settings->m_GD20HM303DLHCGyroFsr);
+        return false;
+    }
+
+    return m_settings->HALWrite(m_gyroSlaveAddr,  L3GD20H_CTRL4, ctrl4, "Failed to set L3GD20H CTRL4");
+}
+
+
+bool RTIMUGD20HM303DLHC::setGyroCTRL5()
+{
+    unsigned char ctrl5;
+
+    //  Turn on hpf
+
+    ctrl5 = 0x10;
+
+#ifdef GD20HM303DLHC_CACHE_MODE
+    //  turn on fifo
+
+    ctrl5 |= 0x40;
+#endif
+
+    return m_settings->HALWrite(m_gyroSlaveAddr,  L3GD20H_CTRL5, ctrl5, "Failed to set L3GD20H CTRL5");
+}
+
+
+bool RTIMUGD20HM303DLHC::setAccelCTRL1()
+{
+    unsigned char ctrl1;
+
+    if ((m_settings->m_GD20HM303DLHCAccelSampleRate < 1) || (m_settings->m_GD20HM303DLHCAccelSampleRate > 7)) {
+        HAL_ERROR1("Illegal LSM303DLHC accel sample rate code %d\n", m_settings->m_GD20HM303DLHCAccelSampleRate);
+        return false;
+    }
+
+    ctrl1 = (m_settings->m_GD20HM303DLHCAccelSampleRate << 4) | 0x07;
+
+    return m_settings->HALWrite(m_accelSlaveAddr,  LSM303DLHC_CTRL1_A, ctrl1, "Failed to set LSM303D CTRL1");
+}
+
+bool RTIMUGD20HM303DLHC::setAccelCTRL4()
+{
+    unsigned char ctrl4;
+
+    switch (m_settings->m_GD20HM303DLHCAccelFsr) {
+    case LSM303DLHC_ACCEL_FSR_2:
+        m_accelScale = (RTFLOAT)0.001 / (RTFLOAT)16;
+        break;
+
+    case LSM303DLHC_ACCEL_FSR_4:
+        m_accelScale = (RTFLOAT)0.002 / (RTFLOAT)16;
+        break;
+
+    case LSM303DLHC_ACCEL_FSR_8:
+        m_accelScale = (RTFLOAT)0.004 / (RTFLOAT)16;
+        break;
+
+    case LSM303DLHC_ACCEL_FSR_16:
+        m_accelScale = (RTFLOAT)0.012 / (RTFLOAT)16;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal LSM303DLHC accel FSR code %d\n", m_settings->m_GD20HM303DLHCAccelFsr);
+        return false;
+    }
+
+    ctrl4 = 0x80 + (m_settings->m_GD20HM303DLHCAccelFsr << 4);
+
+    return m_settings->HALWrite(m_accelSlaveAddr,  LSM303DLHC_CTRL4_A, ctrl4, "Failed to set LSM303DLHC CTRL4");
+}
+
+
+bool RTIMUGD20HM303DLHC::setCompassCRA()
+{
+    unsigned char cra;
+
+    if ((m_settings->m_GD20HM303DLHCCompassSampleRate < 0) || (m_settings->m_GD20HM303DLHCCompassSampleRate > 7)) {
+        HAL_ERROR1("Illegal LSM303DLHC compass sample rate code %d\n", m_settings->m_GD20HM303DLHCCompassSampleRate);
+        return false;
+    }
+
+    cra = (m_settings->m_GD20HM303DLHCCompassSampleRate << 2);
+
+    return m_settings->HALWrite(m_compassSlaveAddr,  LSM303DLHC_CRA_M, cra, "Failed to set LSM303DLHC CRA_M");
+}
+
+bool RTIMUGD20HM303DLHC::setCompassCRB()
+{
+    unsigned char crb;
+
+    //  convert FSR to uT
+
+    switch (m_settings->m_GD20HM303DLHCCompassFsr) {
+    case LSM303DLHC_COMPASS_FSR_1_3:
+        crb = 0x20;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)1100;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)980;
+        break;
+
+    case LSM303DLHC_COMPASS_FSR_1_9:
+        crb = 0x40;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)855;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)760;
+       break;
+
+    case LSM303DLHC_COMPASS_FSR_2_5:
+        crb = 0x60;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)670;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)600;
+        break;
+
+    case LSM303DLHC_COMPASS_FSR_4:
+        crb = 0x80;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)450;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)400;
+        break;
+
+    case LSM303DLHC_COMPASS_FSR_4_7:
+        crb = 0xa0;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)400;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)355;
+        break;
+
+    case LSM303DLHC_COMPASS_FSR_5_6:
+        crb = 0xc0;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)330;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)295;
+        break;
+
+    case LSM303DLHC_COMPASS_FSR_8_1:
+        crb = 0xe0;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)230;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)205;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal LSM303DLHC compass FSR code %d\n", m_settings->m_GD20HM303DLHCCompassFsr);
+        return false;
+    }
+
+    return m_settings->HALWrite(m_compassSlaveAddr,  LSM303DLHC_CRB_M, crb, "Failed to set LSM303DLHC CRB_M");
+}
+
+bool RTIMUGD20HM303DLHC::setCompassCRM()
+{
+     return m_settings->HALWrite(m_compassSlaveAddr,  LSM303DLHC_CRM_M, 0x00, "Failed to set LSM303DLHC CRM_M");
+}
+
+
+int RTIMUGD20HM303DLHC::IMUGetPollInterval()
+{
+    return (400 / m_sampleRate);
+}
+
+bool RTIMUGD20HM303DLHC::IMURead()
+{
+    unsigned char status;
+    unsigned char gyroData[6];
+    unsigned char accelData[6];
+    unsigned char compassData[6];
+
+
+#ifdef GD20HM303DLHC_CACHE_MODE
+    int count;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, L3GD20H_FIFO_SRC, 1, &status, "Failed to read L3GD20 fifo status"))
+        return false;
+
+    if ((status & 0x40) != 0) {
+        HAL_INFO("L3GD20 fifo overrun\n");
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_CTRL5, 0x10, "Failed to set L3GD20 CTRL5"))
+            return false;
+
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_FIFO_CTRL, 0x0, "Failed to set L3GD20 FIFO mode"))
+            return false;
+
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20H_FIFO_CTRL, 0x3f, "Failed to set L3GD20 FIFO mode"))
+            return false;
+
+        if (!setGyroCTRL5())
+            return false;
+
+        m_imuData.timestamp += m_sampleInterval * 32;
+        return false;
+    }
+
+    // get count of samples in fifo
+    count = status & 0x1f;
+
+    if ((m_cacheCount == 0) && (count > 0) && (count < GD20HM303DLHC_FIFO_THRESH)) {
+        // special case of a small fifo and nothing cached - just handle as simple read
+
+        if (!m_settings->HALRead(m_gyroSlaveAddr, 0x80 | L3GD20H_OUT_X_L, 6, gyroData, "Failed to read L3GD20 data"))
+            return false;
+
+        if (!m_settings->HALRead(m_accelSlaveAddr, 0x80 | LSM303DLHC_OUT_X_L_A, 6, accelData, "Failed to read LSM303DLHC accel data"))
+            return false;
+
+        if (!m_settings->HALRead(m_compassSlaveAddr, 0x80 | LSM303DLHC_OUT_X_H_M, 6, compassData, "Failed to read LSM303DLHC compass data"))
+            return false;
+
+        if (m_firstTime)
+            m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+        else
+            m_imuData.timestamp += m_sampleInterval;
+
+        m_firstTime = false;
+    } else {
+        if (count >=  GD20HM303DLHC_FIFO_THRESH) {
+            // need to create a cache block
+
+            if (m_cacheCount == GD20HM303DLHC_CACHE_BLOCK_COUNT) {
+                // all cache blocks are full - discard oldest and update timestamp to account for lost samples
+                m_imuData.timestamp += m_sampleInterval * m_cache[m_cacheOut].count;
+                if (++m_cacheOut == GD20HM303DLHC_CACHE_BLOCK_COUNT)
+                    m_cacheOut = 0;
+                m_cacheCount--;
+            }
+
+            if (!m_settings->HALRead(m_gyroSlaveAddr, 0x80 | L3GD20H_OUT_X_L, GD20HM303DLHC_FIFO_CHUNK_SIZE * GD20HM303DLHC_FIFO_THRESH,
+                         m_cache[m_cacheIn].data, "Failed to read L3GD20 fifo data"))
+                return false;
+
+            if (!m_settings->HALRead(m_accelSlaveAddr, 0x80 | LSM303DLHC_OUT_X_L_A, 6,
+                         m_cache[m_cacheIn].accel, "Failed to read LSM303DLHC accel data"))
+                return false;
+
+            if (!m_settings->HALRead(m_compassSlaveAddr, 0x80 | LSM303DLHC_OUT_X_H_M, 6,
+                         m_cache[m_cacheIn].compass, "Failed to read LSM303DLHC compass data"))
+                return false;
+
+            m_cache[m_cacheIn].count = GD20HM303DLHC_FIFO_THRESH;
+            m_cache[m_cacheIn].index = 0;
+
+            m_cacheCount++;
+            if (++m_cacheIn == GD20HM303DLHC_CACHE_BLOCK_COUNT)
+                m_cacheIn = 0;
+
+        }
+
+        //  now fifo has been read if necessary, get something to process
+
+        if (m_cacheCount == 0)
+            return false;
+
+        memcpy(gyroData, m_cache[m_cacheOut].data + m_cache[m_cacheOut].index, GD20HM303DLHC_FIFO_CHUNK_SIZE);
+        memcpy(accelData, m_cache[m_cacheOut].accel, 6);
+        memcpy(compassData, m_cache[m_cacheOut].compass, 6);
+
+        m_cache[m_cacheOut].index += GD20HM303DLHC_FIFO_CHUNK_SIZE;
+
+        if (--m_cache[m_cacheOut].count == 0) {
+            //  this cache block is now empty
+
+            if (++m_cacheOut == GD20HM303DLHC_CACHE_BLOCK_COUNT)
+                m_cacheOut = 0;
+            m_cacheCount--;
+        }
+        if (m_firstTime)
+            m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+        else
+            m_imuData.timestamp += m_sampleInterval;
+
+        m_firstTime = false;
+    }
+
+#else
+    if (!m_settings->HALRead(m_gyroSlaveAddr, L3GD20H_STATUS, 1, &status, "Failed to read L3GD20H status"))
+        return false;
+
+    if ((status & 0x8) == 0)
+        return false;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, 0x80 | L3GD20H_OUT_X_L, 6, gyroData, "Failed to read L3GD20H data"))
+        return false;
+
+    m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+
+    if (!m_settings->HALRead(m_accelSlaveAddr, 0x80 | LSM303DLHC_OUT_X_L_A, 6, accelData, "Failed to read LSM303DLHC accel data"))
+        return false;
+
+    if (!m_settings->HALRead(m_compassSlaveAddr, 0x80 | LSM303DLHC_OUT_X_H_M, 6, compassData, "Failed to read LSM303DLHC compass data"))
+        return false;
+
+#endif
+
+    RTMath::convertToVector(gyroData, m_imuData.gyro, m_gyroScale, false);
+    RTMath::convertToVector(accelData, m_imuData.accel, m_accelScale, false);
+
+    m_imuData.compass.setX((RTFLOAT)((int16_t)(((uint16_t)compassData[0] << 8) | (uint16_t)compassData[1])) * m_compassScaleXY);
+    m_imuData.compass.setY((RTFLOAT)((int16_t)(((uint16_t)compassData[2] << 8) | (uint16_t)compassData[3])) * m_compassScaleXY);
+    m_imuData.compass.setZ((RTFLOAT)((int16_t)(((uint16_t)compassData[4] << 8) | (uint16_t)compassData[5])) * m_compassScaleZ);
+
+    //  sort out gyro axes
+
+    m_imuData.gyro.setX(m_imuData.gyro.x());
+    m_imuData.gyro.setY(-m_imuData.gyro.y());
+    m_imuData.gyro.setZ(-m_imuData.gyro.z());
+
+    //  sort out accel data;
+
+    m_imuData.accel.setX(-m_imuData.accel.x());
+
+    //  sort out compass axes
+
+    RTFLOAT temp;
+
+    temp = m_imuData.compass.z();
+    m_imuData.compass.setZ(-m_imuData.compass.y());
+    m_imuData.compass.setY(-temp);
+
+    //  now do standard processing
+
+    handleGyroBias();
+    calibrateAverageCompass();
+    calibrateAccel();
+
+    //  now update the filter
+
+    updateFusion();
+
+    return true;
+}
diff --git a/libraries/RTIMULib/utility/RTIMUGD20HM303DLHC.h b/libraries/RTIMULib/utility/RTIMUGD20HM303DLHC.h
new file mode 100644
index 0000000..fa23e3c
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUGD20HM303DLHC.h
@@ -0,0 +1,98 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTIMUGD20HM303DLHC_H
+#define	_RTIMUGD20HM303DLHC_H
+
+#include "RTIMU.h"
+
+//  Define this symbol to use cache mode
+
+//#define GD20M303DLHC_CACHE_MODE   // not reliable at the moment
+
+
+#ifdef GD20M303DLHC_CACHE_MODE
+
+//  Cache defs
+
+#define GD20M303DLHC_FIFO_CHUNK_SIZE    6                       // 6 bytes of gyro data
+#define GD20M303DLHC_FIFO_THRESH        16                      // threshold point in fifo
+#define GD20M303DLHC_CACHE_BLOCK_COUNT  16                      // number of cache blocks
+
+typedef struct
+{
+    unsigned char data[GD20M303DLHC_FIFO_THRESH * GD20M303DLHC_FIFO_CHUNK_SIZE];
+    int count;                                              // number of chunks in the cache block
+    int index;                                              // current index into the cache
+    unsigned char accel[6];                                 // the raw accel readings for the block
+    unsigned char compass[6];                               // the raw compass readings for the block
+
+} GD20M303DLHC_CACHE_BLOCK;
+
+#endif
+
+class RTIMUGD20HM303DLHC : public RTIMU
+{
+public:
+    RTIMUGD20HM303DLHC(RTIMUSettings *settings);
+    ~RTIMUGD20HM303DLHC();
+
+    virtual const char *IMUName() { return "L3GD20H + LSM303DLHC"; }
+    virtual int IMUType() { return RTIMU_TYPE_GD20HM303DLHC; }
+    virtual bool IMUInit();
+    virtual int IMUGetPollInterval();
+    virtual bool IMURead();
+
+private:
+    bool setGyroSampleRate();
+    bool setGyroCTRL2();
+    bool setGyroCTRL4();
+    bool setGyroCTRL5();
+    bool setAccelCTRL1();
+    bool setAccelCTRL4();
+    bool setCompassCRA();
+    bool setCompassCRB();
+    bool setCompassCRM();
+
+    unsigned char m_gyroSlaveAddr;                          // I2C address of L3GD20
+    unsigned char m_accelSlaveAddr;                         // I2C address of LSM303DLHC accel
+    unsigned char m_compassSlaveAddr;                       // I2C address of LSM303DLHC compass
+
+    RTFLOAT m_gyroScale;
+    RTFLOAT m_accelScale;
+    RTFLOAT m_compassScaleXY;
+    RTFLOAT m_compassScaleZ;
+
+#ifdef GD20M303DLHC_CACHE_MODE
+    bool m_firstTime;                                       // if first sample
+
+    GD20M303DLHC_CACHE_BLOCK m_cache[GD20M303DLHC_CACHE_BLOCK_COUNT]; // the cache itself
+    int m_cacheIn;                                          // the in index
+    int m_cacheOut;                                         // the out index
+    int m_cacheCount;                                       // number of used cache blocks
+
+#endif
+};
+
+#endif // _RTIMUGD20HM303DLHC_H
diff --git a/libraries/RTIMULib/utility/RTIMUGD20M303DLHC.cpp b/libraries/RTIMULib/utility/RTIMUGD20M303DLHC.cpp
new file mode 100644
index 0000000..53a7ada
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUGD20M303DLHC.cpp
@@ -0,0 +1,537 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTIMUGD20M303DLHC.h"
+#include "RTIMUSettings.h"
+
+//  this sets the learning rate for compass running average calculation
+
+#define COMPASS_ALPHA 0.2f
+
+RTIMUGD20M303DLHC::RTIMUGD20M303DLHC(RTIMUSettings *settings) : RTIMU(settings)
+{
+    m_sampleRate = 100;
+}
+
+RTIMUGD20M303DLHC::~RTIMUGD20M303DLHC()
+{
+}
+
+bool RTIMUGD20M303DLHC::IMUInit()
+{
+    unsigned char result;
+
+#ifdef GD20M303DLHC_CACHE_MODE
+    m_firstTime = true;
+    m_cacheIn = m_cacheOut = m_cacheCount = 0;
+#endif
+    // set validity flags
+
+    m_imuData.fusionPoseValid = false;
+    m_imuData.fusionQPoseValid = false;
+    m_imuData.gyroValid = true;
+    m_imuData.accelValid = true;
+    m_imuData.compassValid = true;
+    m_imuData.pressureValid = false;
+    m_imuData.temperatureValid = false;
+    m_imuData.humidityValid = false;
+
+    //  configure IMU
+
+    m_gyroSlaveAddr = m_settings->m_I2CSlaveAddress;
+    m_accelSlaveAddr = LSM303DLHC_ACCEL_ADDRESS;
+    m_compassSlaveAddr = LSM303DLHC_COMPASS_ADDRESS;
+
+    setCalibrationData();
+
+    //  enable the I2C bus
+
+    if (!m_settings->HALOpen())
+        return false;
+
+    //  Set up the gyro
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20_CTRL5, 0x80, "Failed to boot L3GD20"))
+        return false;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, L3GD20_WHO_AM_I, 1, &result, "Failed to read L3GD20 id"))
+        return false;
+
+    if (result != L3GD20_ID) {
+        HAL_ERROR1("Incorrect L3GD20 id %d\n", result);
+        return false;
+    }
+
+    if (!setGyroSampleRate())
+            return false;
+
+    if (!setGyroCTRL2())
+            return false;
+
+    if (!setGyroCTRL4())
+            return false;
+
+    //  Set up the accel
+
+    if (!setAccelCTRL1())
+        return false;
+
+    if (!setAccelCTRL4())
+        return false;
+
+    //  Set up the compass
+
+    if (!setCompassCRA())
+        return false;
+
+    if (!setCompassCRB())
+        return false;
+
+    if (!setCompassCRM())
+        return false;
+
+#ifdef GD20M303DLHC_CACHE_MODE
+
+    //  turn on gyro fifo
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20_FIFO_CTRL, 0x3f, "Failed to set L3GD20 FIFO mode"))
+        return false;
+#endif
+
+    if (!setGyroCTRL5())
+            return false;
+
+    gyroBiasInit();
+
+    HAL_INFO("GD20M303DLHC init complete\n");
+    return true;
+}
+
+bool RTIMUGD20M303DLHC::setGyroSampleRate()
+{
+    unsigned char ctrl1;
+
+    switch (m_settings->m_GD20M303DLHCGyroSampleRate) {
+    case L3GD20_SAMPLERATE_95:
+        ctrl1 = 0x0f;
+        m_sampleRate = 95;
+        break;
+
+    case L3GD20_SAMPLERATE_190:
+        ctrl1 = 0x4f;
+        m_sampleRate = 190;
+        break;
+
+    case L3GD20_SAMPLERATE_380:
+        ctrl1 = 0x8f;
+        m_sampleRate = 380;
+        break;
+
+    case L3GD20_SAMPLERATE_760:
+        ctrl1 = 0xcf;
+        m_sampleRate = 760;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal L3GD20 sample rate code %d\n", m_settings->m_GD20M303DLHCGyroSampleRate);
+        return false;
+    }
+
+    m_sampleInterval = (uint64_t)1000000 / m_sampleRate;
+
+    switch (m_settings->m_GD20M303DLHCGyroBW) {
+    case L3GD20_BANDWIDTH_0:
+        ctrl1 |= 0x00;
+        break;
+
+    case L3GD20_BANDWIDTH_1:
+        ctrl1 |= 0x10;
+        break;
+
+    case L3GD20_BANDWIDTH_2:
+        ctrl1 |= 0x20;
+        break;
+
+    case L3GD20_BANDWIDTH_3:
+        ctrl1 |= 0x30;
+        break;
+
+    }
+
+    return (m_settings->HALWrite(m_gyroSlaveAddr, L3GD20_CTRL1, ctrl1, "Failed to set L3GD20 CTRL1"));
+}
+
+bool RTIMUGD20M303DLHC::setGyroCTRL2()
+{
+    if ((m_settings->m_GD20M303DLHCGyroHpf < L3GD20_HPF_0) || (m_settings->m_GD20M303DLHCGyroHpf > L3GD20_HPF_9)) {
+        HAL_ERROR1("Illegal L3GD20 high pass filter code %d\n", m_settings->m_GD20M303DLHCGyroHpf);
+        return false;
+    }
+    return m_settings->HALWrite(m_gyroSlaveAddr,  L3GD20_CTRL2, m_settings->m_GD20M303DLHCGyroHpf, "Failed to set L3GD20 CTRL2");
+}
+
+bool RTIMUGD20M303DLHC::setGyroCTRL4()
+{
+    unsigned char ctrl4;
+
+    switch (m_settings->m_GD20M303DLHCGyroFsr) {
+    case L3GD20_FSR_250:
+        ctrl4 = 0x00;
+        m_gyroScale = (RTFLOAT)0.00875 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    case L3GD20_FSR_500:
+        ctrl4 = 0x10;
+        m_gyroScale = (RTFLOAT)0.0175 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    case L3GD20_FSR_2000:
+        ctrl4 = 0x20;
+        m_gyroScale = (RTFLOAT)0.07 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal L3GD20 FSR code %d\n", m_settings->m_GD20M303DLHCGyroFsr);
+        return false;
+    }
+
+    return m_settings->HALWrite(m_gyroSlaveAddr,  L3GD20_CTRL4, ctrl4, "Failed to set L3GD20 CTRL4");
+}
+
+
+bool RTIMUGD20M303DLHC::setGyroCTRL5()
+{
+    unsigned char ctrl5;
+
+    //  Turn on hpf
+
+    ctrl5 = 0x10;
+
+#ifdef GD20M303DLHC_CACHE_MODE
+    //  turn on fifo
+
+    ctrl5 |= 0x40;
+#endif
+
+    return m_settings->HALWrite(m_gyroSlaveAddr,  L3GD20_CTRL5, ctrl5, "Failed to set L3GD20 CTRL5");
+}
+
+
+bool RTIMUGD20M303DLHC::setAccelCTRL1()
+{
+    unsigned char ctrl1;
+
+    if ((m_settings->m_GD20M303DLHCAccelSampleRate < 1) || (m_settings->m_GD20M303DLHCAccelSampleRate > 7)) {
+        HAL_ERROR1("Illegal LSM303DLHC accel sample rate code %d\n", m_settings->m_GD20M303DLHCAccelSampleRate);
+        return false;
+    }
+
+    ctrl1 = (m_settings->m_GD20M303DLHCAccelSampleRate << 4) | 0x07;
+
+    return m_settings->HALWrite(m_accelSlaveAddr,  LSM303DLHC_CTRL1_A, ctrl1, "Failed to set LSM303D CTRL1");
+}
+
+bool RTIMUGD20M303DLHC::setAccelCTRL4()
+{
+    unsigned char ctrl4;
+
+    switch (m_settings->m_GD20M303DLHCAccelFsr) {
+    case LSM303DLHC_ACCEL_FSR_2:
+        m_accelScale = (RTFLOAT)0.001 / (RTFLOAT)16;
+        break;
+
+    case LSM303DLHC_ACCEL_FSR_4:
+        m_accelScale = (RTFLOAT)0.002 / (RTFLOAT)16;
+        break;
+
+    case LSM303DLHC_ACCEL_FSR_8:
+        m_accelScale = (RTFLOAT)0.004 / (RTFLOAT)16;
+        break;
+
+    case LSM303DLHC_ACCEL_FSR_16:
+        m_accelScale = (RTFLOAT)0.012 / (RTFLOAT)16;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal LSM303DLHC accel FSR code %d\n", m_settings->m_GD20M303DLHCAccelFsr);
+        return false;
+    }
+
+    ctrl4 = 0x80 + (m_settings->m_GD20M303DLHCAccelFsr << 4);
+
+    return m_settings->HALWrite(m_accelSlaveAddr,  LSM303DLHC_CTRL4_A, ctrl4, "Failed to set LSM303DLHC CTRL4");
+}
+
+
+bool RTIMUGD20M303DLHC::setCompassCRA()
+{
+    unsigned char cra;
+
+    if ((m_settings->m_GD20M303DLHCCompassSampleRate < 0) || (m_settings->m_GD20M303DLHCCompassSampleRate > 7)) {
+        HAL_ERROR1("Illegal LSM303DLHC compass sample rate code %d\n", m_settings->m_GD20M303DLHCCompassSampleRate);
+        return false;
+    }
+
+    cra = (m_settings->m_GD20M303DLHCCompassSampleRate << 2);
+
+    return m_settings->HALWrite(m_compassSlaveAddr,  LSM303DLHC_CRA_M, cra, "Failed to set LSM303DLHC CRA_M");
+}
+
+bool RTIMUGD20M303DLHC::setCompassCRB()
+{
+    unsigned char crb;
+
+    //  convert FSR to uT
+
+    switch (m_settings->m_GD20M303DLHCCompassFsr) {
+    case LSM303DLHC_COMPASS_FSR_1_3:
+        crb = 0x20;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)1100;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)980;
+        break;
+
+    case LSM303DLHC_COMPASS_FSR_1_9:
+        crb = 0x40;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)855;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)760;
+       break;
+
+    case LSM303DLHC_COMPASS_FSR_2_5:
+        crb = 0x60;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)670;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)600;
+        break;
+
+    case LSM303DLHC_COMPASS_FSR_4:
+        crb = 0x80;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)450;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)400;
+        break;
+
+    case LSM303DLHC_COMPASS_FSR_4_7:
+        crb = 0xa0;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)400;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)355;
+        break;
+
+    case LSM303DLHC_COMPASS_FSR_5_6:
+        crb = 0xc0;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)330;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)295;
+        break;
+
+    case LSM303DLHC_COMPASS_FSR_8_1:
+        crb = 0xe0;
+        m_compassScaleXY = (RTFLOAT)100 / (RTFLOAT)230;
+        m_compassScaleZ = (RTFLOAT)100 / (RTFLOAT)205;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal LSM303DLHC compass FSR code %d\n", m_settings->m_GD20M303DLHCCompassFsr);
+        return false;
+    }
+
+    return m_settings->HALWrite(m_compassSlaveAddr,  LSM303DLHC_CRB_M, crb, "Failed to set LSM303DLHC CRB_M");
+}
+
+bool RTIMUGD20M303DLHC::setCompassCRM()
+{
+     return m_settings->HALWrite(m_compassSlaveAddr,  LSM303DLHC_CRM_M, 0x00, "Failed to set LSM303DLHC CRM_M");
+}
+
+
+int RTIMUGD20M303DLHC::IMUGetPollInterval()
+{
+    return (400 / m_sampleRate);
+}
+
+bool RTIMUGD20M303DLHC::IMURead()
+{
+    unsigned char status;
+    unsigned char gyroData[6];
+    unsigned char accelData[6];
+    unsigned char compassData[6];
+
+
+#ifdef GD20M303DLHC_CACHE_MODE
+    int count;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, L3GD20_FIFO_SRC, 1, &status, "Failed to read L3GD20 fifo status"))
+        return false;
+
+    if ((status & 0x40) != 0) {
+        HAL_INFO("L3GD20 fifo overrun\n");
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20_CTRL5, 0x10, "Failed to set L3GD20 CTRL5"))
+            return false;
+
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20_FIFO_CTRL, 0x0, "Failed to set L3GD20 FIFO mode"))
+            return false;
+
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, L3GD20_FIFO_CTRL, 0x3f, "Failed to set L3GD20 FIFO mode"))
+            return false;
+
+        if (!setGyroCTRL5())
+            return false;
+
+        m_imuData.timestamp += m_sampleInterval * 32;
+        return false;
+    }
+
+    // get count of samples in fifo
+    count = status & 0x1f;
+
+    if ((m_cacheCount == 0) && (count > 0) && (count < GD20M303DLHC_FIFO_THRESH)) {
+        // special case of a small fifo and nothing cached - just handle as simple read
+
+        if (!m_settings->HALRead(m_gyroSlaveAddr, 0x80 | L3GD20_OUT_X_L, 6, gyroData, "Failed to read L3GD20 data"))
+            return false;
+
+        if (!m_settings->HALRead(m_accelSlaveAddr, 0x80 | LSM303DLHC_OUT_X_L_A, 6, accelData, "Failed to read LSM303DLHC accel data"))
+            return false;
+
+        if (!m_settings->HALRead(m_compassSlaveAddr, 0x80 | LSM303DLHC_OUT_X_H_M, 6, compassData, "Failed to read LSM303DLHC compass data"))
+            return false;
+
+        if (m_firstTime)
+            m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+        else
+            m_imuData.timestamp += m_sampleInterval;
+
+        m_firstTime = false;
+    } else {
+        if (count >=  GD20M303DLHC_FIFO_THRESH) {
+            // need to create a cache block
+
+            if (m_cacheCount == GD20M303DLHC_CACHE_BLOCK_COUNT) {
+                // all cache blocks are full - discard oldest and update timestamp to account for lost samples
+                m_imuData.timestamp += m_sampleInterval * m_cache[m_cacheOut].count;
+                if (++m_cacheOut == GD20M303DLHC_CACHE_BLOCK_COUNT)
+                    m_cacheOut = 0;
+                m_cacheCount--;
+            }
+
+            if (!m_settings->HALRead(m_gyroSlaveAddr, 0x80 | L3GD20_OUT_X_L, GD20M303DLHC_FIFO_CHUNK_SIZE * GD20M303DLHC_FIFO_THRESH,
+                         m_cache[m_cacheIn].data, "Failed to read L3GD20 fifo data"))
+                return false;
+
+            if (!m_settings->HALRead(m_accelSlaveAddr, 0x80 | LSM303DLHC_OUT_X_L_A, 6,
+                         m_cache[m_cacheIn].accel, "Failed to read LSM303DLHC accel data"))
+                return false;
+
+            if (!m_settings->HALRead(m_compassSlaveAddr, 0x80 | LSM303DLHC_OUT_X_H_M, 6,
+                         m_cache[m_cacheIn].compass, "Failed to read LSM303DLHC compass data"))
+                return false;
+
+            m_cache[m_cacheIn].count = GD20M303DLHC_FIFO_THRESH;
+            m_cache[m_cacheIn].index = 0;
+
+            m_cacheCount++;
+            if (++m_cacheIn == GD20M303DLHC_CACHE_BLOCK_COUNT)
+                m_cacheIn = 0;
+
+        }
+
+        //  now fifo has been read if necessary, get something to process
+
+        if (m_cacheCount == 0)
+            return false;
+
+        memcpy(gyroData, m_cache[m_cacheOut].data + m_cache[m_cacheOut].index, GD20M303DLHC_FIFO_CHUNK_SIZE);
+        memcpy(accelData, m_cache[m_cacheOut].accel, 6);
+        memcpy(compassData, m_cache[m_cacheOut].compass, 6);
+
+        m_cache[m_cacheOut].index += GD20M303DLHC_FIFO_CHUNK_SIZE;
+
+        if (--m_cache[m_cacheOut].count == 0) {
+            //  this cache block is now empty
+
+            if (++m_cacheOut == GD20M303DLHC_CACHE_BLOCK_COUNT)
+                m_cacheOut = 0;
+            m_cacheCount--;
+        }
+        if (m_firstTime)
+            m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+        else
+            m_imuData.timestamp += m_sampleInterval;
+
+        m_firstTime = false;
+    }
+
+#else
+    if (!m_settings->HALRead(m_gyroSlaveAddr, L3GD20_STATUS, 1, &status, "Failed to read L3GD20 status"))
+        return false;
+
+    if ((status & 0x8) == 0)
+        return false;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, 0x80 | L3GD20_OUT_X_L, 6, gyroData, "Failed to read L3GD20 data"))
+        return false;
+
+    m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+
+    if (!m_settings->HALRead(m_accelSlaveAddr, 0x80 | LSM303DLHC_OUT_X_L_A, 6, accelData, "Failed to read LSM303DLHC accel data"))
+        return false;
+
+    if (!m_settings->HALRead(m_compassSlaveAddr, 0x80 | LSM303DLHC_OUT_X_H_M, 6, compassData, "Failed to read LSM303DLHC compass data"))
+        return false;
+
+#endif
+
+    RTMath::convertToVector(gyroData, m_imuData.gyro, m_gyroScale, false);
+    RTMath::convertToVector(accelData, m_imuData.accel, m_accelScale, false);
+
+    m_imuData.compass.setX((RTFLOAT)((int16_t)(((uint16_t)compassData[0] << 8) | (uint16_t)compassData[1])) * m_compassScaleXY);
+    m_imuData.compass.setY((RTFLOAT)((int16_t)(((uint16_t)compassData[2] << 8) | (uint16_t)compassData[3])) * m_compassScaleXY);
+    m_imuData.compass.setZ((RTFLOAT)((int16_t)(((uint16_t)compassData[4] << 8) | (uint16_t)compassData[5])) * m_compassScaleZ);
+
+    //  sort out gyro axes
+
+    m_imuData.gyro.setX(m_imuData.gyro.x());
+    m_imuData.gyro.setY(-m_imuData.gyro.y());
+    m_imuData.gyro.setZ(-m_imuData.gyro.z());
+
+    //  sort out accel data;
+
+    m_imuData.accel.setX(-m_imuData.accel.x());
+
+    //  sort out compass axes
+
+    RTFLOAT temp;
+
+    temp = m_imuData.compass.z();
+    m_imuData.compass.setZ(-m_imuData.compass.y());
+    m_imuData.compass.setY(-temp);
+
+    //  now do standard processing
+
+    handleGyroBias();
+    calibrateAverageCompass();
+    calibrateAccel();
+
+    //  now update the filter
+
+    updateFusion();
+
+    return true;
+}
diff --git a/libraries/RTIMULib/utility/RTIMUGD20M303DLHC.h b/libraries/RTIMULib/utility/RTIMUGD20M303DLHC.h
new file mode 100644
index 0000000..036ecde
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUGD20M303DLHC.h
@@ -0,0 +1,97 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTIMUGD20M303DLHC_H
+#define	_RTIMUGD20M303DLHC_H
+
+#include "RTIMU.h"
+
+//  Define this symbol to use cache mode
+
+//#define GD20M303DLHC_CACHE_MODE   // not reliable at the moment
+
+#ifdef GD20M303DLHC_CACHE_MODE
+
+//  Cache defs
+
+#define GD20M303DLHC_FIFO_CHUNK_SIZE    6                       // 6 bytes of gyro data
+#define GD20M303DLHC_FIFO_THRESH        16                      // threshold point in fifo
+#define GD20M303DLHC_CACHE_BLOCK_COUNT  16                      // number of cache blocks
+
+typedef struct
+{
+    unsigned char data[GD20M303DLHC_FIFO_THRESH * GD20M303DLHC_FIFO_CHUNK_SIZE];
+    int count;                                              // number of chunks in the cache block
+    int index;                                              // current index into the cache
+    unsigned char accel[6];                                 // the raw accel readings for the block
+    unsigned char compass[6];                               // the raw compass readings for the block
+
+} GD20M303DLHC_CACHE_BLOCK;
+
+#endif
+
+class RTIMUGD20M303DLHC : public RTIMU
+{
+public:
+    RTIMUGD20M303DLHC(RTIMUSettings *settings);
+    ~RTIMUGD20M303DLHC();
+
+    virtual const char *IMUName() { return "L3GD20 + LSM303DLHC"; }
+    virtual int IMUType() { return RTIMU_TYPE_GD20M303DLHC; }
+    virtual bool IMUInit();
+    virtual int IMUGetPollInterval();
+    virtual bool IMURead();
+
+private:
+    bool setGyroSampleRate();
+    bool setGyroCTRL2();
+    bool setGyroCTRL4();
+    bool setGyroCTRL5();
+    bool setAccelCTRL1();
+    bool setAccelCTRL4();
+    bool setCompassCRA();
+    bool setCompassCRB();
+    bool setCompassCRM();
+
+    unsigned char m_gyroSlaveAddr;                          // I2C address of L3GD20
+    unsigned char m_accelSlaveAddr;                         // I2C address of LSM303DLHC accel
+    unsigned char m_compassSlaveAddr;                       // I2C address of LSM303DLHC compass
+
+    RTFLOAT m_gyroScale;
+    RTFLOAT m_accelScale;
+    RTFLOAT m_compassScaleXY;
+    RTFLOAT m_compassScaleZ;
+
+#ifdef GD20M303DLHC_CACHE_MODE
+    bool m_firstTime;                                       // if first sample
+
+    GD20M303DLHC_CACHE_BLOCK m_cache[GD20M303DLHC_CACHE_BLOCK_COUNT]; // the cache itself
+    int m_cacheIn;                                          // the in index
+    int m_cacheOut;                                         // the out index
+    int m_cacheCount;                                       // number of used cache blocks
+
+#endif
+};
+
+#endif // _RTIMUGD20M303DLHC_H
diff --git a/libraries/RTIMULib/utility/RTIMULSM9DS0.cpp b/libraries/RTIMULib/utility/RTIMULSM9DS0.cpp
new file mode 100644
index 0000000..761ac6f
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMULSM9DS0.cpp
@@ -0,0 +1,538 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTIMULSM9DS0.h"
+#include "RTIMUSettings.h"
+
+//  this sets the learning rate for compass running average calculation
+
+#define COMPASS_ALPHA 0.2f
+
+RTIMULSM9DS0::RTIMULSM9DS0(RTIMUSettings *settings) : RTIMU(settings)
+{
+    m_sampleRate = 100;
+}
+
+RTIMULSM9DS0::~RTIMULSM9DS0()
+{
+}
+
+bool RTIMULSM9DS0::IMUInit()
+{
+    unsigned char result;
+
+#ifdef LSM9DS0_CACHE_MODE
+    m_firstTime = true;
+    m_cacheIn = m_cacheOut = m_cacheCount = 0;
+#endif
+    // set validity flags
+
+    m_imuData.fusionPoseValid = false;
+    m_imuData.fusionQPoseValid = false;
+    m_imuData.gyroValid = true;
+    m_imuData.accelValid = true;
+    m_imuData.compassValid = true;
+    m_imuData.pressureValid = false;
+    m_imuData.temperatureValid = false;
+    m_imuData.humidityValid = false;
+
+    //  configure IMU
+
+    m_gyroSlaveAddr = m_settings->m_I2CSlaveAddress;
+
+    // work out accelmag address
+
+    if (m_settings->HALRead(LSM9DS0_ACCELMAG_ADDRESS0, LSM9DS0_WHO_AM_I, 1, &result, "")) {
+        if (result == LSM9DS0_ACCELMAG_ID) {
+            m_accelCompassSlaveAddr = LSM9DS0_ACCELMAG_ADDRESS0;
+        }
+    } else {
+        m_accelCompassSlaveAddr = LSM9DS0_ACCELMAG_ADDRESS1;
+    }
+
+    setCalibrationData();
+
+    //  enable the I2C bus
+
+    if (!m_settings->HALOpen())
+        return false;
+
+    //  Set up the gyro
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, LSM9DS0_GYRO_CTRL5, 0x80, "Failed to boot LSM9DS0"))
+        return false;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, LSM9DS0_GYRO_WHO_AM_I, 1, &result, "Failed to read LSM9DS0 gyro id"))
+        return false;
+
+    if (result != LSM9DS0_GYRO_ID) {
+        HAL_ERROR1("Incorrect LSM9DS0 gyro id %d\n", result);
+        return false;
+    }
+
+    if (!setGyroSampleRate())
+            return false;
+
+    if (!setGyroCTRL2())
+            return false;
+
+    if (!setGyroCTRL4())
+            return false;
+
+    //  Set up the accel
+
+    if (!m_settings->HALRead(m_accelCompassSlaveAddr, LSM9DS0_WHO_AM_I, 1, &result, "Failed to read LSM9DS0 accel/mag id"))
+        return false;
+
+    if (result != LSM9DS0_ACCELMAG_ID) {
+        HAL_ERROR1("Incorrect LSM9DS0 accel/mag id %d\n", result);
+        return false;
+    }
+
+    if (!setAccelCTRL1())
+        return false;
+
+    if (!setAccelCTRL2())
+        return false;
+
+    if (!setCompassCTRL5())
+        return false;
+
+    if (!setCompassCTRL6())
+        return false;
+
+    if (!setCompassCTRL7())
+        return false;
+
+#ifdef LSM9DS0_CACHE_MODE
+
+    //  turn on gyro fifo
+
+    if (!m_settings->HALWrite(m_gyroSlaveAddr, LSM9DS0_GYRO_FIFO_CTRL, 0x3f, "Failed to set LSM9DS0 FIFO mode"))
+        return false;
+#endif
+
+    if (!setGyroCTRL5())
+            return false;
+
+    gyroBiasInit();
+
+    HAL_INFO("LSM9DS0 init complete\n");
+    return true;
+}
+
+bool RTIMULSM9DS0::setGyroSampleRate()
+{
+    unsigned char ctrl1;
+
+    switch (m_settings->m_LSM9DS0GyroSampleRate) {
+    case LSM9DS0_GYRO_SAMPLERATE_95:
+        ctrl1 = 0x0f;
+        m_sampleRate = 95;
+        break;
+
+    case LSM9DS0_GYRO_SAMPLERATE_190:
+        ctrl1 = 0x4f;
+        m_sampleRate = 190;
+        break;
+
+    case LSM9DS0_GYRO_SAMPLERATE_380:
+        ctrl1 = 0x8f;
+        m_sampleRate = 380;
+        break;
+
+    case LSM9DS0_GYRO_SAMPLERATE_760:
+        ctrl1 = 0xcf;
+        m_sampleRate = 760;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal LSM9DS0 gyro sample rate code %d\n", m_settings->m_LSM9DS0GyroSampleRate);
+        return false;
+    }
+
+    m_sampleInterval = (uint64_t)1000000 / m_sampleRate;
+
+    switch (m_settings->m_LSM9DS0GyroBW) {
+    case LSM9DS0_GYRO_BANDWIDTH_0:
+        ctrl1 |= 0x00;
+        break;
+
+    case LSM9DS0_GYRO_BANDWIDTH_1:
+        ctrl1 |= 0x10;
+        break;
+
+    case LSM9DS0_GYRO_BANDWIDTH_2:
+        ctrl1 |= 0x20;
+        break;
+
+    case LSM9DS0_GYRO_BANDWIDTH_3:
+        ctrl1 |= 0x30;
+        break;
+
+    }
+
+    return (m_settings->HALWrite(m_gyroSlaveAddr, LSM9DS0_GYRO_CTRL1, ctrl1, "Failed to set LSM9DS0 gyro CTRL1"));
+}
+
+bool RTIMULSM9DS0::setGyroCTRL2()
+{
+    if ((m_settings->m_LSM9DS0GyroHpf < LSM9DS0_GYRO_HPF_0) || (m_settings->m_LSM9DS0GyroHpf > LSM9DS0_GYRO_HPF_9)) {
+        HAL_ERROR1("Illegal LSM9DS0 gyro high pass filter code %d\n", m_settings->m_LSM9DS0GyroHpf);
+        return false;
+    }
+    return m_settings->HALWrite(m_gyroSlaveAddr,  LSM9DS0_GYRO_CTRL2, m_settings->m_LSM9DS0GyroHpf, "Failed to set LSM9DS0 gyro CTRL2");
+}
+
+bool RTIMULSM9DS0::setGyroCTRL4()
+{
+    unsigned char ctrl4;
+
+    switch (m_settings->m_LSM9DS0GyroFsr) {
+    case LSM9DS0_GYRO_FSR_250:
+        ctrl4 = 0x00;
+        m_gyroScale = (RTFLOAT)0.00875 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    case LSM9DS0_GYRO_FSR_500:
+        ctrl4 = 0x10;
+        m_gyroScale = (RTFLOAT)0.0175 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    case LSM9DS0_GYRO_FSR_2000:
+        ctrl4 = 0x20;
+        m_gyroScale = (RTFLOAT)0.07 * RTMATH_DEGREE_TO_RAD;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal LSM9DS0 gyro FSR code %d\n", m_settings->m_LSM9DS0GyroFsr);
+        return false;
+    }
+
+    return m_settings->HALWrite(m_gyroSlaveAddr,  LSM9DS0_GYRO_CTRL4, ctrl4, "Failed to set LSM9DS0 gyro CTRL4");
+}
+
+
+bool RTIMULSM9DS0::setGyroCTRL5()
+{
+    unsigned char ctrl5;
+
+    //  Turn on hpf
+
+    ctrl5 = 0x10;
+
+#ifdef LSM9DS0_CACHE_MODE
+    //  turn on fifo
+
+    ctrl5 |= 0x40;
+#endif
+
+    return m_settings->HALWrite(m_gyroSlaveAddr,  LSM9DS0_GYRO_CTRL5, ctrl5, "Failed to set LSM9DS0 gyro CTRL5");
+}
+
+
+bool RTIMULSM9DS0::setAccelCTRL1()
+{
+    unsigned char ctrl1;
+
+    if ((m_settings->m_LSM9DS0AccelSampleRate < 0) || (m_settings->m_LSM9DS0AccelSampleRate > 10)) {
+        HAL_ERROR1("Illegal LSM9DS0 accel sample rate code %d\n", m_settings->m_LSM9DS0AccelSampleRate);
+        return false;
+    }
+
+    ctrl1 = (m_settings->m_LSM9DS0AccelSampleRate << 4) | 0x07;
+
+    return m_settings->HALWrite(m_accelCompassSlaveAddr,  LSM9DS0_CTRL1, ctrl1, "Failed to set LSM9DS0 accell CTRL1");
+}
+
+bool RTIMULSM9DS0::setAccelCTRL2()
+{
+    unsigned char ctrl2;
+
+    if ((m_settings->m_LSM9DS0AccelLpf < 0) || (m_settings->m_LSM9DS0AccelLpf > 3)) {
+        HAL_ERROR1("Illegal LSM9DS0 accel low pass fiter code %d\n", m_settings->m_LSM9DS0AccelLpf);
+        return false;
+    }
+
+    switch (m_settings->m_LSM9DS0AccelFsr) {
+    case LSM9DS0_ACCEL_FSR_2:
+        m_accelScale = (RTFLOAT)0.000061;
+        break;
+
+    case LSM9DS0_ACCEL_FSR_4:
+        m_accelScale = (RTFLOAT)0.000122;
+        break;
+
+    case LSM9DS0_ACCEL_FSR_6:
+        m_accelScale = (RTFLOAT)0.000183;
+        break;
+
+    case LSM9DS0_ACCEL_FSR_8:
+        m_accelScale = (RTFLOAT)0.000244;
+        break;
+
+    case LSM9DS0_ACCEL_FSR_16:
+        m_accelScale = (RTFLOAT)0.000732;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal LSM9DS0 accel FSR code %d\n", m_settings->m_LSM9DS0AccelFsr);
+        return false;
+    }
+
+    ctrl2 = (m_settings->m_LSM9DS0AccelLpf << 6) | (m_settings->m_LSM9DS0AccelFsr << 3);
+
+    return m_settings->HALWrite(m_accelCompassSlaveAddr,  LSM9DS0_CTRL2, ctrl2, "Failed to set LSM9DS0 accel CTRL2");
+}
+
+
+bool RTIMULSM9DS0::setCompassCTRL5()
+{
+    unsigned char ctrl5;
+
+    if ((m_settings->m_LSM9DS0CompassSampleRate < 0) || (m_settings->m_LSM9DS0CompassSampleRate > 5)) {
+        HAL_ERROR1("Illegal LSM9DS0 compass sample rate code %d\n", m_settings->m_LSM9DS0CompassSampleRate);
+        return false;
+    }
+
+    ctrl5 = (m_settings->m_LSM9DS0CompassSampleRate << 2);
+
+#ifdef LSM9DS0_CACHE_MODE
+    //  enable fifo
+
+    ctrl5 |= 0x40;
+#endif
+
+    return m_settings->HALWrite(m_accelCompassSlaveAddr,  LSM9DS0_CTRL5, ctrl5, "Failed to set LSM9DS0 compass CTRL5");
+}
+
+bool RTIMULSM9DS0::setCompassCTRL6()
+{
+    unsigned char ctrl6;
+
+    //  convert FSR to uT
+
+    switch (m_settings->m_LSM9DS0CompassFsr) {
+    case LSM9DS0_COMPASS_FSR_2:
+        ctrl6 = 0;
+        m_compassScale = (RTFLOAT)0.008;
+        break;
+
+    case LSM9DS0_COMPASS_FSR_4:
+        ctrl6 = 0x20;
+        m_compassScale = (RTFLOAT)0.016;
+        break;
+
+    case LSM9DS0_COMPASS_FSR_8:
+        ctrl6 = 0x40;
+        m_compassScale = (RTFLOAT)0.032;
+        break;
+
+    case LSM9DS0_COMPASS_FSR_12:
+        ctrl6 = 0x60;
+        m_compassScale = (RTFLOAT)0.0479;
+        break;
+
+    default:
+        HAL_ERROR1("Illegal LSM9DS0 compass FSR code %d\n", m_settings->m_LSM9DS0CompassFsr);
+        return false;
+    }
+
+    return m_settings->HALWrite(m_accelCompassSlaveAddr,  LSM9DS0_CTRL6, ctrl6, "Failed to set LSM9DS0 compass CTRL6");
+}
+
+bool RTIMULSM9DS0::setCompassCTRL7()
+{
+     return m_settings->HALWrite(m_accelCompassSlaveAddr,  LSM9DS0_CTRL7, 0x60, "Failed to set LSM9DS0CTRL7");
+}
+
+
+
+int RTIMULSM9DS0::IMUGetPollInterval()
+{
+    return (400 / m_sampleRate);
+}
+
+bool RTIMULSM9DS0::IMURead()
+{
+    unsigned char status;
+    unsigned char gyroData[6];
+    unsigned char accelData[6];
+    unsigned char compassData[6];
+
+
+#ifdef LSM9DS0_CACHE_MODE
+    int count;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, LSM9DS0_GYRO_FIFO_SRC, 1, &status, "Failed to read LSM9DS0 gyro fifo status"))
+        return false;
+
+    if ((status & 0x40) != 0) {
+        HAL_INFO("LSM9DS0 gyro fifo overrun\n");
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, LSM9DS0_GYRO_CTRL5, 0x10, "Failed to set LSM9DS0 gyro CTRL5"))
+            return false;
+
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, LSM9DS0_GYRO_FIFO_CTRL, 0x0, "Failed to set LSM9DS0 gyro FIFO mode"))
+            return false;
+
+        if (!m_settings->HALWrite(m_gyroSlaveAddr, LSM9DS0_GYRO_FIFO_CTRL, 0x3f, "Failed to set LSM9DS0 gyro FIFO mode"))
+            return false;
+
+        if (!setGyroCTRL5())
+            return false;
+
+        m_imuData.timestamp += m_sampleInterval * 32;
+        return false;
+    }
+
+    // get count of samples in fifo
+    count = status & 0x1f;
+
+    if ((m_cacheCount == 0) && (count > 0) && (count < LSM9DS0_FIFO_THRESH)) {
+        // special case of a small fifo and nothing cached - just handle as simple read
+
+        if (!m_settings->HALRead(m_gyroSlaveAddr, 0x80 | LSM9DS0_GYRO_OUT_X_L, 6, gyroData, "Failed to read LSM9DS0 gyro data"))
+            return false;
+
+        if (!m_settings->HALRead(m_accelCompassSlaveAddr, 0x80 | LSM9DS0_OUT_X_L_A, 6, accelData, "Failed to read LSM9DS0 accel data"))
+            return false;
+
+        if (!m_settings->HALRead(m_accelCompassSlaveAddr, 0x80 | LSM9DS0_OUT_X_L_M, 6, compassData, "Failed to read LSM9DS0 compass data"))
+            return false;
+
+        if (m_firstTime)
+            m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+        else
+            m_imuData.timestamp += m_sampleInterval;
+
+        m_firstTime = false;
+   } else {
+        if (count >=  LSM9DS0_FIFO_THRESH) {
+            // need to create a cache block
+
+            if (m_cacheCount == LSM9DS0_CACHE_BLOCK_COUNT) {
+                // all cache blocks are full - discard oldest and update timestamp to account for lost samples
+                m_imuData.timestamp += m_sampleInterval * m_cache[m_cacheOut].count;
+                if (++m_cacheOut == LSM9DS0_CACHE_BLOCK_COUNT)
+                    m_cacheOut = 0;
+                m_cacheCount--;
+            }
+
+            if (!m_settings->HALRead(m_gyroSlaveAddr, 0x80 | LSM9DS0_GYRO_OUT_X_L, LSM9DS0_FIFO_CHUNK_SIZE * LSM9DS0_FIFO_THRESH,
+                         m_cache[m_cacheIn].data, "Failed to read LSM9DS0 fifo data"))
+                return false;
+
+            if (!m_settings->HALRead(m_accelCompassSlaveAddr, 0x80 | LSM9DS0_OUT_X_L_A, 6,
+                         m_cache[m_cacheIn].accel, "Failed to read LSM9DS0 accel data"))
+                return false;
+
+            if (!m_settings->HALRead(m_accelCompassSlaveAddr, 0x80 | LSM9DS0_OUT_X_L_M, 6,
+                         m_cache[m_cacheIn].compass, "Failed to read LSM9DS0 compass data"))
+                return false;
+
+            m_cache[m_cacheIn].count = LSM9DS0_FIFO_THRESH;
+            m_cache[m_cacheIn].index = 0;
+
+            m_cacheCount++;
+            if (++m_cacheIn == LSM9DS0_CACHE_BLOCK_COUNT)
+                m_cacheIn = 0;
+
+        }
+
+        //  now fifo has been read if necessary, get something to process
+
+        if (m_cacheCount == 0)
+            return false;
+
+        memcpy(gyroData, m_cache[m_cacheOut].data + m_cache[m_cacheOut].index, LSM9DS0_FIFO_CHUNK_SIZE);
+        memcpy(accelData, m_cache[m_cacheOut].accel, 6);
+        memcpy(compassData, m_cache[m_cacheOut].compass, 6);
+
+        m_cache[m_cacheOut].index += LSM9DS0_FIFO_CHUNK_SIZE;
+
+        if (--m_cache[m_cacheOut].count == 0) {
+            //  this cache block is now empty
+
+            if (++m_cacheOut == LSM9DS0_CACHE_BLOCK_COUNT)
+                m_cacheOut = 0;
+            m_cacheCount--;
+        }
+        if (m_firstTime)
+            m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+        else
+            m_imuData.timestamp += m_sampleInterval;
+
+        m_firstTime = false;
+    }
+
+#else
+    if (!m_settings->HALRead(m_gyroSlaveAddr, LSM9DS0_GYRO_STATUS, 1, &status, "Failed to read LSM9DS0 status"))
+        return false;
+
+    if ((status & 0x8) == 0)
+        return false;
+
+    if (!m_settings->HALRead(m_gyroSlaveAddr, 0x80 | LSM9DS0_GYRO_OUT_X_L, 6, gyroData, "Failed to read LSM9DS0 gyro data"))
+        return false;
+
+    m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+
+    if (!m_settings->HALRead(m_accelCompassSlaveAddr, 0x80 | LSM9DS0_OUT_X_L_A, 6, accelData, "Failed to read LSM9DS0 accel data"))
+        return false;
+
+    if (!m_settings->HALRead(m_accelCompassSlaveAddr, 0x80 | LSM9DS0_OUT_X_L_M, 6, compassData, "Failed to read LSM9DS0 compass data"))
+        return false;
+
+#endif
+
+    RTMath::convertToVector(gyroData, m_imuData.gyro, m_gyroScale, false);
+    RTMath::convertToVector(accelData, m_imuData.accel, m_accelScale, false);
+    RTMath::convertToVector(compassData, m_imuData.compass, m_compassScale, false);
+
+    //  sort out gyro axes and correct for bias
+
+    m_imuData.gyro.setX(m_imuData.gyro.x());
+    m_imuData.gyro.setY(-m_imuData.gyro.y());
+    m_imuData.gyro.setZ(-m_imuData.gyro.z());
+
+    //  sort out accel data;
+
+    m_imuData.accel.setX(-m_imuData.accel.x());
+
+    //  sort out compass axes
+
+    m_imuData.compass.setY(-m_imuData.compass.y());
+
+    //  now do standard processing
+
+    handleGyroBias();
+    calibrateAverageCompass();
+    calibrateAccel();
+
+    //  now update the filter
+
+    updateFusion();
+
+    return true;
+}
diff --git a/libraries/RTIMULib/utility/RTIMULSM9DS0.h b/libraries/RTIMULib/utility/RTIMULSM9DS0.h
new file mode 100644
index 0000000..6ada04b
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMULSM9DS0.h
@@ -0,0 +1,95 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTIMULSM9DS0_H
+#define	_RTIMULSM9DS0_H
+
+#include "RTIMU.h"
+
+//  Define this symbol to use cache mode
+
+//#define LSM9DS0_CACHE_MODE   // not reliable at the moment
+
+#ifdef LSM9DS0_CACHE_MODE
+
+//  Cache defs
+
+#define LSM9DS0_FIFO_CHUNK_SIZE    6                       // 6 bytes of gyro data
+#define LSM9DS0_FIFO_THRESH        16                      // threshold point in fifo
+#define LSM9DS0_CACHE_BLOCK_COUNT  16                      // number of cache blocks
+
+typedef struct
+{
+    unsigned char data[LSM9DS0_FIFO_THRESH * LSM9DS0_FIFO_CHUNK_SIZE];
+    int count;                                              // number of chunks in the cache block
+    int index;                                              // current index into the cache
+    unsigned char accel[6];                                 // the raw accel readings for the block
+    unsigned char compass[6];                               // the raw compass readings for the block
+
+} LSM9DS0_CACHE_BLOCK;
+
+#endif
+
+class RTIMULSM9DS0 : public RTIMU
+{
+public:
+    RTIMULSM9DS0(RTIMUSettings *settings);
+    ~RTIMULSM9DS0();
+
+    virtual const char *IMUName() { return "LSM9DS0"; }
+    virtual int IMUType() { return RTIMU_TYPE_LSM9DS0; }
+    virtual bool IMUInit();
+    virtual int IMUGetPollInterval();
+    virtual bool IMURead();
+
+private:
+    bool setGyroSampleRate();
+    bool setGyroCTRL2();
+    bool setGyroCTRL4();
+    bool setGyroCTRL5();
+    bool setAccelCTRL1();
+    bool setAccelCTRL2();
+    bool setCompassCTRL5();
+    bool setCompassCTRL6();
+    bool setCompassCTRL7();
+
+    unsigned char m_gyroSlaveAddr;                          // I2C address of gyro
+    unsigned char m_accelCompassSlaveAddr;                  // I2C address of accel and mag
+
+    RTFLOAT m_gyroScale;
+    RTFLOAT m_accelScale;
+    RTFLOAT m_compassScale;
+
+#ifdef LSM9DS0_CACHE_MODE
+    bool m_firstTime;                                       // if first sample
+
+    LSM9DS0_CACHE_BLOCK m_cache[LSM9DS0_CACHE_BLOCK_COUNT]; // the cache itself
+    int m_cacheIn;                                          // the in index
+    int m_cacheOut;                                         // the out index
+    int m_cacheCount;                                       // number of used cache blocks
+
+#endif
+};
+
+#endif // _RTIMULSM9DS0_H
diff --git a/libraries/RTIMULib/utility/RTIMUMPU9150.cpp b/libraries/RTIMULib/utility/RTIMUMPU9150.cpp
new file mode 100644
index 0000000..268c313
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUMPU9150.cpp
@@ -0,0 +1,634 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTIMUMPU9150.h"
+#include "RTIMUSettings.h"
+
+RTIMUMPU9150::RTIMUMPU9150(RTIMUSettings *settings) : RTIMU(settings)
+{
+
+}
+
+RTIMUMPU9150::~RTIMUMPU9150()
+{
+}
+
+bool RTIMUMPU9150::setLpf(unsigned char lpf)
+{
+    switch (lpf) {
+    case MPU9150_LPF_256:
+    case MPU9150_LPF_188:
+    case MPU9150_LPF_98:
+    case MPU9150_LPF_42:
+    case MPU9150_LPF_20:
+    case MPU9150_LPF_10:
+    case MPU9150_LPF_5:
+        m_lpf = lpf;
+        return true;
+
+    default:
+        HAL_ERROR1("Illegal MPU9150 lpf %d\n", lpf);
+        return false;
+    }
+}
+
+
+bool RTIMUMPU9150::setSampleRate(int rate)
+{
+    if ((rate < MPU9150_SAMPLERATE_MIN) || (rate > MPU9150_SAMPLERATE_MAX)) {
+        HAL_ERROR1("Illegal sample rate %d\n", rate);
+        return false;
+    }
+    m_sampleRate = rate;
+    m_sampleInterval = (uint64_t)1000000 / m_sampleRate;
+    return true;
+}
+
+bool RTIMUMPU9150::setCompassRate(int rate)
+{
+    if ((rate < MPU9150_COMPASSRATE_MIN) || (rate > MPU9150_COMPASSRATE_MAX)) {
+        HAL_ERROR1("Illegal compass rate %d\n", rate);
+        return false;
+    }
+    m_compassRate = rate;
+    return true;
+}
+
+bool RTIMUMPU9150::setGyroFsr(unsigned char fsr)
+{
+    switch (fsr) {
+    case MPU9150_GYROFSR_250:
+        m_gyroFsr = fsr;
+        m_gyroScale = RTMATH_PI / (131.0 * 180.0);
+        return true;
+
+    case MPU9150_GYROFSR_500:
+        m_gyroFsr = fsr;
+        m_gyroScale = RTMATH_PI / (62.5 * 180.0);
+        return true;
+
+    case MPU9150_GYROFSR_1000:
+        m_gyroFsr = fsr;
+        m_gyroScale = RTMATH_PI / (32.8 * 180.0);
+        return true;
+
+    case MPU9150_GYROFSR_2000:
+        m_gyroFsr = fsr;
+        m_gyroScale = RTMATH_PI / (16.4 * 180.0);
+        return true;
+
+    default:
+        HAL_ERROR1("Illegal MPU9150 gyro fsr %d\n", fsr);
+        return false;
+    }
+}
+
+bool RTIMUMPU9150::setAccelFsr(unsigned char fsr)
+{
+    switch (fsr) {
+    case MPU9150_ACCELFSR_2:
+        m_accelFsr = fsr;
+        m_accelScale = 1.0/16384.0;
+        return true;
+
+    case MPU9150_ACCELFSR_4:
+        m_accelFsr = fsr;
+        m_accelScale = 1.0/8192.0;
+        return true;
+
+    case MPU9150_ACCELFSR_8:
+        m_accelFsr = fsr;
+        m_accelScale = 1.0/4096.0;
+        return true;
+
+    case MPU9150_ACCELFSR_16:
+        m_accelFsr = fsr;
+        m_accelScale = 1.0/2048.0;
+        return true;
+
+    default:
+        HAL_ERROR1("Illegal MPU9150 accel fsr %d\n", fsr);
+        return false;
+    }
+}
+
+
+bool RTIMUMPU9150::IMUInit()
+{
+    unsigned char result;
+
+    m_firstTime = true;
+
+#ifdef MPU9150_CACHE_MODE
+    m_cacheIn = m_cacheOut = m_cacheCount = 0;
+#endif
+
+    // set validity flags
+
+    m_imuData.fusionPoseValid = false;
+    m_imuData.fusionQPoseValid = false;
+    m_imuData.gyroValid = true;
+    m_imuData.accelValid = true;
+    m_imuData.compassValid = true;
+    m_imuData.pressureValid = false;
+    m_imuData.temperatureValid = false;
+    m_imuData.humidityValid = false;
+
+    //  configure IMU
+
+    m_slaveAddr = m_settings->m_I2CSlaveAddress;
+
+    setSampleRate(m_settings->m_MPU9150GyroAccelSampleRate);
+    setCompassRate(m_settings->m_MPU9150CompassSampleRate);
+    setLpf(m_settings->m_MPU9150GyroAccelLpf);
+    setGyroFsr(m_settings->m_MPU9150GyroFsr);
+    setAccelFsr(m_settings->m_MPU9150AccelFsr);
+
+    setCalibrationData();
+
+    //  enable the I2C bus
+
+    if (!m_settings->HALOpen())
+        return false;
+
+    //  reset the MPU9150
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_PWR_MGMT_1, 0x80, "Failed to initiate MPU9150 reset"))
+        return false;
+
+    m_settings->delayMs(100);
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_PWR_MGMT_1, 0x00, "Failed to stop MPU9150 reset"))
+        return false;
+
+    if (!m_settings->HALRead(m_slaveAddr, MPU9150_WHO_AM_I, 1, &result, "Failed to read MPU9150 id"))
+        return false;
+
+    if (result != MPU9150_ID) {
+        HAL_ERROR1("Incorrect MPU9150 id %d\n", result);
+        return false;
+    }
+
+    //  now configure the various components
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_LPF_CONFIG, m_lpf, "Failed to set lpf"))
+        return false;
+
+    if (!setSampleRate())
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_GYRO_CONFIG, m_gyroFsr, "Failed to set gyro fsr"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_ACCEL_CONFIG, m_accelFsr, "Failed to set accel fsr"))
+         return false;
+
+    //  now configure compass
+
+    if (!configureCompass())
+        return false;
+
+    //  enable the sensors
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_PWR_MGMT_1, 1, "Failed to set pwr_mgmt_1"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_PWR_MGMT_2, 0, "Failed to set pwr_mgmt_2"))
+         return false;
+
+    //  select the data to go into the FIFO and enable
+
+    if (!resetFifo())
+        return false;
+
+    gyroBiasInit();
+
+    HAL_INFO("MPU9150 init complete\n");
+    return true;
+}
+
+bool RTIMUMPU9150::configureCompass()
+{
+    unsigned char asa[3];
+    unsigned char id;
+
+    m_compassIs5883 = false;
+    m_compassDataLength = 8;
+
+    bypassOn();
+
+    // get fuse ROM data
+
+    if (!m_settings->HALWrite(AK8975_ADDRESS, AK8975_CNTL, 0, "Failed to set MPU-9150 compass in power down mode 1")) {
+
+        //  check to see if an HMC5883L is fitted
+
+        if (!m_settings->HALRead(HMC5883_ADDRESS, HMC5883_ID, 1, &id, "Failed to find 5883")) {
+            bypassOff();
+
+            //  this is returning true so that MPU-6050 by itself will work
+
+            HAL_INFO("Detected MPU-6050 without compass\n");
+
+            m_imuData.compassValid = false;
+            return true;
+        }
+        if (id != 0x48) {                                   // incorrect id for HMC5883L
+
+            bypassOff();
+
+            //  this is returning true so that MPU-6050 by itself will work
+
+            HAL_INFO("Detected MPU-6050 without compass\n");
+
+            m_imuData.compassValid = false;
+            return true;
+        }
+
+        // HMC5883 is present - use that
+
+        if (!m_settings->HALWrite(HMC5883_ADDRESS, HMC5883_CONFIG_A, 0x38, "Failed to set HMC5883 config A")) {
+            bypassOff();
+            return false;
+        }
+
+        if (!m_settings->HALWrite(HMC5883_ADDRESS, HMC5883_CONFIG_B, 0x20, "Failed to set HMC5883 config B")) {
+            bypassOff();
+            return false;
+        }
+
+        if (!m_settings->HALWrite(HMC5883_ADDRESS, HMC5883_MODE, 0x00, "Failed to set HMC5883 mode")) {
+            bypassOff();
+            return false;
+        }
+
+        HAL_INFO("Detected MPU-6050 with HMC5883\n");
+
+        m_compassDataLength = 6;
+        m_compassIs5883 = true; 
+
+    } else {
+
+        if (!m_settings->HALWrite(AK8975_ADDRESS, AK8975_CNTL, 0x0f, "Failed to set compass in fuse ROM mode")) {
+            bypassOff();
+            return false;
+        }
+
+        if (!m_settings->HALRead(AK8975_ADDRESS, AK8975_ASAX, 3, asa, "")) {
+            bypassOff();
+            return false;
+        }
+
+        //  convert asa to usable scale factor
+
+        m_compassAdjust[0] = ((float)asa[0] - 128.0) / 256.0 + 1.0f;
+        m_compassAdjust[1] = ((float)asa[1] - 128.0) / 256.0 + 1.0f;
+        m_compassAdjust[2] = ((float)asa[2] - 128.0) / 256.0 + 1.0f;
+
+        if (!m_settings->HALWrite(AK8975_ADDRESS, AK8975_CNTL, 0, "Failed to set compass in power down mode 2")) {
+            bypassOff();
+            return false;
+        }
+    }
+
+    bypassOff();
+
+    //  now set up MPU9150 to talk to the compass chip
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_MST_CTRL, 0x40, "Failed to set I2C master mode"))
+        return false;
+
+    if (m_compassIs5883) {
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_SLV0_ADDR, 0x80 | HMC5883_ADDRESS, "Failed to set slave 0 address"))
+                return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_SLV0_REG, HMC5883_DATA_X_HI, "Failed to set slave 0 reg"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_SLV0_CTRL, 0x86, "Failed to set slave 0 ctrl"))
+            return false;
+    } else {
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_SLV0_ADDR, 0x80 | AK8975_ADDRESS, "Failed to set slave 0 address"))
+                return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_SLV0_REG, AK8975_ST1, "Failed to set slave 0 reg"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_SLV0_CTRL, 0x88, "Failed to set slave 0 ctrl"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_SLV1_ADDR, AK8975_ADDRESS, "Failed to set slave 1 address"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_SLV1_REG, AK8975_CNTL, "Failed to set slave 1 reg"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_SLV1_CTRL, 0x81, "Failed to set slave 1 ctrl"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_SLV1_DO, 0x1, "Failed to set slave 1 DO"))
+            return false;
+
+    }
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_MST_DELAY_CTRL, 0x3, "Failed to set mst delay"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_YG_OFFS_TC, 0x80, "Failed to set yg offs tc"))
+        return false;
+
+    if (!setCompassRate())
+        return false;
+
+    return true;
+}
+
+bool RTIMUMPU9150::resetFifo()
+{
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_INT_ENABLE, 0, "Writing int enable"))
+        return false;
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_FIFO_EN, 0, "Writing fifo enable"))
+        return false;
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_USER_CTRL, 0, "Writing user control"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_USER_CTRL, 0x04, "Resetting fifo"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_USER_CTRL, 0x60, "Enabling the fifo"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_INT_ENABLE, 1, "Writing int enable"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_FIFO_EN, 0x78, "Failed to set FIFO enables"))
+        return false;
+
+    return true;
+}
+
+bool RTIMUMPU9150::bypassOn()
+{
+    unsigned char userControl;
+
+    if (!m_settings->HALRead(m_slaveAddr, MPU9150_USER_CTRL, 1, &userControl, "Failed to read user_ctrl reg"))
+        return false;
+
+    userControl &= ~0x20;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_USER_CTRL, 1, &userControl, "Failed to write user_ctrl reg"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_INT_PIN_CFG, 0x82, "Failed to write int_pin_cfg reg"))
+        return false;
+
+    m_settings->delayMs(50);
+    return true;
+}
+
+
+bool RTIMUMPU9150::bypassOff()
+{
+    unsigned char userControl;
+
+    if (!m_settings->HALRead(m_slaveAddr, MPU9150_USER_CTRL, 1, &userControl, "Failed to read user_ctrl reg"))
+        return false;
+
+    userControl |= 0x20;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_USER_CTRL, 1, &userControl, "Failed to write user_ctrl reg"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_INT_PIN_CFG, 0x80, "Failed to write int_pin_cfg reg"))
+         return false;
+
+    m_settings->delayMs(50);
+    return true;
+}
+
+bool RTIMUMPU9150::setSampleRate()
+{
+    int clockRate = 1000;
+
+    if (m_lpf == MPU9150_LPF_256)
+        clockRate = 8000;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_SMPRT_DIV, (unsigned char)(clockRate / m_sampleRate - 1),
+                  "Failed to set sample rate"))
+        return false;
+
+    return true;
+}
+
+bool RTIMUMPU9150::setCompassRate()
+{
+    int rate;
+
+    rate = m_sampleRate / m_compassRate - 1;
+
+    if (rate > 31)
+        rate = 31;
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9150_I2C_SLV4_CTRL, rate, "Failed to set slave ctrl 4"))
+         return false;
+    return true;
+}
+
+int RTIMUMPU9150::IMUGetPollInterval()
+{
+    return (400 / m_sampleRate);
+}
+
+bool RTIMUMPU9150::IMURead()
+{
+    unsigned char fifoCount[2];
+    unsigned int count;
+    unsigned char fifoData[12];
+    unsigned char compassData[8];
+
+    if (!m_settings->HALRead(m_slaveAddr, MPU9150_FIFO_COUNT_H, 2, fifoCount, "Failed to read fifo count"))
+         return false;
+
+    count = ((unsigned int)fifoCount[0] << 8) + fifoCount[1];
+
+    if (count == 1024) {
+        HAL_INFO("MPU9150 fifo has overflowed");
+        resetFifo();
+        m_imuData.timestamp += m_sampleInterval * (1024 / MPU9150_FIFO_CHUNK_SIZE + 1); // try to fix timestamp
+        return false;
+    }
+
+
+#ifdef MPU9150_CACHE_MODE
+    if ((m_cacheCount == 0) && (count  >= MPU9150_FIFO_CHUNK_SIZE) && (count < (MPU9150_CACHE_SIZE * MPU9150_FIFO_CHUNK_SIZE))) {
+        // special case of a small fifo and nothing cached - just handle as simple read
+
+        if (!m_settings->HALRead(m_slaveAddr, MPU9150_FIFO_R_W, MPU9150_FIFO_CHUNK_SIZE, fifoData, "Failed to read fifo data"))
+            return false;
+
+        if (!m_settings->HALRead(m_slaveAddr, MPU9150_EXT_SENS_DATA_00, m_compassDataLength, compassData, "Failed to read compass data"))
+            return false;
+    } else {
+        if (count >= (MPU9150_CACHE_SIZE * MPU9150_FIFO_CHUNK_SIZE)) {
+            if (m_cacheCount == MPU9150_CACHE_BLOCK_COUNT) {
+                // all cache blocks are full - discard oldest and update timestamp to account for lost samples
+                m_imuData.timestamp += m_sampleInterval * m_cache[m_cacheOut].count;
+                if (++m_cacheOut == MPU9150_CACHE_BLOCK_COUNT)
+                    m_cacheOut = 0;
+                m_cacheCount--;
+            }
+
+            int blockCount = count / MPU9150_FIFO_CHUNK_SIZE;   // number of chunks in fifo
+
+            if (blockCount > MPU9150_CACHE_SIZE)
+                blockCount = MPU9150_CACHE_SIZE;
+
+            if (!m_settings->HALRead(m_slaveAddr, MPU9150_FIFO_R_W, MPU9150_FIFO_CHUNK_SIZE * blockCount,
+                                m_cache[m_cacheIn].data, "Failed to read fifo data"))
+                return false;
+
+            if (!m_settings->HALRead(m_slaveAddr, MPU9150_EXT_SENS_DATA_00, 8, m_cache[m_cacheIn].compass, "Failed to read compass data"))
+                return false;
+
+            m_cache[m_cacheIn].count = blockCount;
+            m_cache[m_cacheIn].index = 0;
+
+            m_cacheCount++;
+            if (++m_cacheIn == MPU9150_CACHE_BLOCK_COUNT)
+                m_cacheIn = 0;
+
+        }
+
+        //  now fifo has been read if necessary, get something to process
+
+        if (m_cacheCount == 0)
+            return false;
+
+        memcpy(fifoData, m_cache[m_cacheOut].data + m_cache[m_cacheOut].index, MPU9150_FIFO_CHUNK_SIZE);
+        memcpy(compassData, m_cache[m_cacheOut].compass, 8);
+
+        m_cache[m_cacheOut].index += MPU9150_FIFO_CHUNK_SIZE;
+
+        if (--m_cache[m_cacheOut].count == 0) {
+            //  this cache block is now empty
+
+            if (++m_cacheOut == MPU9150_CACHE_BLOCK_COUNT)
+                m_cacheOut = 0;
+            m_cacheCount--;
+        }
+    }
+
+#else
+
+    if (count > MPU9150_FIFO_CHUNK_SIZE * 40) {
+        // more than 40 samples behind - going too slowly so discard some samples but maintain timestamp correctly
+        while (count >= MPU9150_FIFO_CHUNK_SIZE * 10) {
+            if (!m_settings->HALRead(m_slaveAddr, MPU9150_FIFO_R_W, MPU9150_FIFO_CHUNK_SIZE, fifoData, "Failed to read fifo data"))
+                return false;
+            count -= MPU9150_FIFO_CHUNK_SIZE;
+            m_imuData.timestamp += m_sampleInterval;
+        }
+    }
+
+    if (count < MPU9150_FIFO_CHUNK_SIZE)
+        return false;
+
+    if (!m_settings->HALRead(m_slaveAddr, MPU9150_FIFO_R_W, MPU9150_FIFO_CHUNK_SIZE, fifoData, "Failed to read fifo data"))
+        return false;
+
+    if (!m_settings->HALRead(m_slaveAddr, MPU9150_EXT_SENS_DATA_00, m_compassDataLength, compassData, "Failed to read compass data"))
+        return false;
+
+#endif
+
+    RTMath::convertToVector(fifoData, m_imuData.accel, m_accelScale, true);
+    RTMath::convertToVector(fifoData + 6, m_imuData.gyro, m_gyroScale, true);
+
+    if (m_compassIs5883)
+        RTMath::convertToVector(compassData, m_imuData.compass, 0.092f, true);
+    else
+        RTMath::convertToVector(compassData + 1, m_imuData.compass, 0.3f, false);
+
+    //  sort out gyro axes
+
+    m_imuData.gyro.setX(m_imuData.gyro.x());
+    m_imuData.gyro.setY(-m_imuData.gyro.y());
+    m_imuData.gyro.setZ(-m_imuData.gyro.z());
+
+    //  sort out accel data;
+
+    m_imuData.accel.setX(-m_imuData.accel.x());
+
+
+    if (m_compassIs5883) {
+        //  sort out compass axes
+
+        float temp;
+
+        temp = m_imuData.compass.y();
+        m_imuData.compass.setY(-m_imuData.compass.z());
+        m_imuData.compass.setZ(-temp);
+
+    } else {
+
+        //  use the compass fuse data adjustments
+
+        m_imuData.compass.setX(m_imuData.compass.x() * m_compassAdjust[0]);
+        m_imuData.compass.setY(m_imuData.compass.y() * m_compassAdjust[1]);
+        m_imuData.compass.setZ(m_imuData.compass.z() * m_compassAdjust[2]);
+
+        //  sort out compass axes
+
+        float temp;
+
+        temp = m_imuData.compass.x();
+        m_imuData.compass.setX(m_imuData.compass.y());
+        m_imuData.compass.setY(-temp);
+    }
+
+
+    //  now do standard processing
+
+    handleGyroBias();
+    calibrateAverageCompass();
+    calibrateAccel();
+
+    if (m_firstTime)
+        m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+    else
+        m_imuData.timestamp += m_sampleInterval;
+
+    m_firstTime = false;
+
+    //  now update the filter
+
+    updateFusion();
+
+    return true;
+}
diff --git a/libraries/RTIMULib/utility/RTIMUMPU9150.h b/libraries/RTIMULib/utility/RTIMUMPU9150.h
new file mode 100644
index 0000000..b73da5a
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUMPU9150.h
@@ -0,0 +1,110 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTIMUMPU9150_H
+#define	_RTIMUMPU9150_H
+
+#include "RTIMU.h"
+
+//  Define this symbol to use cache mode
+
+#define MPU9150_CACHE_MODE
+
+//  FIFO transfer size
+
+#define MPU9150_FIFO_CHUNK_SIZE     12                      // gyro and accels take 12 bytes
+
+#ifdef MPU9150_CACHE_MODE
+
+//  Cache mode defines
+
+#define MPU9150_CACHE_SIZE          8                       // number of chunks in a block
+#define MPU9150_CACHE_BLOCK_COUNT   8                      // number of cache blocks
+
+typedef struct
+{
+    unsigned char data[MPU9150_FIFO_CHUNK_SIZE * MPU9150_CACHE_SIZE];
+    int count;                                              // number of chunks in the cache block
+    int index;                                              // current index into the cache
+    unsigned char compass[8];                               // the raw compass readings for the block
+
+} MPU9150_CACHE_BLOCK;
+
+#endif
+
+
+class RTIMUMPU9150 : public RTIMU
+{
+public:
+    RTIMUMPU9150(RTIMUSettings *settings);
+    ~RTIMUMPU9150();
+
+    bool setLpf(unsigned char lpf);
+    bool setSampleRate(int rate);
+    bool setCompassRate(int rate);
+    bool setGyroFsr(unsigned char fsr);
+    bool setAccelFsr(unsigned char fsr);
+
+    virtual const char *IMUName() { return "MPU-9150"; }
+    virtual int IMUType() { return RTIMU_TYPE_MPU9150; }
+    virtual bool IMUInit();
+    virtual bool IMURead();
+    virtual int IMUGetPollInterval();
+
+private:
+    bool configureCompass();                                // configures the compass
+    bool bypassOn();                                        // talk to compass
+    bool bypassOff();                                       // talk to MPU9150
+    bool setSampleRate();
+    bool setCompassRate();
+    bool resetFifo();
+
+    bool m_firstTime;                                       // if first sample
+
+    unsigned char m_slaveAddr;                              // I2C address of MPU9150
+
+    unsigned char m_lpf;                                    // low pass filter setting
+    int m_compassRate;                                      // compass sample rate in Hz
+    unsigned char m_gyroFsr;
+    unsigned char m_accelFsr;
+
+    RTFLOAT m_gyroScale;
+    RTFLOAT m_accelScale;
+
+    bool m_compassIs5883;                                   // if it is an MPU-6050/HMC5883 combo
+    int m_compassDataLength;                                // 8 for MPU-9150, 6 for HMC5883
+    RTFLOAT m_compassAdjust[3];                             // the compass fuse ROM values converted for use
+
+#ifdef MPU9150_CACHE_MODE
+
+    MPU9150_CACHE_BLOCK m_cache[MPU9150_CACHE_BLOCK_COUNT]; // the cache itself
+    int m_cacheIn;                                          // the in index
+    int m_cacheOut;                                         // the out index
+    int m_cacheCount;                                       // number of used cache blocks
+
+#endif
+
+};
+
+#endif // _RTIMUMPU9150_H
diff --git a/libraries/RTIMULib/utility/RTIMUMPU9250.cpp b/libraries/RTIMULib/utility/RTIMUMPU9250.cpp
new file mode 100644
index 0000000..f4ba577
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUMPU9250.cpp
@@ -0,0 +1,657 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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.
+
+//  The MPU-9250 and SPI driver code is based on code generously supplied by
+//  staslock@gmail.com (www.clickdrive.io)
+
+#include "RTIMUMPU9250.h"
+#include "RTIMUSettings.h"
+
+RTIMUMPU9250::RTIMUMPU9250(RTIMUSettings *settings) : RTIMU(settings)
+{
+
+}
+
+RTIMUMPU9250::~RTIMUMPU9250()
+{
+}
+
+bool RTIMUMPU9250::setSampleRate(int rate)
+{
+    if ((rate < MPU9250_SAMPLERATE_MIN) || (rate > MPU9250_SAMPLERATE_MAX)) {
+        HAL_ERROR1("Illegal sample rate %d\n", rate);
+        return false;
+    }
+
+    //  Note: rates interact with the lpf settings
+
+    if ((rate < MPU9250_SAMPLERATE_MAX) && (rate >= 8000))
+        rate = 8000;
+
+    if ((rate < 8000) && (rate >= 1000))
+        rate = 1000;
+
+    if (rate < 1000) {
+        int sampleDiv = (1000 / rate) - 1;
+        m_sampleRate = 1000 / (1 + sampleDiv);
+    } else {
+        m_sampleRate = rate;
+    }
+    m_sampleInterval = (uint64_t)1000000 / m_sampleRate;
+    return true;
+}
+
+bool RTIMUMPU9250::setGyroLpf(unsigned char lpf)
+{
+    switch (lpf) {
+    case MPU9250_GYRO_LPF_8800:
+    case MPU9250_GYRO_LPF_3600:
+    case MPU9250_GYRO_LPF_250:
+    case MPU9250_GYRO_LPF_184:
+    case MPU9250_GYRO_LPF_92:
+    case MPU9250_GYRO_LPF_41:
+    case MPU9250_GYRO_LPF_20:
+    case MPU9250_GYRO_LPF_10:
+    case MPU9250_GYRO_LPF_5:
+        m_gyroLpf = lpf;
+        return true;
+
+    default:
+        HAL_ERROR1("Illegal MPU9250 gyro lpf %d\n", lpf);
+        return false;
+    }
+}
+
+bool RTIMUMPU9250::setAccelLpf(unsigned char lpf)
+{
+    switch (lpf) {
+    case MPU9250_ACCEL_LPF_1130:
+    case MPU9250_ACCEL_LPF_460:
+    case MPU9250_ACCEL_LPF_184:
+    case MPU9250_ACCEL_LPF_92:
+    case MPU9250_ACCEL_LPF_41:
+    case MPU9250_ACCEL_LPF_20:
+    case MPU9250_ACCEL_LPF_10:
+    case MPU9250_ACCEL_LPF_5:
+        m_accelLpf = lpf;
+        return true;
+
+    default:
+        HAL_ERROR1("Illegal MPU9250 accel lpf %d\n", lpf);
+        return false;
+    }
+}
+
+
+bool RTIMUMPU9250::setCompassRate(int rate)
+{
+    if ((rate < MPU9250_COMPASSRATE_MIN) || (rate > MPU9250_COMPASSRATE_MAX)) {
+        HAL_ERROR1("Illegal compass rate %d\n", rate);
+        return false;
+    }
+    m_compassRate = rate;
+    return true;
+}
+
+bool RTIMUMPU9250::setGyroFsr(unsigned char fsr)
+{
+    switch (fsr) {
+    case MPU9250_GYROFSR_250:
+        m_gyroFsr = fsr;
+        m_gyroScale = RTMATH_PI / (131.0 * 180.0);
+        return true;
+
+    case MPU9250_GYROFSR_500:
+        m_gyroFsr = fsr;
+        m_gyroScale = RTMATH_PI / (62.5 * 180.0);
+        return true;
+
+    case MPU9250_GYROFSR_1000:
+        m_gyroFsr = fsr;
+        m_gyroScale = RTMATH_PI / (32.8 * 180.0);
+        return true;
+
+    case MPU9250_GYROFSR_2000:
+        m_gyroFsr = fsr;
+        m_gyroScale = RTMATH_PI / (16.4 * 180.0);
+        return true;
+
+    default:
+        HAL_ERROR1("Illegal MPU9250 gyro fsr %d\n", fsr);
+        return false;
+    }
+}
+
+bool RTIMUMPU9250::setAccelFsr(unsigned char fsr)
+{
+    switch (fsr) {
+    case MPU9250_ACCELFSR_2:
+        m_accelFsr = fsr;
+        m_accelScale = 1.0/16384.0;
+        return true;
+
+    case MPU9250_ACCELFSR_4:
+        m_accelFsr = fsr;
+        m_accelScale = 1.0/8192.0;
+        return true;
+
+    case MPU9250_ACCELFSR_8:
+        m_accelFsr = fsr;
+        m_accelScale = 1.0/4096.0;
+        return true;
+
+    case MPU9250_ACCELFSR_16:
+        m_accelFsr = fsr;
+        m_accelScale = 1.0/2048.0;
+        return true;
+
+    default:
+        HAL_ERROR1("Illegal MPU9250 accel fsr %d\n", fsr);
+        return false;
+    }
+}
+
+
+bool RTIMUMPU9250::IMUInit()
+{
+    unsigned char result;
+
+    m_firstTime = true;
+
+#ifdef MPU9250_CACHE_MODE
+    m_cacheIn = m_cacheOut = m_cacheCount = 0;
+#endif
+
+    // set validity flags
+
+    m_imuData.fusionPoseValid = false;
+    m_imuData.fusionQPoseValid = false;
+    m_imuData.gyroValid = true;
+    m_imuData.accelValid = true;
+    m_imuData.compassValid = true;
+    m_imuData.pressureValid = false;
+    m_imuData.temperatureValid = false;
+    m_imuData.humidityValid = false;
+
+    //  configure IMU
+
+    m_slaveAddr = m_settings->m_I2CSlaveAddress;
+
+    setSampleRate(m_settings->m_MPU9250GyroAccelSampleRate);
+    setCompassRate(m_settings->m_MPU9250CompassSampleRate);
+    setGyroLpf(m_settings->m_MPU9250GyroLpf);
+    setAccelLpf(m_settings->m_MPU9250AccelLpf);
+    setGyroFsr(m_settings->m_MPU9250GyroFsr);
+    setAccelFsr(m_settings->m_MPU9250AccelFsr);
+
+    setCalibrationData();
+
+
+    //  enable the bus
+
+    if (!m_settings->HALOpen())
+        return false;
+
+    //  reset the MPU9250
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_PWR_MGMT_1, 0x80, "Failed to initiate MPU9250 reset"))
+        return false;
+
+    m_settings->delayMs(100);
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_PWR_MGMT_1, 0x00, "Failed to stop MPU9250 reset"))
+        return false;
+
+    if (!m_settings->HALRead(m_slaveAddr, MPU9250_WHO_AM_I, 1, &result, "Failed to read MPU9250 id"))
+        return false;
+
+    if (result != MPU9250_ID) {
+        HAL_ERROR2("Incorrect %s id %d\n", IMUName(), result);
+        return false;
+    }
+
+    //  now configure the various components
+
+    if (!setGyroConfig())
+        return false;
+
+    if (!setAccelConfig())
+        return false;
+
+    if (!setSampleRate())
+        return false;
+
+    if(!compassSetup()) {
+        return false;
+    }
+
+    if (!setCompassRate())
+        return false;
+
+    //  enable the sensors
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_PWR_MGMT_1, 1, "Failed to set pwr_mgmt_1"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_PWR_MGMT_2, 0, "Failed to set pwr_mgmt_2"))
+         return false;
+
+    //  select the data to go into the FIFO and enable
+
+    if (!resetFifo())
+        return false;
+
+    gyroBiasInit();
+
+    HAL_INFO1("%s init complete\n", IMUName());
+    return true;
+}
+
+
+bool RTIMUMPU9250::resetFifo()
+{
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_INT_ENABLE, 0, "Writing int enable"))
+        return false;
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_FIFO_EN, 0, "Writing fifo enable"))
+        return false;
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_USER_CTRL, 0, "Writing user control"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_USER_CTRL, 0x04, "Resetting fifo"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_USER_CTRL, 0x60, "Enabling the fifo"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_INT_ENABLE, 1, "Writing int enable"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_FIFO_EN, 0x78, "Failed to set FIFO enables"))
+        return false;
+
+    return true;
+}
+
+bool RTIMUMPU9250::setGyroConfig()
+{
+    unsigned char gyroConfig = m_gyroFsr + ((m_gyroLpf >> 3) & 3);
+    unsigned char gyroLpf = m_gyroLpf & 7;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_GYRO_CONFIG, gyroConfig, "Failed to write gyro config"))
+         return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_GYRO_LPF, gyroLpf, "Failed to write gyro lpf"))
+         return false;
+    return true;
+}
+
+bool RTIMUMPU9250::setAccelConfig()
+{
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_ACCEL_CONFIG, m_accelFsr, "Failed to write accel config"))
+         return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_ACCEL_LPF, m_accelLpf, "Failed to write accel lpf"))
+         return false;
+    return true;
+}
+
+bool RTIMUMPU9250::setSampleRate()
+{
+    if (m_sampleRate > 1000)
+        return true;                                        // SMPRT not used above 1000Hz
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_SMPRT_DIV, (unsigned char) (1000 / m_sampleRate - 1),
+            "Failed to set sample rate"))
+        return false;
+
+    return true;
+}
+
+bool RTIMUMPU9250::compassSetup() {
+    unsigned char asa[3];
+
+    if (m_settings->m_busIsI2C) {
+        // I2C mode
+
+        bypassOn();
+
+        // get fuse ROM data
+
+        if (!m_settings->HALWrite(AK8963_ADDRESS, AK8963_CNTL, 0, "Failed to set compass in power down mode 1")) {
+            bypassOff();
+            return false;
+        }
+
+        if (!m_settings->HALWrite(AK8963_ADDRESS, AK8963_CNTL, 0x0f, "Failed to set compass in fuse ROM mode")) {
+            bypassOff();
+            return false;
+        }
+
+        if (!m_settings->HALRead(AK8963_ADDRESS, AK8963_ASAX, 3, asa, "Failed to read compass fuse ROM")) {
+            bypassOff();
+            return false;
+        }
+
+        if (!m_settings->HALWrite(AK8963_ADDRESS, AK8963_CNTL, 0, "Failed to set compass in power down mode 2")) {
+            bypassOff();
+            return false;
+        }
+
+        bypassOff();
+
+    } else {
+    //  SPI mode
+
+        bypassOff();
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_MST_CTRL, 0x40, "Failed to set I2C master mode"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV0_ADDR, 0x80 | AK8963_ADDRESS, "Failed to set slave 0 address"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV0_REG, AK8963_ASAX, "Failed to set slave 0 reg"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV0_CTRL, 0x83, "Failed to set slave 0 ctrl"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV1_ADDR, AK8963_ADDRESS, "Failed to set slave 1 address"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV1_REG, AK8963_CNTL, "Failed to set slave 1 reg"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV1_CTRL, 0x81, "Failed to set slave 1 ctrl"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV1_DO, 0x00, "Failed to set compass in power down mode 2"))
+            return false;
+
+        m_settings->delayMs(10);
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV1_DO, 0x0f, "Failed to set compass in fuse mode"))
+            return false;
+
+        if (!m_settings->HALRead(m_slaveAddr, MPU9250_EXT_SENS_DATA_00, 3, asa, "Failed to read compass rom"))
+            return false;
+
+        if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV1_DO, 0x0, "Failed to set compass in power down mode 2"))
+            return false;
+    }
+    //  both interfaces
+
+    //  convert asa to usable scale factor
+
+    m_compassAdjust[0] = ((float)asa[0] - 128.0) / 256.0 + 1.0f;
+    m_compassAdjust[1] = ((float)asa[1] - 128.0) / 256.0 + 1.0f;
+    m_compassAdjust[2] = ((float)asa[2] - 128.0) / 256.0 + 1.0f;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_MST_CTRL, 0x40, "Failed to set I2C master mode"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV0_ADDR, 0x80 | AK8963_ADDRESS, "Failed to set slave 0 address"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV0_REG, AK8963_ST1, "Failed to set slave 0 reg"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV0_CTRL, 0x88, "Failed to set slave 0 ctrl"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV1_ADDR, AK8963_ADDRESS, "Failed to set slave 1 address"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV1_REG, AK8963_CNTL, "Failed to set slave 1 reg"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV1_CTRL, 0x81, "Failed to set slave 1 ctrl"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV1_DO, 0x1, "Failed to set slave 1 DO"))
+        return false;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_MST_DELAY_CTRL, 0x3, "Failed to set mst delay"))
+        return false;
+
+    return true;
+}
+
+bool RTIMUMPU9250::setCompassRate()
+{
+    int rate;
+
+    rate = m_sampleRate / m_compassRate - 1;
+
+    if (rate > 31)
+        rate = 31;
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_I2C_SLV4_CTRL, rate, "Failed to set slave ctrl 4"))
+         return false;
+    return true;
+}
+
+
+bool RTIMUMPU9250::bypassOn()
+{
+    unsigned char userControl;
+
+    if (!m_settings->HALRead(m_slaveAddr, MPU9250_USER_CTRL, 1, &userControl, "Failed to read user_ctrl reg"))
+        return false;
+
+    userControl &= ~0x20;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_USER_CTRL, 1, &userControl, "Failed to write user_ctrl reg"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_INT_PIN_CFG, 0x82, "Failed to write int_pin_cfg reg"))
+        return false;
+
+    m_settings->delayMs(50);
+    return true;
+}
+
+
+bool RTIMUMPU9250::bypassOff()
+{
+    unsigned char userControl;
+
+    if (!m_settings->HALRead(m_slaveAddr, MPU9250_USER_CTRL, 1, &userControl, "Failed to read user_ctrl reg"))
+        return false;
+
+    userControl |= 0x20;
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_USER_CTRL, 1, &userControl, "Failed to write user_ctrl reg"))
+        return false;
+
+    m_settings->delayMs(50);
+
+    if (!m_settings->HALWrite(m_slaveAddr, MPU9250_INT_PIN_CFG, 0x80, "Failed to write int_pin_cfg reg"))
+         return false;
+
+    m_settings->delayMs(50);
+    return true;
+}
+
+
+int RTIMUMPU9250::IMUGetPollInterval()
+{
+    if (m_sampleRate > 400)
+        return 1;
+    else
+        return (400 / m_sampleRate);
+}
+
+bool RTIMUMPU9250::IMURead()
+{
+    unsigned char fifoCount[2];
+    unsigned int count;
+    unsigned char fifoData[12];
+    unsigned char compassData[8];
+
+    if (!m_settings->HALRead(m_slaveAddr, MPU9250_FIFO_COUNT_H, 2, fifoCount, "Failed to read fifo count"))
+         return false;
+
+    count = ((unsigned int)fifoCount[0] << 8) + fifoCount[1];
+
+    if (count == 512) {
+        HAL_INFO("MPU-9250 fifo has overflowed");
+        resetFifo();
+        m_imuData.timestamp += m_sampleInterval * (512 / MPU9250_FIFO_CHUNK_SIZE + 1); // try to fix timestamp
+        return false;
+    }
+
+#ifdef MPU9250_CACHE_MODE
+    if ((m_cacheCount == 0) && (count  >= MPU9250_FIFO_CHUNK_SIZE) && (count < (MPU9250_CACHE_SIZE * MPU9250_FIFO_CHUNK_SIZE))) {
+        // special case of a small fifo and nothing cached - just handle as simple read
+
+        if (!m_settings->HALRead(m_slaveAddr, MPU9250_FIFO_R_W, MPU9250_FIFO_CHUNK_SIZE, fifoData, "Failed to read fifo data"))
+            return false;
+
+        if (!m_settings->HALRead(m_slaveAddr, MPU9250_EXT_SENS_DATA_00, 8, compassData, "Failed to read compass data"))
+            return false;
+    } else {
+        if (count >= (MPU9250_CACHE_SIZE * MPU9250_FIFO_CHUNK_SIZE)) {
+            if (m_cacheCount == MPU9250_CACHE_BLOCK_COUNT) {
+                // all cache blocks are full - discard oldest and update timestamp to account for lost samples
+                m_imuData.timestamp += m_sampleInterval * m_cache[m_cacheOut].count;
+                if (++m_cacheOut == MPU9250_CACHE_BLOCK_COUNT)
+                    m_cacheOut = 0;
+                m_cacheCount--;
+            }
+
+            int blockCount = count / MPU9250_FIFO_CHUNK_SIZE;   // number of chunks in fifo
+
+            if (blockCount > MPU9250_CACHE_SIZE)
+                blockCount = MPU9250_CACHE_SIZE;
+
+            if (!m_settings->HALRead(m_slaveAddr, MPU9250_FIFO_R_W, MPU9250_FIFO_CHUNK_SIZE * blockCount,
+                    m_cache[m_cacheIn].data, "Failed to read fifo data"))
+                return false;
+
+            if (!m_settings->HALRead(m_slaveAddr, MPU9250_EXT_SENS_DATA_00, 8, m_cache[m_cacheIn].compass, "Failed to read compass data"))
+                return false;
+
+            m_cache[m_cacheIn].count = blockCount;
+            m_cache[m_cacheIn].index = 0;
+
+            m_cacheCount++;
+            if (++m_cacheIn == MPU9250_CACHE_BLOCK_COUNT)
+                m_cacheIn = 0;
+
+        }
+
+        //  now fifo has been read if necessary, get something to process
+
+        if (m_cacheCount == 0)
+            return false;
+
+        memcpy(fifoData, m_cache[m_cacheOut].data + m_cache[m_cacheOut].index, MPU9250_FIFO_CHUNK_SIZE);
+        memcpy(compassData, m_cache[m_cacheOut].compass, 8);
+
+        m_cache[m_cacheOut].index += MPU9250_FIFO_CHUNK_SIZE;
+
+        if (--m_cache[m_cacheOut].count == 0) {
+            //  this cache block is now empty
+
+            if (++m_cacheOut == MPU9250_CACHE_BLOCK_COUNT)
+                m_cacheOut = 0;
+            m_cacheCount--;
+        }
+    }
+
+#else
+
+    if (count > MPU9250_FIFO_CHUNK_SIZE * 40) {
+        // more than 40 samples behind - going too slowly so discard some samples but maintain timestamp correctly
+        while (count >= MPU9250_FIFO_CHUNK_SIZE * 10) {
+            if (!m_settings->HALRead(m_slaveAddr, MPU9250_FIFO_R_W, MPU9250_FIFO_CHUNK_SIZE, fifoData, "Failed to read fifo data"))
+                return false;
+            count -= MPU9250_FIFO_CHUNK_SIZE;
+            m_imuData.timestamp += m_sampleInterval;
+        }
+    }
+
+    if (count < MPU9250_FIFO_CHUNK_SIZE)
+        return false;
+
+    if (!m_settings->HALRead(m_slaveAddr, MPU9250_FIFO_R_W, MPU9250_FIFO_CHUNK_SIZE, fifoData, "Failed to read fifo data"))
+        return false;
+
+    if (!m_settings->HALRead(m_slaveAddr, MPU9250_EXT_SENS_DATA_00, 8, compassData, "Failed to read compass data"))
+        return false;
+
+#endif
+
+    RTMath::convertToVector(fifoData, m_imuData.accel, m_accelScale, true);
+    RTMath::convertToVector(fifoData + 6, m_imuData.gyro, m_gyroScale, true);
+    RTMath::convertToVector(compassData + 1, m_imuData.compass, 0.6f, false);
+
+    //  sort out gyro axes
+
+    m_imuData.gyro.setX(m_imuData.gyro.x());
+    m_imuData.gyro.setY(-m_imuData.gyro.y());
+    m_imuData.gyro.setZ(-m_imuData.gyro.z());
+
+    //  sort out accel data;
+
+    m_imuData.accel.setX(-m_imuData.accel.x());
+
+    //  use the compass fuse data adjustments
+
+    m_imuData.compass.setX(m_imuData.compass.x() * m_compassAdjust[0]);
+    m_imuData.compass.setY(m_imuData.compass.y() * m_compassAdjust[1]);
+    m_imuData.compass.setZ(m_imuData.compass.z() * m_compassAdjust[2]);
+
+    //  sort out compass axes
+
+    float temp;
+
+    temp = m_imuData.compass.x();
+    m_imuData.compass.setX(m_imuData.compass.y());
+    m_imuData.compass.setY(-temp);
+
+    //  now do standard processing
+
+    handleGyroBias();
+    calibrateAverageCompass();
+    calibrateAccel();
+
+    if (m_firstTime)
+        m_imuData.timestamp = RTMath::currentUSecsSinceEpoch();
+    else
+        m_imuData.timestamp += m_sampleInterval;
+
+    m_firstTime = false;
+
+    //  now update the filter
+
+    updateFusion();
+
+    return true;
+}
+
+
diff --git a/libraries/RTIMULib/utility/RTIMUMPU9250.h b/libraries/RTIMULib/utility/RTIMUMPU9250.h
new file mode 100644
index 0000000..52bebfd
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUMPU9250.h
@@ -0,0 +1,118 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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.
+
+//  The MPU-9250 and SPI driver code is based on code generously supplied by
+//  staslock@gmail.com (www.clickdrive.io)
+
+
+#ifndef _RTIMUMPU9250_H
+#define	_RTIMUMPU9250_H
+
+#include "RTIMU.h"
+
+//  Define this symbol to use cache mode
+
+#define MPU9250_CACHE_MODE
+
+//  FIFO transfer size
+
+#define MPU9250_FIFO_CHUNK_SIZE     12                      // gyro and accels take 12 bytes
+
+#ifdef MPU9250_CACHE_MODE
+
+//  Cache mode defines
+
+#define MPU9250_CACHE_SIZE          8                       // number of chunks in a block
+#define MPU9250_CACHE_BLOCK_COUNT   8                       // number of cache blocks
+
+typedef struct
+{
+    unsigned char data[MPU9250_FIFO_CHUNK_SIZE * MPU9250_CACHE_SIZE];
+    int count;                                              // number of chunks in the cache block
+    int index;                                              // current index into the cache
+    unsigned char compass[8];                               // the raw compass readings for the block
+
+} MPU9250_CACHE_BLOCK;
+
+#endif
+
+
+class RTIMUMPU9250 : public RTIMU
+{
+public:
+    RTIMUMPU9250(RTIMUSettings *settings);
+    ~RTIMUMPU9250();
+
+    bool setGyroLpf(unsigned char lpf);
+    bool setAccelLpf(unsigned char lpf);
+    bool setSampleRate(int rate);
+    bool setCompassRate(int rate);
+    bool setGyroFsr(unsigned char fsr);
+    bool setAccelFsr(unsigned char fsr);
+
+    virtual const char *IMUName() { return "MPU-9250"; }
+    virtual int IMUType() { return RTIMU_TYPE_MPU9250; }
+    virtual bool IMUInit();
+    virtual bool IMURead();
+    virtual int IMUGetPollInterval();
+
+protected:
+
+    RTFLOAT m_compassAdjust[3];                             // the compass fuse ROM values converted for use
+
+private:
+    bool setGyroConfig();
+    bool setAccelConfig();
+    bool setSampleRate();
+    bool compassSetup();
+    bool setCompassRate();
+    bool resetFifo();
+    bool bypassOn();
+    bool bypassOff();
+
+    bool m_firstTime;                                       // if first sample
+
+    unsigned char m_slaveAddr;                              // I2C address of MPU9150
+
+    unsigned char m_gyroLpf;                                // gyro low pass filter setting
+    unsigned char m_accelLpf;                               // accel low pass filter setting
+    int m_compassRate;                                      // compass sample rate in Hz
+    unsigned char m_gyroFsr;
+    unsigned char m_accelFsr;
+
+    RTFLOAT m_gyroScale;
+    RTFLOAT m_accelScale;
+
+
+#ifdef MPU9250_CACHE_MODE
+
+    MPU9250_CACHE_BLOCK m_cache[MPU9250_CACHE_BLOCK_COUNT]; // the cache itself
+    int m_cacheIn;                                          // the in index
+    int m_cacheOut;                                         // the out index
+    int m_cacheCount;                                       // number of used cache blocks
+
+#endif
+
+};
+
+#endif // _RTIMUMPU9250_H
diff --git a/libraries/RTIMULib/utility/RTIMUNull.cpp b/libraries/RTIMULib/utility/RTIMUNull.cpp
new file mode 100644
index 0000000..22c16cd
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUNull.cpp
@@ -0,0 +1,54 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTIMUNull.h"
+#include "RTIMUSettings.h"
+
+RTIMUNull::RTIMUNull(RTIMUSettings *settings) : RTIMU(settings)
+{
+}
+
+RTIMUNull::~RTIMUNull()
+{
+}
+
+bool RTIMUNull::IMUInit()
+{
+    return true;
+}
+
+int RTIMUNull::IMUGetPollInterval()
+{
+    return (100);                                           // just a dummy value really
+}
+
+bool RTIMUNull::IMURead()
+{
+    updateFusion();
+    return true;
+}
+
+void RTIMUNull::setIMUData(const RTIMU_DATA& data)
+{
+    m_imuData = data;
+}
diff --git a/libraries/RTIMULib/utility/RTIMUNull.h b/libraries/RTIMULib/utility/RTIMUNull.h
new file mode 100644
index 0000000..e8ed6fb
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTIMUNull.h
@@ -0,0 +1,58 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTIMUNULL_H
+#define	_RTIMUNULL_H
+
+//  IMUNull is a dummy IMU that assumes sensor data is coming from elsewhere,
+//  for example, across a network.
+//
+//  Call IMUInit in the normal way. Then for every update, call setIMUData and then IMURead
+//  to kick the kalman filter.
+
+#include "RTIMU.h"
+
+class RTIMUSettings;
+
+class RTIMUNull : public RTIMU
+{
+public:
+    RTIMUNull(RTIMUSettings *settings);
+    ~RTIMUNull();
+
+    // The timestamp parameter is assumed to be from RTMath::currentUSecsSinceEpoch()
+
+    void setIMUData(const RTIMU_DATA& data);
+
+    virtual const char *IMUName() { return "Null IMU"; }
+    virtual int IMUType() { return RTIMU_TYPE_NULL; }
+    virtual bool IMUInit();
+    virtual int IMUGetPollInterval();
+    virtual bool IMURead();
+    virtual bool IMUGyroBiasValid() { return true; }
+
+private:
+    uint64_t m_timestamp;
+};
+
+#endif // _RTIMUNULL_H
diff --git a/libraries/RTIMULib/utility/RTPressure.cpp b/libraries/RTIMULib/utility/RTPressure.cpp
new file mode 100644
index 0000000..e2e8489
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTPressure.cpp
@@ -0,0 +1,70 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTPressure.h"
+
+#include "RTPressureBMP180.h"
+#include "RTPressureLPS25H.h"
+#include "RTPressureMS5611.h"
+#include "RTPressureMS5637.h"
+
+RTPressure *RTPressure::createPressure(RTIMUSettings *settings)
+{
+    switch (settings->m_pressureType) {
+    case RTPRESSURE_TYPE_BMP180:
+        return new RTPressureBMP180(settings);
+
+    case RTPRESSURE_TYPE_LPS25H:
+        return new RTPressureLPS25H(settings);
+
+    case RTPRESSURE_TYPE_MS5611:
+        return new RTPressureMS5611(settings);
+
+    case RTPRESSURE_TYPE_MS5637:
+        return new RTPressureMS5637(settings);
+
+    case RTPRESSURE_TYPE_AUTODISCOVER:
+        if (settings->discoverPressure(settings->m_pressureType, settings->m_I2CPressureAddress)) {
+            settings->saveSettings();
+            return RTPressure::createPressure(settings);
+        }
+        return NULL;
+
+    case RTPRESSURE_TYPE_NULL:
+        return NULL;
+
+    default:
+        return NULL;
+    }
+}
+
+
+RTPressure::RTPressure(RTIMUSettings *settings)
+{
+    m_settings = settings;
+}
+
+RTPressure::~RTPressure()
+{
+}
diff --git a/libraries/RTIMULib/utility/RTPressure.h b/libraries/RTIMULib/utility/RTPressure.h
new file mode 100644
index 0000000..d7cd90c
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTPressure.h
@@ -0,0 +1,55 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTPRESSURELib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTPRESSURE_H
+#define	_RTPRESSURE_H
+
+#include "RTIMUSettings.h"
+#include "RTIMULibDefs.h"
+#include "RTPressureDefs.h"
+
+class RTPressure
+{
+public:
+    //  Pressure sensor objects should always be created with the following call
+
+    static RTPressure *createPressure(RTIMUSettings *settings);
+
+    //  Constructor/destructor
+
+    RTPressure(RTIMUSettings *settings);
+    virtual ~RTPressure();
+
+    //  These functions must be provided by sub classes
+
+    virtual const char *pressureName() = 0;                 // the name of the pressure sensor
+    virtual int pressureType() = 0;                         // the type code of the pressure sensor
+    virtual bool pressureInit() = 0;                        // set up the pressure sensor
+    virtual bool pressureRead(RTIMU_DATA& data) = 0;        // get latest value
+
+protected:
+    RTIMUSettings *m_settings;                              // the settings object pointer
+
+};
+
+#endif // _RTPRESSURE_H
diff --git a/libraries/RTIMULib/utility/RTPressureBMP180.cpp b/libraries/RTIMULib/utility/RTPressureBMP180.cpp
new file mode 100644
index 0000000..5e70de3
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTPressureBMP180.cpp
@@ -0,0 +1,230 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTPressureBMP180.h"
+
+RTPressureBMP180::RTPressureBMP180(RTIMUSettings *settings) : RTPressure(settings)
+{
+    m_validReadings = false;
+}
+
+RTPressureBMP180::~RTPressureBMP180()
+{
+}
+
+bool RTPressureBMP180::pressureInit()
+{
+    unsigned char result;
+    unsigned char data[22];
+
+    m_pressureAddr = m_settings->m_I2CPressureAddress;
+
+    // check ID of chip
+
+    if (!m_settings->HALRead(m_pressureAddr, BMP180_REG_ID, 1, &result, "Failed to read BMP180 id"))
+        return false;
+
+    if (result != BMP180_ID) {
+        HAL_ERROR1("Incorrect BMP180 id %d\n", result);
+        return false;
+    }
+
+    // get calibration data
+
+    if (!m_settings->HALRead(m_pressureAddr, BMP180_REG_AC1, 22, data, "Failed to read BMP180 calibration data"))
+        return false;
+
+    m_AC1 = (int16_t)(((uint16_t)data[0]) << 8) + (uint16_t)data[1];
+    m_AC2 = (int16_t)(((uint16_t)data[2]) << 8) + (uint16_t)data[3];
+    m_AC3 = (int16_t)(((uint16_t)data[4]) << 8) + (uint16_t)data[4];
+    m_AC4 = (((uint16_t)data[6]) << 8) + (uint16_t)data[7];
+    m_AC5 = (((uint16_t)data[8]) << 8) + (uint16_t)data[9];
+    m_AC6 = (((uint16_t)data[10]) << 8) + (uint16_t)data[11];
+    m_B1 = (int16_t)(((uint16_t)data[12]) << 8) + (uint16_t)data[13];
+    m_B2 = (int16_t)(((uint16_t)data[14]) << 8) + (uint16_t)data[15];
+    m_MB = (int16_t)(((uint16_t)data[16]) << 8) + (uint16_t)data[17];
+    m_MC = (int16_t)(((uint16_t)data[18]) << 8) + (uint16_t)data[19];
+    m_MD = (int16_t)(((uint16_t)data[20]) << 8) + (uint16_t)data[21];
+
+    m_state = BMP180_STATE_IDLE;
+    m_oss = BMP180_SCO_PRESSURECONV_ULP;
+    return true;
+}
+
+bool RTPressureBMP180::pressureRead(RTIMU_DATA& data)
+{
+    data.pressureValid = false;
+    data.temperatureValid = false;
+    data.temperature = 0;
+    data.pressure = 0;
+
+    if (m_state == BMP180_STATE_IDLE) {
+        // start a temperature conversion
+        if (!m_settings->HALWrite(m_pressureAddr, BMP180_REG_SCO, BMP180_SCO_TEMPCONV, "Failed to start temperature conversion")) {
+            return false;
+        } else {
+            m_state = BMP180_STATE_TEMPERATURE;
+        }
+    }
+
+    pressureBackground();
+
+    if (m_validReadings) {
+        data.pressureValid = true;
+        data.temperatureValid = true;
+        data.temperature = m_temperature;
+        data.pressure = m_pressure;
+        // printf("P: %f, T: %f\n", m_pressure, m_temperature);
+    }
+    return true;
+}
+
+
+void RTPressureBMP180::pressureBackground()
+{
+    uint8_t data[2];
+
+    switch (m_state) {
+        case BMP180_STATE_IDLE:
+        break;
+
+        case BMP180_STATE_TEMPERATURE:
+        if (!m_settings->HALRead(m_pressureAddr, BMP180_REG_SCO, 1, data, "Failed to read BMP180 temp conv status")) {
+            break;
+        }
+        if ((data[0] & 0x20) == 0x20)
+            break;                                      // conversion not finished
+        if (!m_settings->HALRead(m_pressureAddr, BMP180_REG_RESULT, 2, data, "Failed to read BMP180 temp conv result")) {
+            m_state = BMP180_STATE_IDLE;
+            break;
+        }
+        m_rawTemperature = (((uint16_t)data[0]) << 8) + (uint16_t)data[1];
+
+        data[0] = 0x34 + (m_oss << 6);
+        if (!m_settings->HALWrite(m_pressureAddr, BMP180_REG_SCO, 1, data, "Failed to start pressure conversion")) {
+            m_state = BMP180_STATE_IDLE;
+            break;
+        }
+        m_state = BMP180_STATE_PRESSURE;
+        break;
+
+        case BMP180_STATE_PRESSURE:
+        if (!m_settings->HALRead(m_pressureAddr, BMP180_REG_SCO, 1, data, "Failed to read BMP180 pressure conv status")) {
+            break;
+        }
+        if ((data[0] & 0x20) == 0x20)
+            break;                                      // conversion not finished
+        if (!m_settings->HALRead(m_pressureAddr, BMP180_REG_RESULT, 2, data, "Failed to read BMP180 temp conv result")) {
+            m_state = BMP180_STATE_IDLE;
+            break;
+        }
+        m_rawPressure = (((uint16_t)data[0]) << 8) + (uint16_t)data[1];
+
+        if (!m_settings->HALRead(m_pressureAddr, BMP180_REG_XLSB, 1, data, "Failed to read BMP180 XLSB")) {
+            m_state = BMP180_STATE_IDLE;
+            break;
+        }
+
+        // call this function for testing only
+        // should give T = 150 (15.0C) and pressure 6996 (699.6hPa)
+
+        // setTestData();
+
+        int32_t pressure = ((((uint32_t)(m_rawPressure)) << 8) + (uint32_t)(data[0])) >> (8 - m_oss);
+
+        m_state = BMP180_STATE_IDLE;
+
+        // calculate compensated temperature
+
+        int32_t X1 = (((int32_t)m_rawTemperature - m_AC6) * m_AC5) / 32768;
+
+        if ((X1 + m_MD) == 0) {
+            break;
+        }
+
+        int32_t X2 = (m_MC * 2048)  / (X1 + m_MD);
+        int32_t B5 = X1 + X2;
+        m_temperature = (RTFLOAT)((B5 + 8) / 16) / (RTFLOAT)10;
+
+        // calculate compensated pressure
+
+        int32_t B6 = B5 - 4000;
+        //          printf("B6 = %d\n", B6);
+        X1 = (m_B2 * ((B6 * B6) / 4096)) / 2048;
+        //          printf("X1 = %d\n", X1);
+        X2 = (m_AC2 * B6) / 2048;
+        //          printf("X2 = %d\n", X2);
+        int32_t X3 = X1 + X2;
+        //          printf("X3 = %d\n", X3);
+        int32_t B3 = (((m_AC1 * 4 + X3) << m_oss) + 2) / 4;
+        //          printf("B3 = %d\n", B3);
+        X1 = (m_AC3 * B6) / 8192;
+        //          printf("X1 = %d\n", X1);
+        X2 = (m_B1 * ((B6 * B6) / 4096)) / 65536;
+        //          printf("X2 = %d\n", X2);
+        X3 = ((X1 + X2) + 2) / 4;
+        //          printf("X3 = %d\n", X3);
+        int32_t B4 = (m_AC4 * (unsigned long)(X3 + 32768)) / 32768;
+        //          printf("B4 = %d\n", B4);
+        uint32_t B7 = ((unsigned long)pressure - B3) * (50000 >> m_oss);
+        //          printf("B7 = %d\n", B7);
+
+        int32_t p;
+        if (B7 < 0x80000000)
+        p = (B7 * 2) / B4;
+            else
+        p = (B7 / B4) * 2;
+
+        //          printf("p = %d\n", p);
+        X1 = (p / 256) * (p / 256);
+        //          printf("X1 = %d\n", X1);
+        X1 = (X1 * 3038) / 65536;
+        //          printf("X1 = %d\n", X1);
+        X2 = (-7357 * p) / 65536;
+        //          printf("X2 = %d\n", X2);
+        m_pressure = (RTFLOAT)(p + (X1 + X2 + 3791) / 16) / (RTFLOAT)100;      // the extra 100 factor is to get 1hPa units
+
+        m_validReadings = true;
+
+        // printf("UP = %d, P = %f, UT = %d, T = %f\n", m_rawPressure, m_pressure, m_rawTemperature, m_temperature);
+        break;
+    }
+}
+
+void RTPressureBMP180::setTestData()
+{
+    m_AC1 = 408;
+    m_AC2 = -72;
+    m_AC3 = -14383;
+    m_AC4 = 32741;
+    m_AC5 = 32757;
+    m_AC6 = 23153;
+    m_B1 = 6190;
+    m_B2 = 4;
+    m_MB = -32767;
+    m_MC = -8711;
+    m_MD = 2868;
+
+    m_rawTemperature = 27898;
+    m_rawPressure = 23843;
+}
diff --git a/libraries/RTIMULib/utility/RTPressureBMP180.h b/libraries/RTIMULib/utility/RTPressureBMP180.h
new file mode 100644
index 0000000..3a6d263
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTPressureBMP180.h
@@ -0,0 +1,88 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTPRESSUREBMP180_H_
+#define _RTPRESSUREBMP180_H_
+
+#include "RTPressure.h"
+
+//  State definitions
+
+#define BMP180_STATE_IDLE               0
+#define BMP180_STATE_TEMPERATURE        1
+#define BMP180_STATE_PRESSURE           2
+
+//  Conversion reg defs
+
+#define BMP180_SCO_TEMPCONV             0x2e                // temperature conversion
+#define BMP180_SCO_PRESSURECONV_ULP     0                   // ultra low power pressure conversion
+#define BMP180_SCO_PRESSURECONV_STD     1                   // standard pressure conversion
+#define BMP180_SCO_PRESSURECONV_HR      2                   // high res pressure conversion
+#define BMP180_SCO_PRESSURECONV_UHR     3                   // ultra high res pressure conversion
+
+class RTIMUSettings;
+
+class RTPressureBMP180 : public RTPressure
+{
+public:
+    RTPressureBMP180(RTIMUSettings *settings);
+    ~RTPressureBMP180();
+
+    virtual const char *pressureName() { return "BMP180"; }
+    virtual int pressureType() { return RTPRESSURE_TYPE_BMP180; }
+    virtual bool pressureInit();
+    virtual bool pressureRead(RTIMU_DATA& data);
+
+private:
+    void pressureBackground();
+    void setTestData();
+
+    unsigned char m_pressureAddr;                           // I2C address
+    RTFLOAT m_pressure;                                     // the current pressure
+    RTFLOAT m_temperature;                                  // the current temperature
+
+    // This is the calibration data read from the sensor
+
+    int32_t m_AC1;
+    int32_t m_AC2;
+    int32_t m_AC3;
+    uint32_t m_AC4;
+    uint32_t m_AC5;
+    uint32_t m_AC6;
+    int32_t m_B1;
+    int32_t m_B2;
+    int32_t m_MB;
+    int32_t m_MC;
+    int32_t m_MD;
+
+    int m_state;
+    int m_oss;
+
+    uint16_t m_rawPressure;
+    uint16_t m_rawTemperature;
+
+    bool m_validReadings;
+};
+
+#endif // _RTPRESSUREBMP180_H_
+
diff --git a/libraries/RTIMULib/utility/RTPressureDefs.h b/libraries/RTIMULib/utility/RTPressureDefs.h
new file mode 100644
index 0000000..e273620
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTPressureDefs.h
@@ -0,0 +1,105 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTPRESSUREDEFS_H
+#define	_RTPRESSUREDEFS_H
+
+//  Pressure sensor type codes
+
+#define RTPRESSURE_TYPE_AUTODISCOVER        0                   // audodiscover the pressure sensor
+#define RTPRESSURE_TYPE_NULL                1                   // if no physical hardware
+#define RTPRESSURE_TYPE_BMP180              2                   // BMP180
+#define RTPRESSURE_TYPE_LPS25H              3                   // LPS25H
+#define RTPRESSURE_TYPE_MS5611              4                   // MS5611
+#define RTPRESSURE_TYPE_MS5637              5                   // MS5637
+
+//----------------------------------------------------------
+//
+//  BMP180
+
+//  BMP180 I2C Slave Addresses
+
+#define BMP180_ADDRESS              0x77
+#define BMP180_REG_ID               0xd0
+#define BMP180_ID                   0x55
+
+//	Register map
+
+#define BMP180_REG_AC1              0xaa
+#define BMP180_REG_SCO              0xf4
+#define BMP180_REG_RESULT           0xf6
+#define BMP180_REG_XLSB             0xf8
+
+//----------------------------------------------------------
+//
+//  LPS25H
+
+//  LPS25H I2C Slave Addresses
+
+#define LPS25H_ADDRESS0             0x5c
+#define LPS25H_ADDRESS1             0x5d
+#define LPS25H_REG_ID               0x0f
+#define LPS25H_ID                   0xbd
+
+//	Register map
+
+#define LPS25H_REF_P_XL             0x08
+#define LPS25H_REF_P_XH             0x09
+#define LPS25H_RES_CONF             0x10
+#define LPS25H_CTRL_REG_1           0x20
+#define LPS25H_CTRL_REG_2           0x21
+#define LPS25H_CTRL_REG_3           0x22
+#define LPS25H_CTRL_REG_4           0x23
+#define LPS25H_INT_CFG              0x24
+#define LPS25H_INT_SOURCE           0x25
+#define LPS25H_STATUS_REG           0x27
+#define LPS25H_PRESS_OUT_XL         0x28
+#define LPS25H_PRESS_OUT_L          0x29
+#define LPS25H_PRESS_OUT_H          0x2a
+#define LPS25H_TEMP_OUT_L           0x2b
+#define LPS25H_TEMP_OUT_H           0x2c
+#define LPS25H_FIFO_CTRL            0x2e
+#define LPS25H_FIFO_STATUS          0x2f
+#define LPS25H_THS_P_L              0x30
+#define LPS25H_THS_P_H              0x31
+#define LPS25H_RPDS_L               0x39
+#define LPS25H_RPDS_H               0x3a
+
+//----------------------------------------------------------
+//
+//  MS5611
+
+//  MS5611 I2C Slave Addresses
+
+#define MS5611_ADDRESS0             0x76
+#define MS5611_ADDRESS1             0x77
+
+//	commands
+
+#define MS5611_CMD_RESET            0x1e
+#define MS5611_CMD_CONV_D1          0x48
+#define MS5611_CMD_CONV_D2          0x58
+#define MS5611_CMD_PROM             0xa0
+#define MS5611_CMD_ADC              0x00
+
+#endif // _RTPRESSUREDEFS_H
diff --git a/libraries/RTIMULib/utility/RTPressureLPS25H.cpp b/libraries/RTIMULib/utility/RTPressureLPS25H.cpp
new file mode 100644
index 0000000..a734af8
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTPressureLPS25H.cpp
@@ -0,0 +1,91 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTPressureLPS25H.h"
+#include "RTPressureDefs.h"
+
+RTPressureLPS25H::RTPressureLPS25H(RTIMUSettings *settings) : RTPressure(settings)
+{
+    m_pressureValid = false;
+    m_temperatureValid = false;
+ }
+
+RTPressureLPS25H::~RTPressureLPS25H()
+{
+}
+
+bool RTPressureLPS25H::pressureInit()
+{
+    m_pressureAddr = m_settings->m_I2CPressureAddress;
+
+    if (!m_settings->HALWrite(m_pressureAddr, LPS25H_CTRL_REG_1, 0xc4, "Failed to set LPS25H CTRL_REG_1"))
+        return false;
+
+    if (!m_settings->HALWrite(m_pressureAddr, LPS25H_RES_CONF, 0x05, "Failed to set LPS25H RES_CONF"))
+        return false;
+
+    if (!m_settings->HALWrite(m_pressureAddr, LPS25H_FIFO_CTRL, 0xc0, "Failed to set LPS25H FIFO_CTRL"))
+        return false;
+
+    if (!m_settings->HALWrite(m_pressureAddr, LPS25H_CTRL_REG_2, 0x40, "Failed to set LPS25H CTRL_REG_2"))
+        return false;
+
+    return true;
+}
+
+
+bool RTPressureLPS25H::pressureRead(RTIMU_DATA& data)
+{
+    unsigned char rawData[3];
+    unsigned char status;
+
+    data.pressureValid = false;
+    data.temperatureValid = false;
+    data.temperature = 0;
+    data.pressure = 0;
+
+    if (!m_settings->HALRead(m_pressureAddr, LPS25H_STATUS_REG, 1, &status, "Failed to read LPS25H status"))
+        return false;
+
+    if (status & 2) {
+        if (!m_settings->HALRead(m_pressureAddr, LPS25H_PRESS_OUT_XL + 0x80, 3, rawData, "Failed to read LPS25H pressure"))
+            return false;
+
+        m_pressure = (RTFLOAT)((((unsigned int)rawData[2]) << 16) | (((unsigned int)rawData[1]) << 8) | (unsigned int)rawData[0]) / (RTFLOAT)4096;
+        m_pressureValid = true;
+    }
+    if (status & 1) {
+        if (!m_settings->HALRead(m_pressureAddr, LPS25H_TEMP_OUT_L + 0x80, 2, rawData, "Failed to read LPS25H temperature"))
+            return false;
+
+        m_temperature = (int16_t)((((unsigned int)rawData[1]) << 8) | (unsigned int)rawData[0]) / (RTFLOAT)480 + (RTFLOAT)42.5;
+        m_temperatureValid = true;
+    }
+
+    data.pressureValid = m_pressureValid;
+    data.pressure = m_pressure;
+    data.temperatureValid = m_temperatureValid;
+    data.temperature = m_temperature;
+
+    return true;
+}
diff --git a/libraries/RTIMULib/utility/RTPressureLPS25H.h b/libraries/RTIMULib/utility/RTPressureLPS25H.h
new file mode 100644
index 0000000..96c06e1
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTPressureLPS25H.h
@@ -0,0 +1,53 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTPRESSURELPS25H_H_
+#define _RTPRESSURELPS25H_H_
+
+#include "RTPressure.h"
+
+class RTIMUSettings;
+
+class RTPressureLPS25H : public RTPressure
+{
+public:
+    RTPressureLPS25H(RTIMUSettings *settings);
+    ~RTPressureLPS25H();
+
+    virtual const char *pressureName() { return "LPS25H"; }
+    virtual int pressureType() { return RTPRESSURE_TYPE_LPS25H; }
+    virtual bool pressureInit();
+    virtual bool pressureRead(RTIMU_DATA& data);
+
+private:
+    unsigned char m_pressureAddr;                           // I2C address
+
+    RTFLOAT m_pressure;                                     // the current pressure
+    RTFLOAT m_temperature;                                  // the current temperature
+    bool m_pressureValid;
+    bool m_temperatureValid;
+
+};
+
+#endif // _RTPRESSURELPS25H_H_
+
diff --git a/libraries/RTIMULib/utility/RTPressureMS5611.cpp b/libraries/RTIMULib/utility/RTPressureMS5611.cpp
new file mode 100644
index 0000000..c702f91
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTPressureMS5611.cpp
@@ -0,0 +1,170 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTPressureMS5611.h"
+
+RTPressureMS5611::RTPressureMS5611(RTIMUSettings *settings) : RTPressure(settings)
+{
+    m_validReadings = false;
+}
+
+RTPressureMS5611::~RTPressureMS5611()
+{
+}
+
+bool RTPressureMS5611::pressureInit()
+{
+    unsigned char cmd = MS5611_CMD_PROM + 2;
+    unsigned char data[2];
+
+    m_pressureAddr = m_settings->m_I2CPressureAddress;
+
+    // get calibration data
+
+    for (int i = 0; i < 6; i++) {
+        if (!m_settings->HALRead(m_pressureAddr, cmd, 2, data, "Failed to read MS5611 calibration data"))
+            return false;
+        m_calData[i] = (((uint16_t)data[0]) << 8) + (uint16_t)data[1];
+        // printf("Cal index: %d, data: %d\n", i, m_calData[i]);
+        cmd += 2;
+    }
+
+    m_state = MS5611_STATE_IDLE;
+    return true;
+}
+
+bool RTPressureMS5611::pressureRead(RTIMU_DATA& data)
+{
+    data.pressureValid = false;
+    data.temperatureValid = false;
+    data.temperature = 0;
+    data.pressure = 0;
+
+    if (m_state == MS5611_STATE_IDLE) {
+        // start pressure conversion
+        if (!m_settings->HALWrite(m_pressureAddr, MS5611_CMD_CONV_D1, 0, 0, "Failed to start MS5611 pressure conversion")) {
+            return false;
+        } else {
+            m_state = MS5611_STATE_PRESSURE;
+            m_timer = RTMath::currentUSecsSinceEpoch();
+        }
+    }
+
+    pressureBackground();
+
+    if (m_validReadings) {
+        data.pressureValid = true;
+        data.temperatureValid = true;
+        data.temperature = m_temperature;
+        data.pressure = m_pressure;
+    }
+    return true;
+}
+
+
+void RTPressureMS5611::pressureBackground()
+{
+    uint8_t data[3];
+
+    switch (m_state) {
+        case MS5611_STATE_IDLE:
+        break;
+
+        case MS5611_STATE_PRESSURE:
+        if ((RTMath::currentUSecsSinceEpoch() - m_timer) < 10000)
+            break;                                          // not time yet
+        if (!m_settings->HALRead(m_pressureAddr, MS5611_CMD_ADC, 3, data, "Failed to read MS5611 pressure")) {
+            break;
+        }
+        m_D1 = (((uint32_t)data[0]) << 16) + (((uint32_t)data[1]) << 8) + (uint32_t)data[2];
+
+        // start temperature conversion
+
+        if (!m_settings->HALWrite(m_pressureAddr, MS5611_CMD_CONV_D2, 0, 0, "Failed to start MS5611 temperature conversion")) {
+            break;
+        } else {
+            m_state = MS5611_STATE_TEMPERATURE;
+            m_timer = RTMath::currentUSecsSinceEpoch();
+        }
+        break;
+
+        case MS5611_STATE_TEMPERATURE:
+        if ((RTMath::currentUSecsSinceEpoch() - m_timer) < 10000)
+            break;                                          // not time yet
+        if (!m_settings->HALRead(m_pressureAddr, MS5611_CMD_ADC, 3, data, "Failed to read MS5611 temperature")) {
+            break;
+        }
+        m_D2 = (((uint32_t)data[0]) << 16) + (((uint32_t)data[1]) << 8) + (uint32_t)data[2];
+
+        //  call this function for testing only
+        //  should give T = 2007 (20.07C) and pressure 100009 (1000.09hPa)
+
+        // setTestData();
+
+        //  now calculate the real values
+
+        int64_t deltaT = (int32_t)m_D2 - (((int32_t)m_calData[4]) << 8);
+
+        int32_t temperature = 2000 + ((deltaT * (int64_t)m_calData[5]) >> 23); // note - this needs to be divided by 100
+
+        int64_t offset = ((int64_t)m_calData[1] << 16) + (((int64_t)m_calData[3] * deltaT) >> 7);
+        int64_t sens = ((int64_t)m_calData[0] << 15) + (((int64_t)m_calData[2] * deltaT) >> 8);
+
+        //  do second order temperature compensation
+
+        if (temperature < 2000) {
+            int64_t T2 = (deltaT * deltaT) >> 31;
+            int64_t offset2 = 5 * ((temperature - 2000) * (temperature - 2000)) / 2;
+            int64_t sens2 = offset2 / 2;
+            if (temperature < -1500) {
+                offset2 += 7 * (temperature + 1500) * (temperature + 1500);
+                sens2 += 11 * ((temperature + 1500) * (temperature + 1500)) / 2;
+            }
+            temperature -= T2;
+            offset -= offset2;
+            sens -=sens2;
+        }
+
+        m_pressure = (RTFLOAT)(((((int64_t)m_D1 * sens) >> 21) - offset) >> 15) / (RTFLOAT)100.0;
+        m_temperature = (RTFLOAT)temperature/(RTFLOAT)100;
+
+        // printf("Temp: %f, pressure: %f\n", m_temperature, m_pressure);
+
+        m_validReadings = true;
+        m_state = MS5611_STATE_IDLE;
+        break;
+    }
+}
+
+void RTPressureMS5611::setTestData()
+{
+    m_calData[0] = 40127;
+    m_calData[1] = 36924;
+    m_calData[2] = 23317;
+    m_calData[3] = 23282;
+    m_calData[4] = 33464;
+    m_calData[5] = 28312;
+
+    m_D1 = 9085466;
+    m_D2 = 8569150;
+}
diff --git a/libraries/RTIMULib/utility/RTPressureMS5611.h b/libraries/RTIMULib/utility/RTPressureMS5611.h
new file mode 100644
index 0000000..a31f550
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTPressureMS5611.h
@@ -0,0 +1,69 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTPRESSUREMS5611_H_
+#define _RTPRESSUREMS5611_H_
+
+#include "RTPressure.h"
+
+//  State definitions
+
+#define MS5611_STATE_IDLE               0
+#define MS5611_STATE_TEMPERATURE        1
+#define MS5611_STATE_PRESSURE           2
+
+class RTIMUSettings;
+
+class RTPressureMS5611 : public RTPressure
+{
+public:
+    RTPressureMS5611(RTIMUSettings *settings);
+    ~RTPressureMS5611();
+
+    virtual const char *pressureName() { return "MS5611"; }
+    virtual int pressureType() { return RTPRESSURE_TYPE_MS5611; }
+    virtual bool pressureInit();
+    virtual bool pressureRead(RTIMU_DATA& data);
+
+private:
+    void pressureBackground();
+    void setTestData();
+
+    unsigned char m_pressureAddr;                           // I2C address
+    RTFLOAT m_pressure;                                     // the current pressure
+    RTFLOAT m_temperature;                                  // the current temperature
+
+    int m_state;
+
+    uint16_t m_calData[6];                                  // calibration data
+
+    uint32_t m_D1;
+    uint32_t m_D2;
+
+    uint64_t m_timer;                                       // used to time coversions
+
+    bool m_validReadings;
+};
+
+#endif // _RTPRESSUREMS5611_H_
+
diff --git a/libraries/RTIMULib/utility/RTPressureMS5637.cpp b/libraries/RTIMULib/utility/RTPressureMS5637.cpp
new file mode 100644
index 0000000..1d73acf
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTPressureMS5637.cpp
@@ -0,0 +1,172 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 "RTPressureMS5637.h"
+
+RTPressureMS5637::RTPressureMS5637(RTIMUSettings *settings) : RTPressure(settings)
+{
+    m_validReadings = false;
+}
+
+RTPressureMS5637::~RTPressureMS5637()
+{
+}
+
+bool RTPressureMS5637::pressureInit()
+{
+    unsigned char cmd = MS5611_CMD_PROM + 2;
+    unsigned char data[2];
+
+    m_pressureAddr = m_settings->m_I2CPressureAddress;
+
+    // get calibration data
+
+    for (int i = 0; i < 6; i++) {
+        if (!m_settings->HALRead(m_pressureAddr, cmd, 2, data, "Failed to read MS5611 calibration data"))
+            return false;
+        m_calData[i] = (((uint16_t)data[0]) << 8) | ((uint16_t)data[1]);
+        // printf("Cal index: %d, data: %d\n", i, m_calData[i]);
+        cmd += 2;
+    }
+
+    m_state = MS5637_STATE_IDLE;
+    return true;
+}
+
+bool RTPressureMS5637::pressureRead(RTIMU_DATA& data)
+{
+    data.pressureValid = false;
+    data.temperatureValid = false;
+    data.temperature = 0;
+    data.pressure = 0;
+
+    if (m_state == MS5637_STATE_IDLE) {
+        // start pressure conversion
+        if (!m_settings->HALWrite(m_pressureAddr, MS5611_CMD_CONV_D1, 0, 0, "Failed to start MS5611 pressure conversion")) {
+            return false;
+        } else {
+            m_state = MS5637_STATE_PRESSURE;
+            m_timer = RTMath::currentUSecsSinceEpoch();
+        }
+    }
+
+    pressureBackground();
+
+    if (m_validReadings) {
+        data.pressureValid = true;
+        data.temperatureValid = true;
+        data.temperature = m_temperature;
+        data.pressure = m_pressure;
+    }
+    return true;
+}
+
+
+void RTPressureMS5637::pressureBackground()
+{
+    uint8_t data[3];
+
+    switch (m_state) {
+        case MS5637_STATE_IDLE:
+        break;
+
+        case MS5637_STATE_PRESSURE:
+        if ((RTMath::currentUSecsSinceEpoch() - m_timer) < 10000)
+            break;                                          // not time yet
+        if (!m_settings->HALRead(m_pressureAddr, MS5611_CMD_ADC, 3, data, "Failed to read MS5611 pressure")) {
+            break;
+        }
+        m_D1 = (((uint32_t)data[0]) << 16) | (((uint32_t)data[1]) << 8) | ((uint32_t)data[2]);
+
+        // start temperature conversion
+
+        if (!m_settings->HALWrite(m_pressureAddr, MS5611_CMD_CONV_D2, 0, 0, "Failed to start MS5611 temperature conversion")) {
+            break;
+        } else {
+            m_state = MS5637_STATE_TEMPERATURE;
+            m_timer = RTMath::currentUSecsSinceEpoch();
+        }
+        break;
+
+        case MS5637_STATE_TEMPERATURE:
+        if ((RTMath::currentUSecsSinceEpoch() - m_timer) < 10000)
+            break;                                          // not time yet
+        if (!m_settings->HALRead(m_pressureAddr, MS5611_CMD_ADC, 3, data, "Failed to read MS5611 temperature")) {
+            break;
+        }
+        m_D2 = (((uint32_t)data[0]) << 16) | (((uint32_t)data[1]) << 8) | ((uint32_t)data[2]);
+
+        //  call this function for testing only
+        //  should give T = 2000 (20.00C) and pressure 110002 (1100.02hPa)
+
+        // setTestData();
+
+        //  now calculate the real values
+
+        int64_t deltaT = (int32_t)m_D2 - (((int32_t)m_calData[4]) << 8);
+
+        int32_t temperature = 2000 + ((deltaT * (int64_t)m_calData[5]) >> 23); // note - this still needs to be divided by 100
+
+        int64_t offset = (((int64_t)m_calData[1]) << 17) + ((m_calData[3] * deltaT) >> 6);
+        int64_t sens = (((int64_t)m_calData[0]) << 16) + ((m_calData[2] * deltaT) >> 7);
+
+        //  do second order temperature compensation
+
+        if (temperature < 2000) {
+            int64_t T2 = (3 * (deltaT * deltaT)) >> 33;
+            int64_t offset2 = 61 * ((temperature - 2000) * (temperature - 2000)) / 16;
+            int64_t sens2 = 29 * ((temperature - 2000) * (temperature - 2000)) / 16;
+            if (temperature < -1500) {
+                offset2 += 17 * (temperature + 1500) * (temperature + 1500);
+                sens2 += 9 * ((temperature + 1500) * (temperature + 1500));
+            }
+            temperature -= T2;
+            offset -= offset2;
+            sens -=sens2;
+        } else {
+            temperature -= (5 * (deltaT * deltaT)) >> 38;
+        }
+
+        m_pressure = (RTFLOAT)(((((int64_t)m_D1 * sens) >> 21) - offset) >> 15) / (RTFLOAT)100.0;
+        m_temperature = (RTFLOAT)temperature/(RTFLOAT)100;
+
+        // printf("Temp: %f, pressure: %f\n", m_temperature, m_pressure);
+
+        m_validReadings = true;
+        m_state = MS5637_STATE_IDLE;
+        break;
+    }
+}
+
+void RTPressureMS5637::setTestData()
+{
+    m_calData[0] = 46372;
+    m_calData[1] = 43981;
+    m_calData[2] = 29059;
+    m_calData[3] = 27842;
+    m_calData[4] = 31553;
+    m_calData[5] = 28165;
+
+    m_D1 = 6465444;
+    m_D2 = 8077636;
+}
diff --git a/libraries/RTIMULib/utility/RTPressureMS5637.h b/libraries/RTIMULib/utility/RTPressureMS5637.h
new file mode 100644
index 0000000..8a3ee10
--- /dev/null
+++ b/libraries/RTIMULib/utility/RTPressureMS5637.h
@@ -0,0 +1,69 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTIMULib
+//
+//  Copyright (c) 2014-2015, richards-tech
+//
+//  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 _RTPRESSUREMS5637_H_
+#define _RTPRESSUREMS5637_H_
+
+#include "RTPressure.h"
+
+//  State definitions
+
+#define MS5637_STATE_IDLE               0
+#define MS5637_STATE_TEMPERATURE        1
+#define MS5637_STATE_PRESSURE           2
+
+class RTIMUSettings;
+
+class RTPressureMS5637 : public RTPressure
+{
+public:
+    RTPressureMS5637(RTIMUSettings *settings);
+    ~RTPressureMS5637();
+
+    virtual const char *pressureName() { return "MS5637"; }
+    virtual int pressureType() { return RTPRESSURE_TYPE_MS5611; }
+    virtual bool pressureInit();
+    virtual bool pressureRead(RTIMU_DATA& data);
+
+private:
+    void pressureBackground();
+    void setTestData();
+
+    unsigned char m_pressureAddr;                           // I2C address
+    RTFLOAT m_pressure;                                     // the current pressure
+    RTFLOAT m_temperature;                                  // the current temperature
+
+    int m_state;
+
+    uint16_t m_calData[6];                                  // calibration data
+
+    uint32_t m_D1;
+    uint32_t m_D2;
+
+    uint64_t m_timer;                                       // used to time coversions
+
+    bool m_validReadings;
+};
+
+#endif // _RTPRESSUREMS5637_H_
+
diff --git a/libraries/RTTeensyLink/RTTeensyLink LICENSE b/libraries/RTTeensyLink/RTTeensyLink LICENSE
new file mode 100644
index 0000000..f4d1df7
--- /dev/null
+++ b/libraries/RTTeensyLink/RTTeensyLink LICENSE	
@@ -0,0 +1,22 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTTeensyLink
+//
+//  Copyright (c) 2015, richards-tech, LLC
+//
+//  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.
diff --git a/libraries/RTTeensyLink/RTTeensyLink.cpp b/libraries/RTTeensyLink/RTTeensyLink.cpp
new file mode 100644
index 0000000..51b9d02
--- /dev/null
+++ b/libraries/RTTeensyLink/RTTeensyLink.cpp
@@ -0,0 +1,148 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTTeensyLink
+//
+//  Copyright (c) 2015, richards-tech, LLC
+//
+//  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 "RTTeensyLink.h"
+#include "RTTeensyLinkEEPROM.h"
+#include "RTTeensyLinkUtils.h"
+#include "Arduino.h"
+#include 
+
+RTTeensyLink::RTTeensyLink()
+{
+}
+
+RTTeensyLink::~RTTeensyLink()
+{
+}
+
+void RTTeensyLink::begin(const char *identitySuffix)
+{
+    if (!RTTeensyLinkEEPROMValid())
+        RTTeensyLinkEEPROMDefault();
+
+    m_identitySuffix = identitySuffix;
+
+    RTTeensyLinkRXFrameInit(&(m_RXFrame), &(m_RXFrameBuffer));
+}
+
+
+void RTTeensyLink::background()
+{
+    while (Serial.available()) {
+        if (!RTTeensyLinkReassemble(&(m_RXFrame), Serial.read())) {
+            sendDebugMessage("Reassembly error");
+        } else {
+            if (m_RXFrame.complete) {
+                processReceivedMessage();
+                RTTeensyLinkRXFrameInit(&(m_RXFrame), &(m_RXFrameBuffer));
+            }
+        }
+    }
+}
+
+void RTTeensyLink::processReceivedMessage()
+{
+    RTTEENSYLINK_MESSAGE *message;                          // a pointer to the message part of the frame
+    int identityLength;
+    int suffixLength;
+
+    message = &(m_RXFrameBuffer.message);                   // get the message pointer
+
+    switch (message->messageType)
+    {
+        case RTTEENSYLINK_MESSAGE_POLL:
+        case RTTEENSYLINK_MESSAGE_ECHO:
+             RTTeensyLinkConvertIntToUC2(RTTEENSYLINK_MY_ADDRESS, message->messageAddress);
+             sendFrame(&(m_RXFrameBuffer), m_RXFrameBuffer.messageLength);   // just send the frame back as received
+             break;
+
+        case RTTEENSYLINK_MESSAGE_IDENTITY:
+             identityLength = strlen(RTTeensyLinkConfig.identity);
+             suffixLength = strlen(m_identitySuffix);
+
+             memcpy(message->data, RTTeensyLinkConfig.identity, identityLength + 1);    // copy in identity
+
+             if ((identityLength + suffixLength) < RTTEENSYLINK_DATA_MAX_LEN - 1) {
+                 memcpy(message->data + identityLength, m_identitySuffix, suffixLength + 1); // copy in suffix
+             } else {
+                 suffixLength = 0;
+             }
+             RTTeensyLinkConvertIntToUC2(RTTEENSYLINK_MY_ADDRESS, message->messageAddress);
+             message->data[RTTEENSYLINK_DATA_MAX_LEN - 1] = 0;     // make sure zero terminated if it was truncated
+             sendFrame(&(m_RXFrameBuffer), RTTEENSYLINK_MESSAGE_HEADER_LEN + identityLength + suffixLength + 1);
+             break;
+
+        default:
+            if (message->messageType < RTTEENSYLINK_MESSAGE_CUSTOM) {	// illegal code
+                message->data[0] = RTTEENSYLINK_RESPONSE_ILLEGAL_COMMAND;
+                message->data[1] = message->messageType;        // this is the offending code
+                message->messageType = RTTEENSYLINK_MESSAGE_ERROR;
+                RTTeensyLinkConvertIntToUC2(RTTEENSYLINK_MY_ADDRESS, message->messageAddress);
+                sendFrame(&(m_RXFrameBuffer), RTTEENSYLINK_MESSAGE_HEADER_LEN + 2);
+                break;
+            }
+            processCustomMessage(message->messageType, message->messageParam, message->data,
+                    m_RXFrameBuffer.messageLength - RTTEENSYLINK_MESSAGE_HEADER_LEN);	// see if anyone wants to process it
+            break;
+    }
+}
+
+void RTTeensyLink::sendDebugMessage(const char *debugMessage)
+{
+    RTTEENSYLINK_FRAME frame;
+    int stringLength;
+
+    stringLength = strlen(debugMessage);
+    if (stringLength >= RTTEENSYLINK_DATA_MAX_LEN)
+        stringLength = RTTEENSYLINK_DATA_MAX_LEN-1;
+    memcpy(frame.message.data, debugMessage, stringLength);
+    frame.message.data[stringLength] = 0;
+    frame.message.messageType = RTTEENSYLINK_MESSAGE_DEBUG;
+    RTTeensyLinkConvertIntToUC2(RTTEENSYLINK_MY_ADDRESS, frame.message.messageAddress);
+    sendFrame(&frame, RTTEENSYLINK_MESSAGE_HEADER_LEN + stringLength + 1);
+}
+
+void RTTeensyLink::sendMessage(unsigned char messageType, unsigned char messageParam, unsigned char *data, int length)
+{
+    RTTEENSYLINK_FRAME frame;
+  
+    RTTeensyLinkConvertIntToUC2(RTTEENSYLINK_MY_ADDRESS, frame.message.messageAddress);
+    frame.message.messageType = messageType;
+    frame.message.messageParam = messageParam;
+
+    if (length > RTTEENSYLINK_DATA_MAX_LEN)
+        length = RTTEENSYLINK_DATA_MAX_LEN;
+    memcpy(frame.message.data, data, length);
+
+    sendFrame(&frame, length + RTTEENSYLINK_MESSAGE_HEADER_LEN);
+}
+
+void RTTeensyLink::sendFrame(RTTEENSYLINK_FRAME *frame, int length)
+{
+    frame->sync0 = RTTEENSYLINK_MESSAGE_SYNC0;
+    frame->sync1 = RTTEENSYLINK_MESSAGE_SYNC1;
+    frame->messageLength = length;                          // set length
+    RTTeensyLinkSetChecksum(frame);                           // compute checksum
+    Serial.write((unsigned char *)frame, frame->messageLength + RTTEENSYLINK_FRAME_HEADER_LEN);
+}
+
diff --git a/libraries/RTTeensyLink/RTTeensyLink.h b/libraries/RTTeensyLink/RTTeensyLink.h
new file mode 100644
index 0000000..9b72360
--- /dev/null
+++ b/libraries/RTTeensyLink/RTTeensyLink.h
@@ -0,0 +1,59 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTTeensyLink
+//
+//  Copyright (c) 2015, richards-tech, LLC
+//
+//  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 _RTTEENSYLINK_H
+#define _RTTEENSYLINK_H
+
+#include "RTTeensyLinkDefs.h"
+
+class RTTeensyLink
+{
+public:
+    RTTeensyLink();
+    virtual ~RTTeensyLink();
+
+    void begin(const char *identitySuffix);                 // should be called in setup() code
+    void background();                                      // should be called once per loop()
+    void sendDebugMessage(const char *debugMesssage);       // sends a debug message to the host port
+    void sendMessage(unsigned char messageType, unsigned char messageParam,
+        unsigned char *data, int length);                   // sends a message to the host port
+
+protected:
+//  These are functions that can be overridden
+
+    virtual void processCustomMessage(unsigned char messageType, 
+        unsigned char messageParam, unsigned char *data, int dataLength) {}
+
+private:
+    void processReceivedMessage();                          // process a completed message
+    void sendFrame(RTTEENSYLINK_FRAME *frame, int length);	// send a frame to the host. length is length of data field
+
+    const char *m_identitySuffix;                           // what to add to the EEPROM identity string
+
+    RTTEENSYLINK_RXFRAME m_RXFrame;                         // structure to maintain receive frame state
+    RTTEENSYLINK_FRAME m_RXFrameBuffer;                     // used to assemble received frames
+};
+
+#endif // _RTTEENSYLINK_H
+
diff --git a/libraries/RTTeensyLink/RTTeensyLinkDefs.h b/libraries/RTTeensyLink/RTTeensyLinkDefs.h
new file mode 100644
index 0000000..d49336a
--- /dev/null
+++ b/libraries/RTTeensyLink/RTTeensyLinkDefs.h
@@ -0,0 +1,140 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTTeensyLink
+//
+//  Copyright (c) 2015, richards-tech, LLC
+//
+//  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 _RTTEENSYLINKDEFS_H
+#define _RTTEENSYLINKDEFS_H
+
+//	Some general purpose typedefs - used especially for transferring values greater than
+//	8 bits across the link and avoids endian issues. Assumes processor has 32 bit ints!
+
+typedef	unsigned char RTTEENSYLINK_UC2[2];                  // an array of two unsigned chars
+typedef	unsigned char RTTEENSYLINK_UC4[4];                  // an array of four unsigned chars
+
+//------------------------------------------------------------------------------------------------------
+//
+//	Frame level defs and structure
+
+#define	RTTEENSYLINK_FRAME_MAX_LEN        64                // maximum possible length of a frame
+#define	RTTEENSYLINK_FRAME_HEADER_LEN     4                 // 4 bytes in frame header (must correspond with the structure below!)
+#define	RTTEENSYLINK_MESSAGE_HEADER_LEN   4                 // 4 bytes in message header (must correspond with the structure below!)
+#define	RTTEENSYLINK_MESSAGE_MAX_LEN      (RTTEENSYLINK_FRAME_MAX_LEN - RTTEENSYLINK_FRAME_HEADER_LEN)    // max length of message
+#define	RTTEENSYLINK_DATA_MAX_LEN         (RTTEENSYLINK_MESSAGE_MAX_LEN - RTTEENSYLINK_MESSAGE_HEADER_LEN)// max length of data field
+
+#define	RTTEENSYLINK_MESSAGE_SYNC0        0xAA
+#define	RTTEENSYLINK_MESSAGE_SYNC1        0x55
+
+#define	RTTEENSYLINK_MY_ADDRESS           0                 // the subsystem address for local processing
+#define	RTTEENSYLINK_BROADCAST_ADDRESS    0xffff            // the subsystem address for all subsystems
+#define	RTTEENSYLINK_ADDRESSES            0x1000            // number of addresses
+
+//  RTTEENSYLINK_MESSAGE is carried in the RTTEENSYLINK_FRAME
+//
+//  The messageAddress field allows subsystems to be daisy-chained. Valid addresses are 0 to 65534.
+//  Address 65535 is a broadcast and goes to all subsystems.
+//  Every message has the messageType and messageParam bytes but there can be from 0 to 56 bytes of data
+
+typedef struct
+{
+    RTTEENSYLINK_UC2 messageAddress;                        // subsystem message address
+    unsigned char messageType;                              // message type code
+    unsigned char messageParam;                             // an optional parameter to the message type
+    unsigned char data[RTTEENSYLINK_DATA_MAX_LEN];          // the actual data! Length is computed from messageLength.
+} RTTEENSYLINK_MESSAGE;
+
+//  RTTEENSYLINK_FRAME is the lowest level structure used across the RTTeensyLink
+
+typedef struct
+{
+    unsigned char sync0;                                    // sync0 code
+    unsigned char sync1;                                    // sync1 code
+    unsigned char messageLength;                            // the length of the message in the message field - between 4 and 60 bytes
+    unsigned char frameChecksum;                            // checksum for frame
+    RTTEENSYLINK_MESSAGE message;                           // the actual message
+} RTTEENSYLINK_FRAME;
+
+//  RTTEENSYLINK_RXFRAME is a type that is used to reassemble a frame from a stream of bytes in conjunction with reassemble()
+
+typedef struct
+{
+    RTTEENSYLINK_FRAME *frameBuffer;                        // the frame buffer pointer
+    int length;                                             // current length of frame
+    int bytesLeft;                                          // number of bytes needed to complete
+    bool complete;                                          // true if frame is complete and correct (as far as checksum goes)
+} RTTEENSYLINK_RXFRAME;
+
+//  Message types
+
+//  RTTEENSYLINK_MESSAGE_POLL
+//
+//  The host should poll the RTTeensyLink at every RTTEENSYLINK_POLL_INTERVAL.
+//  The subsystem will respond by echoing the poll message as received.
+
+#define	RTTEENSYLINK_MESSAGE_POLL         0                   // poll message
+
+//  RTTEENSYLINK_MESSAGE_IDENTIFY
+//
+//  The host can send this message to request an identity string from the subsystem.
+//  Only the messageType field is used in the request host -> subsystem. The subsystem
+//  responds with an identity string in the data field.
+
+#define	RTTEENSYLINK_MESSAGE_IDENTITY     1                   // identity message
+
+//  RTTEENSYLINK_MESSAGE_DEBUG
+//
+//  This can be used to send a debug message up to the host. The data field contains a debug message
+
+#define	RTTEENSYLINK_MESSAGE_DEBUG        2                   // debug message
+
+//  RTTEENSYLINK_MESSAGE_INFO
+//
+//  This can be used to send an info message up to the host. The data field contains the message
+
+#define	RTTEENSYLINK_MESSAGE_INFO         3                   // info message
+
+//  RTTEENSYLINK_MESSAGE_ERROR
+//
+//  This code is returned by the subsystem if it received a message with an illegal message type
+//  The first byte of the data is the error code. The rest of the data field depends on the error.
+
+#define	RTTEENSYLINK_MESSAGE_ERROR        4                   // illegal message type response
+
+//  RTTEENSYLINK_MESSAGE_ECHO
+//
+//  This message can be used to test link performance. The addressed subsystem just returns
+//  the entire message to the host.
+
+#define	RTTEENSYLINK_MESSAGE_ECHO         5                   // echo message
+
+//  RTTEENSYLINK_MESSAGE_CUSTOM
+//
+//  This is the first message code that should be used for custom messages 16-255 are available.
+
+#define	RTTEENSYLINK_MESSAGE_CUSTOM       16                  // start of custom messages
+
+//  RTTeensyLink response codes
+
+#define	RTTEENSYLINK_RESPONSE_OK                      0       // means things worked
+#define	RTTEENSYLINK_RESPONSE_ILLEGAL_COMMAND         1       // not a supported message type, data[1] has offending type
+
+
+#endif  // _RTTEENSYLINKDEFS_H
diff --git a/libraries/RTTeensyLink/RTTeensyLinkEEPROM.cpp b/libraries/RTTeensyLink/RTTeensyLinkEEPROM.cpp
new file mode 100644
index 0000000..49c4f92
--- /dev/null
+++ b/libraries/RTTeensyLink/RTTeensyLinkEEPROM.cpp
@@ -0,0 +1,81 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTTeensyLink
+//
+//  Copyright (c) 2015, richards-tech, LLC
+//
+//  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 
+#include "RTTeensyLinkEEPROM.h"
+#include 
+
+//  The global config structure
+
+RTTEENSYLINK_EEPROM RTTeensyLinkConfig;
+
+bool RTTeensyLinkEEPROMValid()
+{
+    RTTeensyLinkEEPROMRead();                              // see what it really is
+    return (RTTeensyLinkConfig.sig0 == RTTEENSYLINKEEPROM_SIG0) && 
+        (RTTeensyLinkConfig.sig1 == RTTEENSYLINKEEPROM_SIG1);
+}
+
+void RTTeensyLinkEEPROMDisplay()
+{
+    Serial.println();
+
+    if ((RTTeensyLinkConfig.sig0 != RTTEENSYLINKEEPROM_SIG0) || 
+        (RTTeensyLinkConfig.sig1 != RTTEENSYLINKEEPROM_SIG1)) {
+        Serial.println("Invalid config");
+        return;
+    }
+    Serial.print("Identity: ");
+    Serial.println(RTTeensyLinkConfig.identity);
+
+}
+
+void RTTeensyLinkEEPROMDefault()
+{
+    RTTeensyLinkConfig.sig0 = RTTEENSYLINKEEPROM_SIG0;       // set to valid signature
+    RTTeensyLinkConfig.sig1 = RTTEENSYLINKEEPROM_SIG1;                        
+    strcpy(RTTeensyLinkConfig.identity, "RTTeensyLink_Teensy");
+
+    RTTeensyLinkEEPROMWrite();
+}
+
+void RTTeensyLinkEEPROMRead()
+{
+    unsigned char *data;
+
+    data = (unsigned char *)&RTTeensyLinkConfig;
+
+    for (int i = 0; i < (int)sizeof(RTTEENSYLINK_EEPROM); i++)
+        *data++ = EEPROM.read(i + RTTEENSYLINK_EEPROM_OFFSET);
+}
+
+void RTTeensyLinkEEPROMWrite()
+{
+    unsigned char *data;
+
+    data = (unsigned char *)&RTTeensyLinkConfig;
+
+    for (int i = 0; i < (int)sizeof(RTTEENSYLINK_EEPROM); i++)
+        EEPROM.write(i + RTTEENSYLINK_EEPROM_OFFSET, *data++);
+}
diff --git a/libraries/RTTeensyLink/RTTeensyLinkEEPROM.h b/libraries/RTTeensyLink/RTTeensyLinkEEPROM.h
new file mode 100644
index 0000000..c52e730
--- /dev/null
+++ b/libraries/RTTeensyLink/RTTeensyLinkEEPROM.h
@@ -0,0 +1,86 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTTeensyLink
+//
+//  Copyright (c) 2015, richards-tech, LLC
+//
+//  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 _RTTEENSYLINKEEPROM_H
+#define _RTTEENSYLINKEEPROM_H
+
+//----------------------------------------------------------
+//  Target-specific includes
+//
+//
+//  Teensyino HAL
+
+#include 
+#include 
+
+#define RTTEENSYLINK_EEPROM_OFFSET         256              // where the config starts in EEPROM
+
+//  RTTEENSYLINKHAL_EEPROM is the target-specific structure used to
+//  store configs in EEPROM
+
+//  Signature bytes indicating valid config
+
+#define RTTEENSYLINKEEPROM_SIG0                  0x38          
+#define RTTEENSYLINKEEPROM_SIG1                  0xc1           
+
+typedef struct
+{
+    unsigned char sig0;                                     // signature byte 0
+    unsigned char sig1;                                     // signature byte 1
+    char identity[RTTEENSYLINK_DATA_MAX_LEN];               // identity string
+} RTTEENSYLINK_EEPROM;
+
+//  The global config structure
+
+extern RTTEENSYLINK_EEPROM RTTeensyLinkConfig;
+
+//  RTTeensyLinkEEPROMValid() returns true if the EEPROM contains a valid configuration,
+//  false otherwise.
+
+    bool RTTeensyLinkEEPROMValid();                         // returns true if a valid config
+
+
+//  RTTeensyLinkEEPROMDisplay() displays the current configuration
+
+    void RTTeensyLinkEEPROMDisplay();                       // display the config
+
+
+//  RTTeensyLinkEEPROMDefault() writes a default config to EEPROM
+
+    void RTTeensyLinkEEPROMDefault();                       // write and load default settings
+
+
+//  RTTeensyLinkEEPROMRead() loads the EEPROM config into the RTTeensyLinkConfig
+//  global structure.
+
+    void RTTeensyLinkEEPROMRead();                          // to load the config
+
+
+//  RTTeensyLinkEEPROMWrite() writes the config in the RTTeensyLinkConfig
+//  global structure back to EEPROM.
+
+    void RTTeensyLinkEEPROMWrite();                          // to write the config
+
+
+#endif // _RTTEENSYLINKEEPROM_H
+
diff --git a/libraries/RTTeensyLink/RTTeensyLinkUtils.cpp b/libraries/RTTeensyLink/RTTeensyLinkUtils.cpp
new file mode 100644
index 0000000..5601c08
--- /dev/null
+++ b/libraries/RTTeensyLink/RTTeensyLinkUtils.cpp
@@ -0,0 +1,175 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTTeensyLink
+//
+//  Copyright (c) 2015, richards-tech, LLC
+//
+//  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 "RTTeensyLinkUtils.h"
+
+//	RTTeensyLinkRXFrameInit initializes the structure for a new frame using frameBuffer for storage
+
+void RTTeensyLinkRXFrameInit(RTTEENSYLINK_RXFRAME *RXFrame, RTTEENSYLINK_FRAME *frameBuffer)
+{
+    RXFrame->complete = false;
+    RXFrame->length = 0;
+    RXFrame->bytesLeft = 0;
+    RXFrame->frameBuffer = frameBuffer;
+}
+
+//  RTTeensyLinkReassemble takes a sequence of received bytes and tries to complete a frame. It returns true if ok
+//  false if error. The caller can determine if the frame is complete by checking the complete flag.
+
+bool RTTeensyLinkReassemble(RTTEENSYLINK_RXFRAME *RXFrame, unsigned char data)
+{
+    bool flag = true;
+
+ 
+    ((unsigned char *)(RXFrame->frameBuffer))[RXFrame->length] = data;  // save byte in correct place
+    switch (RXFrame->length) {
+        case 0:                                             // waiting for sync0
+            if (RXFrame->frameBuffer->sync0 == RTTEENSYLINK_MESSAGE_SYNC0) {
+                RXFrame->length = 1;
+            }
+            break;
+
+        case 1:                                             // waiting for sync1
+            if (RXFrame->frameBuffer->sync1 == RTTEENSYLINK_MESSAGE_SYNC1) {
+                RXFrame->length = 2;
+            } else {
+                RXFrame->length = 0;                        // try again if not correct two byte sequence
+            }
+            break;
+
+        case 2:                                             // should be message length
+            if (RXFrame->frameBuffer->messageLength <= RTTEENSYLINK_MESSAGE_MAX_LEN) {
+                RXFrame->length = 3;
+                RXFrame->bytesLeft = RXFrame->frameBuffer->messageLength + 1;   // +1 to allow for the checksum
+            } else {
+                RXFrame->length = 0;                        // discard this and resync frame
+                flag = false;
+            }
+            break;
+
+        default:
+            RXFrame->length++;
+            RXFrame->bytesLeft--;
+            if (RXFrame->bytesLeft == 0) {                  // a complete frame!
+                if (!RTTeensyLinkCheckChecksum(RXFrame->frameBuffer)) {
+                    RTTeensyLinkRXFrameInit(RXFrame, RXFrame->frameBuffer);
+                    flag = false;                           // flag the error
+                } else {
+                    //  this is a valid frame (so far)
+                    RXFrame->complete = true;
+                }
+            }
+            break;
+    }
+    return flag;
+}
+
+//  RTTeensyLinkSetChecksum correctly sets the checksum field on an RCP frame prior to transmission
+//
+
+void RTTeensyLinkSetChecksum(RTTEENSYLINK_FRAME *frame)
+{
+    int cksm;
+    int i;
+    unsigned char *data;
+
+    for (i = 0, cksm = 0, data = (unsigned char *)&(frame->message); i < frame->messageLength; i++)
+        cksm += *data++;                                    // add up checksum
+    frame->frameChecksum = (255 - cksm) + 1;                // 2s complement
+}
+
+
+//  RTTeensyLinkCheckChecksum checks a received frame's checksum.
+//
+//  It adds up all the bytes from the nFrameCksm byte to the end of the frame. The result should be 0.
+
+bool RTTeensyLinkCheckChecksum(RTTEENSYLINK_FRAME *frame)
+{
+    int length;
+    int i;
+    unsigned char *data;
+    unsigned char cksm;
+
+    length = frame->messageLength + 1;
+    cksm = 0;
+    data = (unsigned char *)&(frame->frameChecksum);
+
+    for (i = 0; i < length; i++)
+        cksm += *data++;
+
+    return cksm == 0;
+}
+
+//  UC2 and UC4 Conversion routines
+//
+
+long RTTeensyLinkConvertUC4ToLong(RTTEENSYLINK_UC4 UC4)
+{
+    long val;
+
+    val = UC4[3];
+    val += (long)UC4[2] << 8;
+    val += (long)UC4[1] << 16;
+    val += (long)UC4[0] << 24;
+    return val;
+}
+
+void RTTeensyLinkConvertLongToUC4(long val, RTTEENSYLINK_UC4 UC4)
+{
+    UC4[3] = val & 0xff;
+    UC4[2] = (val >> 8) & 0xff;
+    UC4[1] = (val >> 16) & 0xff;
+    UC4[0] = (val >> 24) & 0xff;
+}
+
+int RTTeensyLinkConvertUC2ToInt(RTTEENSYLINK_UC2 UC2)
+{
+    int val;
+
+    val = UC2[1];
+    val += (int)UC2[0] << 8;
+    return val;
+}
+
+unsigned int RTTeensyLinkConvertUC2ToUInt(RTTEENSYLINK_UC2 UC2)
+{
+    unsigned int val;
+
+    val = UC2[1];
+    val += (unsigned int)UC2[0] << 8;
+    return val;
+}
+
+
+void RTTeensyLinkConvertIntToUC2(int val, RTTEENSYLINK_UC2 UC2)
+{
+    UC2[1] = val & 0xff;
+    UC2[0] = (val >> 8) & 0xff;
+}
+
+
+void RTTeensyLinkCopyUC2(RTTEENSYLINK_UC2 destUC2, RTTEENSYLINK_UC2 sourceUC2)
+{
+    destUC2[0] = sourceUC2[0];
+    destUC2[1] = sourceUC2[1];
+}
diff --git a/libraries/RTTeensyLink/RTTeensyLinkUtils.h b/libraries/RTTeensyLink/RTTeensyLinkUtils.h
new file mode 100644
index 0000000..1c72199
--- /dev/null
+++ b/libraries/RTTeensyLink/RTTeensyLinkUtils.h
@@ -0,0 +1,48 @@
+////////////////////////////////////////////////////////////////////////////
+//
+//  This file is part of RTTeensyLink
+//
+//  Copyright (c) 2015, richards-tech, LLC
+//
+//  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 _RTTEENSYLINKUTILS_H
+#define _RTTEENSYLINKUTILS_H
+
+#include "RTTeensyLinkDefs.h"
+
+//  Function defs
+
+void RTTeensyLinkRXFrameInit(RTTEENSYLINK_RXFRAME *RXFrame, RTTEENSYLINK_FRAME *frameBuffer);	// initializes RTTEENSYLINK_RXFRAME for a new frame
+bool RTTeensyLinkReassemble(RTTEENSYLINK_RXFRAME *RXFrame, unsigned char data);	// adds a byte to the reassembly, returns false if error
+
+//  Checksum utilities
+
+void RTTeensyLinkSetChecksum(RTTEENSYLINK_FRAME *frame);        // sets the checksum field prior to transmission
+bool RTTeensyLinkCheckChecksum(RTTEENSYLINK_FRAME *frame);      // checks the checksum field after reception - returns true if ok, false if error
+
+//  Type conversion utilities
+
+long RTTeensyLinkConvertUC4ToLong(RTTEENSYLINK_UC4 uc4);        // converts a 4 byte array to a signed long
+void RTTeensyLinkConvertLongToUC4(long val, RTTEENSYLINK_UC4 uc4);  // converts a long to a four byte array
+int	 RTTeensyLinkConvertUC2ToInt(RTTEENSYLINK_UC2 uc2);         // converts a 2 byte array to a signed integer
+unsigned int RTTeensyLinkConvertUC2ToUInt(RTTEENSYLINK_UC2 uc2);// converts a 2 byte array to an unsigned integer
+void RTTeensyLinkConvertIntToUC2(int val, RTTEENSYLINK_UC2 uc2);// converts an integer to a two byte array
+void RTTeensyLinkCopyUC2(RTTEENSYLINK_UC2 destUC2, RTTEENSYLINK_UC2 sourceUC2); // copies a UC2
+
+#endif // _RTTEENSYLINKUTILS_H
diff --git a/libraries/SSD1308/SSD1308.cpp b/libraries/SSD1308/SSD1308.cpp
new file mode 100644
index 0000000..b3180f7
--- /dev/null
+++ b/libraries/SSD1308/SSD1308.cpp
@@ -0,0 +1,195 @@
+// I2Cdev library collection - SSD1308 I2C device class header file
+// Based on Solomon Systech SSD1308 datasheet, rev. 1, 10/2008
+// 8/25/2011 by Andrew Schamp 
+//
+// 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:
+//     2011-08-25 - initial release
+        
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2011 Andrew Schamp
+
+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 "SSD1308.h"
+#include "I2Cdev.h"
+
+//#ifdef SSD1308_USE_FONT
+#include "fixedWidthFont.h"
+//#endif
+
+SSD1308::SSD1308(uint8_t address) :
+  m_devAddr(address)
+{
+}
+
+void SSD1308::initialize() 
+{
+  setHorizontalAddressingMode();
+  clearDisplay();
+}
+
+void SSD1308::clearDisplay()
+{
+  setDisplayOff();
+  setPageAddress(0, 7);     // all pages
+  setColumnAddress(0, 127); // all columns
+  for (uint8_t page = 0; page < 8; page++)
+  {
+    for (uint8_t col = 0; col < 128; col++)
+    {
+      sendData(0x0);
+    }
+  }
+  setDisplayOn();
+}
+
+void SSD1308::fillDisplay()
+{
+  setPageAddress(0, MAX_PAGE);      // all pages
+  setColumnAddress(0, MAX_COL); // all columns
+
+  uint8_t b = 0;
+  for (uint8_t page = 0; page < PAGES; page++)
+  {
+    for (uint8_t col = 0; col < COLUMNS; col++)
+    {
+      sendData(b++);
+    }
+  }
+}
+
+void SSD1308::writeChar(char chr)
+{
+//#ifdef SSD1308_USE_FONT
+  const uint8_t char_index = chr - 0x20;
+  for (uint8_t i = 0; i < 8; i++) {
+     const uint8_t b = pgm_read_byte( &fontData[char_index][i] );
+     sendData( b ); 
+  }
+//#endif
+}
+
+void SSD1308::writeString(uint8_t row, uint8_t col, uint16_t len, const char * text)
+{
+  uint16_t index = 0;
+  setPageAddress(row, MAX_PAGE);
+  const uint8_t col_addr = FONT_WIDTH*col;
+  setColumnAddress(col_addr, MAX_COL);
+
+  while ((col+index) < CHARS && (index < len)) {
+     // write first line, starting at given position
+     writeChar(text[index++]);
+  }
+
+  // write remaining lines
+  // write until the end of memory
+  // then wrap around again from the top.
+  if (index + 1 < len) {
+    setPageAddress(row + 1, MAX_PAGE);
+    setColumnAddress(0, MAX_COL);
+    bool wrapEntireScreen = false;
+    while (index + 1 < len) {
+       writeChar(text[index++]);
+       // if we've written the last character space on the screen, 
+       // reset the page and column address so that it wraps around from the top again
+       if (!wrapEntireScreen && (row*CHARS + col + index) > 127) {
+         setPageAddress(0, MAX_PAGE);
+         setColumnAddress(0, MAX_COL);
+         wrapEntireScreen = true;
+       }
+    }
+  }
+}
+
+void SSD1308::sendCommand(uint8_t command)
+{
+  I2Cdev::writeByte(m_devAddr, COMMAND_MODE, command);
+}
+
+void SSD1308::sendCommands(uint8_t len, uint8_t* commands)
+{
+  I2Cdev::writeBytes(m_devAddr, COMMAND_MODE, len, commands);
+}
+
+void SSD1308::sendData(uint8_t data)
+{
+  I2Cdev::writeByte(m_devAddr, DATA_MODE, data);
+}
+
+void SSD1308::sendData(uint8_t len, uint8_t* data)
+{
+  I2Cdev::writeBytes(m_devAddr, DATA_MODE, len, data);
+}
+
+void SSD1308::setHorizontalAddressingMode()
+{
+  setMemoryAddressingMode(HORIZONTAL_ADDRESSING_MODE); 
+}
+void SSD1308::setVerticalAddressingMode()
+{
+  setMemoryAddressingMode(VERTICAL_ADDRESSING_MODE); 
+}
+void SSD1308::setPageAddressingMode()
+{
+  setMemoryAddressingMode(PAGE_ADDRESSING_MODE); 
+}
+    
+void SSD1308::setMemoryAddressingMode(uint8_t mode)
+{
+  uint8_t cmds[2] = { SET_MEMORY_ADDRESSING_MODE, mode };
+  sendCommands(2, cmds); 
+}
+
+void SSD1308::setDisplayOn()
+{
+  sendCommand(SET_DISPLAY_POWER_ON);
+}
+
+void SSD1308::setDisplayOff()
+{
+  sendCommand(SET_DISPLAY_POWER_OFF);
+}
+
+void SSD1308::setDisplayPower(bool on)
+{
+  if (on) {
+    setDisplayOn();
+  } else {
+    setDisplayOff();
+  }
+}
+
+void SSD1308::setPageAddress(uint8_t start, uint8_t end) 
+{
+  uint8_t data[3] = { SET_PAGE_ADDRESS, start, end };
+  sendCommands(3, data);  
+}
+
+void SSD1308::setColumnAddress(uint8_t start, uint8_t end) 
+{
+  uint8_t data[3] = { SET_COLUMN_ADDRESS, start, end };
+  sendCommands(3, data);  
+}
+
diff --git a/libraries/SSD1308/SSD1308.h b/libraries/SSD1308/SSD1308.h
new file mode 100644
index 0000000..ec23c5f
--- /dev/null
+++ b/libraries/SSD1308/SSD1308.h
@@ -0,0 +1,245 @@
+// I2Cdev library collection - SSD1308 I2C device class header file
+// Based on Solomon Systech SSD1308 datasheet, rev. 1, 10/2008
+// 8/25/2011 by Andrew Schamp 
+//
+// 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:
+//     2011-08-25 - initial release
+        
+/* ============================================
+I2Cdev device library code is placed under the MIT license
+Copyright (c) 2011 Andrew Schamp
+
+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 _SSD1308_h_
+#define _SSD1308_h_
+
+#include 
+
+// this is the 7-bit I2C address
+// which wone is used is determined by the D/C# pin.
+// with D/C# (pin 13) grounded, address is 0x3C
+// tied high, 0x3D
+// assume grounded by default.
+#define SSD1308_ADDRESS_1 0x3C
+#define SSD1308_ADDRESS_2 0x3D
+#define SSD1308_DEFAULT_ADDRESS SSD1308_ADDRESS_1
+
+#define ROWS 64
+#define COLUMNS 128
+#define PAGES 8
+#define PAGE_WIDTH (ROWS / 8)
+#define FONT_WIDTH 8
+#define CHARS (COLUMNS / FONT_WIDTH)
+#define MAX_PAGE (PAGES - 1)
+#define MAX_COL (COLUMNS - 1)
+
+#define HORIZONTAL_ADDRESSING_MODE 0x00
+#define VERTICAL_ADDRESSING_MODE   0x01
+#define PAGE_ADDRESSING_MODE       0x02
+
+#define SET_MEMORY_ADDRESSING_MODE 0x20 // takes one byte
+
+#define SET_COLUMN_ADDRESS 0x21 // takes two bytes, start address and end address of display data RAM
+#define SET_PAGE_ADDRESS   0x22 // takes two bytes, start address and end address of display data RAM
+
+#define SET_CONTRAST 0x81 // takes one byte, 0x00 - 0xFF
+
+#define SET_SEGMENT_REMAP_0   0xA0 // column address 0 is mapped to SEG0
+#define SET_SEGMENT_REMAP_127 0xA1 // column address 127 is mapped to SEG0
+
+#define SET_ENTIRE_DISPLAY_ON 0xA5 // turns all pixels on, does not affect RAM
+#define SET_DISPLAY_GDDRAM    0xA4 // restores display to contents of RAM
+
+#define SET_NORMAL_DISPLAY  0xA6 // a data of 1 indicates 'ON'
+#define SET_INVERSE_DISPLAY 0xA7 // a data of 0 indicates 'ON'
+
+#define SET_MULTIPLEX_RATIO 0xA8 // takes one byte, from 16 to 63 (0x
+
+#define EXTERNAL_IREF 0x10
+#define INTERNAL_IREF 0x00
+#define SET_IREF_SELECTION 0xAD // sets internal or external Iref
+
+#define SET_DISPLAY_POWER_OFF 0xAE
+#define SET_DISPLAY_POWER_ON  0xAF
+
+#define COMMAND_MODE 0x80
+#define DATA_MODE 0x40
+
+#define PAGE0 0x00
+#define PAGE1 0x01
+#define PAGE2 0x02
+#define PAGE3 0x03
+#define PAGE4 0x04
+#define PAGE5 0x05
+#define PAGE6 0x06
+#define PAGE7 0x07
+#define SET_PAGE_START_ADDRESS 0xB0 // | with a page number to get start address
+
+#define SET_DISPLAY_OFFSET 0xD3
+
+#define SET_DISPLAY_CLOCK 0xD5
+
+#define VCOMH_DESELECT_0_65_CODE 0x00
+#define VCOMH_DESELECT_0_77_CODE 0x20
+#define VCOMH_DESELECT_0_83_CODE 0x30
+#define SET_VCOMH_DESELECT_LEVEL 0xDB
+
+#define NOP 0xE3
+
+#define SET_RIGHT_HORIZONTAL_SCROLL 0x26
+#define SET_LEFT_HORIZONTAL_SCROLL  0x27
+#define SET_VERTICAL_RIGHT_HORIZONTAL_SCROLL 0x29
+#define SET_VERTICAL_LEFT_HORIZONTAL_SCROLL  0x2A
+
+#define SET_DEACTIVATE_SCROLL 0x2E
+#define SET_ACTIVATE_SCROLL 0x2F
+
+#define SET_VERTICAL_SCROLL_AREA 0xA3
+
+class SSD1308
+{
+  public:
+    
+      // constructor
+    // takes a 7-b I2C address to use (0x3C by default, assumes D/C# (pin 13) grounded)
+    SSD1308(uint8_t address = SSD1308_DEFAULT_ADDRESS);
+
+    void initialize();
+    void clearDisplay();
+    void fillDisplay(); // crosshatches    
+    
+    // x, y is position (x is row (i.e., page), y is character (0-15), starting at top-left)
+    // text will wrap around until it is done.
+    void writeString(uint8_t row, uint8_t col, uint16_t len, const char* txt);
+    
+    //void setXY(uint8_t, uint8_t y);
+
+    void setHorizontalAddressingMode();
+    void setVerticalAddressingMode();
+    void setPageAddressingMode();
+    
+    void setMemoryAddressingMode(uint8_t mode);
+    
+    // takes one byte, 0x00-0x0F
+    void setLowerColumnStartAddressForPageAddressingMode(uint8_t address);
+    
+    // takes one byte, 0x10-0x1F
+    void setHigherColumnStartAddressForPageAddressingMode(uint8_t address);
+    
+    // takes two bytes, start address and end address of display data RAM
+    void setColumnAddress(uint8_t start, uint8_t end);
+    
+    // takes two bytes, start address and end address of display data RAM
+    void setPageAddress(uint8_t start, uint8_t end);
+    
+    // takes one byte, PAGE0 - PAGE7
+    void setPageStartForPageAddressingMode(uint8_t page);
+    
+    // takes one byte, 0x40-0x7F
+    void setDisplayStartLine(uint8_t line);
+    
+    // takes one byte, 0x00 (lowest) - 0xFF (highest)
+    void setContrastControl(uint8_t contrast);
+    
+    void setEntireDisplayOn();
+    void setEntireDisplayRAM();
+    void setEntireDisplay(bool on);
+    void setNormalDisplay();
+    void setInverseDisplay();
+    
+    // setMultiplexRatio
+    
+    void setInternalIref();
+    void setExternalIref();
+    
+    void setDisplayOn();
+    void setDisplayOff();
+    void setDisplayPower(bool on);
+    
+    // Set vertical shift by COM from 0 - 63 (0x00 - 0x3F)
+    // set to 0x00 after RESET
+    void setDisplayOffset(uint8_t offset);
+    
+    // divide ratio 0x00-0x0F, value +1 (reset 0x00)
+    // oscillator freq 0x00-0x0F (reset 0x08)
+    void setDisplayClock(uint8_t divideRatio, uint8_t oscFreq);
+    
+    // phase1 0x01-0x0F period of up to 15 DCLK clocks (reset 0x02, 0 is invalid)
+    // phase2 0x01-0x0F period of up to 15 DCLK clocks (reset 0x02, 0 is invalid)
+    void setPrechargePeriod(uint8_t phase1, uint8_t phase2);
+    
+    #define VCOM_DESELECT_0_65 0x00
+    #define VCOM_DESELECT_0_77 0x02
+    #define VCOM_DESELECT_0_83 0x03
+    void setVcomhDeselectLevel(uint8_t level);
+    
+    // command for no operation
+    void nop();
+    
+    #define SCROLL_INTERVAL_5_FRAMES   0x00
+    #define SCROLL_INTERVAL_64_FRAMES  0x01
+    #define SCROLL_INTERVAL_128_FRAMES 0x02
+    #define SCROLL_INTERVAL_256_FRAMES 0x03
+    #define SCROLL_INTERVAL_3_FRAMES   0x04
+    #define SCROLL_INTERVAL_4_FRAMES   0x05
+    #define SCROLL_INTERVAL_25_FRAMES  0x06
+    #define SCROLL_INTERVAL_2_FRAMES   0x07
+    // end_page must not be less than start_page
+    void setContinuousHorizontalScroll(bool left, uint8_t start_page, uint8_t interval, uint8_t end_page);
+    // horizontal scroll by one column per interval
+    // offset = 1 (0x01) to 63 (0x3F)
+    void setContinuousVerticalAndHorizontalScroll(bool left, uint8_t start_page, uint8_t interval, uint8_t end_page, uint8_t offset);
+    
+    // note, after deactivating scrolling, the RAM data needs to be rewritten
+    void deactivateScroll();
+    void activateScroll();
+    
+    void setVerticalScrollArea(uint8_t topRowsFixed, uint8_t scrollRows);
+
+    void sendData(uint8_t data);
+    void sendData(uint8_t len, uint8_t* data);
+    // write the configuration registers in accordance with the datasheet and app note 3944
+//    void initialize();
+    
+    // returns true if the device is responding on the I2C bus
+//    bool testConnection();
+
+    // getTouchStatus returns the touch status for the given channel (0 - 11)
+//    bool getTouchStatus(uint8_t channel);
+    // when not given a channel, returns a bitfield of all touch channels.
+//    uint16_t getTouchStatus();
+
+  private:
+    // sends a single-byte command (given) to device
+    void sendCommand(uint8_t command);
+    void sendCommands(uint8_t len, uint8_t* buf);
+
+    void writeChar(char chr);
+    
+    uint8_t m_devAddr; // contains the I2C address of the device
+};
+
+#endif
+
diff --git a/libraries/SSD1308/example.pde b/libraries/SSD1308/example.pde
new file mode 100644
index 0000000..c100dd5
--- /dev/null
+++ b/libraries/SSD1308/example.pde
@@ -0,0 +1,76 @@
+// SSD1308 device demonstration Arduino sketch
+// 9/02/2011 by Andrew Schamp 
+// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
+
+/* ============================================
+SSD1308 device library code is placed under the MIT license
+Copyright (c) 2011 Andrew Schamp
+
+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 
+
+#define SSD1308_USE_FONT
+#include "SSD1308.h"
+#undef SSD1308_USE_FONT
+
+SSD1308 oled;
+
+void setup() {
+    // join I2C bus
+    Wire.begin();
+    
+    // initialize serial communication
+    Serial.begin(38400);
+    
+    // initialize all devices
+    Serial.println("Initializing I2C devices...");
+    oled.initialize();
+
+}
+
+void loop() {
+  oled.setDisplayOff();
+  Serial.println("display off.");
+  delay(1000);
+  oled.setDisplayOn();
+  Serial.println("display on.");
+  delay(1000);
+  oled.clearDisplay();
+  Serial.println("display cleared.");
+  delay(1000);
+  oled.fillDisplay();
+  Serial.println("display filled.");
+  delay(1000);
+  oled.clearDisplay();
+  Serial.println("display cleared.");
+  delay(1000);
+  oled.writeString(0, 0, 8, "Foobar!!");
+  Serial.println("printed something.");
+  delay(5000);
+  oled.writeString(1, 8, 8, "baz quux");
+  Serial.println("printed something.");
+  delay(5000);
+  oled.writeString(2, 0, 272, "a long, rather lengthy, extended string passage thing, eh, that just goes on, and on, and on, and on, and on, and on, and on, yes, further, continuing, extending, expanding beyond all reason or sanity!!!!! and yet, there's more!  so much more!  for ever and ever, oh yeah");
+  Serial.println("printed something.");
+  delay(5000);
+  delay(3000);
+}
diff --git a/libraries/SSD1308/fixedWidthFont.h b/libraries/SSD1308/fixedWidthFont.h
new file mode 100644
index 0000000..a69dfca
--- /dev/null
+++ b/libraries/SSD1308/fixedWidthFont.h
@@ -0,0 +1,108 @@
+#ifndef fixedWidthFont_h
+#define fixedWidthFont_h
+
+#include 
+
+//#ifdef SSD1308_USE_FONT
+//========================
+const uint8_t fontData[][8] PROGMEM = {
+{0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00},
+{0x00,0x00,0x5F,0x00,0x00,0x00,0x00,0x00},
+{0x00,0x00,0x07,0x00,0x07,0x00,0x00,0x00},
+{0x00,0x14,0x7F,0x14,0x7F,0x14,0x00,0x00},
+{0x00,0x24,0x2A,0x7F,0x2A,0x12,0x00,0x00},
+{0x00,0x23,0x13,0x08,0x64,0x62,0x00,0x00},
+{0x00,0x36,0x49,0x55,0x22,0x50,0x00,0x00},
+{0x00,0x00,0x05,0x03,0x00,0x00,0x00,0x00},
+{0x00,0x1C,0x22,0x41,0x00,0x00,0x00,0x00},
+{0x00,0x41,0x22,0x1C,0x00,0x00,0x00,0x00},
+{0x00,0x08,0x2A,0x1C,0x2A,0x08,0x00,0x00},
+{0x00,0x08,0x08,0x3E,0x08,0x08,0x00,0x00},
+{0x00,0xA0,0x60,0x00,0x00,0x00,0x00,0x00},
+{0x00,0x08,0x08,0x08,0x08,0x08,0x00,0x00},
+{0x00,0x60,0x60,0x00,0x00,0x00,0x00,0x00},
+{0x00,0x20,0x10,0x08,0x04,0x02,0x00,0x00},
+{0x00,0x3E,0x51,0x49,0x45,0x3E,0x00,0x00},
+{0x00,0x00,0x42,0x7F,0x40,0x00,0x00,0x00},
+{0x00,0x62,0x51,0x49,0x49,0x46,0x00,0x00},
+{0x00,0x22,0x41,0x49,0x49,0x36,0x00,0x00},
+{0x00,0x18,0x14,0x12,0x7F,0x10,0x00,0x00},
+{0x00,0x27,0x45,0x45,0x45,0x39,0x00,0x00},
+{0x00,0x3C,0x4A,0x49,0x49,0x30,0x00,0x00},
+{0x00,0x01,0x71,0x09,0x05,0x03,0x00,0x00},
+{0x00,0x36,0x49,0x49,0x49,0x36,0x00,0x00},
+{0x00,0x06,0x49,0x49,0x29,0x1E,0x00,0x00},
+{0x00,0x00,0x36,0x36,0x00,0x00,0x00,0x00},
+{0x00,0x00,0xAC,0x6C,0x00,0x00,0x00,0x00},
+{0x00,0x08,0x14,0x22,0x41,0x00,0x00,0x00},
+{0x00,0x14,0x14,0x14,0x14,0x14,0x00,0x00},
+{0x00,0x41,0x22,0x14,0x08,0x00,0x00,0x00},
+{0x00,0x02,0x01,0x51,0x09,0x06,0x00,0x00},
+{0x00,0x32,0x49,0x79,0x41,0x3E,0x00,0x00},
+{0x00,0x7E,0x09,0x09,0x09,0x7E,0x00,0x00},
+{0x00,0x7F,0x49,0x49,0x49,0x36,0x00,0x00},
+{0x00,0x3E,0x41,0x41,0x41,0x22,0x00,0x00},
+{0x00,0x7F,0x41,0x41,0x22,0x1C,0x00,0x00},
+{0x00,0x7F,0x49,0x49,0x49,0x41,0x00,0x00},
+{0x00,0x7F,0x09,0x09,0x09,0x01,0x00,0x00},
+{0x00,0x3E,0x41,0x41,0x51,0x72,0x00,0x00},
+{0x00,0x7F,0x08,0x08,0x08,0x7F,0x00,0x00},
+{0x00,0x41,0x7F,0x41,0x00,0x00,0x00,0x00},
+{0x00,0x20,0x40,0x41,0x3F,0x01,0x00,0x00},
+{0x00,0x7F,0x08,0x14,0x22,0x41,0x00,0x00},
+{0x00,0x7F,0x40,0x40,0x40,0x40,0x00,0x00},
+{0x00,0x7F,0x02,0x0C,0x02,0x7F,0x00,0x00},
+{0x00,0x7F,0x04,0x08,0x10,0x7F,0x00,0x00},
+{0x00,0x3E,0x41,0x41,0x41,0x3E,0x00,0x00},
+{0x00,0x7F,0x09,0x09,0x09,0x06,0x00,0x00},
+{0x00,0x3E,0x41,0x51,0x21,0x5E,0x00,0x00},
+{0x00,0x7F,0x09,0x19,0x29,0x46,0x00,0x00},
+{0x00,0x26,0x49,0x49,0x49,0x32,0x00,0x00},
+{0x00,0x01,0x01,0x7F,0x01,0x01,0x00,0x00},
+{0x00,0x3F,0x40,0x40,0x40,0x3F,0x00,0x00},
+{0x00,0x1F,0x20,0x40,0x20,0x1F,0x00,0x00},
+{0x00,0x3F,0x40,0x38,0x40,0x3F,0x00,0x00},
+{0x00,0x63,0x14,0x08,0x14,0x63,0x00,0x00},
+{0x00,0x03,0x04,0x78,0x04,0x03,0x00,0x00},
+{0x00,0x61,0x51,0x49,0x45,0x43,0x00,0x00},
+{0x00,0x7F,0x41,0x41,0x00,0x00,0x00,0x00},
+{0x00,0x02,0x04,0x08,0x10,0x20,0x00,0x00},
+{0x00,0x41,0x41,0x7F,0x00,0x00,0x00,0x00},
+{0x00,0x04,0x02,0x01,0x02,0x04,0x00,0x00},
+{0x00,0x80,0x80,0x80,0x80,0x80,0x00,0x00},
+{0x00,0x01,0x02,0x04,0x00,0x00,0x00,0x00},
+{0x00,0x20,0x54,0x54,0x54,0x78,0x00,0x00},
+{0x00,0x7F,0x48,0x44,0x44,0x38,0x00,0x00},
+{0x00,0x38,0x44,0x44,0x28,0x00,0x00,0x00},
+{0x00,0x38,0x44,0x44,0x48,0x7F,0x00,0x00},
+{0x00,0x38,0x54,0x54,0x54,0x18,0x00,0x00},
+{0x00,0x08,0x7E,0x09,0x02,0x00,0x00,0x00},
+{0x00,0x18,0xA4,0xA4,0xA4,0x7C,0x00,0x00},
+{0x00,0x7F,0x08,0x04,0x04,0x78,0x00,0x00},
+{0x00,0x00,0x7D,0x00,0x00,0x00,0x00,0x00},
+{0x00,0x80,0x84,0x7D,0x00,0x00,0x00,0x00},
+{0x00,0x7F,0x10,0x28,0x44,0x00,0x00,0x00},
+{0x00,0x41,0x7F,0x40,0x00,0x00,0x00,0x00},
+{0x00,0x7C,0x04,0x18,0x04,0x78,0x00,0x00},
+{0x00,0x7C,0x08,0x04,0x7C,0x00,0x00,0x00},
+{0x00,0x38,0x44,0x44,0x38,0x00,0x00,0x00},
+{0x00,0xFC,0x24,0x24,0x18,0x00,0x00,0x00},
+{0x00,0x18,0x24,0x24,0xFC,0x00,0x00,0x00},
+{0x00,0x00,0x7C,0x08,0x04,0x00,0x00,0x00},
+{0x00,0x48,0x54,0x54,0x24,0x00,0x00,0x00},
+{0x00,0x04,0x7F,0x44,0x00,0x00,0x00,0x00},
+{0x00,0x3C,0x40,0x40,0x7C,0x00,0x00,0x00},
+{0x00,0x1C,0x20,0x40,0x20,0x1C,0x00,0x00},
+{0x00,0x3C,0x40,0x30,0x40,0x3C,0x00,0x00},
+{0x00,0x44,0x28,0x10,0x28,0x44,0x00,0x00},
+{0x00,0x1C,0xA0,0xA0,0x7C,0x00,0x00,0x00},
+{0x00,0x44,0x64,0x54,0x4C,0x44,0x00,0x00},
+{0x00,0x08,0x36,0x41,0x00,0x00,0x00,0x00},
+{0x00,0x00,0x7F,0x00,0x00,0x00,0x00,0x00},
+{0x00,0x41,0x36,0x08,0x00,0x00,0x00,0x00},
+{0x00,0x02,0x01,0x01,0x02,0x01,0x00,0x00},
+{0x00,0x02,0x05,0x05,0x02,0x00,0x00,0x00} 
+};
+//#endif // use font
+
+#endif // include
diff --git a/libraries/SSD1308/library.json b/libraries/SSD1308/library.json
new file mode 100644
index 0000000..9e0db1c
--- /dev/null
+++ b/libraries/SSD1308/library.json
@@ -0,0 +1,18 @@
+{
+  "name": "I2Cdevlib-SSD1308",
+  "keywords": "oled, pled, display, driver, i2cdevlib, i2c",
+  "description": "SSD1308 is a single-chip CMOS OLED/PLED driver with controller for organic / polymer light emitting diode dot-matrix graphic display system",
+  "include": "Arduino/SSD1308",
+  "repository":
+  {
+    "type": "git",
+    "url": "https://github.com/jrowberg/i2cdevlib.git"
+  },
+  "dependencies":
+  {
+    "name": "I2Cdevlib-Core",
+    "frameworks": "arduino"
+  },
+  "frameworks": "arduino",
+  "platforms": "atmelavr"
+}
diff --git a/libraries/SoftwareSerial/SoftwareSerial.cpp b/libraries/SoftwareSerial/SoftwareSerial.cpp
new file mode 100644
index 0000000..c2c2390
--- /dev/null
+++ b/libraries/SoftwareSerial/SoftwareSerial.cpp
@@ -0,0 +1,518 @@
+/*
+SoftwareSerial.cpp (formerly NewSoftSerial.cpp) - 
+Multi-instance software serial library for Arduino/Wiring
+-- Interrupt-driven receive and other improvements by ladyada
+   (http://ladyada.net)
+-- Tuning, circular buffer, derivation from class Print/Stream,
+   multi-instance support, porting to 8MHz processors,
+   various optimizations, PROGMEM delay tables, inverse logic and 
+   direct port writing by Mikal Hart (http://www.arduiniana.org)
+-- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
+-- 20MHz processor support by Garrett Mace (http://www.macetech.com)
+-- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library is distributed in the hope that it will be useful,
+but WITHOUT ANY WARRANTY; without even the implied warranty of
+MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+
+The latest version of this library can always be found at
+http://arduiniana.org.
+*/
+
+// When set, _DEBUG co-opts pins 11 and 13 for debugging with an
+// oscilloscope or logic analyzer.  Beware: it also slightly modifies
+// the bit times, so don't rely on it too much at high baud rates
+#define _DEBUG 0
+#define _DEBUG_PIN1 11
+#define _DEBUG_PIN2 13
+// 
+// Includes
+// 
+#include 
+#include 
+#include 
+#include 
+//
+// Lookup table
+//
+typedef struct _DELAY_TABLE
+{
+  long baud;
+  unsigned short rx_delay_centering;
+  unsigned short rx_delay_intrabit;
+  unsigned short rx_delay_stopbit;
+  unsigned short tx_delay;
+} DELAY_TABLE;
+
+#if F_CPU == 16000000
+
+static const DELAY_TABLE PROGMEM table[] = 
+{
+  //  baud    rxcenter   rxintra    rxstop    tx
+  { 115200,   1,         17,        17,       12,    },
+  { 57600,    10,        37,        37,       33,    },
+  { 38400,    25,        57,        57,       54,    },
+  { 31250,    31,        70,        70,       68,    },
+  { 28800,    34,        77,        77,       74,    },
+  { 19200,    54,        117,       117,      114,   },
+  { 14400,    74,        156,       156,      153,   },
+  { 9600,     114,       236,       236,      233,   },
+  { 4800,     233,       474,       474,      471,   },
+  { 2400,     471,       950,       950,      947,   },
+  { 1200,     947,       1902,      1902,     1899,  },
+  { 600,      1902,      3804,      3804,     3800,  },
+  { 300,      3804,      7617,      7617,     7614,  },
+};
+
+const int XMIT_START_ADJUSTMENT = 5;
+
+#elif F_CPU == 8000000
+
+static const DELAY_TABLE table[] PROGMEM = 
+{
+  //  baud    rxcenter    rxintra    rxstop  tx
+  { 115200,   1,          5,         5,      3,      },
+  { 57600,    1,          15,        15,     13,     },
+  { 38400,    2,          25,        26,     23,     },
+  { 31250,    7,          32,        33,     29,     },
+  { 28800,    11,         35,        35,     32,     },
+  { 19200,    20,         55,        55,     52,     },
+  { 14400,    30,         75,        75,     72,     },
+  { 9600,     50,         114,       114,    112,    },
+  { 4800,     110,        233,       233,    230,    },
+  { 2400,     229,        472,       472,    469,    },
+  { 1200,     467,        948,       948,    945,    },
+  { 600,      948,        1895,      1895,   1890,   },
+  { 300,      1895,       3805,      3805,   3802,   },
+};
+
+const int XMIT_START_ADJUSTMENT = 4;
+
+#elif F_CPU == 20000000
+
+// 20MHz support courtesy of the good people at macegr.com.
+// Thanks, Garrett!
+
+static const DELAY_TABLE PROGMEM table[] =
+{
+  //  baud    rxcenter    rxintra    rxstop  tx
+  { 115200,   3,          21,        21,     18,     },
+  { 57600,    20,         43,        43,     41,     },
+  { 38400,    37,         73,        73,     70,     },
+  { 31250,    45,         89,        89,     88,     },
+  { 28800,    46,         98,        98,     95,     },
+  { 19200,    71,         148,       148,    145,    },
+  { 14400,    96,         197,       197,    194,    },
+  { 9600,     146,        297,       297,    294,    },
+  { 4800,     296,        595,       595,    592,    },
+  { 2400,     592,        1189,      1189,   1186,   },
+  { 1200,     1187,       2379,      2379,   2376,   },
+  { 600,      2379,       4759,      4759,   4755,   },
+  { 300,      4759,       9523,      9523,   9520,   },
+};
+
+const int XMIT_START_ADJUSTMENT = 6;
+
+#else
+
+#error This version of SoftwareSerial supports only 20, 16 and 8MHz processors
+
+#endif
+
+//
+// Statics
+//
+SoftwareSerial *SoftwareSerial::active_object = 0;
+char SoftwareSerial::_receive_buffer[_SS_MAX_RX_BUFF]; 
+volatile uint8_t SoftwareSerial::_receive_buffer_tail = 0;
+volatile uint8_t SoftwareSerial::_receive_buffer_head = 0;
+
+//
+// Debugging
+//
+// This function generates a brief pulse
+// for debugging or measuring on an oscilloscope.
+inline void DebugPulse(uint8_t pin, uint8_t count)
+{
+#if _DEBUG
+  volatile uint8_t *pport = portOutputRegister(digitalPinToPort(pin));
+
+  uint8_t val = *pport;
+  while (count--)
+  {
+    *pport = val | digitalPinToBitMask(pin);
+    *pport = val;
+  }
+#endif
+}
+
+//
+// Private methods
+//
+
+/* static */ 
+inline void SoftwareSerial::tunedDelay(uint16_t delay) { 
+  uint8_t tmp=0;
+
+  asm volatile("sbiw    %0, 0x01 \n\t"
+    "ldi %1, 0xFF \n\t"
+    "cpi %A0, 0xFF \n\t"
+    "cpc %B0, %1 \n\t"
+    "brne .-10 \n\t"
+    : "+r" (delay), "+a" (tmp)
+    : "0" (delay)
+    );
+}
+
+// This function sets the current object as the "listening"
+// one and returns true if it replaces another 
+bool SoftwareSerial::listen()
+{
+  if (active_object != this)
+  {
+    _buffer_overflow = false;
+    uint8_t oldSREG = SREG;
+    cli();
+    _receive_buffer_head = _receive_buffer_tail = 0;
+    active_object = this;
+    SREG = oldSREG;
+    return true;
+  }
+
+  return false;
+}
+
+//
+// The receive routine called by the interrupt handler
+//
+void SoftwareSerial::recv()
+{
+
+#if GCC_VERSION < 40302
+// Work-around for avr-gcc 4.3.0 OSX version bug
+// Preserve the registers that the compiler misses
+// (courtesy of Arduino forum user *etracer*)
+  asm volatile(
+    "push r18 \n\t"
+    "push r19 \n\t"
+    "push r20 \n\t"
+    "push r21 \n\t"
+    "push r22 \n\t"
+    "push r23 \n\t"
+    "push r26 \n\t"
+    "push r27 \n\t"
+    ::);
+#endif  
+
+  uint8_t d = 0;
+
+  // If RX line is high, then we don't see any start bit
+  // so interrupt is probably not for us
+  if (_inverse_logic ? rx_pin_read() : !rx_pin_read())
+  {
+    // Wait approximately 1/2 of a bit width to "center" the sample
+    tunedDelay(_rx_delay_centering);
+    DebugPulse(_DEBUG_PIN2, 1);
+
+    // Read each of the 8 bits
+    for (uint8_t i=0x1; i; i <<= 1)
+    {
+      tunedDelay(_rx_delay_intrabit);
+      DebugPulse(_DEBUG_PIN2, 1);
+      uint8_t noti = ~i;
+      if (rx_pin_read())
+        d |= i;
+      else // else clause added to ensure function timing is ~balanced
+        d &= noti;
+    }
+
+    // skip the stop bit
+    tunedDelay(_rx_delay_stopbit);
+    DebugPulse(_DEBUG_PIN2, 1);
+
+    if (_inverse_logic)
+      d = ~d;
+
+    // if buffer full, set the overflow flag and return
+    if ((_receive_buffer_tail + 1) % _SS_MAX_RX_BUFF != _receive_buffer_head) 
+    {
+      // save new data in buffer: tail points to where byte goes
+      _receive_buffer[_receive_buffer_tail] = d; // save new byte
+      _receive_buffer_tail = (_receive_buffer_tail + 1) % _SS_MAX_RX_BUFF;
+    } 
+    else 
+    {
+#if _DEBUG // for scope: pulse pin as overflow indictator
+      DebugPulse(_DEBUG_PIN1, 1);
+#endif
+      _buffer_overflow = true;
+    }
+  }
+
+#if GCC_VERSION < 40302
+// Work-around for avr-gcc 4.3.0 OSX version bug
+// Restore the registers that the compiler misses
+  asm volatile(
+    "pop r27 \n\t"
+    "pop r26 \n\t"
+    "pop r23 \n\t"
+    "pop r22 \n\t"
+    "pop r21 \n\t"
+    "pop r20 \n\t"
+    "pop r19 \n\t"
+    "pop r18 \n\t"
+    ::);
+#endif
+}
+
+void SoftwareSerial::tx_pin_write(uint8_t pin_state)
+{
+  if (pin_state == LOW)
+    *_transmitPortRegister &= ~_transmitBitMask;
+  else
+    *_transmitPortRegister |= _transmitBitMask;
+}
+
+uint8_t SoftwareSerial::rx_pin_read()
+{
+  return *_receivePortRegister & _receiveBitMask;
+}
+
+//
+// Interrupt handling
+//
+
+/* static */
+inline void SoftwareSerial::handle_interrupt()
+{
+  if (active_object)
+  {
+    active_object->recv();
+  }
+}
+
+#if defined(PCINT0_vect)
+ISR(PCINT0_vect)
+{
+  SoftwareSerial::handle_interrupt();
+}
+#endif
+
+#if defined(PCINT1_vect)
+ISR(PCINT1_vect)
+{
+  SoftwareSerial::handle_interrupt();
+}
+#endif
+
+#if defined(PCINT2_vect)
+ISR(PCINT2_vect)
+{
+  SoftwareSerial::handle_interrupt();
+}
+#endif
+
+#if defined(PCINT3_vect)
+ISR(PCINT3_vect)
+{
+  SoftwareSerial::handle_interrupt();
+}
+#endif
+
+//
+// Constructor
+//
+SoftwareSerial::SoftwareSerial(uint8_t receivePin, uint8_t transmitPin, bool inverse_logic /* = false */) : 
+  _rx_delay_centering(0),
+  _rx_delay_intrabit(0),
+  _rx_delay_stopbit(0),
+  _tx_delay(0),
+  _buffer_overflow(false),
+  _inverse_logic(inverse_logic)
+{
+  setTX(transmitPin);
+  setRX(receivePin);
+}
+
+//
+// Destructor
+//
+SoftwareSerial::~SoftwareSerial()
+{
+  end();
+}
+
+void SoftwareSerial::setTX(uint8_t tx)
+{
+  pinMode(tx, OUTPUT);
+  digitalWrite(tx, HIGH);
+  _transmitBitMask = digitalPinToBitMask(tx);
+  uint8_t port = digitalPinToPort(tx);
+  _transmitPortRegister = portOutputRegister(port);
+}
+
+void SoftwareSerial::setRX(uint8_t rx)
+{
+  pinMode(rx, INPUT);
+  if (!_inverse_logic)
+    digitalWrite(rx, HIGH);  // pullup for normal logic!
+  _receivePin = rx;
+  _receiveBitMask = digitalPinToBitMask(rx);
+  uint8_t port = digitalPinToPort(rx);
+  _receivePortRegister = portInputRegister(port);
+}
+
+//
+// Public methods
+//
+
+void SoftwareSerial::begin(long speed)
+{
+  _rx_delay_centering = _rx_delay_intrabit = _rx_delay_stopbit = _tx_delay = 0;
+
+  for (unsigned i=0; i
+#include 
+
+/******************************************************************************
+* Definitions
+******************************************************************************/
+
+#define _SS_MAX_RX_BUFF 64 // RX buffer size
+#ifndef GCC_VERSION
+#define GCC_VERSION (__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__)
+#endif
+
+class SoftwareSerial : public Stream
+{
+private:
+  // per object data
+  uint8_t _receivePin;
+  uint8_t _receiveBitMask;
+  volatile uint8_t *_receivePortRegister;
+  uint8_t _transmitBitMask;
+  volatile uint8_t *_transmitPortRegister;
+
+  uint16_t _rx_delay_centering;
+  uint16_t _rx_delay_intrabit;
+  uint16_t _rx_delay_stopbit;
+  uint16_t _tx_delay;
+
+  uint16_t _buffer_overflow:1;
+  uint16_t _inverse_logic:1;
+
+  // static data
+  static char _receive_buffer[_SS_MAX_RX_BUFF]; 
+  static volatile uint8_t _receive_buffer_tail;
+  static volatile uint8_t _receive_buffer_head;
+  static SoftwareSerial *active_object;
+
+  // private methods
+  void recv();
+  uint8_t rx_pin_read();
+  void tx_pin_write(uint8_t pin_state);
+  void setTX(uint8_t transmitPin);
+  void setRX(uint8_t receivePin);
+
+  // private static method for timing
+  static inline void tunedDelay(uint16_t delay);
+
+public:
+  // public methods
+  SoftwareSerial(uint8_t receivePin, uint8_t transmitPin, bool inverse_logic = false);
+  ~SoftwareSerial();
+  void begin(long speed);
+  bool listen();
+  void end();
+  bool isListening() { return this == active_object; }
+  bool overflow() { bool ret = _buffer_overflow; _buffer_overflow = false; return ret; }
+  int peek();
+
+  virtual size_t write(uint8_t byte);
+  virtual int read();
+  virtual int available();
+  virtual void flush();
+  
+  using Print::write;
+
+  // public only for easy access by interrupt handlers
+  static inline void handle_interrupt();
+};
+
+// Arduino 0012 workaround
+#undef int
+#undef char
+#undef long
+#undef byte
+#undef float
+#undef abs
+#undef round
+
+#endif
diff --git a/libraries/SoftwareSerial/examples/SoftwareSerialExample/SoftwareSerialExample.ino b/libraries/SoftwareSerial/examples/SoftwareSerialExample/SoftwareSerialExample.ino
new file mode 100644
index 0000000..6101bb1
--- /dev/null
+++ b/libraries/SoftwareSerial/examples/SoftwareSerialExample/SoftwareSerialExample.ino
@@ -0,0 +1,55 @@
+/*
+  Software serial multple serial test
+ 
+ Receives from the hardware serial, sends to software serial.
+ Receives from software serial, sends to hardware serial.
+ 
+ The circuit: 
+ * RX is digital pin 10 (connect to TX of other device)
+ * TX is digital pin 11 (connect to RX of other device)
+ 
+ Note:
+ Not all pins on the Mega and Mega 2560 support change interrupts, 
+ so only the following can be used for RX: 
+ 10, 11, 12, 13, 50, 51, 52, 53, 62, 63, 64, 65, 66, 67, 68, 69
+ 
+ Not all pins on the Leonardo support change interrupts, 
+ so only the following can be used for RX: 
+ 8, 9, 10, 11, 14 (MISO), 15 (SCK), 16 (MOSI).
+ 
+ created back in the mists of time
+ modified 25 May 2012
+ by Tom Igoe
+ based on Mikal Hart's example
+ 
+ This example code is in the public domain.
+ 
+ */
+#include 
+
+SoftwareSerial mySerial(10, 11); // RX, TX
+
+void setup()  
+{
+  // Open serial communications and wait for port to open:
+  Serial.begin(57600);
+  while (!Serial) {
+    ; // wait for serial port to connect. Needed for Leonardo only
+  }
+
+
+  Serial.println("Goodnight moon!");
+
+  // set the data rate for the SoftwareSerial port
+  mySerial.begin(4800);
+  mySerial.println("Hello, world?");
+}
+
+void loop() // run over and over
+{
+  if (mySerial.available())
+    Serial.write(mySerial.read());
+  if (Serial.available())
+    mySerial.write(Serial.read());
+}
+
diff --git a/libraries/SoftwareSerial/examples/TwoPortReceive/TwoPortReceive.ino b/libraries/SoftwareSerial/examples/TwoPortReceive/TwoPortReceive.ino
new file mode 100644
index 0000000..d607ee6
--- /dev/null
+++ b/libraries/SoftwareSerial/examples/TwoPortReceive/TwoPortReceive.ino
@@ -0,0 +1,93 @@
+/*
+  Software serial multple serial test
+ 
+ Receives from the two software serial ports, 
+ sends to the hardware serial port. 
+ 
+ In order to listen on a software port, you call port.listen(). 
+ When using two software serial ports, you have to switch ports
+ by listen()ing on each one in turn. Pick a logical time to switch
+ ports, like the end of an expected transmission, or when the 
+ buffer is empty. This example switches ports when there is nothing
+ more to read from a port
+ 
+ The circuit: 
+ Two devices which communicate serially are needed.
+ * First serial device's TX attached to digital pin 2, RX to pin 3
+ * Second serial device's TX attached to digital pin 4, RX to pin 5
+ 
+ Note:
+ Not all pins on the Mega and Mega 2560 support change interrupts, 
+ so only the following can be used for RX: 
+ 10, 11, 12, 13, 50, 51, 52, 53, 62, 63, 64, 65, 66, 67, 68, 69
+ 
+ Not all pins on the Leonardo support change interrupts, 
+ so only the following can be used for RX: 
+ 8, 9, 10, 11, 14 (MISO), 15 (SCK), 16 (MOSI).
+ 
+ created 18 Apr. 2011
+ modified 25 May 2012
+ by Tom Igoe
+ based on Mikal Hart's twoPortRXExample
+ 
+ This example code is in the public domain.
+ 
+ */
+
+#include 
+// software serial #1: TX = digital pin 10, RX = digital pin 11
+SoftwareSerial portOne(10,11);
+
+// software serial #2: TX = digital pin 8, RX = digital pin 9
+// on the Mega, use other pins instead, since 8 and 9 don't work on the Mega
+SoftwareSerial portTwo(8,9);
+
+void setup()
+{
+ // Open serial communications and wait for port to open:
+  Serial.begin(9600);
+   while (!Serial) {
+    ; // wait for serial port to connect. Needed for Leonardo only
+  }
+
+
+  // Start each software serial port
+  portOne.begin(9600);
+  portTwo.begin(9600);
+}
+
+void loop()
+{
+  // By default, the last intialized port is listening.
+  // when you want to listen on a port, explicitly select it:
+  portOne.listen();
+  Serial.println("Data from port one:");
+  // while there is data coming in, read it
+  // and send to the hardware serial port:
+  while (portOne.available() > 0) {
+    char inByte = portOne.read();
+    Serial.write(inByte);
+  }
+
+  // blank line to separate data from the two ports:
+  Serial.println();
+
+  // Now listen on the second port
+  portTwo.listen();
+  // while there is data coming in, read it
+  // and send to the hardware serial port:
+  Serial.println("Data from port two:");
+  while (portTwo.available() > 0) {
+    char inByte = portTwo.read();
+    Serial.write(inByte);
+  }
+
+  // blank line to separate data from the two ports:
+  Serial.println();
+}
+
+
+
+
+
+
diff --git a/libraries/SoftwareSerial/keywords.txt b/libraries/SoftwareSerial/keywords.txt
new file mode 100644
index 0000000..90d4c15
--- /dev/null
+++ b/libraries/SoftwareSerial/keywords.txt
@@ -0,0 +1,27 @@
+#######################################
+# Syntax Coloring Map for NewSoftSerial
+#######################################
+
+#######################################
+# Datatypes (KEYWORD1)
+#######################################
+
+NewSoftSerial	KEYWORD1
+
+#######################################
+# Methods and Functions (KEYWORD2)
+#######################################
+
+begin	KEYWORD2
+end	KEYWORD2
+read	KEYWORD2
+available	KEYWORD2
+isListening	KEYWORD2
+overflow	KEYWORD2
+flush	KEYWORD2
+listen	KEYWORD2
+
+#######################################
+# Constants (LITERAL1)
+#######################################
+
diff --git a/libraries/Stepper/Stepper.cpp b/libraries/Stepper/Stepper.cpp
new file mode 100644
index 0000000..5d6b5e5
--- /dev/null
+++ b/libraries/Stepper/Stepper.cpp
@@ -0,0 +1,220 @@
+/*
+  Stepper.cpp - - Stepper library for Wiring/Arduino - Version 0.4
+  
+  Original library     (0.1) by Tom Igoe.
+  Two-wire modifications   (0.2) by Sebastian Gassner
+  Combination version   (0.3) by Tom Igoe and David Mellis
+  Bug fix for four-wire   (0.4) by Tom Igoe, bug fix from Noah Shibley  
+
+  Drives a unipolar or bipolar stepper motor using  2 wires or 4 wires
+
+  When wiring multiple stepper motors to a microcontroller,
+  you quickly run out of output pins, with each motor requiring 4 connections. 
+
+  By making use of the fact that at any time two of the four motor
+  coils are the inverse  of the other two, the number of
+  control connections can be reduced from 4 to 2. 
+
+  A slightly modified circuit around a Darlington transistor array or an L293 H-bridge
+  connects to only 2 microcontroler pins, inverts the signals received,
+  and delivers the 4 (2 plus 2 inverted ones) output signals required
+  for driving a stepper motor.
+
+  The sequence of control signals for 4 control wires is as follows:
+
+  Step C0 C1 C2 C3
+     1  1  0  1  0
+     2  0  1  1  0
+     3  0  1  0  1
+     4  1  0  0  1
+
+  The sequence of controls signals for 2 control wires is as follows
+  (columns C1 and C2 from above):
+
+  Step C0 C1
+     1  0  1
+     2  1  1
+     3  1  0
+     4  0  0
+
+  The circuits can be found at 
+ 
+http://www.arduino.cc/en/Tutorial/Stepper
+ 
+ 
+ */
+
+
+#include "Arduino.h"
+#include "Stepper.h"
+
+/*
+ * two-wire constructor.
+ * Sets which wires should control the motor.
+ */
+Stepper::Stepper(int number_of_steps, int motor_pin_1, int motor_pin_2)
+{
+  this->step_number = 0;      // which step the motor is on
+  this->speed = 0;        // the motor speed, in revolutions per minute
+  this->direction = 0;      // motor direction
+  this->last_step_time = 0;    // time stamp in ms of the last step taken
+  this->number_of_steps = number_of_steps;    // total number of steps for this motor
+  
+  // Arduino pins for the motor control connection:
+  this->motor_pin_1 = motor_pin_1;
+  this->motor_pin_2 = motor_pin_2;
+
+  // setup the pins on the microcontroller:
+  pinMode(this->motor_pin_1, OUTPUT);
+  pinMode(this->motor_pin_2, OUTPUT);
+  
+  // When there are only 2 pins, set the other two to 0:
+  this->motor_pin_3 = 0;
+  this->motor_pin_4 = 0;
+  
+  // pin_count is used by the stepMotor() method:
+  this->pin_count = 2;
+}
+
+
+/*
+ *   constructor for four-pin version
+ *   Sets which wires should control the motor.
+ */
+
+Stepper::Stepper(int number_of_steps, int motor_pin_1, int motor_pin_2, int motor_pin_3, int motor_pin_4)
+{
+  this->step_number = 0;      // which step the motor is on
+  this->speed = 0;        // the motor speed, in revolutions per minute
+  this->direction = 0;      // motor direction
+  this->last_step_time = 0;    // time stamp in ms of the last step taken
+  this->number_of_steps = number_of_steps;    // total number of steps for this motor
+  
+  // Arduino pins for the motor control connection:
+  this->motor_pin_1 = motor_pin_1;
+  this->motor_pin_2 = motor_pin_2;
+  this->motor_pin_3 = motor_pin_3;
+  this->motor_pin_4 = motor_pin_4;
+
+  // setup the pins on the microcontroller:
+  pinMode(this->motor_pin_1, OUTPUT);
+  pinMode(this->motor_pin_2, OUTPUT);
+  pinMode(this->motor_pin_3, OUTPUT);
+  pinMode(this->motor_pin_4, OUTPUT);
+
+  // pin_count is used by the stepMotor() method:  
+  this->pin_count = 4;  
+}
+
+/*
+  Sets the speed in revs per minute
+
+*/
+void Stepper::setSpeed(long whatSpeed)
+{
+  this->step_delay = 60L * 1000L / this->number_of_steps / whatSpeed;
+}
+
+/*
+  Moves the motor steps_to_move steps.  If the number is negative, 
+   the motor moves in the reverse direction.
+ */
+void Stepper::step(int steps_to_move)
+{  
+  int steps_left = abs(steps_to_move);  // how many steps to take
+  
+  // determine direction based on whether steps_to_mode is + or -:
+  if (steps_to_move > 0) {this->direction = 1;}
+  if (steps_to_move < 0) {this->direction = 0;}
+    
+    
+  // decrement the number of steps, moving one step each time:
+  while(steps_left > 0) {
+  // move only if the appropriate delay has passed:
+  if (millis() - this->last_step_time >= this->step_delay) {
+      // get the timeStamp of when you stepped:
+      this->last_step_time = millis();
+      // increment or decrement the step number,
+      // depending on direction:
+      if (this->direction == 1) {
+        this->step_number++;
+        if (this->step_number == this->number_of_steps) {
+          this->step_number = 0;
+        }
+      } 
+      else { 
+        if (this->step_number == 0) {
+          this->step_number = this->number_of_steps;
+        }
+        this->step_number--;
+      }
+      // decrement the steps left:
+      steps_left--;
+      // step the motor to step number 0, 1, 2, or 3:
+      stepMotor(this->step_number % 4);
+    }
+  }
+}
+
+/*
+ * Moves the motor forward or backwards.
+ */
+void Stepper::stepMotor(int thisStep)
+{
+  if (this->pin_count == 2) {
+    switch (thisStep) {
+      case 0: /* 01 */
+      digitalWrite(motor_pin_1, LOW);
+      digitalWrite(motor_pin_2, HIGH);
+      break;
+      case 1: /* 11 */
+      digitalWrite(motor_pin_1, HIGH);
+      digitalWrite(motor_pin_2, HIGH);
+      break;
+      case 2: /* 10 */
+      digitalWrite(motor_pin_1, HIGH);
+      digitalWrite(motor_pin_2, LOW);
+      break;
+      case 3: /* 00 */
+      digitalWrite(motor_pin_1, LOW);
+      digitalWrite(motor_pin_2, LOW);
+      break;
+    } 
+  }
+  if (this->pin_count == 4) {
+    switch (thisStep) {
+      case 0:    // 1010
+      digitalWrite(motor_pin_1, HIGH);
+      digitalWrite(motor_pin_2, LOW);
+      digitalWrite(motor_pin_3, HIGH);
+      digitalWrite(motor_pin_4, LOW);
+      break;
+      case 1:    // 0110
+      digitalWrite(motor_pin_1, LOW);
+      digitalWrite(motor_pin_2, HIGH);
+      digitalWrite(motor_pin_3, HIGH);
+      digitalWrite(motor_pin_4, LOW);
+      break;
+      case 2:    //0101
+      digitalWrite(motor_pin_1, LOW);
+      digitalWrite(motor_pin_2, HIGH);
+      digitalWrite(motor_pin_3, LOW);
+      digitalWrite(motor_pin_4, HIGH);
+      break;
+      case 3:    //1001
+      digitalWrite(motor_pin_1, HIGH);
+      digitalWrite(motor_pin_2, LOW);
+      digitalWrite(motor_pin_3, LOW);
+      digitalWrite(motor_pin_4, HIGH);
+      break;
+    } 
+  }
+}
+
+/*
+  version() returns the version of the library:
+*/
+int Stepper::version(void)
+{
+  return 4;
+}
diff --git a/libraries/Stepper/Stepper.h b/libraries/Stepper/Stepper.h
new file mode 100644
index 0000000..4094aee
--- /dev/null
+++ b/libraries/Stepper/Stepper.h
@@ -0,0 +1,83 @@
+/*
+  Stepper.h - - Stepper library for Wiring/Arduino - Version 0.4
+  
+  Original library     (0.1) by Tom Igoe.
+  Two-wire modifications   (0.2) by Sebastian Gassner
+  Combination version   (0.3) by Tom Igoe and David Mellis
+  Bug fix for four-wire   (0.4) by Tom Igoe, bug fix from Noah Shibley
+
+  Drives a unipolar or bipolar stepper motor using  2 wires or 4 wires
+
+  When wiring multiple stepper motors to a microcontroller,
+  you quickly run out of output pins, with each motor requiring 4 connections. 
+
+  By making use of the fact that at any time two of the four motor
+  coils are the inverse  of the other two, the number of
+  control connections can be reduced from 4 to 2. 
+
+  A slightly modified circuit around a Darlington transistor array or an L293 H-bridge
+  connects to only 2 microcontroler pins, inverts the signals received,
+  and delivers the 4 (2 plus 2 inverted ones) output signals required
+  for driving a stepper motor.
+
+  The sequence of control signals for 4 control wires is as follows:
+
+  Step C0 C1 C2 C3
+     1  1  0  1  0
+     2  0  1  1  0
+     3  0  1  0  1
+     4  1  0  0  1
+
+  The sequence of controls signals for 2 control wires is as follows
+  (columns C1 and C2 from above):
+
+  Step C0 C1
+     1  0  1
+     2  1  1
+     3  1  0
+     4  0  0
+
+  The circuits can be found at 
+  http://www.arduino.cc/en/Tutorial/Stepper
+*/
+
+// ensure this library description is only included once
+#ifndef Stepper_h
+#define Stepper_h
+
+// library interface description
+class Stepper {
+  public:
+    // constructors:
+    Stepper(int number_of_steps, int motor_pin_1, int motor_pin_2);
+    Stepper(int number_of_steps, int motor_pin_1, int motor_pin_2, int motor_pin_3, int motor_pin_4);
+
+    // speed setter method:
+    void setSpeed(long whatSpeed);
+
+    // mover method:
+    void step(int number_of_steps);
+
+    int version(void);
+
+  private:
+    void stepMotor(int this_step);
+    
+    int direction;        // Direction of rotation
+    int speed;          // Speed in RPMs
+    unsigned long step_delay;    // delay between steps, in ms, based on speed
+    int number_of_steps;      // total number of steps this motor can take
+    int pin_count;        // whether you're driving the motor with 2 or 4 pins
+    int step_number;        // which step the motor is on
+    
+    // motor pin numbers:
+    int motor_pin_1;
+    int motor_pin_2;
+    int motor_pin_3;
+    int motor_pin_4;
+    
+    long last_step_time;      // time stamp in ms of when the last step was taken
+};
+
+#endif
+
diff --git a/libraries/Stepper/examples/MotorKnob/MotorKnob.ino b/libraries/Stepper/examples/MotorKnob/MotorKnob.ino
new file mode 100644
index 0000000..d428186
--- /dev/null
+++ b/libraries/Stepper/examples/MotorKnob/MotorKnob.ino
@@ -0,0 +1,41 @@
+/*
+ * MotorKnob
+ *
+ * A stepper motor follows the turns of a potentiometer
+ * (or other sensor) on analog input 0.
+ *
+ * http://www.arduino.cc/en/Reference/Stepper
+ * This example code is in the public domain.
+ */
+
+#include 
+
+// change this to the number of steps on your motor
+#define STEPS 100
+
+// create an instance of the stepper class, specifying
+// the number of steps of the motor and the pins it's
+// attached to
+Stepper stepper(STEPS, 8, 9, 10, 11);
+
+// the previous reading from the analog input
+int previous = 0;
+
+void setup()
+{
+  // set the speed of the motor to 30 RPMs
+  stepper.setSpeed(30);
+}
+
+void loop()
+{
+  // get the sensor value
+  int val = analogRead(0);
+
+  // move a number of steps equal to the change in the
+  // sensor reading
+  stepper.step(val - previous);
+
+  // remember the previous value of the sensor
+  previous = val;
+}
\ No newline at end of file
diff --git a/libraries/Stepper/examples/stepper_oneRevolution/stepper_oneRevolution.ino b/libraries/Stepper/examples/stepper_oneRevolution/stepper_oneRevolution.ino
new file mode 100644
index 0000000..2dbb57d
--- /dev/null
+++ b/libraries/Stepper/examples/stepper_oneRevolution/stepper_oneRevolution.ino
@@ -0,0 +1,44 @@
+
+/* 
+ Stepper Motor Control - one revolution
+ 
+ This program drives a unipolar or bipolar stepper motor. 
+ The motor is attached to digital pins 8 - 11 of the Arduino.
+ 
+ The motor should revolve one revolution in one direction, then
+ one revolution in the other direction.  
+ 
+  
+ Created 11 Mar. 2007
+ Modified 30 Nov. 2009
+ by Tom Igoe
+ 
+ */
+
+#include 
+
+const int stepsPerRevolution = 200;  // change this to fit the number of steps per revolution
+                                     // for your motor
+
+// initialize the stepper library on pins 8 through 11:
+Stepper myStepper(stepsPerRevolution, 8,9,10,11);            
+
+void setup() {
+  // set the speed at 60 rpm:
+  myStepper.setSpeed(60);
+  // initialize the serial port:
+  Serial.begin(9600);
+}
+
+void loop() {
+  // step one revolution  in one direction:
+   Serial.println("clockwise");
+  myStepper.step(stepsPerRevolution);
+  delay(500);
+  
+   // step one revolution in the other direction:
+  Serial.println("counterclockwise");
+  myStepper.step(-stepsPerRevolution);
+  delay(500); 
+}
+
diff --git a/libraries/Stepper/examples/stepper_oneStepAtATime/stepper_oneStepAtATime.ino b/libraries/Stepper/examples/stepper_oneStepAtATime/stepper_oneStepAtATime.ino
new file mode 100644
index 0000000..36d3299
--- /dev/null
+++ b/libraries/Stepper/examples/stepper_oneStepAtATime/stepper_oneStepAtATime.ino
@@ -0,0 +1,44 @@
+
+/* 
+ Stepper Motor Control - one step at a time
+ 
+ This program drives a unipolar or bipolar stepper motor. 
+ The motor is attached to digital pins 8 - 11 of the Arduino.
+ 
+ The motor will step one step at a time, very slowly.  You can use this to
+ test that you've got the four wires of your stepper wired to the correct
+ pins. If wired correctly, all steps should be in the same direction.
+ 
+ Use this also to count the number of steps per revolution of your motor,
+ if you don't know it.  Then plug that number into the oneRevolution
+ example to see if you got it right.
+ 
+ Created 30 Nov. 2009
+ by Tom Igoe
+ 
+ */
+
+#include 
+
+const int stepsPerRevolution = 200;  // change this to fit the number of steps per revolution
+                                     // for your motor
+
+// initialize the stepper library on pins 8 through 11:
+Stepper myStepper(stepsPerRevolution, 8,9,10,11);            
+
+int stepCount = 0;         // number of steps the motor has taken
+
+void setup() {
+  // initialize the serial port:
+  Serial.begin(9600);
+}
+
+void loop() {
+  // step one step:
+  myStepper.step(1);
+  Serial.print("steps:" );
+  Serial.println(stepCount);
+  stepCount++;
+  delay(500);
+}
+
diff --git a/libraries/Stepper/examples/stepper_speedControl/stepper_speedControl.ino b/libraries/Stepper/examples/stepper_speedControl/stepper_speedControl.ino
new file mode 100644
index 0000000..1a67a55
--- /dev/null
+++ b/libraries/Stepper/examples/stepper_speedControl/stepper_speedControl.ino
@@ -0,0 +1,48 @@
+
+/* 
+ Stepper Motor Control - speed control
+ 
+ This program drives a unipolar or bipolar stepper motor. 
+ The motor is attached to digital pins 8 - 11 of the Arduino.
+ A potentiometer is connected to analog input 0.
+ 
+ The motor will rotate in a clockwise direction. The higher the potentiometer value,
+ the faster the motor speed. Because setSpeed() sets the delay between steps, 
+ you may notice the motor is less responsive to changes in the sensor value at
+ low speeds.
+ 
+ Created 30 Nov. 2009
+ Modified 28 Oct 2010
+ by Tom Igoe
+ 
+ */
+
+#include 
+
+const int stepsPerRevolution = 200;  // change this to fit the number of steps per revolution
+// for your motor
+
+
+// initialize the stepper library on pins 8 through 11:
+Stepper myStepper(stepsPerRevolution, 8,9,10,11);            
+
+int stepCount = 0;  // number of steps the motor has taken
+
+void setup() {
+  // nothing to do inside the setup
+}
+
+void loop() {
+  // read the sensor value:
+  int sensorReading = analogRead(A0);
+  // map it to a range from 0 to 100:
+  int motorSpeed = map(sensorReading, 0, 1023, 0, 100);
+  // set the motor speed:
+  if (motorSpeed > 0) {
+    myStepper.setSpeed(motorSpeed);
+    // step 1/100 of a revolution:
+    myStepper.step(stepsPerRevolution/100);
+  } 
+}
+
+
diff --git a/libraries/Stepper/keywords.txt b/libraries/Stepper/keywords.txt
new file mode 100644
index 0000000..19a0fad
--- /dev/null
+++ b/libraries/Stepper/keywords.txt
@@ -0,0 +1,28 @@
+#######################################
+# Syntax Coloring Map For Test
+#######################################
+
+#######################################
+# Datatypes (KEYWORD1)
+#######################################
+
+Stepper	KEYWORD1
+
+#######################################
+# Methods and Functions (KEYWORD2)
+#######################################
+
+step	KEYWORD2
+setSpeed	KEYWORD2
+version	KEYWORD2
+
+######################################
+# Instances (KEYWORD2)
+#######################################
+direction	KEYWORD2
+speed	KEYWORD2
+
+
+#######################################
+# Constants (LITERAL1)
+#######################################
diff --git a/libraries/Streaming/Examples/streaming_example/streaming_example.pde b/libraries/Streaming/Examples/streaming_example/streaming_example.pde
new file mode 100644
index 0000000..886dedc
--- /dev/null
+++ b/libraries/Streaming/Examples/streaming_example/streaming_example.pde
@@ -0,0 +1,22 @@
+#include 
+
+void setup()
+{
+  Serial.begin(9600);
+  int lettera = 'A';
+  int month = 4, day = 17, year = 2009;
+  
+  Serial << "This is an example of the new streaming" << endl;
+  Serial << "library.  This allows you to print variables" << endl;
+  Serial << "and strings without having to type line after" << endl;
+  Serial << "line of Serial.print() calls.  Examples: " << endl;
+  
+  Serial << "A is " << lettera << "." << endl;
+  Serial << "The current date is " << day << "-" << month << "-" << year << "." << endl;
+  
+  Serial << "You can use modifiers too, for example:" << endl;
+  Serial << _BYTE(lettera) << " is " << _HEX(lettera) << " in hex. " << endl;
+}
+
+void loop()
+{}
diff --git a/libraries/Streaming/Streaming.h b/libraries/Streaming/Streaming.h
new file mode 100644
index 0000000..d57e559
--- /dev/null
+++ b/libraries/Streaming/Streaming.h
@@ -0,0 +1,108 @@
+/*
+Streaming.h - Arduino library for supporting the << streaming operator
+Copyright (c) 2010-2012 Mikal Hart.  All rights reserved.
+
+This library is free software; you can redistribute it and/or
+modify it under the terms of the GNU Lesser General Public
+License as published by the Free Software Foundation; either
+version 2.1 of the License, or (at your option) any later version.
+
+This library is distributed in the hope that it will be useful,
+but WITHOUT ANY WARRANTY; without even the implied warranty of
+MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+Lesser General Public License for more details.
+
+You should have received a copy of the GNU Lesser General Public
+License along with this library; if not, write to the Free Software
+Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#ifndef ARDUINO_STREAMING
+#define ARDUINO_STREAMING
+
+#if defined(ARDUINO) && ARDUINO >= 100
+#include "Arduino.h"
+#else
+#include "WProgram.h"
+#endif
+
+#define STREAMING_LIBRARY_VERSION 5
+
+#define cout Serial
+#define tabl '\t'
+
+// Generic template
+template 
+inline Print &operator <<(Print &stream, T arg) 
+{ stream.print(arg); return stream; }
+
+struct _BASED 
+{ 
+  long val; 
+  int base;
+  _BASED(long v, int b): val(v), base(b) 
+  {}
+};
+
+#if ARDUINO >= 100
+
+struct _BYTE_CODE
+{
+	byte val;
+	_BYTE_CODE(byte v) : val(v)
+	{}
+};
+#define _BYTE(a)    _BYTE_CODE(a)
+
+inline Print &operator <<(Print &obj, const _BYTE_CODE &arg)
+{ obj.write(arg.val); return obj; } 
+
+#else
+
+#define _BYTE(a)    _BASED(a, BYTE)
+
+#endif
+
+#define _HEX(a)     _BASED(a, HEX)
+#define _DEC(a)     _BASED(a, DEC)
+#define _OCT(a)     _BASED(a, OCT)
+#define _BIN(a)     _BASED(a, BIN)
+
+// Specialization for class _BASED
+// Thanks to Arduino forum user Ben Combee who suggested this 
+// clever technique to allow for expressions like
+//   Serial << _HEX(a);
+
+inline Print &operator <<(Print &obj, const _BASED &arg)
+{ obj.print(arg.val, arg.base); return obj; } 
+
+#if ARDUINO >= 18
+// Specialization for class _FLOAT
+// Thanks to Michael Margolis for suggesting a way
+// to accommodate Arduino 0018's floating point precision
+// feature like this:
+//   Serial << _FLOAT(gps_latitude, 6); // 6 digits of precision
+
+struct _FLOAT
+{
+  float val;
+  int digits;
+  _FLOAT(double v, int d): val(v), digits(d)
+  {}
+};
+
+inline Print &operator <<(Print &obj, const _FLOAT &arg)
+{ obj.print(arg.val, arg.digits); return obj; }
+#endif
+
+// Specialization for enum _EndLineCode
+// Thanks to Arduino forum user Paul V. who suggested this
+// clever technique to allow for expressions like
+//   Serial << "Hello!" << endl;
+
+enum _EndLineCode { endl };
+
+inline Print &operator <<(Print &obj, _EndLineCode arg) 
+{ obj.println(); return obj; }
+
+#endif
diff --git a/libraries/Streaming/keywords.txt b/libraries/Streaming/keywords.txt
new file mode 100644
index 0000000..63060a8
--- /dev/null
+++ b/libraries/Streaming/keywords.txt
@@ -0,0 +1,27 @@
+#######################################
+# Syntax Coloring Map for Streaming
+#######################################
+
+#######################################
+# Datatypes (KEYWORD1)
+#######################################
+
+Streaming	KEYWORD1
+
+#######################################
+# Methods and Functions (KEYWORD2)
+#######################################
+
+_HEX	KEYWORD2
+_DEC	KEYWORD2
+_OCT	KEYWORD2
+_BIN	KEYWORD2
+_BYTE	KEYWORD2
+
+#######################################
+# Constants (LITERAL1)
+#######################################
+
+endl	LITERAL1
+cout	LITERAL1
+tabl	LITERAL1
diff --git a/libraries/TCA6424A/TCA6424A.cpp b/libraries/TCA6424A/TCA6424A.cpp
new file mode 100644
index 0000000..851ee6b
--- /dev/null
+++ b/libraries/TCA6424A/TCA6424A.cpp
@@ -0,0 +1,313 @@
+// I2Cdev library collection - TCA6424A I2C device class
+// Based on Texas Instruments TCA6424A datasheet, 9/2010 (document SCPS193B)
+// 7/31/2011 by Jeff Rowberg 
+// 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.
+===============================================
+*/
+
+#include "TCA6424A.h"
+
+/** Default constructor, uses default I2C address.
+ * @see TCA6424A_DEFAULT_ADDRESS
+ */
+TCA6424A::TCA6424A() {
+    devAddr = TCA6424A_DEFAULT_ADDRESS;
+}
+
+/** Specific address constructor.
+ * @param address I2C address
+ * @see TCA6424A_DEFAULT_ADDRESS
+ * @see TCA6424A_ADDRESS_ADDR_LOW
+ * @see TCA6424A_ADDRESS_ADDR_HIGH
+ */
+TCA6424A::TCA6424A(uint8_t address) {
+    devAddr = address;
+}
+
+/** Power on and prepare for general usage.
+ * The TCA6424A I/O expander requires no preparation after power-on. All pins
+ * will be default to INPUT mode, and the device is ready for usage immediately.
+ * This is an empty function for consistency and/or future expansion.
+ */
+void TCA6424A::initialize() {
+}
+
+/** Verify the I2C connection.
+ * Make sure the device is connected and responds as expected.
+ * @return True if connection is valid, false otherwise
+ */
+bool TCA6424A::testConnection() {
+    return I2Cdev::readBytes(devAddr, TCA6424A_RA_INPUT0, 3, buffer) == 3;
+}
+
+// INPUT* registers (x0h - x2h)
+
+/** Get a single INPUT pin's logic level.
+ * @return Pin logic level (0 or 1)
+ */
+bool TCA6424A::readPin(uint16_t pin) {
+    I2Cdev::readBit(devAddr, TCA6424A_RA_INPUT0 + (pin / 8), pin % 8, buffer);
+    return buffer[0];
+}
+/** Get all pin logic levels from one bank.
+ * @param bank Which bank to read (0/1/2 for P0*, P1*, P2* respectively)
+ * @return 8 pins' logic levels (0 or 1 for each pin)
+ */
+uint8_t TCA6424A::readBank(uint8_t bank) {
+    I2Cdev::readByte(devAddr, TCA6424A_RA_INPUT0 + bank, buffer);
+    return buffer[0];
+}
+/** Get all pin logic levels from all banks.
+ * Reads into single 3-byte data container.
+ * @param banks Container for all bank's pin values (P00-P27)
+ */
+void TCA6424A::readAll(uint8_t *banks) {
+    I2Cdev::readBytes(devAddr, TCA6424A_RA_INPUT0, 3, banks);
+}
+/** Get all pin logic levels from all banks.
+ * Reads into individual 1-byte containers.
+ * @param bank0 Container for Bank 0's pin values (P00-P07)
+ * @param bank1 Container for Bank 1's pin values (P10-P17)
+ * @param bank2 Container for Bank 2's pin values (P20-P27)
+ */
+void TCA6424A::readAll(uint8_t *bank0, uint8_t *bank1, uint8_t *bank2) {
+    I2Cdev::readBytes(devAddr, TCA6424A_RA_INPUT0, 3, buffer);
+    *bank0 = buffer[0];
+    *bank1 = buffer[1];
+    *bank2 = buffer[2];
+}
+
+// OUTPUT* registers (x4h - x6h)
+
+/** Get a single OUTPUT pin's setting.
+ * Note that this returns the level set in the flip-flop, and does not
+ * necessarily represent the actual logic level present at the pin.
+ * @return Pin output setting (0 or 1)
+ */
+bool TCA6424A::getPinOutputLevel(uint16_t pin) {
+    I2Cdev::readBit(devAddr, TCA6424A_RA_OUTPUT0 + (pin / 8), pin % 8, buffer);
+    return buffer[0];
+}
+/** Get all pin output settings from one bank.
+ * Note that this returns the level set in the flip-flop, and does not
+ * necessarily represent the actual logic level present at the pin.
+ * @param bank Which bank to read (0/1/2 for P0*, P1*, P2* respectively)
+ * @return 8 pins' output settings (0 or 1 for each pin)
+ */
+uint8_t TCA6424A::getBankOutputLevel(uint8_t bank) {
+    I2Cdev::readByte(devAddr, TCA6424A_RA_OUTPUT0 + bank, buffer);
+    return buffer[0];
+}
+/** Get all pin output settings from all banks.
+ * Reads into single 3-byte data container.
+ * @param banks Container for all bank's pin values (P00-P27)
+ */
+void TCA6424A::getAllOutputLevel(uint8_t *banks) {
+    I2Cdev::readBytes(devAddr, TCA6424A_RA_OUTPUT0, 3, banks);
+}
+/** Get all pin output settings from all banks.
+ * Reads into individual 1-byte containers. Note that this returns the level
+ * set in the flip-flop, and does not necessarily represent the actual logic
+ * level present at the pin.
+ * @param bank0 Container for Bank 0's pin values (P00-P07)
+ * @param bank1 Container for Bank 1's pin values (P10-P17)
+ * @param bank2 Container for Bank 2's pin values (P20-P27)
+ */
+void TCA6424A::getAllOutputLevel(uint8_t *bank0, uint8_t *bank1, uint8_t *bank2) {
+    I2Cdev::readBytes(devAddr, TCA6424A_RA_OUTPUT0, 3, buffer);
+    *bank0 = buffer[0];
+    *bank1 = buffer[1];
+    *bank2 = buffer[2];
+}
+/** Set a single OUTPUT pin's logic level.
+ * @param pin Which pin to write (0-23)
+ * @param value New pin output logic level (0 or 1)
+ */
+void TCA6424A::writePin(uint16_t pin, bool value) {
+    I2Cdev::writeBit(devAddr, TCA6424A_RA_OUTPUT0 + (pin / 8), pin % 8, value);
+}
+/** Set all OUTPUT pins' logic levels in one bank.
+ * @param bank Which bank to write (0/1/2 for P0*, P1*, P2* respectively)
+ * @param value New pins' output logic level (0 or 1 for each pin)
+ */
+void TCA6424A::writeBank(uint8_t bank, uint8_t value) {
+    I2Cdev::writeByte(devAddr, TCA6424A_RA_OUTPUT0 + bank, value);
+}
+/** Set all OUTPUT pins' logic levels in all banks.
+ * @param banks All pins' new logic values (P00-P27) in 3-byte array
+ */
+void TCA6424A::writeAll(uint8_t *banks) {
+    I2Cdev::writeBytes(devAddr, TCA6424A_RA_OUTPUT0 | TCA6424A_AUTO_INCREMENT, 3, banks);
+}
+/** Set all OUTPUT pins' logic levels in all banks.
+ * @param bank0 Bank 0's new logic values (P00-P07)
+ * @param bank1 Bank 1's new logic values (P10-P17)
+ * @param bank2 Bank 2's new logic values (P20-P27)
+ */
+void TCA6424A::writeAll(uint8_t bank0, uint8_t bank1, uint8_t bank2) {
+    buffer[0] = bank0;
+    buffer[1] = bank1;
+    buffer[2] = bank2;
+    I2Cdev::writeBytes(devAddr, TCA6424A_RA_OUTPUT0 | TCA6424A_AUTO_INCREMENT, 3, buffer);
+}
+
+// POLARITY* registers (x8h - xAh)
+
+/** Get a single pin's polarity (normal/inverted) setting.
+ * @return Pin polarity setting (0 or 1)
+ */
+bool TCA6424A::getPinPolarity(uint16_t pin) {
+    I2Cdev::readBit(devAddr, TCA6424A_RA_POLARITY0 + (pin / 8), pin % 8, buffer);
+    return buffer[0];
+}
+/** Get all pin polarity (normal/inverted) settings from one bank.
+ * @param bank Which bank to read (0/1/2 for P0*, P1*, P2* respectively)
+ * @return 8 pins' polarity settings (0 or 1 for each pin)
+ */
+uint8_t TCA6424A::getBankPolarity(uint8_t bank) {
+    I2Cdev::readByte(devAddr, TCA6424A_RA_POLARITY0 + bank, buffer);
+    return buffer[0];
+}
+/** Get all pin polarity (normal/inverted) settings from all banks.
+ * Reads into single 3-byte data container.
+ * @param banks Container for all bank's pin values (P00-P27)
+ */
+void TCA6424A::getAllPolarity(uint8_t *banks) {
+    I2Cdev::readBytes(devAddr, TCA6424A_RA_POLARITY0, 3, banks);
+}
+/** Get all pin polarity (normal/inverted) settings from all banks.
+ * Reads into individual 1-byte containers.
+ * @param bank0 Container for Bank 0's pin values (P00-P07)
+ * @param bank1 Container for Bank 1's pin values (P10-P17)
+ * @param bank2 Container for Bank 2's pin values (P20-P27)
+ */
+void TCA6424A::getAllPolarity(uint8_t *bank0, uint8_t *bank1, uint8_t *bank2) {
+    I2Cdev::readBytes(devAddr, TCA6424A_RA_POLARITY0, 3, buffer);
+    *bank0 = buffer[0];
+    *bank1 = buffer[1];
+    *bank2 = buffer[2];
+}
+/** Set a single pin's polarity (normal/inverted) setting.
+ * @param pin Which pin to write (0-23)
+ * @param polarity New pin polarity setting (0 or 1)
+ */
+void TCA6424A::setPinPolarity(uint16_t pin, bool polarity) {
+    I2Cdev::writeBit(devAddr, TCA6424A_RA_POLARITY0 + (pin / 8), pin % 8, polarity);
+}
+/** Set all pin polarity (normal/inverted) settings in one bank.
+ * @param bank Which bank to write (0/1/2 for P0*, P1*, P2* respectively)
+ * @return New pins' polarity settings (0 or 1 for each pin)
+ */
+void TCA6424A::setBankPolarity(uint8_t bank, uint8_t polarity) {
+    I2Cdev::writeByte(devAddr, TCA6424A_RA_POLARITY0 + bank, polarity);
+}
+/** Set all pin polarity (normal/inverted) settings in all banks.
+ * @param banks All pins' new logic values (P00-P27) in 3-byte array
+ */
+void TCA6424A::setAllPolarity(uint8_t *banks) {
+    I2Cdev::writeBytes(devAddr, TCA6424A_RA_POLARITY0 | TCA6424A_AUTO_INCREMENT, 3, banks);
+}
+/** Set all pin polarity (normal/inverted) settings in all banks.
+ * @param bank0 Bank 0's new polarity values (P00-P07)
+ * @param bank1 Bank 1's new polarity values (P10-P17)
+ * @param bank2 Bank 2's new polarity values (P20-P27)
+ */
+void TCA6424A::setAllPolarity(uint8_t bank0, uint8_t bank1, uint8_t bank2) {
+    buffer[0] = bank0;
+    buffer[1] = bank1;
+    buffer[2] = bank2;
+    I2Cdev::writeBytes(devAddr, TCA6424A_RA_POLARITY0 | TCA6424A_AUTO_INCREMENT, 3, buffer);
+}
+
+// CONFIG* registers (xCh - xEh)
+
+/** Get a single pin's direction (I/O) setting.
+ * @return Pin direction setting (0 or 1)
+ */
+bool TCA6424A::getPinDirection(uint16_t pin) {
+    I2Cdev::readBit(devAddr, TCA6424A_RA_CONFIG0 + (pin / 8), pin % 8, buffer);
+    return buffer[0];
+}
+/** Get all pin direction (I/O) settings from one bank.
+ * @param bank Which bank to read (0/1/2 for P0*, P1*, P2* respectively)
+ * @return 8 pins' direction settings (0 or 1 for each pin)
+ */
+uint8_t TCA6424A::getBankDirection(uint8_t bank) {
+    I2Cdev::readByte(devAddr, TCA6424A_RA_CONFIG0 + bank, buffer);
+    return buffer[0];
+}
+/** Get all pin direction (I/O) settings from all banks.
+ * Reads into single 3-byte data container.
+ * @param banks Container for all bank's pin values (P00-P27)
+ */
+void TCA6424A::getAllDirection(uint8_t *banks) {
+    I2Cdev::readBytes(devAddr, TCA6424A_RA_CONFIG0, 3, banks);
+}
+/** Get all pin direction (I/O) settings from all banks.
+ * Reads into individual 1-byte containers.
+ * @param bank0 Container for Bank 0's pin values (P00-P07)
+ * @param bank1 Container for Bank 1's pin values (P10-P17)
+ * @param bank2 Container for Bank 2's pin values (P20-P27)
+ */
+void TCA6424A::getAllDirection(uint8_t *bank0, uint8_t *bank1, uint8_t *bank2) {
+    I2Cdev::readBytes(devAddr, TCA6424A_RA_CONFIG0, 3, buffer);
+    *bank0 = buffer[0];
+    *bank1 = buffer[1];
+    *bank2 = buffer[2];
+}
+/** Set a single pin's direction (I/O) setting.
+ * @param pin Which pin to write (0-23)
+ * @param direction Pin direction setting (0 or 1)
+ */
+void TCA6424A::setPinDirection(uint16_t pin, bool direction) {
+    I2Cdev::writeBit(devAddr, TCA6424A_RA_CONFIG0 + (pin / 8), pin % 8, direction);
+}
+/** Set all pin direction (I/O) settings in one bank.
+ * @param bank Which bank to read (0/1/2 for P0*, P1*, P2* respectively)
+ * @param direction New pins' direction settings (0 or 1 for each pin)
+ */
+void TCA6424A::setBankDirection(uint8_t bank, uint8_t direction) {
+    I2Cdev::writeByte(devAddr, TCA6424A_RA_CONFIG0 + bank, direction);
+}
+/** Set all pin direction (I/O) settings in all banks.
+ * @param banks All pins' new direction values (P00-P27) in 3-byte array
+ */
+void TCA6424A::setAllDirection(uint8_t *banks) {
+    I2Cdev::writeBytes(devAddr, TCA6424A_RA_CONFIG0 | TCA6424A_AUTO_INCREMENT, 3, banks);
+}
+/** Set all pin direction (I/O) settings in all banks.
+ * @param bank0 Bank 0's new direction values (P00-P07)
+ * @param bank1 Bank 1's new direction values (P10-P17)
+ * @param bank2 Bank 2's new direction values (P20-P27)
+ */
+void TCA6424A::setAllDirection(uint8_t bank0, uint8_t bank1, uint8_t bank2) {
+    buffer[0] = bank0;
+    buffer[1] = bank1;
+    buffer[2] = bank2;
+    I2Cdev::writeBytes(devAddr, TCA6424A_RA_CONFIG0 | TCA6424A_AUTO_INCREMENT, 3, buffer);
+}
diff --git a/libraries/TCA6424A/TCA6424A.h b/libraries/TCA6424A/TCA6424A.h
new file mode 100644
index 0000000..afcacc4
--- /dev/null
+++ b/libraries/TCA6424A/TCA6424A.h
@@ -0,0 +1,140 @@
+// I2Cdev library collection - TCA6424A I2C device class header file
+// Based on Texas Instruments TCA6424A datasheet, 9/2010 (document SCPS193B)
+// 7/31/2011 by Jeff Rowberg 
+// 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 _TCA6424A_H_
+#define _TCA6424A_H_
+
+#include "I2Cdev.h"
+
+#define TCA6424A_ADDRESS_ADDR_LOW   0x22 // address pin low (GND)
+#define TCA6424A_ADDRESS_ADDR_HIGH  0x23 // address pin high (VCC)
+#define TCA6424A_DEFAULT_ADDRESS    TCA6424A_ADDRESS_ADDR_LOW
+
+#define TCA6424A_RA_INPUT0          0x00
+#define TCA6424A_RA_INPUT1          0x01
+#define TCA6424A_RA_INPUT2          0x02
+#define TCA6424A_RA_OUTPUT0         0x04
+#define TCA6424A_RA_OUTPUT1         0x05
+#define TCA6424A_RA_OUTPUT2         0x06
+#define TCA6424A_RA_POLARITY0       0x08
+#define TCA6424A_RA_POLARITY1       0x09
+#define TCA6424A_RA_POLARITY2       0x0A
+#define TCA6424A_RA_CONFIG0         0x0C
+#define TCA6424A_RA_CONFIG1         0x0D
+#define TCA6424A_RA_CONFIG2         0x0E
+
+#define TCA6424A_AUTO_INCREMENT     0x80
+
+#define TCA6424A_LOW                0
+#define TCA6424A_HIGH               1
+
+#define TCA6424A_POLARITY_NORMAL    0
+#define TCA6424A_POLARITY_INVERTED  1
+
+#define TCA6424A_OUTPUT             0
+#define TCA6424A_INPUT              1
+
+#define TCA6424A_P00                0
+#define TCA6424A_P01                1
+#define TCA6424A_P02                2
+#define TCA6424A_P03                3
+#define TCA6424A_P04                4
+#define TCA6424A_P05                5
+#define TCA6424A_P06                6
+#define TCA6424A_P07                7
+#define TCA6424A_P10                8
+#define TCA6424A_P11                9
+#define TCA6424A_P12                10
+#define TCA6424A_P13                11
+#define TCA6424A_P14                12
+#define TCA6424A_P15                13
+#define TCA6424A_P16                14
+#define TCA6424A_P17                15
+#define TCA6424A_P20                16
+#define TCA6424A_P21                17
+#define TCA6424A_P22                18
+#define TCA6424A_P23                19
+#define TCA6424A_P24                20
+#define TCA6424A_P25                21
+#define TCA6424A_P26                22
+#define TCA6424A_P27                23
+
+class TCA6424A {
+    public:
+        TCA6424A();
+        TCA6424A(uint8_t address);
+        
+        void initialize();
+        bool testConnection();
+        
+        // INPUT* registers (x0h - x2h)
+        bool readPin(uint16_t pin);
+        uint8_t readBank(uint8_t bank);
+        void readAll(uint8_t *banks);
+        void readAll(uint8_t *bank0, uint8_t *bank1, uint8_t *bank2);
+
+        // OUTPUT* registers (x4h - x6h)
+        bool getPinOutputLevel(uint16_t pin);
+        uint8_t getBankOutputLevel(uint8_t bank);
+        void getAllOutputLevel(uint8_t *banks);
+        void getAllOutputLevel(uint8_t *bank0, uint8_t *bank1, uint8_t *bank2);
+        void writePin(uint16_t pin, bool polarity);
+        void writeBank(uint8_t bank, uint8_t value);
+        void writeAll(uint8_t *banks);
+        void writeAll(uint8_t bank0, uint8_t bank1, uint8_t bank2);
+
+        // POLARITY* registers (x8h - xAh)
+        bool getPinPolarity(uint16_t pin);
+        uint8_t getBankPolarity(uint8_t bank);
+        void getAllPolarity(uint8_t *banks);
+        void getAllPolarity(uint8_t *bank0, uint8_t *bank1, uint8_t *bank2);
+        void setPinPolarity(uint16_t pin, bool polarity);
+        void setBankPolarity(uint8_t bank, uint8_t polarity);
+        void setAllPolarity(uint8_t *banks);
+        void setAllPolarity(uint8_t bank0, uint8_t bank1, uint8_t bank2);
+
+        // CONFIG* registers (xCh - xEh)
+        bool getPinDirection(uint16_t pin);
+        uint8_t getBankDirection(uint8_t bank);
+        void getAllDirection(uint8_t *banks);
+        void getAllDirection(uint8_t *bank0, uint8_t *bank1, uint8_t *bank2);
+        void setPinDirection(uint16_t pin, bool direction);
+        void setBankDirection(uint8_t bank, uint8_t direction);
+        void setAllDirection(uint8_t *banks);
+        void setAllDirection(uint8_t bank0, uint8_t bank1, uint8_t bank2);
+
+    private:
+        uint8_t devAddr;
+        uint8_t buffer[3];
+};
+
+#endif /* _TCA6424A_H_ */
diff --git a/libraries/TCA6424A/library.json b/libraries/TCA6424A/library.json
new file mode 100644
index 0000000..a0779df
--- /dev/null
+++ b/libraries/TCA6424A/library.json
@@ -0,0 +1,18 @@
+{
+  "name": "I2Cdevlib-TCA6424A",
+  "keywords": "io, expander, i2cdevlib, i2c",
+  "description": "The TCA6424A is a low-voltage 24-Bit I2C and SMBus I/O expander with interrupt output, reset and configuration registers",
+  "include": "Arduino/TCA6424A",
+  "repository":
+  {
+    "type": "git",
+    "url": "https://github.com/jrowberg/i2cdevlib.git"
+  },
+  "dependencies":
+  {
+    "name": "I2Cdevlib-Core",
+    "frameworks": "arduino"
+  },
+  "frameworks": "arduino",
+  "platforms": "atmelavr"
+}
diff --git a/libraries/TFT_ILI9163C-master/.gitattributes b/libraries/TFT_ILI9163C-master/.gitattributes
new file mode 100644
index 0000000..412eeda
--- /dev/null
+++ b/libraries/TFT_ILI9163C-master/.gitattributes
@@ -0,0 +1,22 @@
+# Auto detect text files and perform LF normalization
+* text=auto
+
+# Custom for Visual Studio
+*.cs     diff=csharp
+*.sln    merge=union
+*.csproj merge=union
+*.vbproj merge=union
+*.fsproj merge=union
+*.dbproj merge=union
+
+# Standard to msysgit
+*.doc	 diff=astextplain
+*.DOC	 diff=astextplain
+*.docx diff=astextplain
+*.DOCX diff=astextplain
+*.dot  diff=astextplain
+*.DOT  diff=astextplain
+*.pdf  diff=astextplain
+*.PDF	 diff=astextplain
+*.rtf	 diff=astextplain
+*.RTF	 diff=astextplain
diff --git a/libraries/TFT_ILI9163C-master/.gitignore b/libraries/TFT_ILI9163C-master/.gitignore
new file mode 100644
index 0000000..b9d6bd9
--- /dev/null
+++ b/libraries/TFT_ILI9163C-master/.gitignore
@@ -0,0 +1,215 @@
+#################
+## Eclipse
+#################
+
+*.pydevproject
+.project
+.metadata
+bin/
+tmp/
+*.tmp
+*.bak
+*.swp
+*~.nib
+local.properties
+.classpath
+.settings/
+.loadpath
+
+# External tool builders
+.externalToolBuilders/
+
+# Locally stored "Eclipse launch configurations"
+*.launch
+
+# CDT-specific
+.cproject
+
+# PDT-specific
+.buildpath
+
+
+#################
+## Visual Studio
+#################
+
+## Ignore Visual Studio temporary files, build results, and
+## files generated by popular Visual Studio add-ons.
+
+# User-specific files
+*.suo
+*.user
+*.sln.docstates
+
+# Build results
+
+[Dd]ebug/
+[Rr]elease/
+x64/
+build/
+[Bb]in/
+[Oo]bj/
+
+# MSTest test Results
+[Tt]est[Rr]esult*/
+[Bb]uild[Ll]og.*
+
+*_i.c
+*_p.c
+*.ilk
+*.meta
+*.obj
+*.pch
+*.pdb
+*.pgc
+*.pgd
+*.rsp
+*.sbr
+*.tlb
+*.tli
+*.tlh
+*.tmp
+*.tmp_proj
+*.log
+*.vspscc
+*.vssscc
+.builds
+*.pidb
+*.log
+*.scc
+
+# Visual C++ cache files
+ipch/
+*.aps
+*.ncb
+*.opensdf
+*.sdf
+*.cachefile
+
+# Visual Studio profiler
+*.psess
+*.vsp
+*.vspx
+
+# Guidance Automation Toolkit
+*.gpState
+
+# ReSharper is a .NET coding add-in
+_ReSharper*/
+*.[Rr]e[Ss]harper
+
+# TeamCity is a build add-in
+_TeamCity*
+
+# DotCover is a Code Coverage Tool
+*.dotCover
+
+# NCrunch
+*.ncrunch*
+.*crunch*.local.xml
+
+# Installshield output folder
+[Ee]xpress/
+
+# DocProject is a documentation generator add-in
+DocProject/buildhelp/
+DocProject/Help/*.HxT
+DocProject/Help/*.HxC
+DocProject/Help/*.hhc
+DocProject/Help/*.hhk
+DocProject/Help/*.hhp
+DocProject/Help/Html2
+DocProject/Help/html
+
+# Click-Once directory
+publish/
+
+# Publish Web Output
+*.Publish.xml
+*.pubxml
+
+# NuGet Packages Directory
+## TODO: If you have NuGet Package Restore enabled, uncomment the next line
+#packages/
+
+# Windows Azure Build Output
+csx
+*.build.csdef
+
+# Windows Store app package directory
+AppPackages/
+
+# Others
+sql/
+*.Cache
+ClientBin/
+[Ss]tyle[Cc]op.*
+~$*
+*~
+*.dbmdl
+*.[Pp]ublish.xml
+*.pfx
+*.publishsettings
+
+# RIA/Silverlight projects
+Generated_Code/
+
+# Backup & report files from converting an old project file to a newer
+# Visual Studio version. Backup files are not needed, because we have git ;-)
+_UpgradeReport_Files/
+Backup*/
+UpgradeLog*.XML
+UpgradeLog*.htm
+
+# SQL Server files
+App_Data/*.mdf
+App_Data/*.ldf
+
+#############
+## Windows detritus
+#############
+
+# Windows image file caches
+Thumbs.db
+ehthumbs.db
+
+# Folder config file
+Desktop.ini
+
+# Recycle Bin used on file shares
+$RECYCLE.BIN/
+
+# Mac crap
+.DS_Store
+
+
+#############
+## Python
+#############
+
+*.py[co]
+
+# Packages
+*.egg
+*.egg-info
+dist/
+build/
+eggs/
+parts/
+var/
+sdist/
+develop-eggs/
+.installed.cfg
+
+# Installer logs
+pip-log.txt
+
+# Unit test / coverage reports
+.coverage
+.tox
+
+#Translations
+*.mo
+
+#Mr Developer
+.mr.developer.cfg
diff --git a/libraries/TFT_ILI9163C-master/README.md b/libraries/TFT_ILI9163C-master/README.md
new file mode 100644
index 0000000..54940cf
--- /dev/null
+++ b/libraries/TFT_ILI9163C-master/README.md
@@ -0,0 +1,221 @@
+TFT_ILI9163C
+
+A fast SPI driver for TFT that use Ilitek ILI9163C driver for Arduino's Teensy's and more...
+
+Current release: 0.9 (old! see below!)
+
+Version 1.0 it's one the corner!
+New version doesn't use the adafruit_GFX and have all the drawing incorporated, this because I've speedup a lot with all processors and uses less resources.
+The very last preview, completely recoded, with GPO Font Rendering an ICON support, also support all the current display around:
+https://github.com/sumotoy/TFT_ILI9163C/tree/Pre-Release-1.0p7
+ +Can be used with IDE 1.0.6 (Teensyduino 1.20) or IDE 1.6.x (Teensyduino 1.21b or better)
+ +Notice: In early 2016 appeared in the market a new version of this display with yellow pins and slight smaller.
+This version needs the 'pre-release' 1.0r6 or better that will released sunday 17/4/2016
+ +![ILI9163C](http://i1189.photobucket.com/albums/z437/theamra/github/CIMG6810.jpg) + + Link to a video: + +https://www.youtube.com/watch?v=y5f-VNBxgEk&feature=youtu.be + + Tested with: + Teensy 3.0 -> really fast + Teensy 3.1 -> really fast + Teensy LC -> still not 100% optimized but fast + UNO and similar -> still not 100% optimized but fast + DUE -> still not 100% optimized but fast + ESP8266 -> use the preview 1.0p4 and works + +========================== + +Features: + + - Very FAST!, expecially with Teensy 3.x where uses hyper fast SPI. + - Tons of examples !!! + - It uses just 4 wires (2 shared with other devices). + - Compatible at command level with Adafruit display series so it's easy to adapt existing code. + - It uses the standard Adafruit_GFX Library (you need to install). + - SPI transaction compatible (only where supported, actually only Teensy3 but soon more) + - Working with IDE 1.0.6, 1.5.8 (or newer), Energia (soon) + - Working with Arduino's (8 and 32 bit), Teensy 3, Teensy 3.1 and Teensy LC + - Working with Energia supported MCU (not yet but really soon) + - A Fast SPI DMA for Nucleo F411RE porting from MasudaNaika https://github.com/MasudaNaika + - Current version should work even with ESP8266! + +http://developer.mbed.org/users/peu605/code/TFT_ILI9163C/ + +Pay Attention to connections!!!!: + + - This display has logic at 3V3 volt so YOU NEED A VOLTAGE CONVERTER if you plan to use with arduino. + If you try to connect directly you can burn it very fast so PAY ATTENTION! + - My display works at 3V3 volt and uses 3V3 for logic but LED background has resistor for 5V. + Your can be different so carefully check out before connect it. + - Library works only in SPI mode by using MOSI,SCLK and a CS pin plus an additional pin for DC (or RS). + I've used also the reset pin but you can save it by connect it at 3V3 volt and use the constructor without + the reset pin. The initialization routine will automatically use the software reset. + + - Teensy 3 and LC cannot use any pin for CS and RS(DC) but should be choosen as follow: + pins:2,6,9 or 10,15 or 20,13 for CS and RS. + The benchmark.ino example has a routine that can help you to understand if you have choosed the right pin for your Teensy. + For reset you can use any pin, if you want to save a wire and not use reset, YOU SHOULD CONNECT TO 3V3 OR USE + A PULLUP RESISTOR (10K to 3V3) BUT NOT LEAVE FLOATING! + +Backgrounds: + + I got one of those displays from a chinese ebay seller but unfortunatly I cannot get + any working library so I decided to work on it. ILI9163C looks pretty similar to other + display driver but it uses it's own commands so it's tricky to work with it unlsess you + carefully fight with his gigantic and confused datasheet. + My display it's a 1.44"", 128x128 that suppose to substitute Nokia 5110 LCD and here's the + first confusion! Many sellers claim that it's compatible with Nokia 5110 (that use a philips + controller) but the only similarity it's the pin names since that this one it's color and + have totally different controller that's not compatible. Altrough I discovered that it's not + 128x128 but 128x160 (!??)... Check links below to see if it's similar to yours. + UPDATE: + Some chinese seller connected the TFT aligned to bottom, other aligned to top, there's not a sure + way to discover witch is yours so better try one of the configurations. + +http://www.ebay.com/itm/Replace-Nokia-5110-LCD-1-44-Red-Serial-128X128-SPI-Color-TFT-LCD-Display-Module-/141196897388 + +http://www.elecrow.com/144-128x-128-tft-lcd-with-spi-interface-p-855.html + + This TFT it's really cheap but has surprising features since it support very high speed SPI trasfer + (over 40Mhz tested!) and can be used as frame buffer, colors are quite tunable and has a tons of settings. + It also support repetitive serial transfer so it can react very fast. + +BLACK, RED or ... + + There's different strain of this display on ebay, I have try to tracking all of them but may missing some species! Actually the more popular has a RED pcb and a BLACK pcb that are completely same pcb but mount a different display that need some tweaking, in particular RED ones need offset but also some tweak for colors, etc. In the .h file in the library try to comment out one of the presets: + //#define __144_RED_PCB__ + #define __144_BLACK_PCB__ + //#define __22_RED_PCB__ + I have a discussion here where a couple of users claim that the _GRAMHEIGH propriety should be always 128. + This is true ONLY if you will never use scroll! Scroll use the entire memory mapped to screen, my RED tag one + it's 128x128 but it uses 128x160! If during scroll you have some garbage means that you have not correctly + setup the display property: + + #define _TFTWIDTH 128//the REAL W resolution of the TFT + #define _TFTHEIGHT 128//the REAL H resolution of the TFT + #define _GRAMWIDTH 128 + #define _GRAMHEIGH 160//Heh? Yes! My display uses offset! + #define _GRAMSIZE _GRAMWIDTH * _GRAMHEIGH // + #define __COLORSPC 1// 1:GBR - 0:RGB + #define __GAMMASET3 //uncomment for another gamma (1,2,3) + #define __OFFSET 32//this is the offset of my display, 160 - 128 = 32 + + You can write your own one by adding it in the .h file but let me know so I can add for other users. + The OFFSET have sense if the chinese vendor decided to align TFT at bottom lines of the controller. + This is nonsense since it will force you to use all the off-screen area as well (visible only when you use + scrolling). + +Code Optimizations: + + The purpose of this library it's SPEED. I have tried to use hardware optimized calls + where was possible and results are quite good for most applications. + Of course it can be improved so feel free to add suggestions. + You will notice that not all display command was added, this because this chip it's really fast + but have very poor hardware design, for example, the display on/off command will result in a bright + white screen since chip will pullup all display lines (at list my display act as this), a nonsense to me, + should be exact the opposite! Apart display there's other commands that act the same so I decided to + don't include to save space. + The Teensy 3 side it's almost complete and quite optimized, however Arduino's side can be tweaked a bit + by using the same Teensy3 technique (multiple transfer with just one CS call, etc), this will be the 1.0 version. + +Needed stuff you have to install first!!! + + This library use Adafruit GFX library as all my TFT,OLED and LCD libraries: + (Remember to update GFX library often to have more features with this and other library!) + + +https://github.com/adafruit/Adafruit-GFX-Library + + Since Adafruit are quite reluctant to update often I have a 100% compatible one that it's faster and has + more features, faster char rendering, ability to use different fonts etc. + +https://github.com/sumotoy/Adafruit-GFX-Library + + It's 100% compatible with the Adafruit one so don't worry about. + + If you plan to use an SD for the SD example you will need Bill Greyman's SdFat + +https://github.com/greiman/SdFat + + +Wiring: + + You are a newbie and need help? Here's: + This display has 8 pin (at the time I'm writing this): + + TFT side -------------------- microprocessor + - Vcc --> +3V3V(!!!!) + - Gnd --> Gnd + - CS --> CS pin (3v3 level!) + - RST --> connect to a MCU pin or tie to +3V3 or 10K to 3V3 (do NOT leave float!) + - A0 --> DC or RS pin (3v3 level!) + - SDA --> Mosi (3v3 level!) + - SCK --> Sclk (3v3 level!) + - LED --> Some display need a resistor (see note below) + +* Note about led: + +Some display have an internal resistor to limit current, you see on the back of the display, following LED pcb +trace with your eyes and if you see a resistor (100 Ohm mine) you can connect this line directly to +5V. +But be careful do not try connect to 5V before you check the presence of this resistor on pcb, you can try first by using a resistor of 220 ohm, if the image looks very dark, try 100 and if still very dark, tie directly to 5v. + +Utility included: + + Included you will find LCD Image Converter a free utility to convert in code a 24bit image. + +https://github.com/riuson/lcd-image-converter + + see example bigPicture.ino. + I have included datasheet as well. +''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''' + +Special Thanks: + + Thanks Adafruit for his Adafruit_GFX! + Thanks to Paul Stoffregen for his beautiful Teensy3 and high speed SPI magic. + Thanks to riuson https://github.com/riuson for kindly provide lcd tool + ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + +Version: + + 0.1a1: First release, compile correctly. Altrough not fully working! + 0.1a3: Some bugfix, still some addressing problems, partial rotation solved. + 0.1b1: Beta version! Fully working but still not tested with Arduino and DUE (altrough it compile) + 0.2b2: Code cleaned and added support for 2.2" RED PCB displays. + 0.2b4: Bug fixes and added color space support. + 0.3b1: Complete rework on Teensy SPI based on Paul Stoffregen work + SPI transaction,added BLACK TAG 2.2 display + 0.3b2: Added 24bit image display code and example. + 0.5: A lot of changes, preliminary scroll, added sleep and some other command but + most important fixed a nasty bug on fillScreen. If you have download any previous + version you should upgrade since there was several fixes. + 0.6: Added subroutines for SD fast load images (mainly for Teensy3) + 0.6b1: Rolled back clearScreen. Again the datasheet have wrong infos! Grrr + 0.6b2: scroll completed. + 0.6b3: ClearScreen v2 fix. Added idle mode. + 0.7: Gold release candidate. Fixed initialization (thanks Masuda) + 0.75: SPI transactions for Arduino's (beta) please report if troubles (not tested) + 0.8: Added compatibility with IDE 1.6.x (Teensyduino 1.21b) + 0.9: Big changes, support for Teensy LC, alt pin for Teensy's, more CPU, faster DUE, separate setting file, + etc., etc. +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + + Legal Notes: + + This library it's free to use but if you port for other MCU or include in distribution or whatever you have + to leave intact the readme inside the library, add your text about modifications but leave intact the text + in the .h file. + If you included in distributions please leave me a note. + If you porting for other MCU or IDE, leave me a note, I will included in the readme here the link. + +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. diff --git a/libraries/TFT_ILI9163C-master/TFT_ILI9163C.cpp b/libraries/TFT_ILI9163C-master/TFT_ILI9163C.cpp new file mode 100644 index 0000000..cbad3bf --- /dev/null +++ b/libraries/TFT_ILI9163C-master/TFT_ILI9163C.cpp @@ -0,0 +1,1114 @@ +#include "TFT_ILI9163C.h" +#include +#include "pins_arduino.h" +#include "wiring_private.h" +#include + +#if defined(SPI_HAS_TRANSACTION) + static SPISettings ILI9163C_SPI; +#endif + + +//constructors + +#if defined(__MK20DX128__) || defined(__MK20DX256__) + TFT_ILI9163C::TFT_ILI9163C(uint8_t cspin,uint8_t dcpin,uint8_t rstpin,uint8_t mosi,uint8_t sclk) : Adafruit_GFX(_TFTWIDTH,_TFTHEIGHT) + { + _cs = cspin; + _rs = dcpin; + _rst = rstpin; + _mosi = mosi; + _sclk = sclk; + } +#elif defined(__MKL26Z64__) + TFT_ILI9163C::TFT_ILI9163C(uint8_t cspin,uint8_t dcpin,uint8_t rstpin,uint8_t mosi,uint8_t sclk) : Adafruit_GFX(_TFTWIDTH,_TFTHEIGHT) + { + _cs = cspin; + _rs = dcpin; + _rst = rstpin; + _mosi = mosi; + _sclk = sclk; + _useSPI1 = false; + if ((_mosi == 0 || _mosi == 21) && (_sclk == 20)) _useSPI1 = true; + } +#else + TFT_ILI9163C::TFT_ILI9163C(uint8_t cspin,uint8_t dcpin,uint8_t rstpin) : Adafruit_GFX(_TFTWIDTH,_TFTHEIGHT) + { + _cs = cspin; + _rs = dcpin; + _rst = rstpin; + } +#endif + + +//Arduino Uno, Leonardo, Mega, Teensy 2.0, etc +#if defined(__AVR__) + + inline void TFT_ILI9163C::spiwrite(uint8_t c) + { + SPDR = c; + while(!(SPSR & _BV(SPIF))); + } + + void TFT_ILI9163C::writecommand(uint8_t c) + { + #if defined(SPI_HAS_TRANSACTION) + SPI.beginTransaction(ILI9163C_SPI); + #endif + *rsport &= ~rspinmask;//low + *csport &= ~cspinmask;//low + spiwrite(c); + *csport |= cspinmask;//hi + #if defined(SPI_HAS_TRANSACTION) + SPI.endTransaction(); + #endif + } + + void TFT_ILI9163C::writedata(uint8_t c) + { + #if defined(SPI_HAS_TRANSACTION) + SPI.beginTransaction(ILI9163C_SPI); + #endif + *rsport |= rspinmask;//hi + *csport &= ~cspinmask;//low + spiwrite(c); + *csport |= cspinmask;//hi + #if defined(SPI_HAS_TRANSACTION) + SPI.endTransaction(); + #endif + } + + void TFT_ILI9163C::writedata16(uint16_t d) + { + #if defined(SPI_HAS_TRANSACTION) + SPI.beginTransaction(ILI9163C_SPI); + #endif + *rsport |= rspinmask;//hi + *csport &= ~cspinmask;//low + spiwrite(d >> 8); + spiwrite(d); + *csport |= cspinmask;//hi + #if defined(SPI_HAS_TRANSACTION) + SPI.endTransaction(); + #endif + } + + void TFT_ILI9163C::setBitrate(uint32_t n) + { + #if !defined (SPI_HAS_TRANSACTION) + if (n >= 8000000) { + SPI.setClockDivider(SPI_CLOCK_DIV2); + } else if (n >= 4000000) { + SPI.setClockDivider(SPI_CLOCK_DIV4); + } else if (n >= 2000000) { + SPI.setClockDivider(SPI_CLOCK_DIV8); + } else { + SPI.setClockDivider(SPI_CLOCK_DIV16); + } + #endif + } +#elif defined(__SAM3X8E__)// Arduino Due + inline void TFT_ILI9163C::spiwrite(uint8_t c) + { + SPI.transfer(c); + } + + void TFT_ILI9163C::writecommand(uint8_t c) + { + #if defined(SPI_HAS_TRANSACTION) + SPI.beginTransaction(ILI9163C_SPI); + #endif + rsport->PIO_CODR |= rspinmask;//LO + csport->PIO_CODR |= cspinmask;//LO + spiwrite(c); + csport->PIO_SODR |= cspinmask;//HI + #if defined(SPI_HAS_TRANSACTION) + SPI.endTransaction(); + #endif + } + + void TFT_ILI9163C::writedata(uint8_t c) + { + #if defined(SPI_HAS_TRANSACTION) + SPI.beginTransaction(ILI9163C_SPI); + #endif + rsport->PIO_SODR |= rspinmask;//HI + csport->PIO_CODR |= cspinmask;//LO + spiwrite(c); + csport->PIO_SODR |= cspinmask;//HI + #if defined(SPI_HAS_TRANSACTION) + SPI.endTransaction(); + #endif + } + + void TFT_ILI9163C::writedata16(uint16_t d) + { + #if defined(SPI_HAS_TRANSACTION) + SPI.beginTransaction(ILI9163C_SPI); + #endif + rsport->PIO_SODR |= rspinmask;//HI + csport->PIO_CODR |= cspinmask;//LO + spiwrite(d >> 8); + spiwrite(d); + csport->PIO_SODR |= cspinmask;//HI + #if defined(SPI_HAS_TRANSACTION) + SPI.endTransaction(); + #endif + } + + + void TFT_ILI9163C::setBitrate(uint32_t n) + { + #if !defined(SPI_HAS_TRANSACTION) + uint32_t divider = 1; + while (divider < 255) { + if (n >= 84000000 / divider) break; + divider = divider - 1; + } + SPI.setClockDivider(divider); + #endif + } +#elif defined(__MKL26Z64__)//Teensy LC (preliminary + + void TFT_ILI9163C::writecommand(uint8_t c) + { + if (_useSPI1){ + SPI1.beginTransaction(ILI9163C_SPI); + digitalWriteFast(_rs,LOW); + digitalWriteFast(_cs,LOW); + SPI1.transfer(c); + digitalWriteFast(_cs,HIGH); + SPI1.endTransaction(); + } else { + SPI.beginTransaction(ILI9163C_SPI); + digitalWriteFast(_rs,LOW); + digitalWriteFast(_cs,LOW); + SPI.transfer(c); + digitalWriteFast(_cs,HIGH); + SPI.endTransaction(); + } + } + + void TFT_ILI9163C::writedata(uint8_t c) + { + if (_useSPI1){ + SPI1.beginTransaction(ILI9163C_SPI); + digitalWriteFast(_rs,HIGH); + digitalWriteFast(_cs,LOW); + SPI1.transfer(c); + digitalWriteFast(_cs,HIGH); + SPI1.endTransaction(); + } else { + SPI.beginTransaction(ILI9163C_SPI); + digitalWriteFast(_rs,HIGH); + digitalWriteFast(_cs,LOW); + SPI.transfer(c); + digitalWriteFast(_cs,HIGH); + SPI.endTransaction(); + } + } + + void TFT_ILI9163C::writedata16(uint16_t d) + { + if (_useSPI1){ + SPI1.beginTransaction(ILI9163C_SPI); + digitalWriteFast(_rs,HIGH); + digitalWriteFast(_cs,LOW); + SPI1.transfer16(d); + digitalWriteFast(_cs,HIGH); + SPI1.endTransaction(); + } else { + SPI.beginTransaction(ILI9163C_SPI); + digitalWriteFast(_rs,HIGH); + digitalWriteFast(_cs,LOW); + SPI.transfer16(d); + digitalWriteFast(_cs,HIGH); + SPI.endTransaction(); + } + } + + void TFT_ILI9163C::setBitrate(uint32_t n) + { + //nop + } +#elif defined(__MK20DX128__) || defined(__MK20DX256__)//Teensy 3.0 & 3.1 + + void TFT_ILI9163C::setBitrate(uint32_t n) + { + //nop + } +#else + + void TFT_ILI9163C::writecommand(uint8_t c) + { + #if defined(SPI_HAS_TRANSACTION) + SPI.beginTransaction(ILI9163C_SPI); + #endif + digitalWrite(_rs,LOW); + digitalWrite(_cs,LOW); + SPI.transfer(c); + digitalWrite(_cs,HIGH); + #if defined(SPI_HAS_TRANSACTION) + SPI.endTransaction(); + #endif + } + + void TFT_ILI9163C::writedata(uint8_t c) + { + #if defined(SPI_HAS_TRANSACTION) + SPI.beginTransaction(ILI9163C_SPI); + #endif + digitalWrite(_rs,HIGH); + digitalWrite(_cs,LOW); + SPI.transfer(c); + digitalWrite(_cs,HIGH); + #if defined(SPI_HAS_TRANSACTION) + SPI.endTransaction(); + #endif + } + + void TFT_ILI9163C::writedata16(uint16_t d) + { + #if defined(SPI_HAS_TRANSACTION) + SPI.beginTransaction(ILI9163C_SPI); + #endif + digitalWrite(_rs,HIGH); + digitalWrite(_cs,LOW); + SPI.transfer(d >> 8); + SPI.transfer(d); + digitalWrite(_cs,HIGH); + #if defined(SPI_HAS_TRANSACTION) + SPI.endTransaction(); + #endif + } + + void TFT_ILI9163C::setBitrate(uint32_t n) + { + //nop + } +#endif //#if defined(TEENSY3.x) + + +void TFT_ILI9163C::begin(void) +{ + sleep = 0; + _initError = 0b00000000; +#if defined(__AVR__) + pinMode(_rs, OUTPUT); + pinMode(_cs, OUTPUT); + csport = portOutputRegister(digitalPinToPort(_cs)); + rsport = portOutputRegister(digitalPinToPort(_rs)); + cspinmask = digitalPinToBitMask(_cs); + rspinmask = digitalPinToBitMask(_rs); + SPI.begin(); + #if !defined(SPI_HAS_TRANSACTION) + SPI.setClockDivider(SPI_CLOCK_DIV2); // 8 MHz + SPI.setBitOrder(MSBFIRST); + SPI.setDataMode(SPI_MODE0); + #else + ILI9163C_SPI = SPISettings(8000000, MSBFIRST, SPI_MODE0); + #endif + *csport &= ~cspinmask;// toggle CS low so it'll listen to us +#elif defined(__SAM3X8E__) + pinMode(_rs, OUTPUT); + pinMode(_cs, OUTPUT); + csport = digitalPinToPort(_cs); + rsport = digitalPinToPort(_rs); + cspinmask = digitalPinToBitMask(_cs); + rspinmask = digitalPinToBitMask(_rs); + SPI.begin(); + #if !defined(SPI_HAS_TRANSACTION) + SPI.setClockDivider(5); // 8 MHz + SPI.setBitOrder(MSBFIRST); + SPI.setDataMode(SPI_MODE0); + #else + ILI9163C_SPI = SPISettings(24000000, MSBFIRST, SPI_MODE0); + #endif + csport ->PIO_CODR |= cspinmask; // toggle CS low so it'll listen to us +#elif defined(__MKL26Z64__)//Teensy LC (preliminary) + pinMode(_rs, OUTPUT); + pinMode(_cs, OUTPUT); + if (_useSPI1){ + if ((_mosi == 0 || _mosi == 21) && (_sclk == 20)) {//identify alternate SPI channel 1 (24Mhz) + ILI9163C_SPI = SPISettings(24000000, MSBFIRST, SPI_MODE0); + SPI1.setMOSI(_mosi); + SPI1.setSCK(_sclk); + SPI1.begin(); + _useSPI1 = true; //confirm + } else { + bitSet(_initError,0); + return; + } + if (!SPI.pinIsChipSelect(_cs)) {//ERROR + bitSet(_initError,1); + return; + } + } else { + if ((_mosi == 11 || _mosi == 7) && (_sclk == 13 || _sclk == 14)) {//valid SPI pins? + ILI9163C_SPI = SPISettings(12000000, MSBFIRST, SPI_MODE0); + SPI.setMOSI(_mosi); + SPI.setSCK(_sclk); + SPI.begin(); + _useSPI1 = false; //confirm + } else { + bitSet(_initError,0); + return; + } + if (!SPI.pinIsChipSelect(_cs)) {//ERROR + bitSet(_initError,1); + return; + } + } + digitalWriteFast(_cs, LOW); +#elif defined(__MK20DX128__) || defined(__MK20DX256__) + ILI9163C_SPI = SPISettings(30000000, MSBFIRST, SPI_MODE0); + if ((_mosi == 11 || _mosi == 7) && (_sclk == 13 || _sclk == 14)) { + SPI.setMOSI(_mosi); + SPI.setSCK(_sclk); + } else { + bitSet(_initError,0); + return; + } + SPI.begin(); + if (SPI.pinIsChipSelect(_cs, _rs)) { + pcs_data = SPI.setCS(_cs); + pcs_command = pcs_data | SPI.setCS(_rs); + } else { + pcs_data = 0; + pcs_command = 0; + bitSet(_initError,1); + return; + } +#else//all the rest of possible boards + pinMode(_rs, OUTPUT); + pinMode(_cs, OUTPUT); + SPI.begin(); + #if !defined(SPI_HAS_TRANSACTION) + SPI.setClockDivider(4); + SPI.setBitOrder(MSBFIRST); + SPI.setDataMode(SPI_MODE0); + #else + ILI9163C_SPI = SPISettings(8000000, MSBFIRST, SPI_MODE0); + #endif + digitalWrite(_cs, LOW); +#endif + if (_rst != 255) { + pinMode(_rst, OUTPUT); + digitalWrite(_rst, HIGH); + delay(500); + digitalWrite(_rst, LOW); + delay(500); + digitalWrite(_rst, HIGH); + delay(500); + } + +/* +7) MY: 1(bottom to top), 0(top to bottom) Row Address Order +6) MX: 1(R to L), 0(L to R) Column Address Order +5) MV: 1(Exchanged), 0(normal) Row/Column exchange +4) ML: 1(bottom to top), 0(top to bottom) Vertical Refresh Order +3) RGB: 1(BGR), 0(RGB) Color Space +2) MH: 1(R to L), 0(L to R) Horizontal Refresh Order +1) +0) + + MY, MX, MV, ML,RGB, MH, D1, D0 + 0 | 0 | 0 | 0 | 1 | 0 | 0 | 0 //normal + 1 | 0 | 0 | 0 | 1 | 0 | 0 | 0 //Y-Mirror + 0 | 1 | 0 | 0 | 1 | 0 | 0 | 0 //X-Mirror + 1 | 1 | 0 | 0 | 1 | 0 | 0 | 0 //X-Y-Mirror + 0 | 0 | 1 | 0 | 1 | 0 | 0 | 0 //X-Y Exchange + 1 | 0 | 1 | 0 | 1 | 0 | 0 | 0 //X-Y Exchange, Y-Mirror + 0 | 1 | 1 | 0 | 1 | 0 | 0 | 0 //XY exchange + 1 | 1 | 1 | 0 | 1 | 0 | 0 | 0 +*/ + _Mactrl_Data = 0b00000000; + _colorspaceData = __COLORSPC;//start with default data; + chipInit(); +} + +uint8_t TFT_ILI9163C::errorCode(void) +{ + return _initError; +} + +void TFT_ILI9163C::chipInit() { + uint8_t i; + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + + writecommand_cont(CMD_SWRESET);//software reset + delay(500); + + writecommand_cont(CMD_SLPOUT);//exit sleep + delay(5); + + writecommand_cont(CMD_PIXFMT);//Set Color Format 16bit + writedata8_cont(0x05); + delay(5); + + writecommand_cont(CMD_GAMMASET);//default gamma curve 3 + writedata8_cont(0x08);//0x04 + delay(1); + + writecommand_cont(CMD_GAMRSEL);//Enable Gamma adj + writedata8_cont(0x01); + delay(1); + + writecommand_cont(CMD_NORML); + + writecommand_cont(CMD_DFUNCTR); + writedata8_cont(0b11111111);// + writedata8_cont(0b00000110);// + + writecommand_cont(CMD_PGAMMAC);//Positive Gamma Correction Setting + for (i=0;i<15;i++){ + writedata8_cont(pGammaSet[i]); + } + + writecommand_cont(CMD_NGAMMAC);//Negative Gamma Correction Setting + for (i=0;i<15;i++){ + writedata8_cont(nGammaSet[i]); + } + + writecommand_cont(CMD_FRMCTR1);//Frame Rate Control (In normal mode/Full colors) + writedata8_cont(0x08);//0x0C//0x08 + writedata8_cont(0x02);//0x14//0x08 + delay(1); + + writecommand_cont(CMD_DINVCTR);//display inversion + writedata8_cont(0x07); + delay(1); + + writecommand_cont(CMD_PWCTR1);//Set VRH1[4:0] & VC[2:0] for VCI1 & GVDD + writedata8_cont(0x0A);//4.30 - 0x0A + writedata8_cont(0x02);//0x05 + delay(1); + + writecommand_cont(CMD_PWCTR2);//Set BT[2:0] for AVDD & VCL & VGH & VGL + writedata8_cont(0x02); + delay(1); + + writecommand_cont(CMD_VCOMCTR1);//Set VMH[6:0] & VML[6:0] for VOMH & VCOML + writedata8_cont(0x50);//0x50 + writedata8_cont(99);//0x5b + delay(1); + + writecommand_cont(CMD_VCOMOFFS); + writedata8_cont(0);//0x40 + delay(1); + + writecommand_cont(CMD_CLMADRS);//Set Column Address + writedata16_cont(0x00); + writedata16_cont(_GRAMWIDTH); + + writecommand_cont(CMD_PGEADRS);//Set Page Address + writedata16_cont(0x00); + writedata16_cont(_GRAMHEIGH); + // set scroll area (thanks Masuda) + writecommand_cont(CMD_VSCLLDEF); + writedata16_cont(__OFFSET); + writedata16_cont(_GRAMHEIGH - __OFFSET); + writedata16_last(0); + + SPI.endTransaction(); + + colorSpace(_colorspaceData); + + setRotation(0); + + SPI.beginTransaction(ILI9163C_SPI); + + writecommand_cont(CMD_DISPON);//display ON + delay(1); + writecommand_last(CMD_RAMWR);//Memory Write + + SPI.endTransaction(); + delay(1); + #else + writecommand(CMD_SWRESET);//software reset + delay(500); + + writecommand(CMD_SLPOUT);//exit sleep + delay(5); + + writecommand(CMD_PIXFMT);//Set Color Format 16bit + writedata(0x05); + delay(5); + + writecommand(CMD_GAMMASET);//default gamma curve 3 + writedata(0x04);//0x04 + delay(1); + + writecommand(CMD_GAMRSEL);//Enable Gamma adj + writedata(0x01); + delay(1); + + writecommand(CMD_NORML); + + writecommand(CMD_DFUNCTR); + writedata(0b11111111);// + writedata(0b00000110);// + + writecommand(CMD_PGAMMAC);//Positive Gamma Correction Setting + for (i=0;i<15;i++){ + writedata(pGammaSet[i]); + } + + writecommand(CMD_NGAMMAC);//Negative Gamma Correction Setting + for (i=0;i<15;i++){ + writedata(nGammaSet[i]); + } + + writecommand(CMD_FRMCTR1);//Frame Rate Control (In normal mode/Full colors) + writedata(0x08);//0x0C//0x08 + writedata(0x02);//0x14//0x08 + delay(1); + + writecommand(CMD_DINVCTR);//display inversion + writedata(0x07); + delay(1); + + writecommand(CMD_PWCTR1);//Set VRH1[4:0] & VC[2:0] for VCI1 & GVDD + writedata(0x0A);//4.30 - 0x0A + writedata(0x02);//0x05 + delay(1); + + writecommand(CMD_PWCTR2);//Set BT[2:0] for AVDD & VCL & VGH & VGL + writedata(0x02); + delay(1); + + writecommand(CMD_VCOMCTR1);//Set VMH[6:0] & VML[6:0] for VOMH & VCOML + writedata(0x50);//0x50 + writedata(99);//0x5b + delay(1); + + writecommand(CMD_VCOMOFFS); + writedata(0);//0x40 + delay(1); + + writecommand(CMD_CLMADRS);//Set Column Address + writedata16(0x00); + writedata16(_GRAMWIDTH); + + writecommand(CMD_PGEADRS);//Set Page Address + writedata16(0X00); + writedata16(_GRAMHEIGH); + // set scroll area (thanks Masuda) + writecommand(CMD_VSCLLDEF); + writedata16(__OFFSET); + writedata16(_GRAMHEIGH - __OFFSET); + writedata16(0); + + colorSpace(_colorspaceData); + + setRotation(0); + writecommand(CMD_DISPON);//display ON + delay(1); + writecommand(CMD_RAMWR);//Memory Write + + delay(1); + #endif + fillScreen(BLACK); +} + +/* +Colorspace selection: +0: RGB +1: GBR +*/ +void TFT_ILI9163C::colorSpace(uint8_t cspace) { + if (cspace < 1){ + bitClear(_Mactrl_Data,3); + } else { + bitSet(_Mactrl_Data,3); + } +} + +void TFT_ILI9163C::invertDisplay(boolean i) { + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + writecommand_last(i ? CMD_DINVON : CMD_DINVOF); + SPI.endTransaction(); + #else + writecommand(i ? CMD_DINVON : CMD_DINVOF); + #endif +} + +void TFT_ILI9163C::display(boolean onOff) { + if (onOff){ + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + writecommand_last(CMD_DISPON); + SPI.endTransaction(); + #else + writecommand(CMD_DISPON); + #endif + } else { + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + writecommand_last(CMD_DISPOFF); + SPI.endTransaction(); + #else + writecommand(CMD_DISPOFF); + #endif + } +} + +void TFT_ILI9163C::idleMode(boolean onOff) { + if (onOff){ + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + writecommand_last(CMD_IDLEON); + SPI.endTransaction(); + #else + writecommand(CMD_IDLEON); + #endif + } else { + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + writecommand_last(CMD_IDLEOF); + SPI.endTransaction(); + #else + writecommand(CMD_IDLEOF); + #endif + } +} + +void TFT_ILI9163C::sleepMode(boolean mode) { + if (mode){ + if (sleep == 1) return;//already sleeping + sleep = 1; + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + writecommand_last(CMD_SLPIN); + SPI.endTransaction(); + #else + writecommand(CMD_SLPIN); + #endif + delay(5);//needed + } else { + if (sleep == 0) return; //Already awake + sleep = 0; + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + writecommand_last(CMD_SLPOUT); + SPI.endTransaction(); + #else + writecommand(CMD_SLPOUT); + #endif + delay(120);//needed + } +} + +void TFT_ILI9163C::defineScrollArea(uint16_t tfa, uint16_t bfa){ + tfa += __OFFSET; + int16_t vsa = _GRAMHEIGH - tfa - bfa; + if (vsa >= 0) { + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + writecommand_cont(CMD_VSCLLDEF); + writedata16_cont(tfa); + writedata16_cont(vsa); + writedata16_last(bfa); + SPI.endTransaction(); + #else + writecommand(CMD_VSCLLDEF); + writedata16(tfa); + writedata16(vsa); + writedata16(bfa); + #endif + } +} + +void TFT_ILI9163C::scroll(uint16_t adrs) { + if (adrs <= _GRAMHEIGH) { + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + writecommand_cont(CMD_VSSTADRS); + writedata16_last(adrs + __OFFSET); + SPI.endTransaction(); + #else + writecommand(CMD_VSSTADRS); + writedata16(adrs + __OFFSET); + #endif + } +} + + +//corrected! v3 +void TFT_ILI9163C::clearScreen(uint16_t color) { + int px; + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + _setAddrWindow(0x00,0x00,_GRAMWIDTH,_GRAMHEIGH); + for (px = 0;px < _GRAMSIZE; px++){ + writedata16_cont(color); + } + writecommand_last(CMD_NOP); + SPI.endTransaction(); + #else + setAddr(0x00,0x00,_GRAMWIDTH,_GRAMHEIGH);//go home + for (px = 0;px < _GRAMSIZE; px++){ + writedata16(color); + } + #endif +} + +void TFT_ILI9163C::startPushData(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1) { + setAddr(x0,y0,x1,y1); +} + +void TFT_ILI9163C::pushData(uint16_t color) { + #if defined(__MK20DX128__) || defined(__MK20DX256__) + writedata16_cont(color); + #else + writedata16(color); + #endif +} + + +void TFT_ILI9163C::endPushData() { + #if defined(__MK20DX128__) || defined(__MK20DX256__) + writecommand_last(CMD_NOP); + SPI.endTransaction(); + #endif +} + + +void TFT_ILI9163C::pushColor(uint16_t color) { + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + writedata16_last(color); + SPI.endTransaction(); + #else + writedata16(color); + #endif +} + +void TFT_ILI9163C::writeScreen24(const uint32_t *bitmap,uint16_t size) { + uint16_t color; + uint16_t px; + #if defined(__MK20DX128__) || defined(__MK20DX256__) + writecommand_cont(CMD_RAMWR); + for (px = 0;px < size; px++){//16384 + color = Color24To565(bitmap[px]); + writedata16_cont(color); + } + _setAddrWindow(0x00,0x00,_GRAMWIDTH,_GRAMHEIGH);//home + SPI.endTransaction(); + #else + writecommand(CMD_RAMWR); + for (px = 0;px < size; px++){ + color = Color24To565(bitmap[px]); + writedata16(color); + } + homeAddress(); + #endif +} + +void TFT_ILI9163C::homeAddress() { + setAddrWindow(0x00,0x00,_GRAMWIDTH,_GRAMHEIGH); +} + + + +void TFT_ILI9163C::setCursor(int16_t x, int16_t y) { + if (boundaryCheck(x,y)) return; + setAddrWindow(0x00,0x00,x,y); + cursor_x = x; + cursor_y = y; +} + + + + + +void TFT_ILI9163C::drawPixel(int16_t x, int16_t y, uint16_t color) { + if (boundaryCheck(x,y)) return; + if ((x < 0) || (y < 0)) return; + setAddr(x,y,x+1,y+1); + #if defined(__MK20DX128__) || defined(__MK20DX256__) + writedata16_last(color); + SPI.endTransaction(); + #else + writedata16(color); + #endif +} + + + +void TFT_ILI9163C::drawFastVLine(int16_t x, int16_t y, int16_t h, uint16_t color) { + // Rudimentary clipping + if (boundaryCheck(x,y)) return; + if (((y + h) - 1) >= _height) h = _height-y; + setAddr(x,y,x,(y+h)-1); + while (h-- > 0) { + #if defined(__MK20DX128__) || defined(__MK20DX256__) + if (h == 0){ + writedata16_last(color); + } else { + writedata16_cont(color); + } + #else + writedata16(color); + #endif + } + #if defined(SPI_HAS_TRANSACTION) + SPI.endTransaction(); + #endif +} + +bool TFT_ILI9163C::boundaryCheck(int16_t x,int16_t y){ + if ((x >= _width) || (y >= _height)) return true; + return false; +} + +void TFT_ILI9163C::drawFastHLine(int16_t x, int16_t y, int16_t w, uint16_t color) { + // Rudimentary clipping + if (boundaryCheck(x,y)) return; + if (((x+w) - 1) >= _width) w = _width-x; + setAddr(x,y,(x+w)-1,y); + while (w-- > 0) { + #if defined(__MK20DX128__) || defined(__MK20DX256__) + if (w == 0){ + writedata16_last(color); + } else { + writedata16_cont(color); + } + #else + writedata16(color); + #endif + } + #if defined(SPI_HAS_TRANSACTION) + SPI.endTransaction(); + #endif +} + +void TFT_ILI9163C::fillScreen(uint16_t color) { + clearScreen(color); +} + +// fill a rectangle +void TFT_ILI9163C::fillRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color) { + if (boundaryCheck(x,y)) return; + if (((x + w) - 1) >= _width) w = _width - x; + if (((y + h) - 1) >= _height) h = _height - y; + setAddr(x,y,(x+w)-1,(y+h)-1); + for (y = h;y > 0;y--) { + for (x = w;x > 1;x--) { + #if defined(__MK20DX128__) || defined(__MK20DX256__) + writedata16_cont(color); + #else + writedata16(color); + #endif + } + #if defined(__MK20DX128__) || defined(__MK20DX256__) + writedata16_last(color); + #else + writedata16(color); + #endif + } + #if defined(SPI_HAS_TRANSACTION) + SPI.endTransaction(); + #endif +} + +#if defined(__MK20DX128__) || defined(__MK20DX256__) +void TFT_ILI9163C::drawLine(int16_t x0, int16_t y0,int16_t x1, int16_t y1, uint16_t color){ + if (y0 == y1) { + if (x1 > x0) { + drawFastHLine(x0, y0, x1 - x0 + 1, color); + } else if (x1 < x0) { + drawFastHLine(x1, y0, x0 - x1 + 1, color); + } else { + drawPixel(x0, y0, color); + } + return; + } else if (x0 == x1) { + if (y1 > y0) { + drawFastVLine(x0, y0, y1 - y0 + 1, color); + } else { + drawFastVLine(x0, y1, y0 - y1 + 1, color); + } + return; + } + + bool steep = abs(y1 - y0) > abs(x1 - x0); + if (steep) { + swap(x0, y0); + swap(x1, y1); + } + if (x0 > x1) { + swap(x0, x1); + swap(y0, y1); + } + + int16_t dx, dy; + dx = x1 - x0; + dy = abs(y1 - y0); + + int16_t err = dx / 2; + int16_t ystep; + + if (y0 < y1) { + ystep = 1; + } else { + ystep = -1; + } + + SPI.beginTransaction(ILI9163C_SPI); + + int16_t xbegin = x0; + if (steep) { + for (; x0<=x1; x0++) { + err -= dy; + if (err < 0) { + int16_t len = x0 - xbegin; + if (len) { + VLine(y0, xbegin, len + 1, color); + } else { + Pixel(y0, x0, color); + } + xbegin = x0 + 1; + y0 += ystep; + err += dx; + } + } + if (x0 > xbegin + 1) { + VLine(y0, xbegin, x0 - xbegin, color); + } + + } else { + for (; x0<=x1; x0++) { + err -= dy; + if (err < 0) { + int16_t len = x0 - xbegin; + if (len) { + HLine(xbegin, y0, len + 1, color); + } else { + Pixel(x0, y0, color); + } + xbegin = x0 + 1; + y0 += ystep; + err += dx; + } + } + if (x0 > xbegin + 1) { + HLine(xbegin, y0, x0 - xbegin, color); + } + } + writecommand_last(CMD_NOP); + SPI.endTransaction(); +} + +void TFT_ILI9163C::drawRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color){ + SPI.beginTransaction(ILI9163C_SPI); + HLine(x, y, w, color); + HLine(x, y+h-1, w, color); + VLine(x, y, h, color); + VLine(x+w-1, y, h, color); + writecommand_last(CMD_NOP); + SPI.endTransaction(); +} + + +#endif + +void TFT_ILI9163C::setAddr(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1){ + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + _setAddrWindow(x0,y0,x1,y1); + #else + setAddrWindow(x0,y0,x1,y1); + #endif +} + +void TFT_ILI9163C::setAddrWindow(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1) { + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + _setAddrWindow(x0,y0,x1,y1); + SPI.endTransaction(); + #else + writecommand(CMD_CLMADRS); // Column + if (rotation == 0 || rotation > 1){ + writedata16(x0); + writedata16(x1); + } else { + writedata16(x0 + __OFFSET); + writedata16(x1 + __OFFSET); + } + + writecommand(CMD_PGEADRS); // Page + if (rotation == 0){ + writedata16(y0 + __OFFSET); + writedata16(y1 + __OFFSET); + } else { + writedata16(y0); + writedata16(y1); + } + writecommand(CMD_RAMWR); //Into RAM + #endif +} + +#if defined(__MK20DX128__) || defined(__MK20DX256__) +void TFT_ILI9163C::_setAddrWindow(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1) { + writecommand_cont(CMD_CLMADRS); // Column + if (rotation == 0 || rotation > 1){ + writedata16_cont(x0); + writedata16_cont(x1); + } else { + writedata16_cont(x0 + __OFFSET); + writedata16_cont(x1 + __OFFSET); + } + writecommand_cont(CMD_PGEADRS); // Page + if (rotation == 0){ + writedata16_cont(y0 + __OFFSET); + writedata16_cont(y1 + __OFFSET); + } else { + writedata16_cont(y0); + writedata16_cont(y1); + } + writecommand_cont(CMD_RAMWR); //Into RAM +} +#endif + +void TFT_ILI9163C::setRotation(uint8_t m) { + rotation = m % 4; // can't be higher than 3 + switch (rotation) { + case 0: + _Mactrl_Data = 0b00001000; + _width = _TFTWIDTH; + _height = _TFTHEIGHT;//-__OFFSET; + break; + case 1: + _Mactrl_Data = 0b01101000; + _width = _TFTHEIGHT;//-__OFFSET; + _height = _TFTWIDTH; + break; + case 2: + _Mactrl_Data = 0b11001000; + _width = _TFTWIDTH; + _height = _TFTHEIGHT;//-__OFFSET; + break; + case 3: + _Mactrl_Data = 0b10101000; + _width = _TFTWIDTH; + _height = _TFTHEIGHT;//-__OFFSET; + break; + } + colorSpace(_colorspaceData); + #if defined(__MK20DX128__) || defined(__MK20DX256__) + SPI.beginTransaction(ILI9163C_SPI); + writecommand_cont(CMD_MADCTL); + writedata8_last(_Mactrl_Data); + SPI.endTransaction(); + #else + writecommand(CMD_MADCTL); + writedata(_Mactrl_Data); + #endif +} + + + + diff --git a/libraries/TFT_ILI9163C-master/TFT_ILI9163C.h b/libraries/TFT_ILI9163C-master/TFT_ILI9163C.h new file mode 100644 index 0000000..f00ff7b --- /dev/null +++ b/libraries/TFT_ILI9163C-master/TFT_ILI9163C.h @@ -0,0 +1,418 @@ +/* + ILI9163C - A fast SPI driver for TFT that use Ilitek ILI9163C. + + Features: + - Very FAST!, expecially with Teensy 3.x where uses hyper optimized SPI. + - It uses just 4 or 5 wires. + - Compatible at command level with Adafruit display series so it's easy to adapt existing code. + - It uses the standard Adafruit_GFX Library (you need to install). + + Background: + I got one of those displays from a chinese ebay seller but unfortunatly I cannot get + any working library so I decided to hack it. ILI9163C looks pretty similar to other + display driver but it uses it's own commands so it's tricky to work with it unlsess you + carefully fight with his gigantic and not so clever datasheet. + My display it's a 1.44"", 128x128 that suppose to substitute Nokia 5110 LCD and here's the + first confusion! Many sellers claim that it's compatible with Nokia 5110 (that use a philips + controller) but the only similarity it's the pin names since that this one it's color and + have totally different controller that's not compatible. + http://www.ebay.com/itm/Replace-Nokia-5110-LCD-1-44-Red-Serial-128X128-SPI-Color-TFT-LCD-Display-Module-/141196897388 + http://www.elecrow.com/144-128x-128-tft-lcd-with-spi-interface-p-855.html + Pay attention that can drive different resolutions and your display can be + 160*128 or whatever, also there's a strain of this display with a black PCB that a friend of mine + got some weeks ago and need some small changes in library to get working. + If you look at TFT_ILI9163C.h file you can add your modifications and let me know so I + can include for future versions. + + Code Optimizations: + The purpose of this library it's SPEED. I have tried to use hardware optimized calls + where was possible and results are quite good for most applications, actually nly filled circles + are still a bit slow. Many SPI call has been optimized by reduce un-needed triggers to RS and CS + lines. Of course it can be improved so feel free to add suggestions. + ------------------------------------------------------------------------------- + Copyright (c) 2014, .S.U.M.O.T.O.Y., coded by Max MC Costa. + + TFT_ILI9163C Library is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + TFT_ILI9163C Library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with Foobar. If not, see . + ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + This file needs the following Libraries: + + Adafruit_GFX by Adafruit: + https://github.com/adafruit/Adafruit-GFX-Library + Remember to update GFX library often to have more features with this library! + From this version I'm using my version of Adafruit_GFX library: + https://github.com/sumotoy/Adafruit-GFX-Library + It has faster char rendering and some small little optimizations but you can + choose one of the two freely since are both fully compatible. + '''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''''' + Special Thanks: + Thanks Adafruit for his Adafruit_GFX! + Thanks to Paul Stoffregen for his beautiful Teensy3 and DMA SPI. + + +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + Version: + 0.1a1: First release, compile correctly. Altrough not fully working! + 0.1a3: Better but still some addressing problems. + 0.1b1: Beta! Addressing solved, now rotation works and boundaries ok. + 0.2b1: Cleaned up. + 0.2b3: Added 2.2" Red PCB parameters + 0.2b4: Bug fixes, added colorSpace (for future send image) + 0.2b5: Cleaning + 0.3b1: Complete rework on Teensy SPI based on Paul Stoffregen work + SPI transaction,added BLACK TAG 2.2 display + 0.3b2: Minor fix, load 24bit image, Added conversion utility + 0.4: some improvement, new ballistic gauge example! + 0.5: Added scroll and more commands, optimizations + 0.6: Small fix, added SD example and subroutines + 0.6b1: Fix clearscreen, missed a parameter. + 0.6b2: Scroll completed. (thanks Masuda) + 0.6b3: Clear Screen fix v2. Added Idle mode. + 0.7: Init correction.Clear Screen fix v3 (last time?) + 0.75: SPI transactions for arduino's (beta) + 0.8: Compatiblke with IDE 1.0.6 (teensyduino 1.20) and IDE 1.6.x (teensyduino 1.21b) + 0.9: Many changes! Now works with more CPU's, alternative pins for Teensy and Teensy LC + Works (in standard SPI) with Teensy LC. + +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + BugList of the current version: + + Please report any! + + +Here's the speed test between 0.2b5 and 0.3b1 on Teensy3.1 (major SPI changes) +------------------------------------------------------------------------ +Lines 17024 16115 BETTER +Horiz/Vert Lines 5360 5080 BETTER +Rectangles (outline) 4384 4217 BETTER +Rectangles (filled) 96315 91265 BETTER +Circles (filled) 16053 15829 LITTLE BETTER +Circles (outline) 11540 20320 WORST! +Triangles (outline) 5359 5143 BETTER +Triangles (filled) 19088 18741 BETTER +Rounded rects (outline) 8681 12498 LITTLE WORST +Rounded rects (filled) 105453 100213 BETTER +Done! + + +*/ +#ifndef _TFT_ILI9163CLIB_H_ +#define _TFT_ILI9163CLIB_H_ + +//defined(__MKL26Z64__) +#include "Arduino.h" +#include "Print.h" +#include + +#include "_settings/TFT_ILI9163C_settings.h" + +#if !defined(_ADAFRUIT_GFX_VARIANT) + #ifdef __AVR__ + #include + #elif defined(__SAM3X8E__) + #include + #define PROGMEM + #define pgm_read_byte(addr) (*(const unsigned char *)(addr)) + #define pgm_read_word(addr) (*(const unsigned short *)(addr)) + typedef unsigned char prog_uchar; + #endif +#endif + + +//--------- Keep out hands from here!------------- + +#define BLACK 0x0000 +#define WHITE 0xFFFF + +#include "_settings/TFT_ILI9163C_registers.h" + + + +class TFT_ILI9163C : public Adafruit_GFX { + + public: + + #if defined(__MK20DX128__) || defined(__MK20DX256__) + TFT_ILI9163C(uint8_t cspin,uint8_t dcpin,uint8_t rstpin=255,uint8_t mosi=11,uint8_t sclk=13); + #elif defined(__MKL26Z64__) + TFT_ILI9163C(uint8_t cspin,uint8_t dcpin,uint8_t rstpin=255,uint8_t mosi=11,uint8_t sclk=13); + #else + TFT_ILI9163C(uint8_t cspin,uint8_t dcpin,uint8_t rstpin=255); + #endif + //TFT_ILI9163C(uint8_t CS, uint8_t DC);//connect rst pin to VDD + + void begin(void), + setAddrWindow(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1),//graphic Addressing + setCursor(int16_t x,int16_t y),//char addressing + pushColor(uint16_t color), + fillScreen(uint16_t color=0x0000), + clearScreen(uint16_t color=0x0000),//same as fillScreen + drawPixel(int16_t x, int16_t y, 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), + #if defined(__MK20DX128__) || defined(__MK20DX256__)//workaround to get more speed from Teensy + drawLine(int16_t x0, int16_t y0,int16_t x1, int16_t y1, uint16_t color), + drawRect(int16_t x, int16_t y, int16_t w, int16_t h, uint16_t color), + #endif + fillRect(int16_t x, int16_t y, int16_t w, int16_t h,uint16_t color), + setRotation(uint8_t r), + invertDisplay(boolean i); + uint8_t errorCode(void); + void idleMode(boolean onOff); + void display(boolean onOff); + void sleepMode(boolean mode); + void defineScrollArea(uint16_t tfa, uint16_t bfa); + void scroll(uint16_t adrs); + void startPushData(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1); + void pushData(uint16_t color); + void endPushData(); + void writeScreen24(const uint32_t *bitmap,uint16_t size=_TFTWIDTH*_TFTHEIGHT); + inline uint16_t Color565(uint8_t r, uint8_t g, uint8_t b) {return ((r & 0xF8) << 8) | ((g & 0xFC) << 3) | (b >> 3);}; + //convert 24bit color into packet 16 bit one (credits for this are all mine) + inline uint16_t Color24To565(int32_t color_) { return ((((color_ >> 16) & 0xFF) / 8) << 11) | ((((color_ >> 8) & 0xFF) / 4) << 5) | (((color_) & 0xFF) / 8);} + void setBitrate(uint32_t n); + protected: + volatile uint8_t _Mactrl_Data;//container for the memory access control data + uint8_t _colorspaceData; + + #if defined(__AVR__) + void spiwrite(uint8_t); + volatile uint8_t *dataport, *clkport, *csport, *rsport; + uint8_t _cs,_rs,_rst; + uint8_t datapinmask, clkpinmask, cspinmask, rspinmask; + #elif defined(__SAM3X8E__) + void spiwrite(uint8_t); + Pio *dataport, *clkport, *csport, *rsport; + uint8_t _cs,_rs,_rst; + uint32_t datapinmask, clkpinmask, cspinmask, rspinmask; + #elif defined(__MKL26Z64__) + uint8_t _cs,_rs,_rst; + uint8_t _mosi, _sclk; + bool _useSPI1; + #elif defined(__MK20DX128__) || defined(__MK20DX256__) + uint8_t _cs, _rs, _rst; + uint8_t pcs_data, pcs_command; + uint8_t _mosi, _sclk; + + void _setAddrWindow(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1);//graphic Addressing for Teensy + + + //Here's Paul Stoffregen magic in action... + void waitFifoNotFull(void) { + uint32_t sr; + uint32_t tmp __attribute__((unused)); + do { + #if ARDUINO >= 160 + sr = KINETISK_SPI0.SR; + #else + sr = SPI0.SR; + #endif + if (sr & 0xF0) tmp = SPI0_POPR; // drain RX FIFO + } while ((sr & (15 << 12)) > (3 << 12)); + } + + void waitFifoEmpty(void) { + uint32_t sr; + uint32_t tmp __attribute__((unused)); + do { + #if ARDUINO >= 160 + sr = KINETISK_SPI0.SR; + if (sr & 0xF0) tmp = KINETISK_SPI0.POPR; // drain RX FIFO + #else + sr = SPI0.SR; + if (sr & 0xF0) tmp = SPI0_POPR; // drain RX FIFO + #endif + } while ((sr & 0xF0F0) > 0); // wait both RX & TX empty + } + + #if !defined(__FORCECOMPAT_SPI)//faster + void waitTransmitComplete(void) + __attribute__((always_inline)) { + uint32_t tmp __attribute__((unused)); + #if ARDUINO >= 160 + while (!(KINETISK_SPI0.SR & SPI_SR_TCF)) ; // wait until final output done + #else + while (!(SPI0.SR & SPI_SR_TCF)) ; // wait until final output done + #endif + tmp = SPI0_POPR; // drain the final RX FIFO word + } + #else + void waitTransmitComplete(uint32_t mcr) + __attribute__((always_inline)) { + uint32_t tmp __attribute__((unused)); + #if ARDUINO >= 160 + while (1) { + uint32_t sr = KINETISK_SPI0.SR; + if (sr & SPI_SR_EOQF) break; // wait for last transmit + if (sr & 0xF0) tmp = KINETISK_SPI0.POPR; + } + KINETISK_SPI0.SR = SPI_SR_EOQF; + SPI0_MCR = mcr; + while (KINETISK_SPI0.SR & 0xF0) { + tmp = KINETISK_SPI0.POPR; + } + #else + while (1) { + uint32_t sr = SPI0.SR; + if (sr & SPI_SR_EOQF) break; // wait for last transmit + if (sr & 0xF0) tmp = SPI0_POPR; + } + SPI0.SR = SPI_SR_EOQF; + SPI0_MCR = mcr; + while (SPI0.SR & 0xF0) { + tmp = SPI0_POPR; + } + #endif + } + #endif + + void writecommand_cont(uint8_t c) + __attribute__((always_inline)) { + #if ARDUINO >= 160 + KINETISK_SPI0.PUSHR = c | (pcs_command << 16) | SPI_PUSHR_CTAS(0) | SPI_PUSHR_CONT; + #else + SPI0.PUSHR = c | (pcs_command << 16) | SPI_PUSHR_CTAS(0) | SPI_PUSHR_CONT; + #endif + waitFifoNotFull(); + } + + void writedata8_cont(uint8_t c) + __attribute__((always_inline)) { + #if ARDUINO >= 160 + KINETISK_SPI0.PUSHR = c | (pcs_data << 16) | SPI_PUSHR_CTAS(0) | SPI_PUSHR_CONT; + #else + SPI0.PUSHR = c | (pcs_data << 16) | SPI_PUSHR_CTAS(0) | SPI_PUSHR_CONT; + #endif + waitFifoNotFull(); + } + + void writedata16_cont(uint16_t d) + __attribute__((always_inline)) { + #if ARDUINO >= 160 + KINETISK_SPI0.PUSHR = d | (pcs_data << 16) | SPI_PUSHR_CTAS(1) | SPI_PUSHR_CONT; + #else + SPI0.PUSHR = d | (pcs_data << 16) | SPI_PUSHR_CTAS(1) | SPI_PUSHR_CONT; + #endif + waitFifoNotFull(); + } + + #if !defined(__FORCECOMPAT_SPI) + void writecommand_last(uint8_t c) + __attribute__((always_inline)) { + waitFifoEmpty(); + #if ARDUINO >= 160 + KINETISK_SPI0.SR = SPI_SR_TCF; + KINETISK_SPI0.PUSHR = c | (pcs_command << 16) | SPI_PUSHR_CTAS(0); + #else + SPI0.SR = SPI_SR_TCF; + SPI0.PUSHR = c | (pcs_command << 16) | SPI_PUSHR_CTAS(0); + #endif + waitTransmitComplete(); + } + + + void writedata8_last(uint8_t c) + __attribute__((always_inline)) { + waitFifoEmpty(); + #if ARDUINO >= 160 + KINETISK_SPI0.SR = SPI_SR_TCF; + KINETISK_SPI0.PUSHR = c | (pcs_data << 16) | SPI_PUSHR_CTAS(0); + #else + SPI0.SR = SPI_SR_TCF; + SPI0.PUSHR = c | (pcs_data << 16) | SPI_PUSHR_CTAS(0); + #endif + waitTransmitComplete(); + } + + void writedata16_last(uint16_t d) + __attribute__((always_inline)) { + waitFifoEmpty(); + #if ARDUINO >= 160 + KINETISK_SPI0.SR = SPI_SR_TCF; + KINETISK_SPI0.PUSHR = d | (pcs_data << 16) | SPI_PUSHR_CTAS(1); + #else + SPI0.SR = SPI_SR_TCF; + SPI0.PUSHR = d | (pcs_data << 16) | SPI_PUSHR_CTAS(1); + #endif + waitTransmitComplete(); + } + #else + void writecommand_last(uint8_t c) + __attribute__((always_inline)) { + uint32_t mcr = SPI0_MCR; + #if ARDUINO >= 160 + KINETISK_SPI0.PUSHR = c | (pcs_command << 16) | SPI_PUSHR_CTAS(0) | SPI_PUSHR_EOQ; + #else + SPI0.PUSHR = c | (pcs_command << 16) | SPI_PUSHR_CTAS(0) | SPI_PUSHR_EOQ; + #endif + waitTransmitComplete(mcr); + } + + + void writedata8_last(uint8_t c) + __attribute__((always_inline)) { + uint32_t mcr = SPI0_MCR; + #if ARDUINO >= 160 + KINETISK_SPI0.PUSHR = c | (pcs_data << 16) | SPI_PUSHR_CTAS(0) | SPI_PUSHR_EOQ; + #else + SPI0.PUSHR = c | (pcs_data << 16) | SPI_PUSHR_CTAS(0) | SPI_PUSHR_EOQ; + #endif + waitTransmitComplete(mcr); + } + + + void writedata16_last(uint16_t d) + __attribute__((always_inline)) { + uint32_t mcr = SPI0_MCR; + #if ARDUINO >= 160 + KINETISK_SPI0.PUSHR = d | (pcs_data << 16) | SPI_PUSHR_CTAS(1) | SPI_PUSHR_EOQ; + #else + SPI0.PUSHR = d | (pcs_data << 16) | SPI_PUSHR_CTAS(1) | SPI_PUSHR_EOQ; + #endif + waitTransmitComplete(mcr); + } + #endif + void HLine(int16_t x, int16_t y, int16_t w, uint16_t color) + __attribute__((always_inline)) { + _setAddrWindow(x, y, x+w-1, y); + do { writedata16_cont(color); } while (--w > 0); + } + + void VLine(int16_t x, int16_t y, int16_t h, uint16_t color) + __attribute__((always_inline)) { + _setAddrWindow(x, y, x, y+h-1); + do { writedata16_cont(color); } while (--h > 0); + } + + void Pixel(int16_t x, int16_t y, uint16_t color) + __attribute__((always_inline)) { + _setAddrWindow(x, y, x, y); + writedata16_cont(color); + } + #else + uint8_t _cs,_rs,_rst; + #endif + + #if !defined(__MK20DX128__) && !defined(__MK20DX256__) + void writecommand(uint8_t c); + void writedata(uint8_t d); + void writedata16(uint16_t d); + #endif + private: + void colorSpace(uint8_t cspace); + void setAddr(uint16_t x0, uint16_t y0, uint16_t x1, uint16_t y1); + uint8_t sleep; + void chipInit(); + bool boundaryCheck(int16_t x,int16_t y); + void homeAddress(); + uint8_t _initError; +}; +#endif \ No newline at end of file diff --git a/libraries/TFT_ILI9163C-master/_settings/TFT_ILI9163C_registers.h b/libraries/TFT_ILI9163C-master/_settings/TFT_ILI9163C_registers.h new file mode 100644 index 0000000..d31e58a --- /dev/null +++ b/libraries/TFT_ILI9163C-master/_settings/TFT_ILI9163C_registers.h @@ -0,0 +1,54 @@ +#ifndef _TFT_ILI9163C_REG_H_ +#define _TFT_ILI9163C_REG_H_ + + +//ILI9163C registers----------------------- +#define CMD_NOP 0x00//Non operation +#define CMD_SWRESET 0x01//Soft Reset +#define CMD_SLPIN 0x10//Sleep ON +#define CMD_SLPOUT 0x11//Sleep OFF +#define CMD_PTLON 0x12//Partial Mode ON +#define CMD_NORML 0x13//Normal Display ON +#define CMD_DINVOF 0x20//Display Inversion OFF +#define CMD_DINVON 0x21//Display Inversion ON +#define CMD_GAMMASET 0x26//Gamma Set (0x01[1],0x02[2],0x04[3],0x08[4]) +#define CMD_DISPOFF 0x28//Display OFF +#define CMD_DISPON 0x29//Display ON +#define CMD_IDLEON 0x39//Idle Mode ON +#define CMD_IDLEOF 0x38//Idle Mode OFF +#define CMD_CLMADRS 0x2A//Column Address Set +#define CMD_PGEADRS 0x2B//Page Address Set + +#define CMD_RAMWR 0x2C//Memory Write +#define CMD_RAMRD 0x2E//Memory Read +#define CMD_CLRSPACE 0x2D//Color Space : 4K/65K/262K +#define CMD_PARTAREA 0x30//Partial Area +#define CMD_VSCLLDEF 0x33//Vertical Scroll Definition +#define CMD_TEFXLON 0x35//Tearing Effect Line ON +#define CMD_TEFXLOF 0x34//Tearing Effect Line OFF +#define CMD_MADCTL 0x36//Memory Access Control +#define CMD_VSSTADRS 0x37//Vertical Scrolling Start address +#define CMD_PIXFMT 0x3A//Interface Pixel Format +#define CMD_FRMCTR1 0xB1//Frame Rate Control (In normal mode/Full colors) +#define CMD_FRMCTR2 0xB2//Frame Rate Control(In Idle mode/8-colors) +#define CMD_FRMCTR3 0xB3//Frame Rate Control(In Partial mode/full colors) +#define CMD_DINVCTR 0xB4//Display Inversion Control +#define CMD_RGBBLK 0xB5//RGB Interface Blanking Porch setting +#define CMD_DFUNCTR 0xB6//Display Fuction set 5 +#define CMD_SDRVDIR 0xB7//Source Driver Direction Control +#define CMD_GDRVDIR 0xB8//Gate Driver Direction Control + +#define CMD_PWCTR1 0xC0//Power_Control1 +#define CMD_PWCTR2 0xC1//Power_Control2 +#define CMD_PWCTR3 0xC2//Power_Control3 +#define CMD_PWCTR4 0xC3//Power_Control4 +#define CMD_PWCTR5 0xC4//Power_Control5 +#define CMD_VCOMCTR1 0xC5//VCOM_Control 1 +#define CMD_VCOMCTR2 0xC6//VCOM_Control 2 +#define CMD_VCOMOFFS 0xC7//VCOM Offset Control +#define CMD_PGAMMAC 0xE0//Positive Gamma Correction Setting +#define CMD_NGAMMAC 0xE1//Negative Gamma Correction Setting +#define CMD_GAMRSEL 0xF2//GAM_R_SEL + + +#endif \ No newline at end of file diff --git a/libraries/TFT_ILI9163C-master/_settings/TFT_ILI9163C_settings.h b/libraries/TFT_ILI9163C-master/_settings/TFT_ILI9163C_settings.h new file mode 100644 index 0000000..c540dda --- /dev/null +++ b/libraries/TFT_ILI9163C-master/_settings/TFT_ILI9163C_settings.h @@ -0,0 +1,107 @@ +#ifndef _TFT_ILI9163C_USETT_H_ +#define _TFT_ILI9163C_USETT_H_ + + +//DID YOU HAVE A RED PCB, BLACk PCB or WHAT DISPLAY TYPE???????????? +// ---> SELECT HERE <---- +#define __144_RED_PCB__//128x128 +//#define __144_BLACK_PCB__//128x128 +//#define __22_RED_PCB__//240x320 +//--------------------------------------- + + +#if defined(__144_RED_PCB__) +/* +This display: +http://www.ebay.com/itm/Replace-Nokia-5110-LCD-1-44-Red-Serial-128X128-SPI-Color-TFT-LCD-Display-Module-/271422122271 +This particular display has a design error! The controller has 3 pins to configure to constrain +the memory and resolution to a fixed dimension (in that case 128x128) but they leaved those pins +configured for 128x160 so there was several pixel memory addressing problems. +I solved by setup several parameters that dinamically fix the resolution as needed so below +the parameters for this diplay. If you have a strain or a correct display (can happen with chinese) +you can copy those parameters and create setup for different displays. +*/ + #define _TFTWIDTH 128//the REAL W resolution of the TFT + #define _TFTHEIGHT 128//the REAL H resolution of the TFT + #define _GRAMWIDTH 128 + #define _GRAMHEIGH 160//160 + #define _GRAMSIZE _GRAMWIDTH * _GRAMHEIGH//*see note 1 + #define __COLORSPC 1// 1:GBR - 0:RGB + #define __GAMMASET3 //uncomment for another gamma + #define __OFFSET 32//*see note 2 + //Tested! +#elif defined (__144_BLACK_PCB__) + #define _TFTWIDTH 128//the REAL W resolution of the TFT + #define _TFTHEIGHT 128//the REAL H resolution of the TFT + #define _GRAMWIDTH 128 + #define _GRAMHEIGH 128 + #define _GRAMSIZE _GRAMWIDTH * _GRAMHEIGH//*see note 1 + #define __COLORSPC 1// 1:GBR - 0:RGB + #define __GAMMASET1 //uncomment for another gamma + #define __OFFSET 0 + //not tested +#elif defined (__22_RED_PCB__) +/* +Like this one: +http://www.ebay.it/itm/2-2-Serial-SPI-TFT-LCD-Display-Module-240x320-Chip-ILI9340C-PCB-Adapter-SD-Card-/281304733556 +Not tested! +*/ + #define _TFTWIDTH 240//the REAL W resolution of the TFT + #define _TFTHEIGHT 320//the REAL H resolution of the TFT + #define _GRAMWIDTH 240 + #define _GRAMHEIGH 320 + #define _GRAMSIZE _GRAMWIDTH * _GRAMHEIGH + #define __COLORSPC 1// 1:GBR - 0:RGB + #define __GAMMASET1 //uncomment for another gamma + #define __OFFSET 0 +#else + #define _TFTWIDTH 128//128 + #define _TFTHEIGHT 160//160 + #define _GRAMWIDTH 128 + #define _GRAMHEIGH 160 + #define _GRAMSIZE _GRAMWIDTH * _GRAMHEIGH + #define __COLORSPC 1// 1:GBR - 0:RGB + #define __GAMMASET1 + #define __OFFSET 0 +#endif + + #if defined(__GAMMASET1) + const uint8_t pGammaSet[15]= {0x36,0x29,0x12,0x22,0x1C,0x15,0x42,0xB7,0x2F,0x13,0x12,0x0A,0x11,0x0B,0x06}; + const uint8_t nGammaSet[15]= {0x09,0x16,0x2D,0x0D,0x13,0x15,0x40,0x48,0x53,0x0C,0x1D,0x25,0x2E,0x34,0x39}; + #elif defined(__GAMMASET2) + const uint8_t pGammaSet[15]= {0x3F,0x21,0x12,0x22,0x1C,0x15,0x42,0xB7,0x2F,0x13,0x02,0x0A,0x01,0x00,0x00}; + const uint8_t nGammaSet[15]= {0x09,0x18,0x2D,0x0D,0x13,0x15,0x40,0x48,0x53,0x0C,0x1D,0x25,0x2E,0x24,0x29}; + #elif defined(__GAMMASET3) + const uint8_t pGammaSet[15]= {0x3F,0x26,0x23,0x30,0x28,0x10,0x55,0xB7,0x40,0x19,0x10,0x1E,0x02,0x01,0x00}; + const uint8_t nGammaSet[15]= {0x09,0x18,0x2D,0x0D,0x13,0x15,0x40,0x48,0x53,0x0C,0x1D,0x25,0x2E,0x24,0x29}; + #else + const uint8_t pGammaSet[15]= {0x3F,0x25,0x1C,0x1E,0x20,0x12,0x2A,0x90,0x24,0x11,0x00,0x00,0x00,0x00,0x00}; + const uint8_t nGammaSet[15]= {0x20,0x20,0x20,0x20,0x05,0x15,0x00,0xA7,0x3D,0x18,0x25,0x2A,0x2B,0x2B,0x3A}; + #endif +/* + Note 1: The __144_RED_PCB__ display has hardware addressing of 128 x 160 + but the tft resolution it's 128 x 128 so the dram should be set correctly + + Note 2: This is the offset between image in RAM and TFT. In that case 160 - 128 = 32; +*/ +#endif + +/* + +Benchmark Time (microseconds) +Screen fill 74698 +Text 4253 +Text2 15366 +Lines 16034 +Horiz/Vert Lines 5028 +Rectangles (outline) 4183 +Rectangles (filled) 91226 +Circles (filled) 14436 +Circles (outline) 14910 +Triangles (outline) 5069 +Triangles (filled) 30717 +Rounded rects (outline) 9910 +Rounded rects (filled) 99550 +Done! + +*/ \ No newline at end of file diff --git a/libraries/TFT_ILI9163C-master/_utility/ILI9163C.pdf b/libraries/TFT_ILI9163C-master/_utility/ILI9163C.pdf new file mode 100644 index 0000000..273af15 Binary files /dev/null and b/libraries/TFT_ILI9163C-master/_utility/ILI9163C.pdf differ diff --git a/libraries/TFT_ILI9163C-master/_utility/lcd-image-converter.zip b/libraries/TFT_ILI9163C-master/_utility/lcd-image-converter.zip new file mode 100644 index 0000000..69ac28c Binary files /dev/null and b/libraries/TFT_ILI9163C-master/_utility/lcd-image-converter.zip differ diff --git a/libraries/TFT_ILI9163C-master/examples/SD_example/SD_example.ino b/libraries/TFT_ILI9163C-master/examples/SD_example/SD_example.ino new file mode 100644 index 0000000..918d2f1 --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/SD_example/SD_example.ino @@ -0,0 +1,165 @@ +/* +An SD bmp image load example. (extracted and modded by Adafruit old library http://www.adafruit.com ) + This use NOT the adafruit SD library (or the standard arduino SD!) + but SdFat created by bill greiman https://github.com/greiman/SdFat much better to me!!! + Note about SPI Transactions <------------------------------------------- + To enable compatibility for SPI Transactions please open + SfFatCinfig.h in SdFat libary and set + #define ENABLE_SPI_TRANSACTION 0 + to + #define ENABLE_SPI_TRANSACTION 1 + */ + +#include +#include +#include +#include + +//PINS +#define __CS 10 +#define __DC 9 +#define __SDCS 2 + +// This function opens a Windows Bitmap (BMP) file and +// displays it at the given coordinates. It's sped up +// by reading many pixels worth of data at a time +// (rather than pixel by pixel). Increasing the buffer +// size takes more of the Arduino's precious RAM but +// makes loading a little faster. 20 pixels seems a +// good balance. +#define BUFFPIXEL 20 + +boolean SDInited = true; + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); +SdFat SD; +SdFile myFile; + +void setup(void) { + Serial.begin(9600); + + tft.begin(); + //tft.setRotation(2); + + //I have a crappy chinese SD card holder that it's not compatible + //with hi speeds SPI (SPI_FULL_SPEED). If you have better luck set it to + //SPI_FULL_SPEED + if (!SD.begin(__SDCS,SPI_HALF_SPEED)) { + tft.setCursor(0,0); + tft.print("sd failed!"); + SDInited = false; + } + Serial.println("OK!"); + //your image here! + bmpDraw("star.bmp", 0, 0); +} + +void loop() { +} + + + +void bmpDraw(const char *filename, uint8_t x, uint16_t y) { + if (SDInited){ + + File bmpFile; + uint16_t bmpWidth, bmpHeight; // W+H in pixels + uint8_t bmpDepth; // Bit depth (currently must be 24) + uint32_t bmpImageoffset; // Start of image data in file + uint32_t rowSize; // Not always = bmpWidth; may have padding + uint8_t sdbufferLen = BUFFPIXEL * 3; + uint8_t sdbuffer[sdbufferLen]; // pixel buffer (R+G+B per pixel) + uint8_t buffidx = sdbufferLen; // Current position in sdbuffer + boolean goodBmp = false; // Set to true on valid header parse + boolean flip = true; // BMP is stored bottom-to-top + uint16_t w, h, row, col; + uint8_t r, g, b; + uint32_t pos = 0; + + if((x >= tft.width()) || (y >= tft.height())) return; + + // Open requested file on SD card + if ((bmpFile = SD.open(filename)) == NULL) { + tft.setCursor(0,0); + tft.print("file not found!"); + return; + } + + // Parse BMP header + if(read16(bmpFile) == 0x4D42) { // BMP signature + read32(bmpFile); + (void)read32(bmpFile); // Read & ignore creator bytes + bmpImageoffset = read32(bmpFile); // Start of image data + // Read DIB header + read32(bmpFile); + bmpWidth = read32(bmpFile); + bmpHeight = read32(bmpFile); + if(read16(bmpFile) == 1) { // # planes -- must be '1' + bmpDepth = read16(bmpFile); // bits per pixel + if((bmpDepth == 24) && (read32(bmpFile) == 0)) { // 0 = uncompressed + goodBmp = true; // Supported BMP format -- proceed! + rowSize = (bmpWidth * 3 + 3) & ~3;// BMP rows are padded (if needed) to 4-byte boundary + if (bmpHeight < 0) { + bmpHeight = -bmpHeight; + flip = false; + } + // Crop area to be loaded + w = bmpWidth; + h = bmpHeight; + if((x+w-1) >= tft.width()) w = tft.width() - x; + if((y+h-1) >= tft.height()) h = tft.height() - y; + tft.startPushData(x, y, x+w-1, y+h-1); + for (row=0; row= sdbufferLen) { // Indeed + bmpFile.read(sdbuffer, sdbufferLen); + buffidx = 0; // Set index to beginning + } + // Convert pixel from BMP to TFT format, push to display + b = sdbuffer[buffidx++]; + g = sdbuffer[buffidx++]; + r = sdbuffer[buffidx++]; + tft.pushData(tft.Color565(r,g,b)); + } // end pixel + } // end scanline + tft.endPushData(); + } // end goodBmp + } + } + + bmpFile.close(); + if(!goodBmp) { + tft.setCursor(0,0); + tft.print("file unrecognized!"); + } + } +} + + +uint16_t read16(File &f) { + uint16_t result; + ((uint8_t *)&result)[0] = f.read(); // LSB + ((uint8_t *)&result)[1] = f.read(); // MSB + return result; +} + +uint32_t read32(File &f) { + uint32_t result; + ((uint8_t *)&result)[0] = f.read(); // LSB + ((uint8_t *)&result)[1] = f.read(); + ((uint8_t *)&result)[2] = f.read(); + ((uint8_t *)&result)[3] = f.read(); // MSB + return result; +} + diff --git a/libraries/TFT_ILI9163C-master/examples/benchmark/benchmark.ino b/libraries/TFT_ILI9163C-master/examples/benchmark/benchmark.ino new file mode 100644 index 0000000..fcc1dfe --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/benchmark/benchmark.ino @@ -0,0 +1,377 @@ + +#include +#include +#include + +#if defined(__SAM3X8E__) +#undef __FlashStringHelper::F(string_literal) +#define F(string_literal) string_literal +#endif + + +// Color definitions +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF + +uint8_t errorCode = 0; + +/* +Teensy3.x and Arduino's +You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 6 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 +Arduino's 8 bit: any +DUE: check arduino site +If you do not use reset, tie it to +3V3 +*/ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC, 23); + +void setup() { + Serial.begin(38400); + long unsigned debug_start = millis (); + while (!Serial && ((millis () - debug_start) <= 5000)) ; + tft.begin(); + //the following it's mainly for Teensy + //it will help you to understand if you have choosed the + //wrong combination of pins! + errorCode = tft.errorCode(); + if (errorCode != 0) { + Serial.print("Init error! "); + if (bitRead(errorCode, 0)) Serial.print("MOSI or SCLK pin mismach!\n"); + if (bitRead(errorCode, 1)) Serial.print("CS or DC pin mismach!\n"); + } else { + Serial.println(F("Benchmark Time (microseconds)")); + } + if (errorCode == 0) { + Serial.print(F("Screen fill ")); + Serial.println(testFillScreen()); + delay(500); + + Serial.print(F("Text ")); + Serial.println(testText()); + delay(3000); + + Serial.print(F("Text2 ")); + Serial.println(testText2()); + delay(3000); + + Serial.print(F("Lines ")); + Serial.println(testLines(CYAN)); + delay(500); + + Serial.print(F("Horiz/Vert Lines ")); + Serial.println(testFastLines(RED, BLUE)); + delay(500); + + Serial.print(F("Rectangles (outline) ")); + Serial.println(testRects(GREEN)); + delay(500); + + Serial.print(F("Rectangles (filled) ")); + Serial.println(testFilledRects(YELLOW, MAGENTA)); + delay(500); + + Serial.print(F("Circles (filled) ")); + Serial.println(testFilledCircles(10, MAGENTA)); + + Serial.print(F("Circles (outline) ")); + Serial.println(testCircles(10, WHITE)); + delay(500); + + Serial.print(F("Triangles (outline) ")); + Serial.println(testTriangles()); + delay(500); + + Serial.print(F("Triangles (filled) ")); + Serial.println(testFilledTriangles()); + delay(500); + + Serial.print(F("Rounded rects (outline) ")); + Serial.println(testRoundRects()); + delay(500); + + Serial.print(F("Rounded rects (filled) ")); + Serial.println(testFilledRoundRects()); + delay(500); + + Serial.println(F("Done!")); + } +} + +void loop(void) { + for (uint8_t rotation = 0; rotation < 4; rotation++) { + tft.setRotation(rotation); + testText(); + delay(2000); + } +} + + +unsigned long testFillScreen() { + unsigned long start = micros(); + tft.fillScreen(); + tft.fillScreen(RED); + tft.fillScreen(GREEN); + tft.fillScreen(BLUE); + tft.fillScreen(); + return micros() - start; +} + +unsigned long testText() { + tft.fillScreen(); + unsigned long start = micros(); + tft.setCursor(0, 0); + tft.setTextColor(WHITE); + tft.setTextSize(1); + tft.println("Hello World!"); + tft.setTextColor(YELLOW); + tft.setTextSize(2); + tft.println(1234.56); + tft.setTextColor(RED); + tft.setTextSize(3); + tft.println(0xDEAD, HEX); + tft.println(); + tft.setTextColor(GREEN); + tft.setTextSize(4); + tft.println("Hello"); + return micros() - start; + + +} + +unsigned long testText2() { + tft.fillScreen(); + unsigned long start = micros(); + tft.setCursor(0, 0); + tft.setTextColor(WHITE); + tft.setTextSize(2); + tft.println("I implore thee,"); + tft.setTextSize(1); + tft.println("my foonting turlingdromes."); + tft.println("And hooptiously drangle me"); + tft.println("with crinkly bindlewurdles,"); + tft.println("Or I will rend thee"); + tft.println("in the gobberwarts"); + tft.println("with my blurglecruncheon,"); + tft.println("see if I don't!"); + return micros() - start; +} + +unsigned long testLines(uint16_t color) { + unsigned long start, t; + int x1, y1, x2, y2, + w = tft.width(), + h = tft.height(); + + tft.fillScreen(); + + x1 = y1 = 0; + y2 = h - 1; + start = micros(); + for (x2 = 0; x2 < w; x2 += 6) tft.drawLine(x1, y1, x2, y2, color); + x2 = w - 1; + for (y2 = 0; y2 < h; y2 += 6) tft.drawLine(x1, y1, x2, y2, color); + t = micros() - start; // fillScreen doesn't count against timing + + tft.fillScreen(); + + x1 = w - 1; + y1 = 0; + y2 = h - 1; + start = micros(); + for (x2 = 0; x2 < w; x2 += 6) tft.drawLine(x1, y1, x2, y2, color); + x2 = 0; + for (y2 = 0; y2 < h; y2 += 6) tft.drawLine(x1, y1, x2, y2, color); + t += micros() - start; + + tft.fillScreen(); + + x1 = 0; + y1 = h - 1; + y2 = 0; + start = micros(); + for (x2 = 0; x2 < w; x2 += 6) tft.drawLine(x1, y1, x2, y2, color); + x2 = w - 1; + for (y2 = 0; y2 < h; y2 += 6) tft.drawLine(x1, y1, x2, y2, color); + t += micros() - start; + + tft.fillScreen(); + + x1 = w - 1; + y1 = h - 1; + y2 = 0; + start = micros(); + for (x2 = 0; x2 < w; x2 += 6) tft.drawLine(x1, y1, x2, y2, color); + x2 = 0; + for (y2 = 0; y2 < h; y2 += 6) tft.drawLine(x1, y1, x2, y2, color); + + return micros() - start; +} + +unsigned long testFastLines(uint16_t color1, uint16_t color2) { + unsigned long start; + int x, y, w = tft.width(), h = tft.height(); + + tft.fillScreen(); + start = micros(); + for (y = 0; y < h; y += 5) tft.drawFastHLine(0, y, w, color1); + for (x = 0; x < w; x += 5) tft.drawFastVLine(x, 0, h, color2); + + return micros() - start; +} + +unsigned long testRects(uint16_t color) { + unsigned long start; + int n, i, i2, + cx = tft.width() / 2, + cy = tft.height() / 2; + + tft.fillScreen(); + n = min(tft.width(), tft.height()); + start = micros(); + for (i = 2; i < n; i += 6) { + i2 = i / 2; + tft.drawRect(cx - i2, cy - i2, i, i, color); + } + + return micros() - start; +} + +unsigned long testFilledRects(uint16_t color1, uint16_t color2) { + unsigned long start, t = 0; + int n, i, i2, + cx = (tft.width() / 2) - 1, + cy = (tft.height() / 2) - 1; + + tft.fillScreen(); + n = min(tft.width(), tft.height()); + for (i = n; i > 0; i -= 6) { + i2 = i / 2; + start = micros(); + tft.fillRect(cx - i2, cy - i2, i, i, color1); + t += micros() - start; + // Outlines are not included in timing results + tft.drawRect(cx - i2, cy - i2, i, i, color2); + } + + return t; +} + +unsigned long testFilledCircles(uint8_t radius, uint16_t color) { + unsigned long start; + int x, y, w = tft.width(), h = tft.height(), r2 = radius * 2; + + tft.fillScreen(); + start = micros(); + for (x = radius; x < w; x += r2) { + for (y = radius; y < h; y += r2) { + tft.fillCircle(x, y, radius, color); + } + } + + return micros() - start; +} + +unsigned long testCircles(uint8_t radius, uint16_t color) { + unsigned long start; + int x, y, r2 = radius * 2, + w = tft.width() + radius, + h = tft.height() + radius; + + // Screen is not cleared for this one -- this is + // intentional and does not affect the reported time. + start = micros(); + for (x = 0; x < w; x += r2) { + for (y = 0; y < h; y += r2) { + tft.drawCircle(x, y, radius, color); + } + } + + return micros() - start; +} + +unsigned long testTriangles() { + unsigned long start; + int n, i, cx = tft.width() / 2 - 1, + cy = (tft.height() / 2) - 1; + + tft.fillScreen(); + n = min(cx, cy); + start = micros(); + for (i = 0; i < n; i += 5) { + tft.drawTriangle( + cx , cy - i, // peak + cx - i, cy + i, // bottom left + cx + i, cy + i, // bottom right + tft.Color565(0, 0, i)); + } + + return micros() - start; +} + +unsigned long testFilledTriangles() { + unsigned long start, t = 0; + int i, cx = (tft.width() / 2) - 1, + cy = tft.height() / 2 - 1; + + tft.fillScreen(); + start = micros(); + for (i = min(cx, cy); i > 10; i -= 5) { + start = micros(); + tft.fillTriangle(cx, cy - i, cx - i, cy + i, cx + i, cy + i, + tft.Color565(0, i, i)); + t += micros() - start; + tft.drawTriangle(cx, cy - i, cx - i, cy + i, cx + i, cy + i, + tft.Color565(i, i, 0)); + } + + return t; +} + +unsigned long testRoundRects() { + unsigned long start; + int w, i, i2, + cx = (tft.width() / 2) - 1, + cy = (tft.height() / 2) - 1; + + tft.fillScreen(); + w = min(tft.width(), tft.height()); + start = micros(); + for (i = 0; i < w; i += 6) { + i2 = i / 2; + tft.drawRoundRect(cx - i2, cy - i2, i, i, i / 8, tft.Color565(i, 0, 0)); + } + + return micros() - start; +} + +unsigned long testFilledRoundRects() { + unsigned long start; + int i, i2, + cx = (tft.width() / 2) - 1, + cy = (tft.height() / 2) - 1; + + tft.fillScreen(); + start = micros(); + for (i = min(tft.width(), tft.height()); i > 20; i -= 6) { + i2 = i / 2; + tft.fillRoundRect(cx - i2, cy - i2, i, i, i / 8, tft.Color565(0, i, 0)); + } + + return micros() - start; +} \ No newline at end of file diff --git a/libraries/TFT_ILI9163C-master/examples/bigPicture/bigPicture.ino b/libraries/TFT_ILI9163C-master/examples/bigPicture/bigPicture.ino new file mode 100644 index 0000000..aeb9d22 --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/bigPicture/bigPicture.ino @@ -0,0 +1,61 @@ +#include +#include +#include + +/* +Want to load 24 bit iamges directly? This demo it's cool to understand how it works. +The 24bit data can also be stored in a flash if you like! +be careful, big ram requirements!! Only Teensy or DUE probably work +You need the utility lcd-image-converter in the utility folder. +Open an image with lcd-image-converter, go to menu->Options->Conversion... +'Prepare' sub-menu tag should be set as follow: +Type: color +Main Scan Direction: Top to Bottom +Line Scan Direction: Forwaed +All the rest should be unchecked. +Go to sub-menu tag 'Image' +Prefix:0x +Block size: 24bit +Delimeter:, +Byte Order: Little-Endian +Done. Now save preset if you like! +Now go to menu File->Convert and save .c file +Open with any text editor, you need to copy in your sketch only the data so the array +that start with static const uint24_t yourimage[16384] = { ....}; +Change uint24_t to uint32_t. + +*/ +/* +Teensy3.x and Arduino's +You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 +Arduino's 8 bit: any +DUE: check arduino site +If you do not use reset, tie it to +3V3 +*/ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + + +static const uint32_t image_data_batman_ume[16384] = { + 0x976a40, 0xaa8a3f, 0xb49f42, 0xb3a044, 0xb19b45, 0xac983f, 0xaa963d, 0xaf9946, 0xb2a054, 0xa79668, 0x8f826f, 0x827b6b, 0x9d9976, 0xc2b684, 0xccb684, 0xcfba81, 0xcbb373, 0xae9a55, 0xac9142, 0xb19d46, 0xb8aa49, 0xabaa50, 0xb9ac50, 0xf8e55b, 0xfff256, 0xfde954, 0xfde755, 0xffea51, 0xffe84c, 0xffe64b, 0xfee749, 0xfee646, 0xfde441, 0xfbe440, 0xfee33a, 0xfce034, 0xfde336, 0xfde233, 0xffe12e, 0xfee12d, 0xfee028, 0xfee026, 0xfce027, 0xffe127, 0xfee226, 0xfee12d, 0xffde37, 0xfcd538, 0xffcd33, 0xefbf37, 0xc0a151, 0x6f562e, 0x3e3120, 0x483517, 0x694c14, 0x956c14, 0xc28b14, 0xc2881a, 0xc28918, 0xc28b17, 0xc4911e, 0xc99528, 0xcd972b, 0xce982e, 0xcb9729, 0xc99424, 0xc69225, 0xc58f22, 0xcb8d20, 0xaa771e, 0x826930, 0x746546, 0x52371c, 0x5c3611, 0x6f4014, 0x8f4514, 0xc86512, 0xeb7b15, 0xf08116, 0xf98b18, 0xfa9219, 0xf9971a, 0xf79c1a, 0xf79e1e, 0xf9a221, 0xf7a31f, 0xf6a522, 0xf6a728, 0xf5ab24, 0xf5ad25, 0xf4b125, 0xf4b125, 0xf5b225, 0xf5b426, 0xf3b429, 0xf2b529, 0xf3b32b, 0xefb530, 0xf4b12e, 0xf0ab2a, 0xf2c54e, 0xf4dc7a, 0xfcda80, 0xeec164, 0xbd9138, 0xb68735, 0xc09044, 0xbe9253, 0xc0965a, 0xcea261, 0xcda162, 0xb98a44, 0xa8742b, 0xa26922, 0xa76729, 0xa46427, 0x9a5d24, 0x995d2b, 0x925622, 0x864913, 0x82470d, 0x884b12, 0x8e4c10, 0x844212, 0x71360e, 0x5f2e0d, 0x44260e, 0x31200c, 0xb59e3e, 0xbba53f, 0xb29b3d, 0xaf973d, 0xb8a144, 0xbda646, 0xb3a248, 0x9c8d4a, 0x827757, 0x6e6754, 0x615f53, 0x69665d, 0x787264, 0x87785b, 0x937e53, 0x988656, 0x968047, 0x997e3b, 0xa88d3e, 0xb69d43, 0xb3a94a, 0xaaa348, 0xe1cd5a, 0xfff660, 0xfcee57, 0xfeea55, 0xffe955, 0xffea53, 0xfde84f, 0xffe84c, 0xfee749, 0xffe948, 0xfde543, 0xfde441, 0xfee33a, 0xfde137, 0xfee439, 0xfee334, 0xffe22f, 0xfee12d, 0xfee02a, 0xfee028, 0xfde02a, 0xffe129, 0xfee227, 0xfee12d, 0xffde37, 0xfdd538, 0xffcb37, 0xebbc3a, 0xb69649, 0x70582c, 0x3f331d, 0x493616, 0x755113, 0x7f5813, 0x815c16, 0x7f5712, 0xa07727, 0xac8c35, 0xac8e36, 0xc6974f, 0xd79e5b, 0xd3a05e, 0xd19f60, 0xcf9d56, 0xcc9a53, 0xcc9957, 0xd29b5b, 0xa97c45, 0x6d5129, 0x594427, 0x523517, 0x5d3a12, 0x6e3e16, 0x894518, 0xc66919, 0xe58316, 0xed8719, 0xfa8f1b, 0xfd971b, 0xfc9d1d, 0xfaa21d, 0xf9a21f, 0xf8a420, 0xf9a720, 0xf9ab25, 0xf8ab27, 0xf6ac27, 0xf6ae26, 0xf5b027, 0xf4b125, 0xf4b325, 0xf5b327, 0xf4b52a, 0xf3b62a, 0xf2b42d, 0xf3b431, 0xf1b02e, 0xf2b938, 0xf2c64b, 0xf5be4a, 0xe8be5c, 0xeecb71, 0xc99742, 0xa07121, 0x996d22, 0x996f25, 0x98732f, 0x91733d, 0xa48a59, 0xbc9e6c, 0xbb9c66, 0xa57c48, 0x956229, 0x92571f, 0x9c5829, 0x9a5625, 0x8a4816, 0x7f3d0d, 0x84410d, 0x884510, 0x88470f, 0x914c0b, 0x974d10, 0x873d0c, 0x77360c, 0x622d0e, 0xb29f39, 0xb2993d, 0xbca33e, 0xbaa645, 0xa49142, 0x998749, 0x7b6e4b, 0x565246, 0x4c453b, 0x4e4b3c, 0x5d5747, 0x514b3b, 0x3e372f, 0x42362a, 0x695935, 0x7c6836, 0x87743c, 0x98813d, 0xa38c40, 0xb4963e, 0xafa045, 0xbfad49, 0xfde966, 0xfef260, 0xfeee5b, 0xfeec5a, 0xfeea57, 0xffeb58, 0xfde954, 0xfde84f, 0xfde64a, 0xfeea4b, 0xfde545, 0xfde442, 0xfde43f, 0xfee33a, 0xfde239, 0xfee437, 0xfde432, 0xfde22f, 0xffe02e, 0xffe02d, 0xfee12d, 0xffe22c, 0xfce229, 0xfee12e, 0xfedd38, 0xfdd43a, 0xfecb32, 0xeabf3f, 0xae944a, 0x725728, 0x4c3a22, 0x453416, 0x725313, 0x815c18, 0x7a5715, 0x7a5715, 0x9c7730, 0xa8883d, 0x9a7f32, 0xaa8541, 0xba8d4c, 0xb68d4b, 0xb68d4f, 0xb58c4e, 0xb5884f, 0xb28750, 0xb2854c, 0xab864f, 0x745b32, 0x4d351b, 0x563919, 0x623b14, 0x6f4014, 0x944816, 0xc36819, 0xe78918, 0xee8d1a, 0xf7971e, 0xfc9d1d, 0xfda21e, 0xfca821, 0xfcaa22, 0xfbaa23, 0xfbae24, 0xfab127, 0xf9af28, 0xf8b028, 0xf7b229, 0xf8b328, 0xf7b428, 0xf7b628, 0xf5b728, 0xf3b628, 0xf3b62a, 0xf3b32b, 0xf4b631, 0xf3b931, 0xf4be3a, 0xf3b136, 0xf7a92d, 0xe6a733, 0xc8a446, 0xcfa251, 0xaa7b2d, 0xa37430, 0x9d702c, 0x8a6727, 0x785d28, 0x735823, 0x745c2c, 0x8e774e, 0x967f55, 0x856d41, 0x7d643c, 0x74542d, 0x754119, 0x813a10, 0x8c400e, 0x89400d, 0x843d0f, 0x8a400f, 0x89400b, 0x8a400f, 0x954510, 0x994b0d, 0x8f420a, 0xbda239, 0xbca442, 0xa08d3e, 0x7a6b40, 0x594f43, 0x4f4a44, 0x4e4a3f, 0x554d40, 0x544c39, 0x4e4631, 0x4e432f, 0x4a3f2b, 0x483f2e, 0x40382d, 0x574831, 0x756335, 0x826d34, 0x927a3a, 0xa0863c, 0xaf9541, 0xad953b, 0xdbc152, 0xfff871, 0xfcee6b, 0xffed63, 0xffef64, 0xfceb5f, 0xfdea5d, 0xfcec5b, 0xfeea57, 0xfee950, 0xfde94c, 0xfee749, 0xfee445, 0xfee542, 0xfee63e, 0xfde23b, 0xfee439, 0xfce535, 0xfee533, 0xffe22f, 0xfee12d, 0xfee12d, 0xffe22c, 0xfde32c, 0xfee12e, 0xfedb37, 0xfed53d, 0xffca32, 0xe9c348, 0xb49c54, 0x72572a, 0x43341d, 0x47361c, 0x6f5216, 0x7d5b14, 0x7f5a13, 0x805b17, 0x845d18, 0x845d18, 0x825b16, 0x835d1c, 0x86601f, 0x855d1f, 0x825b20, 0x805c1e, 0x815b1c, 0x7e5619, 0x81571b, 0x7a561c, 0x684f26, 0x523e25, 0x523817, 0x623c15, 0x704115, 0x8b471a, 0xc6681e, 0xe3901a, 0xee961b, 0xf89a1c, 0xfea31f, 0xfba720, 0xfdad22, 0xfdb024, 0xfcb124, 0xfbb426, 0xfab529, 0xfab529, 0xfab929, 0xfab72a, 0xf9b627, 0xf9b828, 0xf8ba29, 0xf6ba28, 0xf6b92a, 0xf6b92b, 0xf7b930, 0xf3bb30, 0xf5bb35, 0xf3b733, 0xf7b138, 0xf0ae34, 0xffac32, 0xd8942f, 0xaa862e, 0xaa8431, 0xa2782c, 0x98732f, 0x8b6d2f, 0x826730, 0x7b5f2d, 0x6a532a, 0x5c4523, 0x544121, 0x55432d, 0x65553e, 0x4d492e, 0x2c2d1b, 0x3d2d14, 0x63390f, 0x853e12, 0x97410e, 0x8b3d0c, 0x853b0e, 0x8b3d0f, 0x8c400f, 0x92430b, 0x97470c, 0xa48f40, 0x716239, 0x4c433a, 0x433e38, 0x51493e, 0x544d3b, 0x564e39, 0x554b32, 0x514932, 0x4f4732, 0x4e4331, 0x4e432f, 0x48402b, 0x413b2f, 0x47392c, 0x695532, 0x7d6934, 0x8b7239, 0x9e8038, 0xa48f3e, 0xb3903c, 0xf2cf5b, 0xfdfb72, 0xfeec6c, 0xfeec6c, 0xfff06f, 0xfdec6a, 0xfcea64, 0xfded64, 0xfeeb60, 0xffea59, 0xfee952, 0xfeea4d, 0xfee648, 0xfce442, 0xfee540, 0xfee33c, 0xfde53b, 0xfce63a, 0xffe637, 0xfde432, 0xffe22f, 0xfce22d, 0xffe22c, 0xfde42f, 0xfee030, 0xfedb37, 0xfed53f, 0xffc934, 0xedc353, 0xc6aa60, 0x3b2b12, 0x1f1a14, 0x574021, 0x6f5218, 0x7d5c17, 0x7d5c17, 0x7e5819, 0x835d1c, 0x845e1d, 0x83601e, 0x876122, 0x896221, 0x855f21, 0x835d1f, 0x815d1f, 0x866022, 0x825921, 0x83591d, 0x805c22, 0x674e26, 0x514026, 0x583a18, 0x633d18, 0x77481a, 0x372416, 0xa9591a, 0xf2981d, 0xef991e, 0xf5a021, 0xfea722, 0xfeac24, 0xfdb225, 0xfcb326, 0xfcb527, 0xfcb829, 0xfcb92a, 0xfcba28, 0xfbbe28, 0xfabc29, 0xfabc29, 0xfcbe2b, 0xfbbf2b, 0xf9bd2b, 0xf8bb2c, 0xf9ba2d, 0xf5bd32, 0xf6bd30, 0xf6be37, 0xf4bb36, 0xf6b43a, 0xf4b23a, 0xf5a832, 0xfda632, 0xbd872f, 0xa37931, 0xa3772e, 0x95702c, 0x8b6b2e, 0x84672f, 0x795e2f, 0x6d562c, 0x634b25, 0x554023, 0x4b3a26, 0x43321e, 0x352213, 0x2c1f0e, 0x2c260e, 0x2b2912, 0x3c3113, 0x5e320f, 0x863e0c, 0x9b460d, 0x923f0b, 0x8c3f0b, 0x90400b, 0x913e08, 0x4c4437, 0x3f3534, 0x4e4639, 0x554b32, 0x534633, 0x514433, 0x524735, 0x564b39, 0x544933, 0x504533, 0x4b432c, 0x4d422c, 0x463e29, 0x423b2b, 0x3c3226, 0x53412b, 0x746230, 0x846f36, 0x977c37, 0x9e8737, 0xbe9140, 0xfbd75f, 0xfff86c, 0xffeb6b, 0xfced70, 0xfcee73, 0xfeee74, 0xfdeb6d, 0xffee6c, 0xfeeb68, 0xffea63, 0xffea5b, 0xffeb54, 0xffe84c, 0xfde545, 0xfde642, 0xfee63e, 0xfee63e, 0xfde53b, 0xfde638, 0xfce533, 0xfde22f, 0xfde32e, 0xfde32e, 0xfce631, 0xffe131, 0xfdda38, 0xfed440, 0xffca34, 0xf6cb5b, 0xb09757, 0x000000, 0x221e1b, 0x5c4621, 0x6d5016, 0x7e5b17, 0x7f5c1a, 0x7e5b19, 0x86611d, 0x855f1e, 0x836121, 0x886023, 0x8b6222, 0x866321, 0x836020, 0x876122, 0x855d20, 0x835c25, 0x835c21, 0x7c5b26, 0x674f2b, 0x574225, 0x593b19, 0x664019, 0x8b5622, 0x04020d, 0x5a340d, 0xffa823, 0xeb9b20, 0xfba126, 0xfda923, 0xffaf28, 0xffb329, 0xfdb628, 0xfcb829, 0xfebb2c, 0xfdbc2c, 0xfcbf29, 0xffc32d, 0xfbc22b, 0xfbc22b, 0xfcc32c, 0xfac12a, 0xfac12c, 0xfac02e, 0xfcbf30, 0xfbc131, 0xf6c133, 0xf8c037, 0xf7bb37, 0xf9ba39, 0xf7af36, 0xf7a832, 0xfeab31, 0xd89433, 0x9e762e, 0x9d7831, 0x907130, 0x8a6c30, 0x7f642d, 0x725b2f, 0x695429, 0x5c4825, 0x513f29, 0x4f3d27, 0x3b2915, 0x291808, 0x301d0c, 0x311c07, 0x35230d, 0x2b250d, 0x211e0d, 0x39250c, 0x5e3309, 0x8c430c, 0xa34708, 0x914209, 0x8e410d, 0x443e30, 0x4d4433, 0x4e4331, 0x4f442e, 0x524532, 0x524534, 0x514630, 0x514934, 0x564732, 0x504332, 0x4d4530, 0x49412a, 0x4a3d2a, 0x453a26, 0x3d3423, 0x3f3229, 0x66502b, 0x7c6730, 0x8c7434, 0x9d7f36, 0xc39540, 0xfcdc63, 0xfff369, 0xffee6c, 0xffed71, 0xfeee74, 0xfeef78, 0xfded74, 0xfeeb72, 0xffed6f, 0xfeeb6a, 0xfde964, 0xfde859, 0xfde753, 0xfce54a, 0xfde545, 0xfde642, 0xfde43f, 0xfde43f, 0xfde53b, 0xfee63b, 0xfee334, 0xfee332, 0xfee330, 0xfce533, 0xfee032, 0xfdda38, 0xffd342, 0xffc83a, 0xfdd863, 0x837351, 0x000002, 0x342d1a, 0x5a4623, 0x705319, 0x7e5c1d, 0x7c5a1b, 0x795c1a, 0x82611c, 0x86601f, 0x846121, 0x876327, 0x8b6527, 0x856125, 0x816126, 0x865f24, 0x865f26, 0x825d26, 0x835f23, 0x7b5c26, 0x654e2c, 0x584121, 0x5b3d19, 0x6c451c, 0x8f5822, 0x150d0b, 0x14110a, 0xf4a127, 0xf4a225, 0xf8a628, 0xfdac27, 0xfeb22b, 0xfeb72b, 0xfdb92a, 0xfdbc2c, 0xfec031, 0xfdc12f, 0xffc32d, 0xfec72e, 0xfdc82e, 0xfcc92f, 0xfcc92f, 0xfdc82e, 0xfdc82e, 0xfcc630, 0xfbc531, 0xfcc433, 0xfcc439, 0xfbc33a, 0xfac03b, 0xf8bc38, 0xf8b236, 0xfbab32, 0xffaa36, 0xdd9a31, 0xa17c2e, 0x987730, 0x8e7233, 0x86692f, 0x7c622f, 0x72572c, 0x624c27, 0x594427, 0x54422a, 0x40311c, 0x2b1c09, 0x2f1d09, 0x35200b, 0x33210d, 0x331c0a, 0x321b0b, 0x32200c, 0x281d0b, 0x1e180a, 0x311f0b, 0x6c360a, 0xa04c0c, 0xa04808, 0x463d2c, 0x493e2c, 0x4c4030, 0x4d422e, 0x4e442b, 0x50452f, 0x4e432d, 0x50452f, 0x4d452e, 0x50452f, 0x4d422e, 0x493f26, 0x493d27, 0x433b24, 0x3f3923, 0x392c23, 0x4a3927, 0x76602e, 0x826e31, 0x947630, 0xc59942, 0xffde63, 0xffe864, 0xfeed69, 0xffee70, 0xfdee71, 0xfdef75, 0xfeed79, 0xffeb76, 0xffec73, 0xfced6e, 0xfee96c, 0xfee861, 0xfee95a, 0xfee652, 0xfee54b, 0xfee644, 0xfce442, 0xffe442, 0xfee540, 0xffe73d, 0xfee238, 0xfee334, 0xffe433, 0xfce535, 0xfee032, 0xffd938, 0xffd344, 0xf9ca3c, 0xf8d265, 0x524a3d, 0x010101, 0x40311c, 0x5d4626, 0x6e5421, 0x7e5f1f, 0x7d591d, 0x7f5b1f, 0x836121, 0x856324, 0x856324, 0x876528, 0x876526, 0x85622a, 0x816229, 0x856127, 0x876029, 0x835e2a, 0x876027, 0x7a5a29, 0x614c2f, 0x5a4324, 0x62421b, 0x6d4722, 0x8e5923, 0x2c1d16, 0x000105, 0xc78926, 0xffaf28, 0xf5a729, 0xfeb22b, 0xfdb52d, 0xfdb82d, 0xfdbc2c, 0xfec02f, 0xfdc333, 0xfcc431, 0xfec72e, 0xfec92f, 0xfdca30, 0xfcce30, 0xfcce30, 0xfbce2d, 0xfece30, 0xfdcc31, 0xf9cb30, 0xfacc38, 0xfeca38, 0xfdc638, 0xfcc43d, 0xfabe39, 0xfcb332, 0xfaae36, 0xfdaa32, 0xeaa435, 0xa67f30, 0x947233, 0x8e7034, 0x836831, 0x735e31, 0x6b5229, 0x5d4627, 0x58442b, 0x4a391f, 0x311e0d, 0x2e1c08, 0x37230a, 0x362009, 0x341f0a, 0x2e1d09, 0x322008, 0x2f1d09, 0x301b08, 0x351f0a, 0x221608, 0x1a1309, 0x4a290a, 0x854508, 0x463b27, 0x473c2a, 0x493e2c, 0x4d422c, 0x4d432a, 0x4d422c, 0x4d422e, 0x4d422c, 0x4b432c, 0x50442c, 0x4d412b, 0x453d28, 0x463c23, 0x473b23, 0x403521, 0x3d3121, 0x372d21, 0x5e4a27, 0x7d672d, 0x896d2c, 0xc29b40, 0xffdd62, 0xffe160, 0xfded64, 0xfeed6b, 0xffec71, 0xfcec73, 0xffee78, 0xfeeb75, 0xfdea71, 0xfdeb6f, 0xffea6d, 0xfde868, 0xfeea65, 0xfee75b, 0xfee554, 0xfee74c, 0xfee447, 0xffe443, 0xfce442, 0xfde640, 0xfee33e, 0xfee439, 0xfde338, 0xffe435, 0xffdf36, 0xfed73c, 0xffd243, 0xffd148, 0xdab861, 0x211f20, 0x000004, 0x46381e, 0x5c472a, 0x6e5222, 0x7d5f23, 0x7d5d22, 0x7c5c21, 0x846225, 0x866427, 0x83632a, 0x846429, 0x89662c, 0x84642b, 0x82632c, 0x83632a, 0x84602c, 0x815e28, 0x856228, 0x795a2c, 0x624f31, 0x5c4525, 0x62441e, 0x704b21, 0x945b26, 0x382717, 0x000002, 0x7f5c1a, 0xffbe30, 0xf0a92d, 0xfbb22f, 0xfeb532, 0xfdb932, 0xfdbe31, 0xffc234, 0xfcc336, 0xfec737, 0xfdc935, 0xfccb30, 0xfdcf33, 0xfdcf31, 0xfed130, 0xfdd22e, 0xfdd331, 0xfdd333, 0xfed336, 0xfed337, 0xfdce38, 0xfccc3a, 0xfbc839, 0xfcbe35, 0xfdb636, 0xfdb235, 0xf9ad33, 0xefaa35, 0xaa8433, 0x8c6f35, 0x8a6d33, 0x7e6431, 0x71592d, 0x634b27, 0x5b472e, 0x513f27, 0x362410, 0x2d1b07, 0x372308, 0x362207, 0x37210a, 0x321d0a, 0x311f09, 0x331f07, 0x311f0b, 0x321d0a, 0x301b08, 0x2e1c08, 0x2b1809, 0x201003, 0x271a0a, 0x453923, 0x473c28, 0x453a26, 0x493e2a, 0x4b402a, 0x4c412b, 0x4d422c, 0x4b402a, 0x4b402a, 0x4c412b, 0x4e422c, 0x4b402a, 0x463b25, 0x43371f, 0x40341e, 0x3d321e, 0x392b22, 0x433222, 0x745f2a, 0x82652b, 0xbd9742, 0xfdd75c, 0xffde60, 0xfce861, 0xfeed69, 0xfeec6e, 0xfeeb73, 0xffec76, 0xfeeb73, 0xfce971, 0xffec73, 0xffe96f, 0xfde86b, 0xfce968, 0xfee861, 0xffe658, 0xffe753, 0xfee54b, 0xfee447, 0xfde545, 0xfee743, 0xffe43d, 0xfde336, 0xfde338, 0xfee33a, 0xfede3b, 0xfdd63b, 0xfed047, 0xffdb71, 0xb9965e, 0x030712, 0x000207, 0x4a3925, 0x624d2e, 0x6d5525, 0x7f5f22, 0x7d5e25, 0x7d5e25, 0x836328, 0x85652a, 0x83642d, 0x86662d, 0x8b6830, 0x86652f, 0x84652f, 0x86652f, 0x82612e, 0x81602b, 0x89662c, 0x795c30, 0x635032, 0x5e4725, 0x664824, 0x744e27, 0x96612b, 0x3e281a, 0x000000, 0x3b2b14, 0xfeb836, 0xf8ae33, 0xfbb232, 0xfdb735, 0xfeba35, 0xfdbd35, 0xfdc238, 0xfec53a, 0xfdc83c, 0xffcb3a, 0xfdce3a, 0xfed13a, 0xfed337, 0xfed434, 0xfed432, 0xfdd633, 0xfdd736, 0xfdd736, 0xfed73a, 0xfed53b, 0xffd33c, 0xfbcc38, 0xfcc334, 0xfebb36, 0xfbb436, 0xf5b136, 0xeeb037, 0xad8837, 0x8a6d35, 0x886a38, 0x795e2f, 0x6b5229, 0x60482e, 0x57462a, 0x3f2d15, 0x2f1a07, 0x362209, 0x37230b, 0x342005, 0x331f07, 0x341f0a, 0x331f07, 0x2f1d09, 0x331f06, 0x2f1d07, 0x2f1a07, 0x2e1906, 0x2c1b09, 0x2d1b07, 0x271708, 0x42361e, 0x443820, 0x463b25, 0x443925, 0x493e2a, 0x493e28, 0x4c4028, 0x4b3f27, 0x4b3f27, 0x483d29, 0x4b402a, 0x4c4028, 0x463b25, 0x42381f, 0x42361c, 0x3e321a, 0x3b2e1e, 0x36281f, 0x564323, 0x7b5c25, 0xb89440, 0xf6d053, 0xf9d656, 0xffe35e, 0xfdeb63, 0xfeeb6b, 0xfeea71, 0xffea73, 0xfeeb73, 0xfbe870, 0xfee972, 0xfde970, 0xfee86e, 0xfbe868, 0xfde966, 0xffe55d, 0xfee557, 0xffe552, 0xfee54b, 0xffe64b, 0xfde543, 0xffe540, 0xfee13b, 0xfee33c, 0xfde23d, 0xfede3d, 0xfdd63b, 0xfecd56, 0xfee388, 0xa68856, 0x00010d, 0x000105, 0x4e422a, 0x655231, 0x6f5729, 0x81602a, 0x7e602a, 0x7e6129, 0x85652c, 0x87672e, 0x856731, 0x866731, 0x896832, 0x866834, 0x846632, 0x886732, 0x826233, 0x836330, 0x88682f, 0x785c34, 0x645335, 0x624c27, 0x6b4d29, 0x785128, 0x9b672e, 0x3d2c18, 0x010000, 0x0a080b, 0xdc9f35, 0xfeb937, 0xf9b337, 0xfdb839, 0xfebb39, 0xfebf3c, 0xfdc33e, 0xffc740, 0xfec841, 0xfeca42, 0xfdcf46, 0xfdd247, 0xfdd245, 0xfed442, 0xfdd53f, 0xfcd83c, 0xfdd93b, 0xfdd93a, 0xfcd83a, 0xfcd93d, 0xfed53d, 0xfccd39, 0xfdc636, 0xfdc034, 0xf8b735, 0xf0b537, 0xedb638, 0xab8837, 0x846934, 0x816536, 0x725a2a, 0x654c2d, 0x5e4a31, 0x48361e, 0x2e1c06, 0x342005, 0x3a240c, 0x372109, 0x342008, 0x2f1d05, 0x331f06, 0x321c05, 0x311f07, 0x2e1c04, 0x2f1b03, 0x2f1a05, 0x2f1a05, 0x2d1805, 0x2c1a06, 0x2b1a08, 0x3e321c, 0x41351d, 0x443820, 0x453a26, 0x423725, 0x473c28, 0x483c24, 0x4a3e24, 0x4c3d26, 0x443925, 0x473c26, 0x4a3e26, 0x463a22, 0x3f351c, 0x40341a, 0x413318, 0x3c3219, 0x34281a, 0x3b2b1b, 0x6a4d21, 0xa98837, 0xebc94e, 0xf4ce51, 0xfddb56, 0xfee75d, 0xfdeb65, 0xfeea6d, 0xfee972, 0xffed77, 0xfee972, 0xfee870, 0xfee972, 0xfce86d, 0xfce86b, 0xfee969, 0xfde55f, 0xfde35a, 0xffe554, 0xfde34e, 0xfee34a, 0xfee648, 0xffe546, 0xffe141, 0xfee13f, 0xfcdf3b, 0xfddb3c, 0xfdd43e, 0xfecc5d, 0xffe08b, 0x826c47, 0x02000d, 0x000004, 0x51452d, 0x675434, 0x70582c, 0x80622e, 0x7d622d, 0x80622e, 0x866731, 0x886933, 0x866834, 0x866834, 0x896936, 0x846836, 0x896b39, 0x8b6a37, 0x826337, 0x856735, 0x8a6933, 0x795f3a, 0x67563a, 0x664e2a, 0x6e502c, 0x7b542b, 0xa06c33, 0x3f3019, 0x000002, 0x000000, 0xa3792d, 0xfec93f, 0xf7b239, 0xfab93b, 0xfdbc3c, 0xfec142, 0xfec341, 0xfdc741, 0xfeca43, 0xfcca43, 0xfece46, 0xffd14a, 0xfed24b, 0xfed44c, 0xfed44a, 0xfed94d, 0xfedb4d, 0xffdc4c, 0xfdda48, 0xfedb43, 0xfcd53a, 0xfccd37, 0xfec737, 0xfbc036, 0xf6bb39, 0xeeb83a, 0xeab83b, 0xaa893c, 0x806538, 0x796230, 0x6a532a, 0x624c34, 0x514024, 0x33210d, 0x321e05, 0x3a250a, 0x372207, 0x38220a, 0x321d08, 0x342005, 0x321e06, 0x341e07, 0x311d05, 0x2e1c04, 0x301c03, 0x2b1903, 0x2e1906, 0x301c04, 0x2d1b07, 0x2b1807, 0x392e1c, 0x3f331b, 0x43351a, 0x443820, 0x3f3722, 0x413924, 0x453a24, 0x4a3b24, 0x483c24, 0x453921, 0x443923, 0x463a22, 0x463a22, 0x41351d, 0x3e321a, 0x403217, 0x3e3317, 0x382d17, 0x302416, 0x49331e, 0x997833, 0xdebd4c, 0xebc548, 0xfbd451, 0xffe158, 0xffe85e, 0xfdea67, 0xfce970, 0xfeeb75, 0xffeb72, 0xfde76f, 0xfee972, 0xfbe76c, 0xfee96c, 0xffe769, 0xfee765, 0xfde35b, 0xffe457, 0xfde14f, 0xfde44c, 0xfee54b, 0xfee648, 0xffe242, 0xffdf3f, 0xfddd3d, 0xfdd83f, 0xfed23e, 0xfcce54, 0xfbd17b, 0x4e453c, 0x040612, 0x020003, 0x59472f, 0x6f5c3b, 0x705930, 0x7f642f, 0x7e6230, 0x816533, 0x896936, 0x8a6a37, 0x866a3a, 0x8b6d3b, 0x8c6e3c, 0x866a3a, 0x896d3b, 0x8c6c3b, 0x84673b, 0x88693a, 0x8a6a37, 0x78623d, 0x68573b, 0x6a522e, 0x705331, 0x805b31, 0xa3703b, 0x41301e, 0x000002, 0x000000, 0x7a5b25, 0xfed049, 0xf4b33d, 0xf9b93e, 0xfdbd41, 0xfec144, 0xfec343, 0xfdc741, 0xfeca43, 0xfdcb44, 0xffce45, 0xfed046, 0xfed349, 0xfed44c, 0xfdd54f, 0xfed954, 0xfedb59, 0xfedb59, 0xffdc5a, 0xffd952, 0xfdd349, 0xfecd44, 0xfec63d, 0xf9c138, 0xf0be37, 0xeab938, 0xe7b93f, 0xa07f3a, 0x846c40, 0x7b6637, 0x61492d, 0x5e4a2f, 0x3a2a11, 0x301c04, 0x3d2509, 0x38220a, 0x382308, 0x331f07, 0x372207, 0x341e06, 0x362008, 0x341e06, 0x311d04, 0x341e06, 0x2c1a04, 0x2e1a02, 0x301b06, 0x2b1a06, 0x2b1905, 0x2c1b09, 0x352d1a, 0x3b2f19, 0x413319, 0x40341a, 0x423721, 0x3f3722, 0x433822, 0x453923, 0x463a22, 0x483a20, 0x42381f, 0x413620, 0x473821, 0x443820, 0x3e321a, 0x3d2f14, 0x402f13, 0x3a2f13, 0x332616, 0x34211b, 0x755526, 0xd2ad42, 0xe3c040, 0xf1ca49, 0xfeda52, 0xffe359, 0xffe960, 0xfdea6a, 0xfde970, 0xffea72, 0xfde76d, 0xfde76f, 0xfde96e, 0xffe86c, 0xfde567, 0xfee767, 0xfee35e, 0xffe258, 0xfee252, 0xffe44f, 0xfee54b, 0xfde449, 0xffe244, 0xffdc42, 0xfed942, 0xfed440, 0xfed140, 0xfdd54f, 0xd5af64, 0x2a2b2f, 0x0f131c, 0x000100, 0x5b4a30, 0x75613e, 0x725c33, 0x816736, 0x816736, 0x826837, 0x8a6c3a, 0x8b6d3b, 0x876c3d, 0x8b6f40, 0x8c7040, 0x876c3f, 0x8a6e3f, 0x8b6f3f, 0x866b40, 0x8b6c3d, 0x8b6c3e, 0x786443, 0x6e5b3d, 0x705836, 0x775b36, 0x856036, 0xa6743f, 0x3d2d1d, 0x010002, 0x010101, 0x53411d, 0xffcc4d, 0xf3b73f, 0xf5b941, 0xfcbe45, 0xfcbe43, 0xfec343, 0xffc744, 0xfec842, 0xffcc44, 0xffce45, 0xffcf47, 0xfed349, 0xfed44c, 0xfed650, 0xfed955, 0xfddc59, 0xfedc5e, 0xfeda62, 0xfed55f, 0xffd05c, 0xffca58, 0xfdc450, 0xf6c449, 0xebbf42, 0xe6ba3f, 0xdfb549, 0x947439, 0x7f683e, 0x75613e, 0x5f4b30, 0x48341b, 0x2e1d03, 0x3b2307, 0x3c2408, 0x382308, 0x342008, 0x362207, 0x362104, 0x372109, 0x341f04, 0x321e05, 0x331e03, 0x301c04, 0x2f1a05, 0x2f1d05, 0x2b1901, 0x2a1706, 0x2c1b09, 0x2c1c05, 0x362b15, 0x362b15, 0x3a2e18, 0x40311a, 0x40341a, 0x42361e, 0x40351f, 0x423721, 0x443820, 0x46381e, 0x43371d, 0x41351d, 0x40341c, 0x43341d, 0x3f3117, 0x3d2f14, 0x3f2f0e, 0x3d2f14, 0x392a13, 0x2f1e16, 0x4d341e, 0xbd993b, 0xdebc41, 0xe8c140, 0xf6d049, 0xffdb51, 0xffe558, 0xfee85f, 0xfce767, 0xffe96f, 0xfde76d, 0xfde569, 0xfde76d, 0xffe56a, 0xfde567, 0xfde666, 0xffe35e, 0xfde257, 0xfde253, 0xfee250, 0xfee34a, 0xfde44a, 0xffe047, 0xfed845, 0xfed643, 0xffd243, 0xfcd144, 0xffdd59, 0xac935b, 0x171b27, 0x1b1b23, 0x000103, 0x5a4c32, 0x7a6643, 0x766037, 0x826a3c, 0x836b3d, 0x846c3c, 0x8a703f, 0x8b7041, 0x887042, 0x8b7345, 0x8d7245, 0x897145, 0x8d7245, 0x8a7244, 0x856c43, 0x8e6f41, 0x8a6f44, 0x7a6747, 0x73603f, 0x735c3c, 0x7c6039, 0x89643a, 0xa47942, 0x332b18, 0x010002, 0x000000, 0x241e12, 0xf2bd4d, 0xf9be48, 0xf5ba44, 0xfabd48, 0xfbbf45, 0xffc446, 0xffc645, 0xfec842, 0xffcb43, 0xfecd44, 0xfecf45, 0xfed046, 0xfed349, 0xfdd54f, 0xfed955, 0xfdda5a, 0xfeda5f, 0xffd765, 0xfdd25f, 0xffce5b, 0xfec85b, 0xf9c45e, 0xf1c363, 0xe8bd5e, 0xe4bc5a, 0xd2ad55, 0x856a35, 0x735b37, 0x6c543a, 0x523f21, 0x342008, 0x392405, 0x3e2507, 0x3a2508, 0x362008, 0x362106, 0x3a2508, 0x352005, 0x372205, 0x331d06, 0x341f04, 0x331d05, 0x301c04, 0x2f1b02, 0x2c1a04, 0x2b1a06, 0x2d1b03, 0x2c1c05, 0x2e1c06, 0x372b11, 0x342913, 0x342915, 0x3c3018, 0x413117, 0x423219, 0x40341c, 0x3c341f, 0x43341d, 0x45361f, 0x45371d, 0x42341a, 0x3c301a, 0x413319, 0x423218, 0x3c3016, 0x3b2d12, 0x3c2b0f, 0x3d2d13, 0x372614, 0x2e1b15, 0x916f30, 0xdab83d, 0xdeb83b, 0xedc740, 0xfbd44b, 0xfede4f, 0xfee453, 0xfce65d, 0xfbe868, 0xfce86d, 0xfee566, 0xfee66a, 0xfee567, 0xfee668, 0xfde463, 0xfee25d, 0xfce156, 0xfde253, 0xfee04e, 0xffe14f, 0xfde34e, 0xfedf49, 0xfed847, 0xfed547, 0xffd147, 0xf8ce44, 0xffde62, 0x968152, 0x0c1125, 0x1a1b1f, 0x010000, 0x534633, 0x816d4a, 0x79633c, 0x836e3f, 0x856d3f, 0x887042, 0x8e7344, 0x8c7446, 0x8a7347, 0x8d764a, 0x8f774b, 0x8c754b, 0x8e764a, 0x8c754b, 0x897248, 0x957648, 0x8a7148, 0x7a6a49, 0x786642, 0x776040, 0x7f633e, 0x916a41, 0xa47c49, 0x2f2519, 0x000100, 0x000100, 0x020109, 0xcea042, 0xffc750, 0xf3ba46, 0xf8bd49, 0xfcc048, 0xffc347, 0xfec446, 0xffc945, 0xfdc942, 0xffca48, 0xfdcd45, 0xfed046, 0xfed346, 0xffd64a, 0xfed84f, 0xfed955, 0xffda5b, 0xfed559, 0xfbd15b, 0xfeca5c, 0xfec55c, 0xf5c45e, 0xecc163, 0xe4bc65, 0xe2bc69, 0xbd9a56, 0x745c2c, 0x6f573b, 0x624b2b, 0x3b270c, 0x372205, 0x3e2708, 0x3d2406, 0x352106, 0x382308, 0x392105, 0x372205, 0x372205, 0x321e06, 0x362106, 0x351d03, 0x321c04, 0x311b03, 0x2e1c04, 0x2c1a04, 0x2e1c06, 0x2e1c06, 0x2e1c04, 0x2f1d05, 0x362a12, 0x362a10, 0x322a13, 0x332b16, 0x3d2f15, 0x423113, 0x423419, 0x3d3119, 0x3e311e, 0x42331c, 0x45351b, 0x423419, 0x3d3117, 0x3d2e17, 0x3f3117, 0x3b3014, 0x3a2b14, 0x3a2a10, 0x3e2e0d, 0x3d2c10, 0x291b12, 0x593e23, 0xc8a237, 0xd4b237, 0xe4bd3a, 0xf3cc43, 0xfbd647, 0xffda4d, 0xfde253, 0xfde561, 0xffe868, 0xfee668, 0xfde466, 0xfde567, 0xffe365, 0xfee362, 0xfee25b, 0xfcdf53, 0xfde152, 0xfedf50, 0xfde14f, 0xffe14f, 0xffda4f, 0xfbd64a, 0xfbd448, 0xfdd14a, 0xf4c947, 0xffdb6d, 0x716044, 0x020919, 0x1c1d1f, 0x000000, 0x51452f, 0x897552, 0x7a6641, 0x866f43, 0x897047, 0x8b7347, 0x8d764a, 0x8d784b, 0x8d784d, 0x907b50, 0x917a50, 0x907950, 0x917c4f, 0x907950, 0x8d764d, 0x987c4c, 0x8a744f, 0x7e6f52, 0x786844, 0x7c6545, 0x866844, 0x937245, 0xa27c4b, 0x242014, 0x010000, 0x010103, 0x000000, 0xae883d, 0xffce55, 0xeeba4d, 0xf6bd4a, 0xf8c049, 0xfec449, 0xffc448, 0xffc744, 0xfec844, 0xfdcb44, 0xffce45, 0xfecf43, 0xfed346, 0xffd64a, 0xffd54b, 0xfed650, 0xfed754, 0xfdd04f, 0xffcd58, 0xfbc759, 0xf6c55f, 0xf1c15d, 0xe8bd61, 0xdcb665, 0xdbba6b, 0xa28245, 0x674e2f, 0x685537, 0x463114, 0x371f03, 0x402804, 0x402709, 0x392405, 0x3a2206, 0x3b2307, 0x3a2206, 0x3a2206, 0x371f05, 0x341f04, 0x362106, 0x321d02, 0x321e05, 0x311d04, 0x321e06, 0x301b06, 0x301c04, 0x321e06, 0x2f1d05, 0x2c1a06, 0x2e2611, 0x342810, 0x372b11, 0x332812, 0x362a14, 0x3f2f15, 0x413117, 0x3d3117, 0x3b2f17, 0x3e2f18, 0x42341a, 0x413318, 0x3f2f15, 0x3c2d16, 0x3a2e14, 0x3d2d13, 0x3b2c0f, 0x37290f, 0x3d2d0c, 0x3f2c0c, 0x382713, 0x341912, 0x94722a, 0xd4b038, 0xd8b237, 0xe7bf39, 0xf8cd43, 0xfdd542, 0xfedb49, 0xfce352, 0xfde65a, 0xffe564, 0xfce460, 0xfee564, 0xfee360, 0xfde25d, 0xfee25a, 0xfcdf53, 0xfedf51, 0xffdf50, 0xfedd50, 0xfdde52, 0xffd952, 0xfdd64b, 0xffd04e, 0xfacd4c, 0xf1ca49, 0xf7d373, 0x4e4536, 0x101626, 0x1d1d1f, 0x000100, 0x49402f, 0x8e7c58, 0x7e6c46, 0x86734b, 0x8b764b, 0x8c774c, 0x907a51, 0x927c55, 0x927a54, 0x957e55, 0x947e57, 0x907c57, 0x987f56, 0x937b55, 0x917a58, 0x957c53, 0x8d7654, 0x847153, 0x7e6e4d, 0x826e4d, 0x8a7149, 0x9b794c, 0x9e7c4f, 0x1e1a17, 0x010100, 0x010302, 0x010000, 0x96773e, 0xffd660, 0xeebc4d, 0xf2bd4b, 0xf7bf4e, 0xfbc048, 0xffc448, 0xffc648, 0xffc847, 0xfec945, 0xffcb43, 0xfdce42, 0xffd245, 0xfdd446, 0xfdd446, 0xfdd448, 0xfcd248, 0xfed047, 0xffc847, 0xfcc455, 0xf4c55d, 0xebc15d, 0xe2bb5e, 0xdab366, 0xccab5a, 0x917545, 0x7a6248, 0x523d22, 0x382101, 0x3f2808, 0x402907, 0x3d250b, 0x3b2309, 0x3e2507, 0x3a2304, 0x3b2309, 0x382006, 0x371f03, 0x382004, 0x341e06, 0x331d05, 0x321d02, 0x301c04, 0x301c03, 0x311d05, 0x311d05, 0x301e06, 0x2d1b05, 0x2d1b03, 0x2c2411, 0x322713, 0x37290f, 0x37290e, 0x332812, 0x372b15, 0x3e2e15, 0x3e3013, 0x403217, 0x3a2e16, 0x3b2f17, 0x403016, 0x403016, 0x3d2d14, 0x392910, 0x3b2b11, 0x3f2e12, 0x37270d, 0x39280a, 0x412e0d, 0x3d2d0c, 0x301c11, 0x52341c, 0xbb9834, 0xd5ae2f, 0xddb637, 0xecc23c, 0xf6cf43, 0xfdd341, 0xfed847, 0xffe051, 0xfee459, 0xfde159, 0xfde15a, 0xfde15a, 0xfee159, 0xfee157, 0xfdde52, 0xfddc51, 0xfddc51, 0xffd952, 0xfed954, 0xfdd856, 0xfdd551, 0xfecd4d, 0xf6cb49, 0xf3ce59, 0xe2c174, 0x353128, 0x1d212c, 0x1c1c1e, 0x000002, 0x3f352b, 0x967f5f, 0x87704e, 0x8b7752, 0x8c7951, 0x917b52, 0x967f55, 0x957f56, 0x927f57, 0x96825d, 0x95815e, 0x94805d, 0x99835e, 0x937f5c, 0x96805b, 0x9a8158, 0x907c59, 0x887857, 0x817251, 0x86724f, 0x917850, 0xa17f52, 0x9c7d4e, 0x16120f, 0x010000, 0x020305, 0x000002, 0x786135, 0xffd56c, 0xebba53, 0xf1bc4c, 0xf3be4c, 0xf7c04b, 0xfac249, 0xfdc647, 0xfec746, 0xfec748, 0xfec945, 0xfdcc43, 0xffd046, 0xfcd146, 0xfed348, 0xffd248, 0xfdce44, 0xfeca42, 0xffc442, 0xf7c44e, 0xebc04d, 0xe4bd56, 0xdbb65e, 0xd4ae5b, 0xb79653, 0x9f8960, 0x786346, 0x392203, 0x402605, 0x432b09, 0x3f2808, 0x3b2405, 0x3e2604, 0x3d2406, 0x3a2103, 0x392105, 0x3a2208, 0x392203, 0x371f03, 0x341f04, 0x341f04, 0x331d05, 0x352005, 0x321e05, 0x331f04, 0x331f06, 0x2c1a06, 0x2f1d05, 0x2e1e04, 0x2d2210, 0x2c2411, 0x31270e, 0x382a10, 0x342810, 0x322711, 0x392b11, 0x3f3013, 0x3f3013, 0x3c3016, 0x372b13, 0x3e2e15, 0x3f2f15, 0x3e2e14, 0x3c2b11, 0x36260c, 0x3b2a0e, 0x3b2c0d, 0x39280c, 0x3b2b0a, 0x412d0a, 0x3f2c0e, 0x2d1511, 0x785722, 0xd2ac31, 0xd5ae2f, 0xdfb932, 0xebc63a, 0xf6cd3d, 0xfbd141, 0xffd648, 0xffde51, 0xfddd54, 0xfddb53, 0xfede55, 0xfedc54, 0xfedc54, 0xfddb53, 0xfed851, 0xfed851, 0xfed652, 0xfed653, 0xfdd657, 0xfbd455, 0xf9cb51, 0xf2c94d, 0xf9d370, 0xcdb06e, 0x262221, 0x262932, 0x1e201f, 0x010000, 0x3a3426, 0x988660, 0x887554, 0x907c57, 0x937d58, 0x957f5a, 0x9b8860, 0x9f8d65, 0xa59268, 0xb19c71, 0xb29c73, 0xab9772, 0xaf9c72, 0xaa9673, 0xaa926c, 0xa48d64, 0x938062, 0x8d7c60, 0x867758, 0x8c7857, 0x957b58, 0xab8b5c, 0x8d714c, 0x07080c, 0x000200, 0x030200, 0x000100, 0x4e3a21, 0xffcc70, 0xebbd5f, 0xf1ba55, 0xf3bf4f, 0xf3c04b, 0xf8c14a, 0xf8c546, 0xfbc646, 0xfcc544, 0xfeca43, 0xffcc44, 0xffcd46, 0xfece46, 0xffd148, 0xffcf46, 0xfec841, 0xfbc53f, 0xf4c342, 0xedc144, 0xe8be46, 0xddb74a, 0xd4ae4b, 0xc9a54d, 0xa5885c, 0x816e50, 0x453011, 0x3a2200, 0x442a05, 0x422a06, 0x3e2506, 0x402709, 0x3e2604, 0x3c2305, 0x3a2005, 0x3c2506, 0x3a2304, 0x382004, 0x382006, 0x352003, 0x331f04, 0x362008, 0x331e03, 0x342005, 0x331f06, 0x2e1a02, 0x301f05, 0x2e1d03, 0x2e1d03, 0x31250d, 0x2c210f, 0x2a2110, 0x332711, 0x38280e, 0x362710, 0x332711, 0x3a2c11, 0x3d2e11, 0x3f2e14, 0x3b2d13, 0x372b13, 0x3b2b11, 0x3d2e11, 0x3b2c0f, 0x37270d, 0x392a0d, 0x3b2b0a, 0x3c2909, 0x382709, 0x422b09, 0x432c0a, 0x372511, 0x3b1f14, 0x9f7627, 0xd5b02e, 0xd6af2e, 0xe2ba34, 0xecc53a, 0xf6cb3e, 0xfad046, 0xfcd647, 0xfdd74e, 0xffd751, 0xffd952, 0xfed851, 0xfed851, 0xfdd752, 0xfed350, 0xfdd552, 0xfdd454, 0xfed353, 0xfbd359, 0xfad260, 0xf5cb5d, 0xf0c960, 0xfcd882, 0xbea165, 0x14181b, 0x272a33, 0x202123, 0x010000, 0x2f2b20, 0x998761, 0x927e5d, 0x9f8868, 0xab986d, 0xb19c71, 0xab956e, 0x978463, 0x88795c, 0x7d6f55, 0x74684e, 0x796d53, 0x7c6e53, 0x746852, 0x8b7c5f, 0x9d8d69, 0xa89876, 0xae9c78, 0x9b8d6a, 0x92805c, 0x987e5b, 0xb59765, 0x796648, 0x000104, 0x050409, 0x020106, 0x000200, 0x352315, 0xeab361, 0xf1c266, 0xedbb5a, 0xf0bd52, 0xf2bf4a, 0xf6bf48, 0xf6c24a, 0xfbc446, 0xfac344, 0xfcc743, 0xfeca43, 0xffca46, 0xfecc47, 0xfdcd47, 0xfeca43, 0xfdc43f, 0xf5c242, 0xefc243, 0xeabe45, 0xe3b94b, 0xd6b043, 0xcea83d, 0xb69454, 0x8f7a5d, 0x573f25, 0x381e00, 0x482e0b, 0x422a06, 0x3f2705, 0x422709, 0x402806, 0x3f2607, 0x3d2406, 0x3c2305, 0x3d2405, 0x3a2303, 0x371f03, 0x371f03, 0x362104, 0x362104, 0x331e03, 0x352106, 0x331f04, 0x311d04, 0x331f06, 0x311d02, 0x321e05, 0x311d05, 0x32280f, 0x302310, 0x2b1f0f, 0x2a220f, 0x36280d, 0x39290f, 0x34250e, 0x31250d, 0x3b2b11, 0x3e2d11, 0x3f3013, 0x392b11, 0x37290f, 0x3b2c0f, 0x392a0b, 0x3a2b0e, 0x352609, 0x3b270c, 0x3d2a0a, 0x372608, 0x3e2708, 0x432b07, 0x402e0a, 0x301c11, 0x512b16, 0xb48a26, 0xdaaf2d, 0xdbb02d, 0xe2bc37, 0xf1c339, 0xf4c93c, 0xf6d047, 0xf9d249, 0xfdd34d, 0xfcd44e, 0xfdd24f, 0xfed350, 0xfbd350, 0xfcd151, 0xfbd050, 0xfdd156, 0xf9d05a, 0xf7d067, 0xf6ce6c, 0xf4cb6f, 0xeac670, 0xffdf8d, 0xa18a56, 0x080b14, 0x2b2b35, 0x202425, 0x000100, 0x1d1814, 0xad9b77, 0xa89670, 0x8f8061, 0x6f604b, 0x473e2d, 0x29241e, 0x151515, 0x040509, 0x000002, 0x010100, 0x000000, 0x010000, 0x000000, 0x050706, 0x1a1915, 0x373529, 0x615642, 0x8a7a61, 0xb39b77, 0xbba075, 0xc9a970, 0x6e5d41, 0x010101, 0x070508, 0x010302, 0x000100, 0x231a13, 0xd09b57, 0xedba61, 0xedc05b, 0xeabc4d, 0xefbb4d, 0xf0be4b, 0xf3c04a, 0xf7c049, 0xf9c347, 0xfbc547, 0xfac747, 0xfbc848, 0xfcca47, 0xfac845, 0xf9c442, 0xf7c03f, 0xf1c145, 0xe9bd44, 0xe5b845, 0xdbb248, 0xd0aa3f, 0xc19f48, 0xa78e65, 0x725d40, 0x422805, 0x462a03, 0x442a07, 0x412907, 0x422a08, 0x422805, 0x3f2703, 0x3e2506, 0x3d2405, 0x412809, 0x3c2305, 0x382004, 0x392202, 0x3a2304, 0x392407, 0x352003, 0x352204, 0x331f04, 0x321e06, 0x352106, 0x331f04, 0x352108, 0x331f04, 0x321e05, 0x2d220e, 0x35270d, 0x33250b, 0x2b200e, 0x2d220e, 0x342609, 0x38290c, 0x33240d, 0x35250c, 0x3b2c0f, 0x3e2d0f, 0x3d2c10, 0x382a10, 0x37290e, 0x3c2b0d, 0x3a2a09, 0x362509, 0x35240a, 0x39280a, 0x3b2808, 0x3d2607, 0x432d06, 0x452f08, 0x3d2a0a, 0x361f11, 0x6a4318, 0xbb8e29, 0xdab22e, 0xdcb830, 0xe5bb35, 0xedc235, 0xf0c640, 0xf6cc46, 0xf8cd4a, 0xfacf4d, 0xfbd050, 0xfacf4f, 0xf9cd50, 0xf8cf53, 0xf8cc53, 0xf7cc5b, 0xf7cd67, 0xf3ce76, 0xf2cc79, 0xefc978, 0xe9c577, 0xffe08d, 0x7b6941, 0x00020f, 0x2e2d32, 0x272b2c, 0x040807, 0x0b090a, 0x4e4639, 0x322c20, 0x0b0c07, 0x000100, 0x000000, 0x000000, 0x000000, 0x000002, 0x020204, 0x020204, 0x010204, 0x010204, 0x040203, 0x000000, 0x020100, 0x000100, 0x000100, 0x08080a, 0x35312e, 0x6b5c47, 0xbba375, 0x60513a, 0x000000, 0x080808, 0x030200, 0x010000, 0x0e110a, 0xbb9155, 0xdda85a, 0xeabe5d, 0xebbf52, 0xecb950, 0xeec051, 0xf0be4b, 0xf1be49, 0xf5c147, 0xf6c346, 0xf6c447, 0xf9c848, 0xf9c744, 0xf5c340, 0xf3c040, 0xf0bf3f, 0xeabc44, 0xe3ba44, 0xdbb342, 0xd1aa41, 0xc39e45, 0xb89962, 0x97845a, 0x513913, 0x432501, 0x4b2d09, 0x432904, 0x452b08, 0x432906, 0x412905, 0x3d2604, 0x3f2407, 0x412907, 0x3d2503, 0x392203, 0x3a2206, 0x3c2505, 0x3b2404, 0x392105, 0x3a2304, 0x352003, 0x331f06, 0x352106, 0x342005, 0x331f04, 0x321e03, 0x321e05, 0x332002, 0x2c210b, 0x2f230b, 0x37270d, 0x31220b, 0x271f0a, 0x2c210b, 0x36260c, 0x38290a, 0x32230c, 0x352609, 0x3c2c0b, 0x3b2a0c, 0x37270d, 0x35270d, 0x38290a, 0x402909, 0x3c2807, 0x352406, 0x36270a, 0x3f2806, 0x3e2708, 0x3e2a05, 0x452e05, 0x46300b, 0x36240c, 0x442a11, 0x7b531f, 0xab7e23, 0xd8ab2e, 0xe1bb36, 0xe5ba37, 0xeabe3b, 0xefc442, 0xf1c848, 0xf5c84b, 0xf6ca4d, 0xf5cc50, 0xf5c950, 0xf3cb52, 0xf4ca54, 0xf3c963, 0xf3ca70, 0xeec877, 0xefcb7f, 0xebc779, 0xf0cb7d, 0xf6d284, 0x584b29, 0x000613, 0x2d2f2c, 0x2c2b31, 0x171518, 0x000000, 0x000100, 0x000000, 0x000004, 0x050507, 0x070506, 0x070707, 0x050505, 0x060606, 0x070506, 0x070506, 0x060608, 0x060606, 0x070508, 0x030708, 0x060606, 0x030406, 0x060604, 0x010000, 0x010000, 0x010100, 0x121011, 0x121013, 0x12110f, 0x040404, 0x020403, 0x000100, 0x020202, 0xa58850, 0xd3a45c, 0xd5a551, 0xecbf5a, 0xecbc50, 0xeaba4b, 0xf0bc4e, 0xf0bd4a, 0xf3c04a, 0xf3c04a, 0xf3c148, 0xf4c448, 0xf3c242, 0xf2bc3e, 0xefbd42, 0xeabb45, 0xe5b845, 0xdcb443, 0xd3ad48, 0xc7a249, 0xbc985e, 0xb4976f, 0x6e552d, 0x412500, 0x4b2e04, 0x482c05, 0x472f03, 0x472b03, 0x452806, 0x3f2806, 0x3d2904, 0x452904, 0x402605, 0x3e2506, 0x3c2505, 0x3c2505, 0x3b2307, 0x3b2307, 0x3b2405, 0x382102, 0x341f04, 0x382304, 0x352204, 0x362207, 0x342005, 0x331f04, 0x352204, 0x342005, 0x2e220c, 0x2e220a, 0x312309, 0x36270a, 0x32230c, 0x281d09, 0x2e2208, 0x38290c, 0x37270d, 0x302009, 0x36270a, 0x3c2c0b, 0x3d2a0a, 0x382709, 0x36270a, 0x3c290b, 0x3b2807, 0x3a2508, 0x382505, 0x3a2804, 0x3b2706, 0x3a2506, 0x422c07, 0x4b2f08, 0x402c0b, 0x36240e, 0x5b3d17, 0x7e571e, 0x9f7022, 0xc69a2f, 0xe4ba34, 0xedbf36, 0xe8bd3b, 0xebc244, 0xeec44b, 0xf0c449, 0xf0c64d, 0xf0c650, 0xf0c650, 0xf1c759, 0xeec76c, 0xedc474, 0xedc677, 0xebc77b, 0xebc982, 0xe6c57e, 0xdcb66b, 0x453d26, 0x070a19, 0x2d2f2e, 0x2f3034, 0x17181d, 0x000000, 0x060606, 0x060604, 0x060606, 0x060606, 0x060606, 0x060606, 0x070707, 0x040404, 0x060606, 0x060606, 0x070506, 0x060606, 0x060606, 0x060606, 0x050505, 0x050505, 0x050505, 0x050505, 0x050505, 0x030303, 0x000000, 0x0d0d0d, 0x1a1a1a, 0x000000, 0x030303, 0x000000, 0x000000, 0x8c7647, 0xd5ae63, 0xbe934f, 0xd8a554, 0xefc058, 0xedbf50, 0xeaba4e, 0xedbb4a, 0xeebb48, 0xf1be48, 0xf2c148, 0xeec048, 0xedbb42, 0xecb93c, 0xe9b93d, 0xe5b843, 0xdfb444, 0xd6ae4c, 0xcba55a, 0xbd9965, 0xbe9e77, 0x856941, 0x442700, 0x4e2d00, 0x4a2e09, 0x472e06, 0x492e03, 0x462a03, 0x422805, 0x432906, 0x442a05, 0x412905, 0x3d2606, 0x3e2602, 0x3d2503, 0x3d2405, 0x3e2506, 0x3c2505, 0x362104, 0x372205, 0x382304, 0x392203, 0x3a2304, 0x352204, 0x342103, 0x352003, 0x321e03, 0x2c1a02, 0x2f2107, 0x2f2009, 0x2d2107, 0x32240a, 0x36270a, 0x31210a, 0x2c1d0a, 0x2c2006, 0x3a2707, 0x362708, 0x32220b, 0x39280a, 0x3f2c0b, 0x3b2b0a, 0x362509, 0x372608, 0x3a2707, 0x3d2908, 0x392405, 0x362303, 0x3d2908, 0x3d2904, 0x402804, 0x492f0a, 0x4b3209, 0x3d2607, 0x43290e, 0x735318, 0x81601b, 0x906822, 0xb38730, 0xd6a838, 0xe8bd3b, 0xedc23f, 0xeec245, 0xedc148, 0xefc34a, 0xeec44c, 0xeec454, 0xecc163, 0xe9c46c, 0xe9c273, 0xe9c476, 0xedc97f, 0xeac783, 0xd2b16c, 0xd0ac62, 0x3f3724, 0x080c18, 0x303133, 0x35363a, 0x2e2f33, 0x080808, 0x040404, 0x060604, 0x050505, 0x050505, 0x060606, 0x040404, 0x030303, 0x060606, 0x050505, 0x060606, 0x060606, 0x050505, 0x050505, 0x060606, 0x060606, 0x060606, 0x050505, 0x050505, 0x030303, 0x020202, 0x060606, 0x141414, 0x0b0b0b, 0x010101, 0x020202, 0x010101, 0x000000, 0x78643f, 0xdab469, 0xb89656, 0xbb9250, 0xd1a451, 0xe7bb52, 0xecbe4e, 0xefbd4c, 0xeebd47, 0xeebb46, 0xedbc45, 0xebba41, 0xebb83b, 0xe7b73b, 0xe0b544, 0xdeb34d, 0xd7ad59, 0xcea660, 0xc39e67, 0xbf9f6c, 0x91754d, 0x472905, 0x4c2d01, 0x4f3208, 0x4b2f07, 0x4c2f05, 0x482c04, 0x442b03, 0x462a03, 0x472b06, 0x452d09, 0x412702, 0x402601, 0x3f2705, 0x3d2405, 0x3f2705, 0x3d2606, 0x392203, 0x3c2506, 0x3b2607, 0x3c2304, 0x382306, 0x362303, 0x382101, 0x3a2304, 0x301f05, 0x2d1b03, 0x321f01, 0x2f2106, 0x2d1e09, 0x2e220a, 0x2e2208, 0x312108, 0x382807, 0x2f1f08, 0x281d09, 0x312205, 0x392908, 0x342506, 0x312108, 0x3c2908, 0x3d2906, 0x3b2808, 0x3a2707, 0x392608, 0x3d2906, 0x3e2705, 0x382304, 0x382504, 0x412b06, 0x432904, 0x442c06, 0x4f330b, 0x482f06, 0x3a2208, 0x5a3a11, 0x816019, 0x8c6721, 0x8e6726, 0x987426, 0xb68e36, 0xc7a03b, 0xd2ad43, 0xd4af45, 0xd8b34b, 0xdab655, 0xdcb95b, 0xe3bf69, 0xe8c373, 0xecc779, 0xe9c57b, 0xdfbd76, 0xd1af6f, 0xc0a15e, 0xcbaa63, 0x352f21, 0x0b0f1b, 0x2b2c2e, 0x323337, 0x242527, 0x0c0c0c, 0x050505, 0x050505, 0x0a0a0c, 0x070707, 0x080808, 0x0e0e0e, 0x0b0b0b, 0x050706, 0x050706, 0x050706, 0x060807, 0x070707, 0x060606, 0x060606, 0x060606, 0x050505, 0x040404, 0x040404, 0x030303, 0x020202, 0x040404, 0x030303, 0x040404, 0x030303, 0x020202, 0x020202, 0x000000, 0x6c5a36, 0xd9b569, 0xb89956, 0xb99656, 0xb79152, 0xc29850, 0xd5a950, 0xe0b650, 0xe3b94b, 0xe3b94b, 0xe3b848, 0xe4b446, 0xe3b347, 0xddb24c, 0xd8b156, 0xd9b05e, 0xd6b069, 0xcba564, 0xb79660, 0x927549, 0x52350d, 0x492c02, 0x53360c, 0x4e3105, 0x4d3004, 0x4e3107, 0x482c05, 0x452c03, 0x4b3005, 0x472b04, 0x422805, 0x432a02, 0x452902, 0x412704, 0x402806, 0x402708, 0x392405, 0x3d2606, 0x3e2604, 0x3c2505, 0x3d2606, 0x382101, 0x3b2405, 0x382306, 0x311d02, 0x341f04, 0x362104, 0x2d1b03, 0x291c09, 0x2e2006, 0x2f1e0a, 0x2f2009, 0x302205, 0x332309, 0x392a0b, 0x302007, 0x291a05, 0x312309, 0x392907, 0x342305, 0x322107, 0x3e2a09, 0x412907, 0x3f2806, 0x382306, 0x3c2805, 0x412b04, 0x3f2904, 0x3a2506, 0x402907, 0x442a05, 0x422a04, 0x4c3106, 0x513408, 0x432b05, 0x40260b, 0x6f4c14, 0x89641d, 0x967228, 0xa18230, 0xa8863c, 0xab8a3b, 0xbb9b4e, 0xc9ad5a, 0xd1b260, 0xd8b86b, 0xdaba6d, 0xddb96b, 0xd9b569, 0xd3af63, 0xc5a35c, 0xbd9c59, 0xb99a5a, 0xc1a261, 0xc4a765, 0x2e2a21, 0x0f131e, 0x292a2c, 0x2b2b2d, 0x0e0f11, 0x050505, 0x0d0d0d, 0x0e0e0e, 0x0d0d0f, 0x141414, 0x1a1a1c, 0x18181a, 0x19191b, 0x18191b, 0x101113, 0x050706, 0x080808, 0x060606, 0x050505, 0x060606, 0x060606, 0x050505, 0x040404, 0x030303, 0x020202, 0x020202, 0x040404, 0x050505, 0x060606, 0x030303, 0x020202, 0x020202, 0x000000, 0x5f5033, 0xd6b16b, 0xba9757, 0xba9753, 0xb89754, 0xbd9854, 0xc49e53, 0xc7a357, 0xcda95b, 0xd4b45d, 0xdeb75c, 0xe3b55d, 0xe1b761, 0xe0b664, 0xdcb065, 0xcea75c, 0xb6944d, 0x9c7941, 0x806037, 0x583b13, 0x4f2f00, 0x553607, 0x4e3109, 0x533405, 0x503105, 0x4b2e06, 0x4a2d05, 0x4d3008, 0x482f07, 0x432a02, 0x472b04, 0x452b06, 0x432904, 0x432a02, 0x402804, 0x3c2505, 0x3f2705, 0x3f2703, 0x3f2806, 0x3e2602, 0x392502, 0x3d2405, 0x372203, 0x311d04, 0x362104, 0x352003, 0x2c1a02, 0x2f1b02, 0x281b08, 0x291d07, 0x2f1f08, 0x2f1f06, 0x322209, 0x2e1f08, 0x312205, 0x3b2807, 0x311f07, 0x261b07, 0x312107, 0x3d2904, 0x322105, 0x352108, 0x412903, 0x422a06, 0x3e2707, 0x3b2706, 0x3e2803, 0x422a04, 0x3f2806, 0x3d2405, 0x422805, 0x462f06, 0x4a2e07, 0x503103, 0x4f3208, 0x3c2708, 0x56370b, 0x7f5a13, 0x8d671e, 0x9b7628, 0xaa8733, 0xb6923c, 0xb69643, 0xba9b4b, 0xc1a14e, 0xc3a251, 0xbd9c4f, 0xb8924b, 0xb38e47, 0xb59147, 0xb4934e, 0xb79857, 0xba9a5d, 0xc5a666, 0xb79a5e, 0x25211e, 0x151922, 0x262729, 0x131315, 0x050706, 0x0d0d0d, 0x0e0e10, 0x131416, 0x19191b, 0x202123, 0x252628, 0x212226, 0x212226, 0x212226, 0x202123, 0x141416, 0x090909, 0x060606, 0x060606, 0x060606, 0x050505, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x060606, 0x040404, 0x040404, 0x020202, 0x010101, 0x000000, 0x52482f, 0xd8b36d, 0xba9755, 0xb69552, 0xb89555, 0xbd9750, 0xc19e4d, 0xc6a153, 0xcaa557, 0xd0ac58, 0xd6ad55, 0xd4aa54, 0xc9a551, 0xbf9c4b, 0xb28c45, 0x977535, 0x836028, 0x775728, 0x63431a, 0x543506, 0x573706, 0x563607, 0x533405, 0x513204, 0x513005, 0x4b2e04, 0x4f3208, 0x4d3008, 0x472b04, 0x472b04, 0x482c05, 0x452b06, 0x432b05, 0x432904, 0x3f2703, 0x402804, 0x412702, 0x432b07, 0x3f2806, 0x3c2400, 0x3f2607, 0x372203, 0x332002, 0x392203, 0x341f04, 0x2e1a02, 0x321e03, 0x341f04, 0x302207, 0x291c09, 0x291a03, 0x2f1f06, 0x2e1d09, 0x302104, 0x2f1f05, 0x352204, 0x3d2906, 0x2f1f06, 0x291b01, 0x362305, 0x3f2806, 0x352204, 0x382504, 0x422c05, 0x432b05, 0x3e2803, 0x3e2705, 0x452b06, 0x452c04, 0x3e2602, 0x412704, 0x462d05, 0x472e05, 0x4f3405, 0x523607, 0x493008, 0x462909, 0x6e4710, 0x866017, 0x886217, 0x8f6a1c, 0x9c7623, 0x9e7728, 0x9e782d, 0xa37d34, 0xa68238, 0xa78639, 0xad893f, 0xb18f48, 0xb7924b, 0xb79653, 0xb99758, 0xb9995c, 0xc8a86b, 0xad945e, 0x151515, 0x15181d, 0x151517, 0x080808, 0x080a09, 0x111111, 0x131315, 0x1e1f21, 0x28282a, 0x2b2c2e, 0x37383c, 0x404145, 0x35363a, 0x292a2e, 0x28272c, 0x212123, 0x131114, 0x090909, 0x070707, 0x060606, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x040404, 0x050505, 0x050505, 0x030303, 0x020202, 0x020202, 0x000000, 0x493e28, 0xd5b270, 0xb79857, 0xb89752, 0xb6914b, 0xb89048, 0xb69045, 0xb28d46, 0xb38e3e, 0xb68d3b, 0xb48a38, 0xaa8334, 0xa27d2f, 0x9b752a, 0x936e2a, 0x88642a, 0x83622c, 0x715223, 0x5a3a0b, 0x5a3b05, 0x583a06, 0x563605, 0x593707, 0x513408, 0x503105, 0x523304, 0x4e3203, 0x482b01, 0x4b2e06, 0x4c3008, 0x462d05, 0x472b04, 0x422a04, 0x402804, 0x422803, 0x452902, 0x442a05, 0x3f2703, 0x3e2602, 0x402907, 0x392202, 0x362104, 0x3a2506, 0x341f02, 0x2f1b02, 0x352003, 0x382004, 0x321e05, 0x2e1e05, 0x302207, 0x2b1c05, 0x291a07, 0x2e1e04, 0x312107, 0x312203, 0x301e06, 0x382504, 0x3c2805, 0x301f03, 0x2a1a01, 0x3a2506, 0x3f2b06, 0x311e00, 0x392502, 0x432c03, 0x442c06, 0x412905, 0x412903, 0x452c03, 0x452c04, 0x432904, 0x452b06, 0x4e3203, 0x4b2f08, 0x533708, 0x553a05, 0x462a05, 0x58350d, 0x7d5812, 0x8a621a, 0x8d6821, 0x957123, 0xa07b2b, 0xa37e2e, 0xa48034, 0xa6843c, 0xa9873d, 0xac8b44, 0xb08e47, 0xb6914b, 0xb59451, 0xb99758, 0xba9a5d, 0xcaaa6d, 0x9f8958, 0x0d0e10, 0x0a0e11, 0x0a0a0c, 0x080808, 0x101211, 0x101012, 0x1e1e20, 0x353638, 0x404143, 0x47484a, 0x4c4c4e, 0x545358, 0x515055, 0x424347, 0x353537, 0x29292b, 0x1b1b1d, 0x0b0b0b, 0x060606, 0x050505, 0x040404, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x050505, 0x060606, 0x040404, 0x020202, 0x020202, 0x010101, 0x3f3323, 0xceac6d, 0xb89959, 0xb69455, 0xb79452, 0xb8934c, 0xb18c46, 0xad8b43, 0xb0893a, 0xb08536, 0xac8334, 0xa67f34, 0xa47c36, 0x9d7631, 0x906e2e, 0x8a662c, 0x79592a, 0x634310, 0x5e3e05, 0x5b3909, 0x583809, 0x593906, 0x573706, 0x503404, 0x543506, 0x563607, 0x4e2f01, 0x4c2f05, 0x4f3004, 0x4c2f05, 0x4b2f07, 0x462a03, 0x452904, 0x432a02, 0x472b04, 0x4a2e09, 0x402804, 0x402802, 0x422a06, 0x392203, 0x392405, 0x3e2604, 0x331e03, 0x2f1e02, 0x392202, 0x382102, 0x342005, 0x382004, 0x2c1b09, 0x2c1c03, 0x312205, 0x2e2005, 0x2b1c07, 0x2d1d04, 0x2f2003, 0x312205, 0x2e2005, 0x3c2503, 0x3f2806, 0x2e1e04, 0x291b00, 0x3d2405, 0x422805, 0x342005, 0x412a01, 0x492d05, 0x462d04, 0x412903, 0x432904, 0x4c3008, 0x462d04, 0x422803, 0x4a2f04, 0x4e3105, 0x553407, 0x5b3a07, 0x553607, 0x493007, 0x6b4812, 0x865e16, 0x89631c, 0x906c1e, 0x9c7625, 0xa07a29, 0xa07c32, 0xa47f39, 0xab853c, 0xac8540, 0xad8b44, 0xb28d49, 0xb39151, 0xb69455, 0xb7975c, 0xccac71, 0x988157, 0x07080c, 0x07080a, 0x070508, 0x0e0e0e, 0x0f1110, 0x131315, 0x36353a, 0x535458, 0x6a6b6d, 0x767678, 0x6c6c6e, 0x646466, 0x5d5d5f, 0x535456, 0x434446, 0x2a2a2c, 0x212123, 0x0f0f0f, 0x070707, 0x050505, 0x040404, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x040404, 0x060606, 0x040404, 0x040404, 0x030303, 0x000000, 0x332d1f, 0xcba86e, 0xba9b5b, 0xb69454, 0xb79450, 0xb18e4a, 0xae8d4a, 0xb18b40, 0xb28b3e, 0xac8739, 0xa98436, 0xa78035, 0xa07a33, 0x93702e, 0x88682d, 0x805f2a, 0x6d4c19, 0x613e08, 0x603c0a, 0x5f3b07, 0x623d08, 0x573706, 0x513505, 0x593707, 0x563603, 0x4d3004, 0x513108, 0x523305, 0x4d3004, 0x4c2f05, 0x492c04, 0x452904, 0x4a2d05, 0x4b2e06, 0x482c05, 0x432904, 0x432904, 0x412907, 0x3c2505, 0x3d2405, 0x3e2506, 0x341f02, 0x341f00, 0x3a2304, 0x372205, 0x382304, 0x3b2203, 0x3a2304, 0x2e1e04, 0x2e1e05, 0x2e1e04, 0x312002, 0x2e1e04, 0x2b1d03, 0x2f1f05, 0x321e05, 0x332206, 0x352003, 0x3c2505, 0x412a08, 0x301f05, 0x301e06, 0x422a06, 0x3f2902, 0x352504, 0x492d08, 0x4c2f05, 0x4b3005, 0x422b02, 0x4b3005, 0x4b3003, 0x492c04, 0x4a2f04, 0x523307, 0x513203, 0x5d3905, 0x5f3e0b, 0x50350a, 0x59370a, 0x7c5416, 0x89611b, 0x8d651d, 0x967123, 0x9d762b, 0x9e7a30, 0x9f7d33, 0xa7803b, 0xa7853e, 0xab8844, 0xad8b4c, 0xb29051, 0xb49555, 0xb5965f, 0xccae72, 0x927f57, 0x020307, 0x040404, 0x090909, 0x111111, 0x101010, 0x1c1c1e, 0x4d4d4f, 0x676769, 0x7d7d7f, 0x868688, 0x858587, 0x78787a, 0x606062, 0x555658, 0x444547, 0x2e2f31, 0x1f2024, 0x151517, 0x0a0a0c, 0x060606, 0x030303, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x050505, 0x070707, 0x050505, 0x030303, 0x030303, 0x000000, 0x262219, 0xc1a46a, 0xbc9d5d, 0xb79556, 0xb49350, 0xae8c4c, 0xae8b47, 0xb28b40, 0xae863e, 0xac853a, 0xa78035, 0xa27c35, 0x98732f, 0x8f6b2f, 0x88652d, 0x785420, 0x69450b, 0x65420a, 0x643e0d, 0x633f0b, 0x5b3c06, 0x543604, 0x583805, 0x5c3806, 0x523104, 0x543506, 0x523304, 0x523305, 0x4f3206, 0x492c02, 0x492d05, 0x4a2f02, 0x4d3101, 0x4b2e04, 0x452c04, 0x462d05, 0x422805, 0x3e2604, 0x402a05, 0x3a2303, 0x332002, 0x3b2404, 0x3c2505, 0x3d2405, 0x3d2604, 0x3b2704, 0x3c2304, 0x301c04, 0x2e1c04, 0x2e2006, 0x301f05, 0x2c1c02, 0x312205, 0x2e1d01, 0x2c1c03, 0x322103, 0x302104, 0x372302, 0x352001, 0x3c2803, 0x422a04, 0x352001, 0x331f04, 0x452c04, 0x402804, 0x3e2803, 0x4c2f03, 0x4c2f03, 0x4c3106, 0x462d05, 0x4f3304, 0x503405, 0x4b2e04, 0x503103, 0x563605, 0x563605, 0x63400a, 0x5d3d0a, 0x53360c, 0x6c4712, 0x875f19, 0x89631c, 0x8f6b21, 0x9a7328, 0x9d772e, 0x9c7a32, 0xa27d36, 0xa88241, 0xa98644, 0xab894a, 0xb08e4f, 0xb29255, 0xb5945e, 0xcfaf72, 0x8d7954, 0x000004, 0x010101, 0x0b0b0b, 0x1b1b1d, 0x111113, 0x1f1f21, 0x616264, 0x727274, 0x838385, 0x8d8e90, 0x969799, 0x858587, 0x666668, 0x535456, 0x47484a, 0x333438, 0x212025, 0x161618, 0x0c0c0c, 0x070707, 0x050505, 0x040404, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x050505, 0x070707, 0x060606, 0x040404, 0x030303, 0x000000, 0x1b1811, 0xba9d65, 0xbfa060, 0xb49555, 0xb39151, 0xac8a4a, 0xaf8c48, 0xaf8942, 0xac863d, 0xaa823a, 0xa47e37, 0x9d7631, 0x956f30, 0x8c682c, 0x7d5a22, 0x6e4b15, 0x6c450c, 0x68430f, 0x674305, 0x623f07, 0x5a3808, 0x5c3804, 0x5d3907, 0x563603, 0x573706, 0x5a380a, 0x533406, 0x543506, 0x4d2e02, 0x4c2f05, 0x4f3002, 0x4f3208, 0x4b3005, 0x482c05, 0x4e2e07, 0x422803, 0x402804, 0x442a05, 0x3a2303, 0x341f04, 0x3d2604, 0x3e2507, 0x3c2505, 0x402804, 0x422803, 0x362104, 0x301c04, 0x3a2200, 0x2f1f06, 0x2f1e00, 0x2b1d00, 0x302006, 0x2e1d03, 0x332208, 0x332002, 0x2d1d04, 0x2f2003, 0x312006, 0x3c2601, 0x382304, 0x3f2904, 0x472f09, 0x341f00, 0x3b2203, 0x4b3005, 0x402a03, 0x432a02, 0x533207, 0x4f3004, 0x4d3205, 0x4c3104, 0x563603, 0x543405, 0x4e3306, 0x593707, 0x5a3906, 0x5e3d08, 0x67420b, 0x5c3c0b, 0x5e3d12, 0x7d5615, 0x87611a, 0x8a651e, 0x956d25, 0x9c742c, 0x997632, 0x9c7935, 0xa5803c, 0xa78442, 0xa98748, 0xae8c4d, 0xaf8f54, 0xb4935d, 0xd0b073, 0x826f4e, 0x000002, 0x040404, 0x0e0e10, 0x1f1f21, 0x141416, 0x252628, 0x68696b, 0x777779, 0x808082, 0x8f9092, 0x9b9c9e, 0x8c8d8f, 0x6d6e70, 0x5e5f61, 0x4c4d51, 0x35363a, 0x1f1e23, 0x161618, 0x0c0c0c, 0x080808, 0x060606, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x040404, 0x060606, 0x060606, 0x040404, 0x020202, 0x000000, 0x0f0e09, 0xb09462, 0xc2a363, 0xb29456, 0xae8e51, 0xae8c4c, 0xae8c45, 0xac8741, 0xaa843d, 0xa7813a, 0xa17a37, 0x96702f, 0x916b2d, 0x876329, 0x775319, 0x6c480e, 0x6b460f, 0x6e4609, 0x664208, 0x5c3b05, 0x623e04, 0x623d06, 0x593707, 0x593805, 0x5b3a05, 0x553504, 0x573708, 0x513204, 0x4e3203, 0x563607, 0x533408, 0x513003, 0x4a2f02, 0x4b2e02, 0x432702, 0x462a05, 0x482c05, 0x392502, 0x3b2402, 0x402804, 0x402806, 0x3e2803, 0x442801, 0x422505, 0x331f04, 0x352003, 0x3e2604, 0x3a2304, 0x2a1a03, 0x2f1f05, 0x312004, 0x2f1f05, 0x312004, 0x341f02, 0x372406, 0x332204, 0x2f1e02, 0x302104, 0x372205, 0x3e2705, 0x362102, 0x432a02, 0x472e05, 0x382004, 0x412905, 0x513204, 0x432b07, 0x4b2d07, 0x573706, 0x553705, 0x4f3206, 0x553504, 0x593803, 0x513506, 0x543403, 0x5f3a06, 0x5c3c09, 0x65420a, 0x6b440b, 0x5c3d0e, 0x724a16, 0x865f1a, 0x89641d, 0x8e6722, 0x987028, 0x99742e, 0x997737, 0xa27d37, 0xa58242, 0xa98547, 0xac8a4b, 0xae8e55, 0xb2935c, 0xd0b073, 0x786449, 0x010101, 0x060606, 0x111113, 0x222224, 0x18191b, 0x2c2d2f, 0x5d5e60, 0x707072, 0x777779, 0x7a7b7d, 0x7f8082, 0x7e7f81, 0x6d6e70, 0x5b5c60, 0x47484c, 0x323337, 0x1f2024, 0x18181a, 0x0d0d0d, 0x090909, 0x060606, 0x030303, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x040404, 0x060606, 0x060606, 0x050505, 0x030303, 0x000000, 0x060604, 0xa78c5d, 0xc6a467, 0xb09158, 0xad8d50, 0xb18e4e, 0xaf8a46, 0xab8642, 0xa6813b, 0xa27d39, 0x9b7534, 0x956f31, 0x8b672b, 0x80591e, 0x744d12, 0x70490e, 0x6d490d, 0x6f470a, 0x65400b, 0x664208, 0x674005, 0x5d3a04, 0x5b3c06, 0x5f3a06, 0x583704, 0x573603, 0x543405, 0x553506, 0x573706, 0x553607, 0x533205, 0x503103, 0x4c2f03, 0x452904, 0x492e03, 0x452c03, 0x3b2404, 0x3f2703, 0x442b03, 0x422805, 0x412905, 0x432904, 0x3f2703, 0x331f04, 0x3c2506, 0x422805, 0x341f02, 0x331e01, 0x2f2106, 0x2c1a06, 0x301c03, 0x312002, 0x312006, 0x352204, 0x362303, 0x352202, 0x382304, 0x352201, 0x322105, 0x3a2303, 0x412a01, 0x3f2705, 0x472e05, 0x482f06, 0x3b2404, 0x462a02, 0x513506, 0x452e04, 0x503404, 0x5a3906, 0x583704, 0x543507, 0x5a3a07, 0x5b3a07, 0x563603, 0x5a3906, 0x61400b, 0x65420a, 0x6e470e, 0x68450d, 0x6b4514, 0x7e5619, 0x87601b, 0x896322, 0x956f28, 0x9b752a, 0x997636, 0x9d7a38, 0xa48141, 0xa78345, 0xaa8849, 0xac8d56, 0xb0915a, 0xd1af72, 0x6f5e44, 0x000000, 0x060606, 0x171719, 0x2c2c2e, 0x191a1c, 0x333436, 0x545557, 0x5f5f61, 0x6c6c6e, 0x6f6f71, 0x6f6f71, 0x707072, 0x68696d, 0x525357, 0x3f4044, 0x2a2b2f, 0x1f2024, 0x1a1a1c, 0x0e0e0e, 0x0b0b0b, 0x060606, 0x030303, 0x020202, 0x010101, 0x020202, 0x020202, 0x010101, 0x040404, 0x070707, 0x060606, 0x060606, 0x040404, 0x000000, 0x010101, 0x9b8556, 0xc8a669, 0xae8f58, 0xaf9050, 0xae8b49, 0xac8645, 0xa8833f, 0xa47f3b, 0x9d7736, 0x987234, 0x936c31, 0x876025, 0x795217, 0x764e11, 0x774f11, 0x724a0d, 0x68430c, 0x6b4409, 0x6c4407, 0x623f09, 0x5f3c06, 0x633f05, 0x613e06, 0x593906, 0x583606, 0x563603, 0x5a3904, 0x593707, 0x543405, 0x523304, 0x4e3105, 0x482c05, 0x4a2f02, 0x462d05, 0x3f2904, 0x442b02, 0x482c05, 0x422807, 0x472b03, 0x482a06, 0x392504, 0x3a2506, 0x432c03, 0x3f2703, 0x371f05, 0x372203, 0x3c2304, 0x2b1c05, 0x352204, 0x301c03, 0x2e1a01, 0x352204, 0x322103, 0x362104, 0x362102, 0x382304, 0x3d2606, 0x352202, 0x372203, 0x3f2607, 0x412b04, 0x422803, 0x4c3102, 0x4e3107, 0x3d2702, 0x4d3004, 0x543506, 0x4a2f02, 0x563605, 0x5f3c06, 0x5c3b08, 0x583606, 0x5f3a06, 0x5e3e05, 0x593906, 0x623e0a, 0x694509, 0x6b470d, 0x744c0f, 0x67430f, 0x744d16, 0x875e1c, 0x896322, 0x8e6925, 0x997129, 0x997332, 0x9c7939, 0xa07e3e, 0xa58143, 0xa9874a, 0xab8c55, 0xae905a, 0xd0ad73, 0x695940, 0x000000, 0x060608, 0x1e1e20, 0x303032, 0x18191b, 0x404143, 0x555658, 0x494a4c, 0x555557, 0x5d5d5f, 0x656567, 0x656567, 0x58575c, 0x414246, 0x303135, 0x252628, 0x242527, 0x1b1b1b, 0x0d0d0d, 0x0b0b0b, 0x070707, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x050505, 0x080808, 0x060606, 0x060606, 0x040404, 0x000000, 0x000002, 0x937e53, 0xc7a568, 0xae8f59, 0xaf9050, 0xac8949, 0xaa8446, 0xa57f3e, 0xa37d3c, 0x9a7435, 0x967032, 0x8e682a, 0x805a1c, 0x7c5417, 0x7b5315, 0x785012, 0x71490c, 0x6e470c, 0x6e480a, 0x684108, 0x643f08, 0x684106, 0x663f06, 0x604007, 0x5a3906, 0x593906, 0x5e3b05, 0x5c3b06, 0x573505, 0x563605, 0x4e3105, 0x4c2f03, 0x4e3306, 0x452c03, 0x412903, 0x4c2f05, 0x4b2e04, 0x442b02, 0x4a2f04, 0x442b03, 0x3d2604, 0x432a02, 0x462a03, 0x3d2405, 0x372205, 0x3e2506, 0x412704, 0x3c2304, 0x2b1903, 0x2c1c03, 0x352106, 0x2e1c04, 0x301c03, 0x362302, 0x382504, 0x382403, 0x392405, 0x3a2304, 0x3d2604, 0x3a2605, 0x392405, 0x3e2604, 0x492d05, 0x452c04, 0x533406, 0x4e3403, 0x412903, 0x563107, 0x563806, 0x4d3101, 0x5e3a08, 0x634006, 0x5f3a05, 0x5e3a06, 0x644006, 0x613e06, 0x613e08, 0x6c450a, 0x6d460d, 0x724a0d, 0x704c12, 0x704b16, 0x815818, 0x88631f, 0x8b6526, 0x976f2a, 0x9a7531, 0x997634, 0x9e7a3c, 0xa48042, 0xa8854b, 0xa98a51, 0xad8f59, 0xcfac74, 0x67593f, 0x000000, 0x09090b, 0x262628, 0x2e2e30, 0x1d1d1f, 0x545557, 0x5c5d5f, 0x424345, 0x3b3b3d, 0x38393b, 0x3c3c3e, 0x3c3c3e, 0x313035, 0x28292b, 0x242527, 0x232426, 0x202123, 0x171717, 0x0c0c0c, 0x0a0a0a, 0x070707, 0x030303, 0x020202, 0x020202, 0x010101, 0x020202, 0x030303, 0x060606, 0x090909, 0x060606, 0x070707, 0x050505, 0x010101, 0x000002, 0x8a774f, 0xc8a669, 0xb0915a, 0xaf8d50, 0xaa8848, 0xa98345, 0xa37d3e, 0x9d7739, 0x987234, 0x936d2f, 0x896124, 0x7f5719, 0x7e5716, 0x7b5315, 0x754d0f, 0x744c0e, 0x734b0d, 0x6b4409, 0x674307, 0x6c4407, 0x6a4205, 0x664206, 0x5f3c06, 0x603d07, 0x633f05, 0x5d3c07, 0x593805, 0x5a3904, 0x523304, 0x523305, 0x4f3206, 0x482c05, 0x492c02, 0x503105, 0x4a2e06, 0x4c2f05, 0x4e2f03, 0x412704, 0x422805, 0x472e05, 0x452b06, 0x3d2406, 0x3e2506, 0x422805, 0x3f2705, 0x3e2604, 0x3c2304, 0x362209, 0x2d1d06, 0x2a1a03, 0x332204, 0x342103, 0x331f06, 0x362303, 0x3a2603, 0x3d2604, 0x3a2605, 0x3f2705, 0x422b02, 0x3d2700, 0x3f2705, 0x402806, 0x493105, 0x4c2f05, 0x563502, 0x573507, 0x462d05, 0x573706, 0x593707, 0x533304, 0x633f05, 0x684203, 0x623d06, 0x654009, 0x664206, 0x663f06, 0x68410a, 0x70490e, 0x724c0d, 0x76500f, 0x704b16, 0x7b5318, 0x886120, 0x896324, 0x916a27, 0x99722f, 0x9b7534, 0x9d793b, 0xa37f41, 0xa7844a, 0xa88950, 0xac8c59, 0xcfaa73, 0x695b41, 0x000000, 0x0a0b0f, 0x2b2a2f, 0x2e2d32, 0x1f1f21, 0x5f6062, 0x626365, 0x454648, 0x2b2c2e, 0x262729, 0x232426, 0x212224, 0x1f1e23, 0x202022, 0x202022, 0x1b1b1d, 0x131315, 0x101010, 0x0d0d0d, 0x080808, 0x050505, 0x050505, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x060606, 0x080808, 0x050505, 0x060606, 0x050505, 0x010101, 0x000000, 0x82704c, 0xc8a86d, 0xaf9059, 0xad8b4e, 0xa78546, 0xa58143, 0xa17b3d, 0x9a7338, 0x977035, 0x8f672a, 0x865e20, 0x825b1a, 0x805918, 0x7b5315, 0x774f12, 0x774f11, 0x71490b, 0x6f4709, 0x6f4709, 0x6d4507, 0x684106, 0x623d06, 0x663f08, 0x684204, 0x623d06, 0x5f3b07, 0x5b3b08, 0x563603, 0x563804, 0x523606, 0x4c2d01, 0x4e3105, 0x543506, 0x513204, 0x513206, 0x4d3006, 0x432a02, 0x482c05, 0x4a2f04, 0x422803, 0x3e2403, 0x3f2904, 0x452b08, 0x432904, 0x3e2602, 0x3a2005, 0x362106, 0x301e0a, 0x392405, 0x352202, 0x2d1d04, 0x331f04, 0x392405, 0x341e06, 0x372403, 0x3c2505, 0x3f2705, 0x412905, 0x412905, 0x432b05, 0x422a06, 0x402802, 0x452c04, 0x503103, 0x4d3004, 0x5c3b06, 0x583807, 0x4a2d01, 0x5c3b08, 0x5c3804, 0x593707, 0x684106, 0x684106, 0x674005, 0x6c4407, 0x6e4609, 0x664206, 0x6f480d, 0x774e10, 0x774f11, 0x7a5415, 0x775015, 0x845c1f, 0x8b6222, 0x8e6628, 0x96702f, 0x9c7436, 0x9a7839, 0xa17d41, 0xa68349, 0xa78851, 0xad8c59, 0xccac71, 0x716245, 0x000000, 0x0d0e10, 0x29292b, 0x232124, 0x1d1c21, 0x65696c, 0x5c6164, 0x474b4c, 0x353537, 0x232428, 0x202123, 0x202123, 0x1f1f21, 0x1c1c1e, 0x161618, 0x151517, 0x101211, 0x0c0c0e, 0x0c0c0c, 0x060606, 0x050505, 0x040404, 0x020202, 0x020202, 0x020202, 0x010100, 0x050505, 0x0e0e0e, 0x0a0a0a, 0x040404, 0x060606, 0x050505, 0x010103, 0x000100, 0x866f4d, 0xcba86e, 0xae8f58, 0xab8850, 0xa78548, 0xa28043, 0x9c783e, 0x9a7338, 0x936d2f, 0x8a6224, 0x87601f, 0x855d1f, 0x7d5517, 0x7c5313, 0x7c5311, 0x764f0e, 0x754c0c, 0x744b0b, 0x704908, 0x6b4305, 0x674005, 0x6b4308, 0x6c4406, 0x684106, 0x644006, 0x5e3a06, 0x5a3906, 0x5a3a07, 0x543405, 0x4f2f06, 0x553607, 0x533405, 0x533205, 0x553407, 0x4b2e04, 0x492e03, 0x4e3105, 0x4a2d05, 0x432a02, 0x462a03, 0x472b04, 0x482c05, 0x432904, 0x3e2604, 0x3c2305, 0x3a2005, 0x3a2103, 0x241808, 0x2b1c05, 0x3d2607, 0x3a2206, 0x302104, 0x301f03, 0x3d2604, 0x3a2206, 0x392405, 0x3f2904, 0x412903, 0x452c04, 0x462e02, 0x492e03, 0x482c05, 0x442b03, 0x492e03, 0x523607, 0x543507, 0x613c05, 0x5e3a08, 0x503405, 0x603d05, 0x5b3a07, 0x623d06, 0x6c4406, 0x6c4407, 0x6a4405, 0x6f470a, 0x6f470a, 0x6a460a, 0x784f11, 0x7a5214, 0x7a5312, 0x7c5618, 0x81591c, 0x8a6322, 0x8b6325, 0x946c2e, 0x9b7433, 0x987637, 0x9f7b41, 0xa5824a, 0xa88751, 0xac8b58, 0xc8a86f, 0x726346, 0x000002, 0x101113, 0x262628, 0x121214, 0x222126, 0x5e6265, 0x474b4e, 0x595a5c, 0x474749, 0x25262a, 0x232428, 0x232428, 0x232227, 0x19181d, 0x111015, 0x1a1a1c, 0x101012, 0x090909, 0x070707, 0x050505, 0x060606, 0x030303, 0x040404, 0x010101, 0x030303, 0x000000, 0x040404, 0x111111, 0x0a0a0a, 0x040404, 0x070707, 0x070707, 0x010103, 0x000000, 0x8a744f, 0xcaa76d, 0xac8d56, 0xab8850, 0xa68349, 0x9e7a40, 0x9d763b, 0x997134, 0x91692b, 0x8d6625, 0x886120, 0x835c1b, 0x825919, 0x7f5614, 0x7b5210, 0x784f0d, 0x784c0b, 0x744b0b, 0x71490b, 0x6d4508, 0x6f4608, 0x6f4608, 0x694305, 0x663f08, 0x613c07, 0x603d05, 0x5c3b06, 0x533205, 0x563603, 0x5c3b05, 0x583606, 0x583807, 0x533406, 0x4a2d03, 0x4d3207, 0x4d3205, 0x492d05, 0x472b04, 0x4a2c06, 0x4c2f05, 0x4a2d05, 0x432904, 0x3e2506, 0x3b2405, 0x3b2404, 0x3b2301, 0x3d2405, 0x35230b, 0x2a1d0a, 0x251909, 0x362305, 0x422a06, 0x352204, 0x322103, 0x422805, 0x3a2603, 0x3d2700, 0x442b03, 0x472b04, 0x4a2f04, 0x4c3106, 0x4d3008, 0x4b3001, 0x482f06, 0x4b3005, 0x573505, 0x593707, 0x654105, 0x5d3a02, 0x563708, 0x634006, 0x603d05, 0x694207, 0x704803, 0x6e4608, 0x6d4508, 0x73490d, 0x734b0d, 0x744c0e, 0x7c5313, 0x7e5515, 0x7f5719, 0x81591c, 0x8a6320, 0x8f6626, 0x91692c, 0x9b7433, 0x9a7638, 0x9d793f, 0xa38048, 0xa88751, 0xac8b56, 0xc7a76e, 0x746548, 0x000002, 0x111113, 0x1f1f21, 0x070709, 0x323337, 0x3c3d41, 0x212224, 0x4f5052, 0x565759, 0x36373b, 0x25262a, 0x242529, 0x26272b, 0x1e1f23, 0x212025, 0x272729, 0x0d0d0d, 0x070705, 0x070705, 0x050505, 0x030303, 0x030303, 0x020202, 0x040404, 0x000000, 0x060608, 0x232325, 0x121214, 0x010101, 0x060606, 0x060606, 0x060606, 0x020403, 0x000000, 0x8d7750, 0xc8a56b, 0xab8c56, 0xa7874e, 0xa38048, 0x9f7a43, 0x9d7739, 0x976f31, 0x90682a, 0x8e6726, 0x896020, 0x855c1a, 0x845b19, 0x825615, 0x7e5211, 0x7f540f, 0x7a4e0d, 0x744b0b, 0x714808, 0x734a0a, 0x704707, 0x6c4406, 0x6a4406, 0x643f08, 0x623e04, 0x603d07, 0x593805, 0x5e3a06, 0x5f3c06, 0x5b3a05, 0x5e3a06, 0x543506, 0x513301, 0x563508, 0x503103, 0x472b03, 0x4a2e07, 0x4e3203, 0x502f02, 0x4b2f07, 0x432a02, 0x3f2703, 0x3f2705, 0x3e2604, 0x422807, 0x412809, 0x3d2405, 0x422d10, 0x3e2b0d, 0x2f200b, 0x251903, 0x2f1e04, 0x442c06, 0x3f2902, 0x372203, 0x402804, 0x432b09, 0x3d2702, 0x462f05, 0x4e2f03, 0x4e2f01, 0x4f3304, 0x513206, 0x503405, 0x4b3005, 0x523106, 0x5a3b05, 0x5c3b06, 0x694207, 0x663f04, 0x5d3c06, 0x664208, 0x663d05, 0x6e4608, 0x734a08, 0x71480a, 0x754c0a, 0x794d0c, 0x744c0f, 0x7b5210, 0x835716, 0x815816, 0x835b1d, 0x886120, 0x916828, 0x90682b, 0x967031, 0x9d7738, 0x9c783e, 0xa08047, 0xa6854f, 0xaa8b54, 0xc6a66d, 0x746546, 0x000000, 0x0e0d12, 0x1d1e20, 0x121315, 0x3e3f43, 0x212025, 0x141416, 0x272729, 0x505153, 0x4e4f51, 0x353638, 0x222325, 0x18191d, 0x232428, 0x323335, 0x2b2b2d, 0x080808, 0x080808, 0x070707, 0x040404, 0x020202, 0x020202, 0x010101, 0x000000, 0x060606, 0x1a1b1f, 0x2e2d32, 0x1b1b1d, 0x010101, 0x050505, 0x060606, 0x060606, 0x020403, 0x000000, 0x89734c, 0xc6a36b, 0xa98b55, 0xa5844e, 0xa17e48, 0x9f7b41, 0x997334, 0x966e30, 0x926a2c, 0x8e6527, 0x896020, 0x895d1c, 0x865b17, 0x815612, 0x805413, 0x7d520d, 0x7a4e0d, 0x77490b, 0x774a09, 0x734a08, 0x6f4807, 0x6a4205, 0x6b4306, 0x664204, 0x603d07, 0x603b04, 0x674005, 0x623d06, 0x613c08, 0x5e3b05, 0x573704, 0x553506, 0x563804, 0x513204, 0x4e2f03, 0x533304, 0x533304, 0x503405, 0x492e01, 0x442d04, 0x412704, 0x422805, 0x462d05, 0x462d05, 0x412704, 0x3c2305, 0x3a2206, 0x35250e, 0x402c13, 0x442d0b, 0x39250a, 0x281c04, 0x2c1c03, 0x402909, 0x442c06, 0x3e2506, 0x432906, 0x4a2e07, 0x442b03, 0x462d04, 0x4e3203, 0x533302, 0x553705, 0x543405, 0x533503, 0x513506, 0x553407, 0x5c3b06, 0x613e06, 0x6d4404, 0x684108, 0x623e04, 0x6c4206, 0x694106, 0x734a08, 0x794c09, 0x754c0a, 0x78500b, 0x7b4f0e, 0x79500e, 0x835716, 0x875c18, 0x845d1c, 0x886023, 0x906725, 0x936c2b, 0x956f31, 0x9d7537, 0x9d793d, 0xa07d45, 0xa5844e, 0xa98a53, 0xc5a56c, 0x786847, 0x010101, 0x141318, 0x030406, 0x3e3f41, 0x909193, 0x2e2e30, 0x111113, 0x0d0d0f, 0x313234, 0x55565a, 0x3c3d41, 0x232428, 0x0e0f13, 0x202125, 0x47484a, 0x3a3a3c, 0x060606, 0x0b0b0d, 0x060606, 0x030303, 0x010100, 0x000000, 0x000000, 0x09090b, 0x19191b, 0x25262a, 0x222126, 0x171719, 0x0a0a0a, 0x050505, 0x040404, 0x070707, 0x030504, 0x000002, 0x846e49, 0xc8a56d, 0xa88a54, 0xa3824c, 0xa07d47, 0x9d793b, 0x9a7435, 0x976f31, 0x926a2c, 0x8e6527, 0x8b6222, 0x8a5f1b, 0x865b17, 0x855815, 0x835615, 0x7b5210, 0x7b4e0a, 0x7f500a, 0x794e0a, 0x734a08, 0x6e4505, 0x6f4608, 0x6d4508, 0x643f08, 0x663f04, 0x6a4308, 0x663f04, 0x674005, 0x633e07, 0x5b3a05, 0x5a3904, 0x593805, 0x513506, 0x4f3504, 0x553705, 0x573708, 0x503405, 0x452c03, 0x452b08, 0x422805, 0x492d05, 0x4a2f04, 0x452b06, 0x402708, 0x3d2405, 0x3f2504, 0x472b06, 0x362511, 0x33240d, 0x3b2a0c, 0x462d0e, 0x462d0e, 0x312205, 0x2c1c03, 0x3f2705, 0x4b2e04, 0x402907, 0x422a04, 0x4c2f05, 0x4b2e06, 0x4d3207, 0x523304, 0x573706, 0x5a3906, 0x583606, 0x573704, 0x533503, 0x5b3707, 0x613e04, 0x634008, 0x744608, 0x6a4205, 0x683f07, 0x6e4507, 0x6e4505, 0x7a4d09, 0x7b4e0b, 0x79510c, 0x82530f, 0x7e530f, 0x825615, 0x8a5f1a, 0x8a5e1d, 0x896022, 0x8e6726, 0x956e2b, 0x967032, 0x9c7638, 0x9f7b3f, 0x9f7c44, 0xa4834e, 0xaa8b54, 0xc6a36b, 0x806d4d, 0x010005, 0x0e0d12, 0x18181a, 0x2b2d2c, 0x49494b, 0x5b5b5d, 0x343436, 0x070709, 0x101113, 0x3a3b3f, 0x38393d, 0x2d2e32, 0x27282c, 0x2d2e32, 0x606165, 0x3e3e40, 0x020204, 0x141318, 0x0e0e10, 0x070707, 0x000000, 0x020202, 0x18181a, 0x2b2b2d, 0x2f2e33, 0x202022, 0x0d0d0f, 0x08080a, 0x0d0d0d, 0x080808, 0x060606, 0x050505, 0x010302, 0x000002, 0x88724d, 0xc5a26a, 0xa58751, 0xa4834d, 0xa27f47, 0x9e7b3b, 0x9d7538, 0x976f31, 0x916a29, 0x8f6626, 0x8f6322, 0x8b5e1b, 0x895c19, 0x865916, 0x815411, 0x7f530c, 0x805310, 0x7d500f, 0x794d0c, 0x754a05, 0x764b06, 0x6f4606, 0x694008, 0x6d4309, 0x6d4605, 0x6b4506, 0x6a4308, 0x613f02, 0x603d03, 0x613c08, 0x5a3906, 0x583608, 0x583704, 0x593a03, 0x573907, 0x503307, 0x492d05, 0x482c05, 0x4d3102, 0x503309, 0x4b2f07, 0x432b05, 0x3f2806, 0x422805, 0x4a2c08, 0x512d09, 0x532d08, 0x473312, 0x3d290e, 0x34240d, 0x362509, 0x422b0b, 0x493008, 0x402907, 0x312006, 0x362303, 0x4c2f05, 0x4c2f03, 0x462d04, 0x4e3105, 0x4f3206, 0x503309, 0x543405, 0x593707, 0x613e08, 0x5f3c06, 0x5b3a05, 0x5b3a04, 0x5d3907, 0x663f06, 0x6e4507, 0x754a06, 0x6e4609, 0x6d4307, 0x724909, 0x754908, 0x7e5207, 0x7e510e, 0x825210, 0x835612, 0x855815, 0x895c19, 0x8d601c, 0x8b5f1e, 0x8d6625, 0x956e2b, 0x9a7234, 0x9d7739, 0xa27c3e, 0xa17d43, 0xa3824f, 0xa98a53, 0xc6a16a, 0x877352, 0x000105, 0x111113, 0x292929, 0x030303, 0x000000, 0x080808, 0x363636, 0x373739, 0x0d0d0f, 0x0d0e12, 0x2d2e32, 0x3a3b3f, 0x4d4e52, 0x323337, 0x67686c, 0x434345, 0x000000, 0x242426, 0x202022, 0x000002, 0x0a0b0d, 0x2f3032, 0x434345, 0x38383a, 0x18181a, 0x030303, 0x010101, 0x010101, 0x010101, 0x050505, 0x050505, 0x050505, 0x000002, 0x000002, 0x917b52, 0xc29f67, 0xa78852, 0xa6834d, 0xa17e44, 0xa07a39, 0x9c7437, 0x976f31, 0x946b2b, 0x916924, 0x906521, 0x8d601c, 0x8c5d19, 0x885915, 0x845511, 0x865510, 0x80530f, 0x7a4f0a, 0x774c07, 0x774c08, 0x724607, 0x6e4505, 0x744807, 0x734706, 0x6e4505, 0x6b4306, 0x664204, 0x654105, 0x623d06, 0x5e3b05, 0x603a09, 0x603b07, 0x5f3b07, 0x593a04, 0x513505, 0x4e3105, 0x4f2e01, 0x533405, 0x503605, 0x4a2d01, 0x472b04, 0x452c04, 0x4b2e06, 0x533008, 0x562f08, 0x583108, 0x5f380d, 0x503910, 0x4e3610, 0x462f0d, 0x37260a, 0x32220b, 0x3f2a0d, 0x4c3408, 0x482f07, 0x382505, 0x392407, 0x4a2e07, 0x533304, 0x4b2e06, 0x4f3407, 0x573905, 0x553504, 0x593805, 0x613c05, 0x644006, 0x623d06, 0x623d06, 0x613c07, 0x613c07, 0x6a4406, 0x6d4404, 0x7c4d07, 0x714806, 0x714a09, 0x784d09, 0x7b4e0d, 0x83540e, 0x84550f, 0x845713, 0x875a17, 0x885b1a, 0x91621c, 0x916420, 0x8d6527, 0x936c2b, 0x9d7432, 0x9d7738, 0xa27c3d, 0xa58145, 0xa3824f, 0xa98a53, 0xc7a067, 0x8b7452, 0x000105, 0x131416, 0x0c0c0c, 0x000000, 0x010101, 0x000000, 0x000100, 0x1e1e1e, 0x2a2a2c, 0x131315, 0x0c0d0f, 0x27282a, 0x595a5e, 0x141318, 0x515153, 0x5d5d5d, 0x000000, 0x303030, 0x1c1c1c, 0x08090b, 0x424347, 0x48494d, 0x292a2c, 0x090909, 0x000000, 0x030301, 0x040404, 0x010101, 0x000000, 0x010101, 0x040404, 0x050505, 0x010103, 0x020204, 0x978056, 0xc09c62, 0xa88855, 0xa5824a, 0xa48044, 0xa07a3b, 0x9b7338, 0x987130, 0x976e2c, 0x946924, 0x916420, 0x8f601c, 0x8d5e1a, 0x8a5b15, 0x8a5b15, 0x855610, 0x83530b, 0x7f500a, 0x784d09, 0x724909, 0x754908, 0x784b0a, 0x764b07, 0x744807, 0x6e4507, 0x6a4205, 0x6b4308, 0x663f08, 0x643d06, 0x644006, 0x634006, 0x613e04, 0x5c3b06, 0x533408, 0x543507, 0x573905, 0x573708, 0x503405, 0x493008, 0x452e05, 0x503009, 0x583108, 0x5c3107, 0x5f350b, 0x603b0e, 0x613f11, 0x644415, 0x5c4513, 0x573f11, 0x563b10, 0x543810, 0x462f0d, 0x35240a, 0x3b260b, 0x483108, 0x533708, 0x462f05, 0x3d2607, 0x472b06, 0x563709, 0x533406, 0x553504, 0x5e3905, 0x5a3a07, 0x5d3a04, 0x633f03, 0x6a4207, 0x6b4308, 0x663f04, 0x653e03, 0x674307, 0x6f4608, 0x744706, 0x7c5009, 0x774c08, 0x774b0a, 0x7d4d0b, 0x82530d, 0x86580d, 0x885810, 0x8b5a15, 0x8d5e1a, 0x8f621e, 0x936622, 0x936824, 0x946b29, 0x997332, 0xa0783a, 0xa47c3e, 0xa88148, 0xa4844b, 0xab8755, 0xc6a369, 0x89734c, 0x000309, 0x08090b, 0x000000, 0x020100, 0x040406, 0x050507, 0x030504, 0x000000, 0x000000, 0x131315, 0x100f14, 0x111216, 0x262a2d, 0x000000, 0x3e3e3e, 0x5d5f5e, 0x000000, 0x444446, 0x373739, 0x39393b, 0x3a3a3c, 0x161618, 0x000000, 0x000000, 0x040404, 0x040404, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x050505, 0x000000, 0x070705, 0x9b845a, 0xbf9c64, 0xa98a54, 0xa78548, 0xa27e42, 0xa17b3d, 0x9c7534, 0x9b7433, 0x966e29, 0x936823, 0x926521, 0x91621e, 0x905f1a, 0x8e5e16, 0x89590f, 0x86560c, 0x84540c, 0x7f500c, 0x794c09, 0x7b4e0a, 0x7c5009, 0x794c08, 0x774a07, 0x724909, 0x6f4805, 0x6c4607, 0x694209, 0x6b440b, 0x6b4305, 0x6c4407, 0x663f08, 0x593805, 0x573905, 0x5d3c07, 0x5f3b07, 0x573706, 0x513505, 0x4d3205, 0x513408, 0x5a3509, 0x5c3307, 0x62350b, 0x683c0f, 0x684211, 0x6c4814, 0x6e4d18, 0x704d17, 0x604917, 0x644914, 0x674913, 0x5c4511, 0x5b4110, 0x56390f, 0x422b09, 0x3c240c, 0x462c09, 0x593a0c, 0x563806, 0x452c04, 0x472e06, 0x563806, 0x583805, 0x563508, 0x613c07, 0x5d3c07, 0x613c08, 0x664208, 0x6d4605, 0x6f4606, 0x6d4508, 0x6c4206, 0x6a4308, 0x724907, 0x7a4b07, 0x815109, 0x7e4f07, 0x7d500c, 0x82530b, 0x87570f, 0x8a5a10, 0x8e5e16, 0x91601b, 0x91621c, 0x936622, 0x966b27, 0x946b29, 0x997231, 0xa1793b, 0xa57d3f, 0xa68248, 0xa7874e, 0xaa8956, 0xc6a36b, 0x91784f, 0x010206, 0x09090b, 0x080806, 0x070705, 0x010101, 0x040406, 0x020202, 0x282828, 0x575958, 0x000201, 0x000100, 0x0d1112, 0x0f1314, 0x000002, 0x171717, 0x303030, 0x010103, 0x272729, 0x333333, 0x161616, 0x020202, 0x000000, 0x000000, 0x030303, 0x000000, 0x000000, 0x010101, 0x000000, 0x020202, 0x020202, 0x010101, 0x040404, 0x000000, 0x090907, 0xa2875c, 0xbd9a62, 0xaa8953, 0xa7844c, 0xa27f45, 0xa07a3c, 0x9f7638, 0x9b7232, 0x996e2a, 0x966925, 0x966721, 0x93641c, 0x916119, 0x8d5d13, 0x8a5a12, 0x885712, 0x83520d, 0x805006, 0x825409, 0x805109, 0x7b4c08, 0x7b4e0b, 0x784b07, 0x744807, 0x724607, 0x714508, 0x734708, 0x6f4606, 0x6b4507, 0x644006, 0x603d05, 0x613c07, 0x623f05, 0x604007, 0x593906, 0x523807, 0x523708, 0x5d370a, 0x60350a, 0x673908, 0x6a3e0d, 0x6c4410, 0x714d13, 0x775317, 0x775518, 0x765319, 0x74541b, 0x694e17, 0x6c4f15, 0x6d4f13, 0x6f5017, 0x6c4d16, 0x684b13, 0x604412, 0x53370f, 0x402b0c, 0x3f2a0b, 0x53360e, 0x623e0e, 0x503309, 0x4a3206, 0x553703, 0x5b3909, 0x5d3905, 0x654107, 0x654107, 0x644006, 0x6c4409, 0x744809, 0x764905, 0x734706, 0x6e4608, 0x71480a, 0x764906, 0x805008, 0x855509, 0x84560b, 0x82530b, 0x88560f, 0x8c5c10, 0x906016, 0x936319, 0x94651d, 0x966721, 0x9a6d29, 0x996d2c, 0x9a7131, 0xa0783a, 0xa57d3f, 0xa78347, 0xa98950, 0xaa8b55, 0xbc9c63, 0xaa8e5f, 0x131210, 0x14171c, 0x1f2022, 0x0b0b09, 0x060606, 0x000000, 0x010101, 0x32312f, 0xb2acac, 0x61605c, 0x1a1917, 0x010101, 0x000100, 0x060405, 0x000000, 0x000000, 0x040406, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x000000, 0x010101, 0x010101, 0x000000, 0x030303, 0x000000, 0x171611, 0xb39466, 0xb99660, 0xab8852, 0xa7844c, 0xa37f43, 0xa37b3d, 0x9f7638, 0x9c702f, 0x9b6e2b, 0x9a6b25, 0x976820, 0x96661a, 0x936317, 0x8f5f15, 0x8b5b13, 0x885712, 0x84540a, 0x88570a, 0x855408, 0x815107, 0x805008, 0x794d06, 0x774a07, 0x754a06, 0x734a08, 0x764a09, 0x724907, 0x6b4506, 0x674307, 0x674309, 0x6d460b, 0x69450b, 0x60410a, 0x593e09, 0x5c3b08, 0x663e0d, 0x693a0c, 0x6d3b0a, 0x6f400c, 0x724710, 0x7a5014, 0x7f5817, 0x7f5a16, 0x7e5819, 0x7b571b, 0x77571c, 0x76581c, 0x745419, 0x70561b, 0x71571a, 0x795718, 0x795717, 0x765716, 0x765414, 0x705013, 0x634511, 0x51350e, 0x462f0d, 0x4d340c, 0x61400b, 0x5e3f09, 0x4f3409, 0x563708, 0x5f4009, 0x623e0c, 0x674309, 0x6b4305, 0x6b4308, 0x6f4709, 0x764b07, 0x7a4d09, 0x7a4b05, 0x724605, 0x754908, 0x7c4f0b, 0x835309, 0x8a590c, 0x8a580f, 0x8a580f, 0x8c5c10, 0x916014, 0x95631a, 0x98681e, 0x9a6a22, 0x9e6f29, 0x9f722f, 0x9e7231, 0xa0783a, 0xa57d3f, 0xa98547, 0xad8a52, 0xae8f59, 0xb5945f, 0xc4a370, 0x29251c, 0x0a0e17, 0x2d2e33, 0x0e0e10, 0x0c0c0c, 0x060807, 0x020403, 0x0e0a09, 0x2f2725, 0x645454, 0x433535, 0x0a0404, 0x010101, 0x000000, 0x010101, 0x000000, 0x030102, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x000000, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x030303, 0x000000, 0x342e22, 0xc5a471, 0xaf915b, 0xaa8953, 0xa8854b, 0xa88043, 0xa47d3c, 0x9e7736, 0xa07330, 0xa0712d, 0x9e6e26, 0x9a6a20, 0x97671b, 0x956417, 0x905f13, 0x8d5b12, 0x8d5c0f, 0x8d5c10, 0x88570b, 0x87560a, 0x85530a, 0x805008, 0x7d4e08, 0x784c05, 0x7a4d09, 0x7d4e08, 0x774c08, 0x6f470a, 0x6c4608, 0x724b08, 0x724b0a, 0x6a460a, 0x5f420a, 0x61420b, 0x68430c, 0x70400f, 0x753d0c, 0x77420c, 0x794b0d, 0x825713, 0x855d17, 0x865d1b, 0x845d1c, 0x835d1e, 0x805d1b, 0x825f1d, 0x825f1f, 0x7d591b, 0x775d22, 0x7b5f20, 0x7a5d1b, 0x7b5e1a, 0x83611a, 0x87621b, 0x84621a, 0x856019, 0x825c15, 0x775317, 0x674613, 0x523513, 0x4a3210, 0x5e3e0f, 0x694410, 0x5d3f0b, 0x5b390c, 0x5f400a, 0x6a430a, 0x6e440a, 0x72490b, 0x70480a, 0x6f4807, 0x7d4e08, 0x82520a, 0x805008, 0x7c4f0c, 0x794c08, 0x83540c, 0x88570b, 0x905d0e, 0x8d5c0f, 0x8d5c10, 0x936216, 0x98671b, 0x99691d, 0x9d6d23, 0xa07028, 0xa2732d, 0xa17632, 0xa17a39, 0xa67e40, 0xab8547, 0xb08b54, 0xb0915b, 0xb39360, 0xcfae78, 0x3e3524, 0x010008, 0x323137, 0x1f1f21, 0x070707, 0x0c0e0d, 0x121212, 0x080808, 0x090806, 0x080904, 0x20201e, 0x292929, 0x191b1a, 0x0e0e10, 0x0a0a0a, 0x050706, 0x000100, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x020202, 0x010101, 0x010101, 0x010101, 0x050505, 0x000000, 0x4e4232, 0xcead77, 0xad8f59, 0xab8a54, 0xaa864c, 0xa98144, 0xa57c3c, 0xa27a35, 0xa37632, 0xa1722c, 0xa07026, 0x9d6d23, 0x9a691d, 0x986418, 0x956115, 0x956115, 0x935e0e, 0x905d0e, 0x8c5b0e, 0x87560a, 0x845209, 0x835309, 0x835309, 0x84540a, 0x815308, 0x7a4f0a, 0x734b06, 0x774f0a, 0x794e0a, 0x754c0e, 0x6a460a, 0x634507, 0x6a450e, 0x71440b, 0x7f440c, 0x83480e, 0x805010, 0x895c18, 0x8e641c, 0x91651c, 0x8c641c, 0x8c641e, 0x8a641d, 0x8b651e, 0x8a651e, 0x88631c, 0x84611d, 0x815f1f, 0x766225, 0x7e6320, 0x866520, 0x886720, 0x89691e, 0x8f6b1f, 0x916b20, 0x956e1f, 0x946a1e, 0x8a691a, 0x84621a, 0x7c5919, 0x624314, 0x4b3412, 0x543810, 0x70470f, 0x6a4711, 0x643f0b, 0x694209, 0x6c450a, 0x70480a, 0x784c0b, 0x794c0b, 0x794c08, 0x81520a, 0x88570b, 0x855408, 0x825208, 0x83530b, 0x88570b, 0x8f5c0d, 0x956213, 0x966216, 0x976317, 0x9c681c, 0x9d6c1f, 0xa17023, 0xa37226, 0xa5752d, 0xa67a33, 0xa47b39, 0xa88140, 0xac8648, 0xb18c55, 0xb3925d, 0xb59562, 0xd6b57f, 0x5d4f34, 0x000002, 0x343436, 0x242426, 0x0c0c0c, 0x070908, 0x111312, 0x151515, 0x212121, 0x2b292a, 0x262427, 0x1f2022, 0x262a2b, 0x37383c, 0x323335, 0x252628, 0x070506, 0x000000, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x050505, 0x000000, 0x685841, 0xd0af79, 0xaf9059, 0xae8a56, 0xaa864c, 0xa88045, 0xaa7e3f, 0xa97c38, 0xa87933, 0xa5752b, 0xa37226, 0xa06f23, 0x9e6a1f, 0x9c671b, 0x9b6616, 0x9a6515, 0x986111, 0x925d0d, 0x8d5a0b, 0x88570a, 0x88570a, 0x89580b, 0x88570b, 0x84520b, 0x7c510d, 0x7e510d, 0x83520f, 0x7f520f, 0x704d0b, 0x694a0a, 0x724a0d, 0x7e4a0e, 0x844a0b, 0x8d4b0f, 0x8c5713, 0x8f6318, 0x986a1c, 0x986a1d, 0x986c21, 0x996b1e, 0x946d1e, 0x956e21, 0x956b1f, 0x956b21, 0x916b20, 0x8b661f, 0x836121, 0x7f5f22, 0x806727, 0x85692a, 0x856824, 0x8d6b21, 0x927120, 0x967321, 0x9c7623, 0x9b7721, 0x9d7724, 0xa77923, 0xa77820, 0xa0701e, 0x9a661b, 0x825419, 0x5e3d14, 0x523813, 0x664417, 0x744e0d, 0x6f480f, 0x6e470c, 0x71490b, 0x76490e, 0x7f500a, 0x7e540c, 0x805109, 0x85530a, 0x8d5a09, 0x8d5a0b, 0x88570a, 0x89580b, 0x905c10, 0x976212, 0x9c6717, 0x9b6616, 0x9f6a1a, 0xa37021, 0xa37223, 0xa67528, 0xaa782f, 0xac7c34, 0xad803c, 0xac8341, 0xad8749, 0xb28e54, 0xb79660, 0xb99b67, 0xd5b680, 0x887451, 0x000100, 0x252628, 0x2c2b30, 0x17181a, 0x070908, 0x010101, 0x080808, 0x151314, 0x171719, 0x0f0f11, 0x1b1c1e, 0x414548, 0x45464a, 0x2a2b2f, 0x292a2c, 0x0a0809, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x8d7958, 0xcaab75, 0xb1905b, 0xb18c57, 0xaf864e, 0xac8246, 0xb08340, 0xaf7e39, 0xac7c34, 0xaa792d, 0xa87428, 0xa57223, 0xa46f21, 0xa46d1d, 0xa16a18, 0x9b6714, 0x9a6310, 0x945f0f, 0x915c0e, 0x905d0c, 0x905d0c, 0x8c590a, 0x87560a, 0x865509, 0x89580b, 0x87570f, 0x7d550f, 0x74520b, 0x7f5312, 0x8f4e14, 0x994810, 0xa64d11, 0xaf5c16, 0xb8661a, 0xb86d1c, 0xb26f1e, 0xa97522, 0x9f7521, 0xa27522, 0xa17725, 0xa07624, 0x9d7422, 0x987122, 0x946e25, 0x8f6a26, 0x8b6828, 0x8a6727, 0x896626, 0x886d2a, 0x8a6d2b, 0x90722a, 0x917428, 0x947427, 0x9d7a29, 0xa17f26, 0xa98227, 0xbf8728, 0xc48126, 0xcd8129, 0xd18b2b, 0xce8c2b, 0xc78223, 0xb77622, 0x8d591d, 0x603e18, 0x5f3b17, 0x764d17, 0x7d5112, 0x774b0e, 0x774e0c, 0x79510c, 0x83540e, 0x87570f, 0x88580c, 0x8b5a0d, 0x925e0b, 0x945f0f, 0x915d11, 0x925f10, 0x976214, 0x9d6915, 0xa46d1b, 0xa36f1c, 0xa67322, 0xa97625, 0xad792d, 0xae7d31, 0xb08036, 0xb4833e, 0xb18544, 0xb1894b, 0xb28f55, 0xb6955f, 0xbea06c, 0xceaf79, 0xaf966e, 0x0a0809, 0x141319, 0x2c2f36, 0x26272b, 0x191919, 0x121210, 0x0b0b0b, 0x020605, 0x0f1012, 0x343436, 0x555557, 0x5d5d5f, 0x3b3b3d, 0x242527, 0x2b2c2e, 0x080808, 0x000000, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x020202, 0x000000, 0x0c0c0c, 0xb0956a, 0xc0a26e, 0xb2915e, 0xb48c58, 0xb5884d, 0xb58948, 0xb5843f, 0xb3823f, 0xb17f36, 0xaf7b30, 0xac7729, 0xaa7525, 0xaa7321, 0xa6701a, 0xa36c19, 0x9d6916, 0x9b6414, 0x9b6412, 0x99620f, 0x965f0d, 0x915c0e, 0x8f5b0f, 0x8d5c0f, 0x8c5d0d, 0x8a5a10, 0x80560e, 0x845713, 0x955515, 0xa45010, 0xba5f19, 0xbf711c, 0xcb8928, 0xdb9e33, 0xdba136, 0xd69833, 0xcf8a2b, 0xc77d26, 0xb67d26, 0xa98028, 0xaa7d28, 0xa67c28, 0x9e7728, 0x98742a, 0x977329, 0x977128, 0x976f27, 0x936e2a, 0x8e6b2b, 0x927330, 0x947630, 0x96742a, 0x987b2f, 0xa07b2a, 0x9a802b, 0xa8842c, 0xce872f, 0xd08a2a, 0xdb9b31, 0xebb134, 0xf0bc34, 0xf1bd35, 0xeeba32, 0xe9b02d, 0xe0a42a, 0xc28922, 0x90641d, 0x68451f, 0x6e4819, 0x845915, 0x80530f, 0x805312, 0x835410, 0x865510, 0x905b0d, 0x915b11, 0x915d11, 0x9b6310, 0x9c6513, 0x9a6612, 0x9d6616, 0xa06c18, 0xa96f1d, 0xad7321, 0xab7723, 0xae7a27, 0xb27d2f, 0xb38235, 0xb58539, 0xb98740, 0xb68c44, 0xb68d4d, 0xb89253, 0xba9662, 0xc1a16e, 0xcaab7c, 0xd1b283, 0x2c281f, 0x010103, 0x18191d, 0x1f2227, 0x191e24, 0x1e2629, 0x222625, 0x2a2b2f, 0x3d3d3f, 0x5a5a5c, 0x555356, 0x36373b, 0x24292d, 0x28292d, 0x2f2f2d, 0x070908, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000201, 0x010101, 0x020100, 0x000201, 0x000002, 0x030102, 0x000000, 0x241f1b, 0xc0a173, 0xbf9e69, 0xb7935f, 0xb9905a, 0xbd8f53, 0xbe8c4d, 0xba8a42, 0xb7873b, 0xb68237, 0xb18031, 0xb47d2b, 0xb27a27, 0xae7724, 0xab7320, 0xa76d1b, 0xa16a17, 0xa56815, 0xa06917, 0x9c6513, 0x9a6110, 0x966310, 0x966314, 0x935e10, 0x8c5e10, 0x855e11, 0x955c19, 0xa95614, 0xbb6417, 0xc87f20, 0xdb9b2d, 0xe7ac38, 0xebb33c, 0xecb33f, 0xebb741, 0xf3bb42, 0xeebb46, 0xe6ac3e, 0xd08b2c, 0xb37f2c, 0xa9842c, 0xa9802e, 0xa87f2d, 0xa57c2c, 0xa27b2c, 0x9e792b, 0x99742d, 0x926f2d, 0x8e6c2d, 0x917836, 0x9a7c36, 0x9e7d36, 0xa37e2e, 0xa3852d, 0xab8731, 0xc78934, 0xd18f31, 0xe5b537, 0xf9ca40, 0xfbc73d, 0xf9c33d, 0xfcc439, 0xfbc434, 0xfcc537, 0xf5bd32, 0xedb730, 0xe4ae2a, 0xbf8b25, 0x795420, 0x69471a, 0x875a19, 0x895813, 0x875812, 0x8a5b15, 0x8c5a11, 0x946112, 0x976310, 0x9c6312, 0xa06815, 0xa46e18, 0xa56d1a, 0xa66f1c, 0xaa7320, 0xb07825, 0xb37c29, 0xb27e2a, 0xb8812e, 0xbd8636, 0xbd893d, 0xbe8d41, 0xbf8e49, 0xbe9251, 0xbf9658, 0xbd9a62, 0xc0a26c, 0xc7ab79, 0xe3c28c, 0x524735, 0x010000, 0x000100, 0x0d0908, 0x2d2324, 0x1a1e21, 0x0b1517, 0x272d39, 0x393d3c, 0x373739, 0x282c2f, 0x222627, 0x24252a, 0x2c2c2e, 0x353439, 0x07080a, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x030102, 0x010101, 0x000002, 0x040404, 0x000000, 0x2a231d, 0xc5a375, 0xc29e6e, 0xbf9763, 0xc1985a, 0xc39854, 0xc2914c, 0xbf8f45, 0xbf8b40, 0xbc8739, 0xb98532, 0xb5812e, 0xb37f2c, 0xb27928, 0xae7621, 0xab731c, 0xa9711e, 0xa56d16, 0x9f6b17, 0x9e6a17, 0xa16912, 0x9d6616, 0x976415, 0x916117, 0x906215, 0xa26016, 0xb8611a, 0xcd7c21, 0xdf9e2a, 0xecb133, 0xedb234, 0xedb135, 0xf1b33c, 0xf2b83d, 0xf1b942, 0xf1ba43, 0xf2b945, 0xf2c34d, 0xeeba4a, 0xcf8e30, 0xb2832b, 0xb18931, 0xad852e, 0xa88231, 0xa37e30, 0x9c7a30, 0x997632, 0x987734, 0x957334, 0x9f7e3b, 0x9b7d35, 0xa08536, 0xa58634, 0xa88a34, 0xc48c37, 0xd79132, 0xebb93c, 0xf7cc41, 0xf2c43b, 0xf8c73e, 0xfdc83c, 0xffc73c, 0xffc83d, 0xfeca39, 0xfeca38, 0xfdc435, 0xf9bb32, 0xf4b931, 0xdaa22b, 0x946924, 0x754f22, 0x85581d, 0x916014, 0x926017, 0x916115, 0x966216, 0x9d6614, 0xa06916, 0xa46e18, 0xa87117, 0xac751b, 0xae751e, 0xac7822, 0xb27c26, 0xb8802b, 0xbb832e, 0xbd8633, 0xbf8b38, 0xbf8f3b, 0xc59146, 0xc4964b, 0xc19953, 0xc59c5e, 0xc69d65, 0xc4a36e, 0xcbac7d, 0xe9c990, 0x625745, 0x000002, 0x010101, 0x19100b, 0x815b50, 0x967468, 0x634e49, 0x231e22, 0x161e29, 0x242d34, 0x292d30, 0x272b2e, 0x27252a, 0x2d2e32, 0x444645, 0x080705, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020001, 0x040203, 0x030102, 0x030104, 0x010101, 0x030406, 0x000000, 0x332a21, 0xcaa976, 0xc8a06f, 0xc89d66, 0xca9d5c, 0xc99a56, 0xcb9650, 0xc49347, 0xc88e44, 0xc38c3a, 0xc2893a, 0xbe8534, 0xb9812c, 0xb67d26, 0xb37b24, 0xae7820, 0xac741d, 0xaa711a, 0xa9711c, 0xa76f1a, 0xa16d17, 0x9e6919, 0x9a691c, 0x9b6618, 0xaf651e, 0xc76d1f, 0xdb9325, 0xefb02f, 0xf3b230, 0xf6b233, 0xf7b636, 0xf9ba37, 0xfbbc3b, 0xf9be3e, 0xf9bf42, 0xf7bf48, 0xf5be47, 0xeebd46, 0xf4c34c, 0xf2b948, 0xc18e33, 0xac8736, 0xac8834, 0xa98434, 0xa78232, 0xa48034, 0x9e7b37, 0x9d7b34, 0x9a7936, 0x9b823f, 0xa2843c, 0xa98839, 0xab8c3a, 0xb68e39, 0xd0933a, 0xe5b23c, 0xf8ca41, 0xf7c33c, 0xf9c740, 0xfbca41, 0xfdcc3f, 0xfdcc3f, 0xfccb3e, 0xfece3e, 0xfece3c, 0xffd03d, 0xffcc3b, 0xfec337, 0xffc335, 0xf0b12e, 0xb17f2a, 0x885e24, 0x885f21, 0x905f1a, 0x9a6718, 0x9b6618, 0x9d681a, 0xa26e18, 0xa87019, 0xad741b, 0xaf791f, 0xb57c22, 0xb77e25, 0xb88029, 0xbb842a, 0xc18831, 0xc28c36, 0xc4903c, 0xcb9442, 0xcf9649, 0xd19e4f, 0xd09f53, 0xcda160, 0xc8a468, 0xc8a772, 0xd0b183, 0xf6d39d, 0x605541, 0x010000, 0x010000, 0x2d1f1c, 0xb7846f, 0xd99f89, 0xe9b4a2, 0xb49382, 0x4c3932, 0x0c0a0d, 0x0c151c, 0x252c32, 0x22252a, 0x34353a, 0x52534e, 0x030303, 0x000000, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x040203, 0x040203, 0x030303, 0x040203, 0x030104, 0x000000, 0x020305, 0x010101, 0x352b1f, 0xd7ac77, 0xd9a66d, 0xd8a667, 0xd8a361, 0xd39e58, 0xd39b50, 0xcb9849, 0xcc9543, 0xca9340, 0xc78f3a, 0xc38a33, 0xbf8531, 0xbb832e, 0xb77f28, 0xb57c23, 0xb37a23, 0xb07720, 0xac741d, 0xab731e, 0xa97021, 0xa76e1d, 0xa86b1b, 0xbe7320, 0xd37b24, 0xe7992d, 0xf9b633, 0xfab62f, 0xfbb835, 0xfebe3a, 0xffbe3c, 0xfec23e, 0xfdc441, 0xfec343, 0xfdc345, 0xf9c146, 0xf5c147, 0xf5c04e, 0xf2bd4b, 0xf6c952, 0xd8aa48, 0xaf8839, 0xb48e3b, 0xb08a39, 0xae8738, 0xaa8439, 0xa8833d, 0xa17e3c, 0x9c7a3a, 0x9d8643, 0xa08542, 0xa78c3f, 0xa98e3d, 0xc6923f, 0xdea33d, 0xf4c746, 0xf4c843, 0xf8c840, 0xfbcc42, 0xfccd3f, 0xfdce42, 0xffd044, 0xffd241, 0xfdd33f, 0xfdd341, 0xfdd33f, 0xffd33f, 0xffd241, 0xfece3e, 0xffcb39, 0xf9be36, 0xc48e2c, 0xa3742c, 0x996a22, 0x95651b, 0xa06d1e, 0xa46f1f, 0xa8701d, 0xac741f, 0xb17924, 0xb47b21, 0xb98026, 0xbf842a, 0xbe872c, 0xc08a30, 0xca8f35, 0xd49339, 0xd6963f, 0xd99749, 0xdf9d49, 0xe3a252, 0xe4a659, 0xe0a762, 0xd7ab6c, 0xd3aa76, 0xcead78, 0xfddfa1, 0x5a4f39, 0x000100, 0x000004, 0x46312c, 0xda9f81, 0xcb937a, 0xdeaf9d, 0xeac0b2, 0x9a6c5f, 0x87665f, 0x655b59, 0x0d090a, 0x0f131e, 0x55545a, 0x6f6f71, 0x020305, 0x000000, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x040203, 0x040203, 0x030102, 0x020202, 0x040203, 0x030102, 0x010000, 0x020202, 0x000000, 0x33291f, 0xecb177, 0xedb071, 0xe7ae69, 0xe4a862, 0xe3a55a, 0xe1a454, 0xdda050, 0xd59848, 0xcc9545, 0xc8923c, 0xca9138, 0xc88c34, 0xc08730, 0xbf832b, 0xbf832b, 0xb87f25, 0xb37d27, 0xb07a22, 0xb07624, 0xb57422, 0xb77922, 0xcb8128, 0xe3882b, 0xeda02c, 0xfeba33, 0xffbb32, 0xfebe38, 0xffc139, 0xffc43a, 0xfdc941, 0xfcc63f, 0xffc442, 0xffc648, 0xfdc647, 0xfec749, 0xfac44a, 0xf7c451, 0xf5c352, 0xf6c755, 0xedbe54, 0xc19647, 0xb78e3f, 0xb38d3c, 0xb18c3e, 0xac8740, 0xa8863f, 0xa58343, 0xa18242, 0xa58c4a, 0xa98e4b, 0xa98d44, 0xac9144, 0xc89345, 0xe7b544, 0xfacb49, 0xf8c744, 0xfbc944, 0xfdcb46, 0xfecf45, 0xffd042, 0xffd344, 0xfdd343, 0xfdd542, 0xffd843, 0xfed643, 0xfed643, 0xfed53f, 0xfed444, 0xffd447, 0xffd541, 0xfcc63f, 0xd29b37, 0xc08c36, 0xab7829, 0x9e6a1f, 0xa77226, 0xae7724, 0xaf7923, 0xb27a25, 0xbc8125, 0xc08529, 0xc1882f, 0xca8d34, 0xd39035, 0xd99439, 0xde973f, 0xe59e42, 0xeaa945, 0xf1af4e, 0xf7b459, 0xf8b95c, 0xf5bc63, 0xf2b96c, 0xe9b579, 0xe3b47c, 0xe8c490, 0x302c21, 0x000000, 0x000000, 0x53423b, 0xeeb69d, 0xc6927a, 0xd2a590, 0xca998a, 0xa47a6c, 0xe0b6a6, 0xe5bead, 0xa3887f, 0x514642, 0x252b29, 0x293335, 0x000000, 0x010101, 0x030303, 0x030303, 0x020202, 0x020202, 0x040203, 0x040203, 0x040203, 0x040203, 0x020202, 0x030102, 0x010101, 0x040301, 0x020202, 0x000000, 0x2e251e, 0xfbbd72, 0xfcbf6e, 0xfabd6d, 0xf8ba67, 0xf8b65f, 0xf6b358, 0xf7b152, 0xefaa4f, 0xe19f48, 0xd69843, 0xcc8f3c, 0xcb923b, 0xcb9238, 0xc2892f, 0xbf862d, 0xbd842b, 0xbc832c, 0xbd7f2a, 0xc07e2a, 0xc58629, 0xd28e2b, 0xea9431, 0xf59f30, 0xffbc35, 0xffc038, 0xfec337, 0xfcc439, 0xfec63f, 0xffc841, 0xfdc740, 0xfdc941, 0xfec841, 0xffc847, 0xfcc949, 0xfec949, 0xffc94f, 0xfbc852, 0xf8c550, 0xf7c353, 0xf4c455, 0xc8a152, 0xb8914c, 0xb79242, 0xb38e40, 0xb18c46, 0xb08b44, 0xad8c47, 0xa8884b, 0xa89052, 0xac914a, 0xb2944e, 0xb9984b, 0xd39b48, 0xeebe4f, 0xf7cb48, 0xf7ca49, 0xffca4c, 0xfecc45, 0xffd046, 0xffd147, 0xfed442, 0xffd742, 0xffd742, 0xfed640, 0xfdda42, 0xffd742, 0xfed442, 0xffd241, 0xffd245, 0xfdd343, 0xfed94a, 0xfdcb44, 0xe2af44, 0xe0aa48, 0xbc842f, 0xaa7525, 0xaf7c29, 0xb67e27, 0xba8127, 0xbb852b, 0xc48830, 0xce8f32, 0xda9133, 0xe19236, 0xe69d3e, 0xefac44, 0xf9b64b, 0xfdb94e, 0xfcbe51, 0xfebe5c, 0xffc363, 0xfbc668, 0xfec872, 0xfac575, 0xfcd683, 0xdcb278, 0x08090d, 0x000002, 0x050908, 0x29211e, 0xe6b7a3, 0xdfa081, 0xc0886f, 0xb28474, 0xba9080, 0xd2a995, 0xc39d90, 0xf9ded5, 0xeecabc, 0x927066, 0x392019, 0x19110e, 0x010101, 0x020202, 0x020202, 0x030102, 0x030102, 0x030102, 0x030102, 0x040203, 0x040203, 0x020003, 0x030102, 0x030303, 0x030303, 0x020200, 0x000100, 0x100c09, 0xf1b96e, 0xffd073, 0xffc16c, 0xfec26c, 0xffc063, 0xffbb5c, 0xfeb952, 0xfbb553, 0xfeb04b, 0xf1a943, 0xe2a042, 0xd2943f, 0xce9a44, 0xd39d43, 0xc68831, 0xc78632, 0xca892f, 0xd08d34, 0xd39130, 0xd89834, 0xeb9c33, 0xf8a233, 0xfebe3a, 0xffc438, 0xfec43c, 0xfcc73d, 0xfec93f, 0xfec841, 0xffca40, 0xfeca40, 0xfacf45, 0xfdcd45, 0xfdcd47, 0xfecb4b, 0xfdca4b, 0xfcc850, 0xfec752, 0xfcc551, 0xf6c455, 0xf3c458, 0xd6b45d, 0xcda95d, 0xc29d4f, 0xb99348, 0xbb9451, 0xb6914d, 0xb18f50, 0xae8d57, 0xac9456, 0xb39454, 0xb29752, 0xbc9a53, 0xdfa34d, 0xf2c253, 0xf6ca4d, 0xfbca51, 0xfcd04d, 0xfed24d, 0xfdd248, 0xfdd34b, 0xfed44c, 0xfcd647, 0xfcd741, 0xfcd645, 0xfcd740, 0xfcd643, 0xfed545, 0xfed444, 0xfcd347, 0xfcd049, 0xffd148, 0xffd749, 0xf6cb4b, 0xf2c659, 0xeeb94f, 0xcd912f, 0xbd8331, 0xba822f, 0xbf862f, 0xc28c32, 0xce8e34, 0xda9039, 0xe3983b, 0xeba83f, 0xf8b542, 0xffb846, 0xffb84c, 0xfebb52, 0xfdbc58, 0xffbf5f, 0xfbc364, 0xffc66d, 0xfcca75, 0xfec673, 0xfef495, 0x9b7e54, 0x010000, 0x040507, 0x171b1a, 0x000002, 0x7f6558, 0xffcdb0, 0xc48b70, 0xa87b66, 0xad8677, 0xba8a73, 0x876961, 0xa57d7b, 0x86635f, 0x6a4646, 0x58332b, 0x291a15, 0x010101, 0x010101, 0x010101, 0x030102, 0x030102, 0x030102, 0x030102, 0x040203, 0x060203, 0x040205, 0x030102, 0x010302, 0x020202, 0x010000, 0x000100, 0x000000, 0xc09759, 0xfee07e, 0xfdc46d, 0xfdc36f, 0xffbf65, 0xffbb60, 0xfeba57, 0xfdb757, 0xfdb350, 0xfbb44a, 0xffb248, 0xf0a643, 0xd59c42, 0xe1a954, 0xe29e49, 0xd08f33, 0xda993b, 0xde9d39, 0xdca236, 0xeba43a, 0xf4a53e, 0xf9bc3d, 0xffca3c, 0xffc53d, 0xffc83a, 0xfec841, 0xfccb40, 0xfdce42, 0xfcce44, 0xfed144, 0xffce45, 0xffcf49, 0xfdcf48, 0xfecb4b, 0xfcca4d, 0xfdcb52, 0xfbc853, 0xfbc956, 0xf7c759, 0xf3c661, 0xf1c86c, 0xf1c974, 0xd0a95e, 0xbc9550, 0xbc9655, 0xb99557, 0xb3935a, 0xb0915b, 0xb1975c, 0xb2985d, 0xb39a57, 0xbe9b57, 0xdea556, 0xf0c554, 0xf8ca52, 0xfeca54, 0xffcf53, 0xffd14f, 0xfed351, 0xfcd64d, 0xfed94c, 0xfbda4d, 0xfdd84b, 0xffd646, 0xfdd448, 0xfed346, 0xffd744, 0xfdd542, 0xfdd446, 0xfcd248, 0xfdd349, 0xfdd248, 0xfdcf48, 0xf8cd5c, 0xffd76b, 0xf1c258, 0xdea440, 0xd09a3a, 0xc69036, 0xcf8f38, 0xda943c, 0xe59d39, 0xf8af40, 0xfeb846, 0xffb548, 0xfeb74b, 0xfcbc50, 0xfcbd54, 0xffc15e, 0xffc564, 0xfcc568, 0xfec870, 0xfdc674, 0xffdf80, 0xfeda7c, 0x1a1914, 0x010101, 0x08080a, 0x13120e, 0x13171a, 0x040203, 0xc49a82, 0xffc4a2, 0xb07d68, 0x8b6155, 0x906457, 0xb99b91, 0xcaada5, 0xc19a95, 0xad7874, 0x653f3e, 0x402b2a, 0x0b0203, 0x020001, 0x010101, 0x040203, 0x040203, 0x040203, 0x040203, 0x030303, 0x040203, 0x040203, 0x040203, 0x030303, 0x000000, 0x010101, 0x030303, 0x000000, 0x6c5938, 0xffed84, 0xffc46c, 0xfdc56e, 0xfec367, 0xfec168, 0xfebc5e, 0xfeb95a, 0xffb755, 0xfeb54e, 0xfcb14c, 0xfcb549, 0xf9aa45, 0xeaa74c, 0xfab95d, 0xeaa847, 0xd9a23d, 0xdea740, 0xe1ab3f, 0xefab3e, 0xf8b540, 0xffcb43, 0xfdc83c, 0xffc942, 0xffcb43, 0xfdce44, 0xfecf45, 0xffd248, 0xfed046, 0xfdd248, 0xfed047, 0xfdcf46, 0xfecd4c, 0xffcc4f, 0xfecc53, 0xfdcc55, 0xfecb58, 0xffcb5b, 0xfbca63, 0xf7c773, 0xf8ca7f, 0xfccc82, 0xd8ad69, 0xbc9655, 0xbe9a5c, 0xbe9a5e, 0xbb975d, 0xb69761, 0xb59c64, 0xba9c60, 0xbc9f5d, 0xc19e5c, 0xdfac5b, 0xf2ca5b, 0xf7cc5c, 0xfbcc5a, 0xfdcf57, 0xfed257, 0xfed353, 0xfcd64f, 0xfed652, 0xffd950, 0xfddd4c, 0xffda4b, 0xfdd849, 0xfbd449, 0xffd34a, 0xffd244, 0xfdd341, 0xfdd247, 0xffd148, 0xfcd248, 0xfed24b, 0xfdd156, 0xfcd16b, 0xffd670, 0xfcd266, 0xedb954, 0xe0a140, 0xe29b3f, 0xeda13f, 0xfbb546, 0xfbb845, 0xfdb748, 0xffb94f, 0xfcbd53, 0xfebd57, 0xffc25b, 0xffc361, 0xfbc666, 0xfec86e, 0xfcc872, 0xffd076, 0xfef78c, 0x645430, 0x000002, 0x090a0c, 0x050608, 0x0a0809, 0x1e231f, 0x010609, 0x1c1211, 0xe7af94, 0xf6b693, 0x956551, 0x845f57, 0xd5b7af, 0xe8c5af, 0xa57767, 0x8e524a, 0x794c49, 0x482c2b, 0x0a0404, 0x000000, 0x020202, 0x030303, 0x040203, 0x040203, 0x050102, 0x030301, 0x040203, 0x030102, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x010101, 0x0b0c07, 0xf1c471, 0xfddd78, 0xfbc46a, 0xfec76d, 0xfcc36c, 0xffbd66, 0xfbbf5d, 0xfdbe57, 0xfcb857, 0xffb755, 0xfbb34f, 0xffb64b, 0xf8b544, 0xfaba56, 0xfdc862, 0xe9b64d, 0xdcad43, 0xecad46, 0xf6b342, 0xfdc846, 0xfcca43, 0xffcb44, 0xfdce44, 0xfece46, 0xffd046, 0xfdd247, 0xfed348, 0xffd249, 0xfdd14c, 0xfcd04d, 0xffcf4f, 0xfdd14e, 0xffcf53, 0xfecd54, 0xfdce58, 0xfbcc5a, 0xffcc5f, 0xfcca69, 0xf7ca77, 0xf7c880, 0xf8cc85, 0xd5ae6b, 0xc29b5a, 0xc49e5f, 0xbd9d62, 0xbf9c64, 0xbe9a68, 0xd1b77a, 0xccaf75, 0xc4a668, 0xc1a262, 0xdcae61, 0xf4c961, 0xf7ce5c, 0xfbcd5d, 0xffd05a, 0xfed15a, 0xfbd55a, 0xfed65a, 0xffd754, 0xfeda52, 0xffdb53, 0xfed851, 0xfdd74e, 0xfed84f, 0xfcd64d, 0xfed549, 0xfdd248, 0xfed24b, 0xfdd248, 0xffd346, 0xffd245, 0xfcd14e, 0xfcd063, 0xfed26f, 0xf9d46a, 0xebc058, 0xeeb450, 0xf6b750, 0xffbd4c, 0xfeb648, 0xffb74e, 0xfbbb51, 0xffbc53, 0xffbe58, 0xfdc25e, 0xfdc360, 0xfcc767, 0xfec96d, 0xfec872, 0xfecb70, 0xfef888, 0x967b44, 0x000103, 0x0c0d0f, 0x111214, 0x080806, 0x080a07, 0x1b1b1b, 0x1c1c1e, 0x000002, 0x291f1d, 0xecb193, 0xf1b495, 0xa87f6d, 0xb9897b, 0xc6927d, 0x875749, 0x4a2e23, 0x090400, 0x000100, 0x000002, 0x000103, 0x030305, 0x020001, 0x050304, 0x030303, 0x040205, 0x020202, 0x030102, 0x020001, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x000004, 0x53452a, 0xfff084, 0xffcc70, 0xfcc36c, 0xfdc56e, 0xfdc46a, 0xffbf63, 0xfebd5f, 0xfcbb5d, 0xffb957, 0xfebb53, 0xfbbe53, 0xffbd4c, 0xfcbc4e, 0xffcb65, 0xefbf5b, 0xdead46, 0xf1b248, 0xfbc144, 0xffd147, 0xfecd44, 0xfece48, 0xfed047, 0xffcf47, 0xffd048, 0xfed24b, 0xfdd14c, 0xffd14f, 0xfed150, 0xfdd252, 0xffd255, 0xfed056, 0xfecf5b, 0xfdce5c, 0xfccf5c, 0xfdcd5f, 0xfdcc63, 0xfccb6e, 0xfbca7d, 0xfac984, 0xf6c781, 0xd1aa67, 0xc6a05f, 0xc9a364, 0xc5a167, 0xc3a06a, 0xbd9f6b, 0x7b6b49, 0xa99469, 0xc9b379, 0xe4c17f, 0xf9c879, 0xffd86f, 0xfcd065, 0xfbcc62, 0xfed060, 0xffd161, 0xfdd25f, 0xfdd55b, 0xffd75b, 0xffd95a, 0xfcdc55, 0xfddb55, 0xfcda55, 0xffd753, 0xfed650, 0xfdd752, 0xfdd54f, 0xfed44c, 0xffd34c, 0xffd14a, 0xfdd14a, 0xfdd14a, 0xfdd14c, 0xfed561, 0xe9c25b, 0xe5b851, 0xf4c156, 0xfecf5b, 0xffcc56, 0xffc056, 0xfcbb53, 0xfbbc53, 0xffbf5b, 0xffc15c, 0xfcc560, 0xfdc566, 0xffc86b, 0xfdc56e, 0xffcd74, 0xfff788, 0xa38b4f, 0x000002, 0x0d0c14, 0x1f1e1c, 0x111514, 0x0c0807, 0x030303, 0x181617, 0x242422, 0x13171a, 0x000000, 0x31241e, 0xebb294, 0xefb7a0, 0xc7a091, 0xc8a295, 0xaa897a, 0xa9887f, 0x6f5852, 0x251717, 0x120807, 0x010000, 0x020204, 0x040203, 0x030102, 0x030303, 0x040203, 0x060105, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020400, 0x000004, 0x987a48, 0xfff589, 0xffce72, 0xffc36d, 0xfcc66e, 0xfbc56b, 0xfcbf64, 0xfbbf5d, 0xfebf5e, 0xfdbf58, 0xfec059, 0xffc157, 0xfcc34f, 0xffc756, 0xebb956, 0xe9b349, 0xf6c24a, 0xfecd4a, 0xfece48, 0xffcf49, 0xffcf49, 0xffd04e, 0xffd04c, 0xffd14f, 0xffd251, 0xfed351, 0xfdd454, 0xfcd556, 0xfdd559, 0xffd25b, 0xffd05e, 0xfcce5e, 0xfdcf60, 0xfccc5d, 0xffcc5f, 0xfdca61, 0xfbc968, 0xf9c879, 0xfccc8a, 0xeec17d, 0xcba564, 0xcaa66a, 0xd2ab72, 0xd5b177, 0xdeba7e, 0xdebd87, 0x000000, 0x070604, 0x2d271b, 0x595236, 0x987c4c, 0xe4be6b, 0xffe779, 0xfff27f, 0xffec7b, 0xffe36d, 0xffd666, 0xffd562, 0xffd660, 0xffd75e, 0xfdda5c, 0xffd75e, 0xffd95d, 0xffda58, 0xfdd854, 0xfdd653, 0xfed853, 0xfdd750, 0xfcd450, 0xfbd252, 0xfed353, 0xffd350, 0xfed24b, 0xfbd350, 0xf0c650, 0xf6c755, 0xffce58, 0xffd05c, 0xfacf5e, 0xfdcd61, 0xfdc75d, 0xffc65f, 0xfcc05e, 0xffc361, 0xfcc664, 0xfec86e, 0xfdc56e, 0xfde07a, 0xfff086, 0x927d46, 0x010000, 0x090e11, 0x232122, 0x171c18, 0x191a1c, 0x151611, 0x050304, 0x0d0e12, 0x242321, 0x1e2221, 0x060709, 0x000002, 0x2c211d, 0xd6a690, 0xfccaaf, 0xe4c6bb, 0xe9d1cd, 0xe6cdc6, 0xc4a299, 0x89675b, 0x653f36, 0x2d1c15, 0x050402, 0x000002, 0x030104, 0x030303, 0x030303, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x040203, 0x010101, 0x000000, 0x947c4c, 0xffef85, 0xfddc7b, 0xfdc36f, 0xffc370, 0xfec470, 0xfcc56a, 0xfcc465, 0xfbc460, 0xfcc55e, 0xfdc459, 0xfec456, 0xffc853, 0xf7c353, 0xfac751, 0xfed152, 0xffd052, 0xffcf53, 0xffd052, 0xffd050, 0xfdd252, 0xffd153, 0xffd356, 0xfcd357, 0xffd35a, 0xffd25b, 0xffd25d, 0xfed15e, 0xfcd15e, 0xfdce62, 0xfece5f, 0xfccb64, 0xffcb65, 0xffc766, 0xffcb69, 0xfed36a, 0xfed97e, 0xffe294, 0xfdd689, 0xeac27d, 0xe0bc7e, 0xccae78, 0xb29a6e, 0x94805d, 0x776c50, 0x010300, 0x010000, 0x000002, 0x000103, 0x000000, 0x11100b, 0x4a3f2b, 0x806e3e, 0xb79b52, 0xe8c766, 0xffea77, 0xfcfb7c, 0xfdf876, 0xffe46c, 0xffd863, 0xfdda62, 0xffd95c, 0xfed85d, 0xffda5f, 0xffd75b, 0xfed758, 0xfed758, 0xfed758, 0xfdd657, 0xfed557, 0xfcd353, 0xfed557, 0xfdd154, 0xffd356, 0xfed557, 0xfed559, 0xfecf5b, 0xffcd60, 0xffcb65, 0xfacf67, 0xffcb68, 0xfdc86a, 0xfcc66c, 0xfdc66c, 0xfdce72, 0xfef083, 0xedc56d, 0x56482b, 0x000100, 0x121117, 0x1f2324, 0x1b1d1c, 0x1d1d1f, 0x202221, 0x1f211e, 0x0a0c0b, 0x090907, 0x181d20, 0x272928, 0x151314, 0x030000, 0x000100, 0x1f1715, 0xaa7c6c, 0xd2a794, 0xdab9b2, 0xdab9b2, 0xb28c7f, 0x845a4e, 0x704840, 0x3a2721, 0x050402, 0x000002, 0x030305, 0x020202, 0x010302, 0x000201, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020204, 0x050505, 0x020001, 0x000000, 0x655232, 0xeecf72, 0xfef087, 0xffcc74, 0xfcc56b, 0xfec671, 0xfdc669, 0xfdc765, 0xfbc660, 0xfdca5f, 0xffc95d, 0xfbcb5c, 0xfecf59, 0xffd258, 0xfdcf57, 0xfecd56, 0xfdcf55, 0xfdd158, 0xffd25a, 0xfcd259, 0xffd25b, 0xffd35c, 0xfed15c, 0xffd25f, 0xffd161, 0xfdce62, 0xfdcd61, 0xffcd62, 0xffd167, 0xfeda6c, 0xffe57a, 0xffe97a, 0xffe77d, 0xffd87b, 0xf0c672, 0xc9a96c, 0x9c845e, 0x7f6b4a, 0x5c4d38, 0x42382c, 0x23201b, 0x070b0a, 0x000000, 0x010000, 0x030102, 0x020202, 0x060203, 0x020202, 0x030303, 0x000000, 0x000100, 0x010000, 0x000000, 0x1b1c16, 0x504529, 0x82733c, 0xb89f4b, 0xefd566, 0xfff97c, 0xfefe7c, 0xffec6f, 0xfddf65, 0xfcd762, 0xfed964, 0xffd660, 0xffd55d, 0xffd75e, 0xffd55d, 0xfad65b, 0xffd65d, 0xfed45b, 0xfed65d, 0xfdd55c, 0xfdd45e, 0xfed561, 0xfcd55c, 0xfdd261, 0xfdce66, 0xfecc6b, 0xfccb6e, 0xfdca6f, 0xfdd170, 0xfdeb7d, 0xffe67f, 0xa38950, 0x130e0a, 0x010000, 0x171b1c, 0x1f2022, 0x202125, 0x212322, 0x202022, 0x20201e, 0x26252a, 0x191917, 0x050704, 0x151714, 0x262628, 0x212322, 0x080607, 0x000201, 0x010002, 0x000100, 0x62453d, 0x926957, 0x7b5749, 0x694535, 0x482b23, 0x251b19, 0x0c0b09, 0x010101, 0x020202, 0x010101, 0x010101, 0x020001, 0x020001, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x010302, 0x020403, 0x040601, 0x010103, 0x000000, 0x18140b, 0xa3894e, 0xffe481, 0xffe880, 0xffcb70, 0xfdc66b, 0xffca6c, 0xfdcd6b, 0xfccd63, 0xfdcd5e, 0xfbcc62, 0xfcce5f, 0xfece60, 0xfecc5d, 0xfed15e, 0xfdd05b, 0xfed15e, 0xfdd261, 0xfed060, 0xfcd35f, 0xffd061, 0xfece62, 0xfdd164, 0xffd86a, 0xffe572, 0xffee7c, 0xffed7d, 0xfedb75, 0xebbe6b, 0xbf9a56, 0x937c4a, 0x685439, 0x3e3428, 0x16170f, 0x020106, 0x000200, 0x000000, 0x000100, 0x000000, 0x010000, 0x000002, 0x020001, 0x000000, 0x010204, 0x000201, 0x020200, 0x020401, 0x020204, 0x030104, 0x010302, 0x040404, 0x040404, 0x00000c, 0x000005, 0x00000d, 0x0e0e1a, 0x2b2b21, 0x5b5731, 0x9c8b43, 0xe5ce64, 0xfefa7d, 0xffff7a, 0xffe86e, 0xffda68, 0xfdd866, 0xfdd865, 0xffd664, 0xffd662, 0xfed464, 0xffd565, 0xfed762, 0xffd863, 0xffd765, 0xfed466, 0xfed464, 0xfed36a, 0xfdd26c, 0xfbcd6b, 0xffd171, 0xffed84, 0xfdec82, 0xbba35d, 0x443923, 0x000100, 0x00070f, 0x1c2021, 0x1e1e1c, 0x1e201f, 0x222423, 0x252527, 0x232426, 0x25262a, 0x2a2a2c, 0x26252a, 0x0c0e0d, 0x0f0f0d, 0x242422, 0x2a2b2d, 0x111715, 0x050402, 0x030303, 0x010000, 0x000002, 0x130707, 0x080500, 0x080403, 0x000000, 0x000000, 0x000000, 0x030303, 0x020200, 0x000201, 0x010101, 0x030102, 0x000201, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x030200, 0x020202, 0x030303, 0x040404, 0x030207, 0x000000, 0x010000, 0x453e22, 0xc8ac62, 0xfee682, 0xffed7f, 0xfdcf71, 0xfcc96d, 0xfecc6d, 0xffca6a, 0xfdcd67, 0xfdcc65, 0xffcc66, 0xffce65, 0xfcd063, 0xfdd166, 0xffd068, 0xfecf65, 0xffce65, 0xfecf65, 0xffdb70, 0xffef7d, 0xffee7c, 0xf9d26d, 0xd5ac5c, 0x9a8149, 0x695532, 0x3b3320, 0x130f0c, 0x000000, 0x010100, 0x000100, 0x000100, 0x000000, 0x000002, 0x010204, 0x060503, 0x060606, 0x050505, 0x000000, 0x010101, 0x282725, 0x4c4d4f, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x030303, 0x040404, 0x040404, 0x020202, 0x000000, 0x010101, 0x0b0c0e, 0x16171c, 0x131521, 0x0f1223, 0x0b0d22, 0x2a2927, 0x595730, 0xa49949, 0xecd669, 0xfffe83, 0xfefa7f, 0xffdc6e, 0xffdc6c, 0xfee070, 0xffe071, 0xffde6d, 0xffdb6b, 0xffd76b, 0xffd56d, 0xffd66d, 0xfdd36d, 0xfed36d, 0xffdb76, 0xfdf883, 0xffeb7e, 0xb9a455, 0x4b4126, 0x000002, 0x010000, 0x121212, 0x1c1c1c, 0x191919, 0x1c1c1c, 0x202221, 0x202221, 0x242527, 0x28292b, 0x2b2d2c, 0x323433, 0x3d3f3c, 0x1f2120, 0x0c0c0c, 0x1f1f1f, 0x393939, 0x252525, 0x080808, 0x040404, 0x040404, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x020202, 0x010101, 0x010101, 0x000201, 0x010101, 0x010101, 0x000000, 0x010101, 0x020202, 0x020202, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x040404, 0x020202, 0x000000, 0x000000, 0x4c4229, 0xbda25f, 0xfee980, 0xffeb7e, 0xfccd71, 0xffc96f, 0xfbcd6d, 0xfdcc70, 0xfdcd6b, 0xffce6b, 0xffd670, 0xfbdf72, 0xffe276, 0xfee275, 0xffed7d, 0xffef83, 0xf0cd6f, 0xb1924f, 0x5c522f, 0x201c13, 0x030000, 0x000002, 0x000000, 0x000000, 0x000000, 0x010101, 0x030303, 0x050505, 0x050505, 0x050505, 0x050505, 0x050505, 0x050505, 0x000000, 0x000000, 0x1c1c1c, 0x464646, 0x4f4f4f, 0x232325, 0x060606, 0x000000, 0x010101, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x030305, 0x030303, 0x060604, 0x010100, 0x000000, 0x000100, 0x0d0e10, 0x1d1e20, 0x1a1d24, 0x161a33, 0x111022, 0x252722, 0x625a2c, 0xbfae56, 0xfbf982, 0xfff780, 0xffe675, 0xffe576, 0xffe979, 0xfeed7b, 0xfff47e, 0xfff981, 0xfff981, 0xfff883, 0xfef880, 0xfcdb74, 0xa6954d, 0x463f23, 0x000100, 0x010005, 0x080c0f, 0x131313, 0x101010, 0x121212, 0x171717, 0x222222, 0x222222, 0x252525, 0x292b2a, 0x2f3130, 0x3c3e3d, 0x454746, 0x595b5a, 0x4a4c4b, 0x171717, 0x171719, 0x404042, 0x363638, 0x0b0b0b, 0x090909, 0x080808, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x030303, 0x000000, 0x010101, 0x010101, 0x010101, 0x020202, 0x000000, 0x000000, 0x030303, 0x030303, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x040404, 0x010103, 0x000002, 0x020003, 0x474127, 0xc1a55c, 0xffea80, 0xfef181, 0xfee980, 0xffe87e, 0xffee84, 0xffe780, 0xfed579, 0xf0c26d, 0xe3b963, 0xddba68, 0xb49952, 0x5d5433, 0x13150a, 0x010103, 0x030000, 0x000100, 0x000103, 0x050304, 0x020605, 0x040404, 0x050505, 0x050505, 0x040404, 0x060606, 0x040404, 0x050505, 0x050505, 0x000000, 0x000000, 0x101010, 0x424242, 0x595959, 0x323232, 0x000000, 0x000000, 0x1a1a1a, 0x0f0f0f, 0x000000, 0x010101, 0x030303, 0x020202, 0x010101, 0x020202, 0x030303, 0x030303, 0x030303, 0x030303, 0x050505, 0x050505, 0x000000, 0x000000, 0x000000, 0x111214, 0x242529, 0x262932, 0x03081c, 0x090810, 0x443f1f, 0x504726, 0x3b3320, 0x36301a, 0x3f391f, 0x4c4322, 0x63562a, 0x84703d, 0x927c43, 0x957d41, 0x72643d, 0x242215, 0x000200, 0x030000, 0x0b0c10, 0x121116, 0x11110f, 0x0f1110, 0x121212, 0x141414, 0x171717, 0x1a1a1a, 0x232323, 0x2f2f2f, 0x353535, 0x424242, 0x4f4f4d, 0x585a57, 0x585a59, 0x686a69, 0x3a3a3a, 0x121214, 0x48484a, 0x555557, 0x151515, 0x050505, 0x0d0d0d, 0x070707, 0x000000, 0x010101, 0x000000, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x030303, 0x000000, 0x000000, 0x020202, 0x010101, 0x020202, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x020202, 0x030303, 0x010101, 0x030303, 0x030303, 0x030504, 0x000000, 0x000103, 0x000200, 0x53452a, 0x998047, 0xba9753, 0xbe9851, 0xa08b4a, 0x5d512b, 0x291f15, 0x14110c, 0x050601, 0x060606, 0x000002, 0x010000, 0x000000, 0x020204, 0x050608, 0x050706, 0x050507, 0x060407, 0x060604, 0x040404, 0x060606, 0x050505, 0x050505, 0x050505, 0x070707, 0x000000, 0x000000, 0x0b0b0b, 0x3e3e3e, 0x585858, 0x444444, 0x070707, 0x000000, 0x010101, 0x000000, 0x292929, 0x282828, 0x141414, 0x000000, 0x030303, 0x010101, 0x010101, 0x020202, 0x010302, 0x030303, 0x030303, 0x030305, 0x050507, 0x040404, 0x060606, 0x070707, 0x040402, 0x000000, 0x010000, 0x050505, 0x232321, 0x32323a, 0x121328, 0x000100, 0x000000, 0x000000, 0x010103, 0x000002, 0x000100, 0x000100, 0x000100, 0x000000, 0x010000, 0x000100, 0x020403, 0x070908, 0x0a0a0a, 0x0d0c0a, 0x0e0e0e, 0x101012, 0x101010, 0x101010, 0x121212, 0x111111, 0x1a1a1a, 0x272727, 0x323232, 0x3d3d3d, 0x464644, 0x41413f, 0x3c3e3d, 0x424242, 0x2d2d2d, 0x171719, 0x2c2c2e, 0x383838, 0x131313, 0x030303, 0x060606, 0x0d0d0d, 0x070707, 0x000000, 0x030303, 0x000000, 0x010101, 0x010101, 0x000000, 0x020202, 0x000000, 0x000000, 0x070707, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x010101, 0x000000, 0x000000, 0x020202, 0x040404, 0x050505, 0x030303, 0x040404, 0x050304, 0x040603, 0x080607, 0x060608, 0x000000, 0x000100, 0x000100, 0x010000, 0x000100, 0x000002, 0x010000, 0x000100, 0x000100, 0x010101, 0x010000, 0x000105, 0x070707, 0x060405, 0x070707, 0x050706, 0x050503, 0x040406, 0x060709, 0x070707, 0x050505, 0x030303, 0x060606, 0x080808, 0x020202, 0x000000, 0x040404, 0x333333, 0x565656, 0x4b4b4b, 0x121212, 0x000000, 0x000000, 0x010101, 0x060606, 0x0c0c0c, 0x313131, 0x2e2e2e, 0x2f2f2f, 0x151515, 0x020202, 0x030303, 0x010101, 0x010101, 0x020202, 0x020202, 0x030303, 0x030303, 0x040402, 0x030301, 0x040402, 0x060604, 0x060405, 0x040500, 0x010204, 0x020001, 0x000000, 0x070c08, 0x302f35, 0x3e3f43, 0x2b2c2e, 0x000000, 0x020001, 0x080607, 0x0a0a0a, 0x070707, 0x060807, 0x050706, 0x070705, 0x050507, 0x030305, 0x010302, 0x030303, 0x040605, 0x070906, 0x0a0a0a, 0x0a0a0a, 0x0b0b0b, 0x0c0c0c, 0x0c0c0c, 0x090909, 0x090909, 0x0d0d0d, 0x0c0c0c, 0x0a0a08, 0x070705, 0x050505, 0x010101, 0x080808, 0x161616, 0x111111, 0x080808, 0x0a0a0a, 0x050505, 0x030303, 0x050505, 0x0d0d0d, 0x070707, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x040404, 0x3e3e3e, 0x343434, 0x020202, 0x000000, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x050505, 0x080808, 0x090909, 0x080808, 0x080808, 0x0c0c0c, 0x0b0b0b, 0x090b0a, 0x0a0a0a, 0x0b0b0b, 0x0b0b0b, 0x0c0a0d, 0x09090b, 0x000403, 0x000004, 0x000103, 0x040404, 0x060606, 0x060807, 0x08080a, 0x060608, 0x060805, 0x060606, 0x050608, 0x050706, 0x050505, 0x070508, 0x070506, 0x080705, 0x060407, 0x060606, 0x070707, 0x040404, 0x000000, 0x020202, 0x2a2a2a, 0x4e4e4e, 0x4f4f4f, 0x181818, 0x000000, 0x010101, 0x000000, 0x0a0a0a, 0x0b0b0b, 0x0f0f0f, 0x181818, 0x2f2f2f, 0x2a2a2a, 0x2f2f2f, 0x2a2a2a, 0x0e0e0e, 0x0b0b0b, 0x0b0b0b, 0x030303, 0x010000, 0x020202, 0x030303, 0x030303, 0x010101, 0x050505, 0x040406, 0x050507, 0x050507, 0x050304, 0x050304, 0x010103, 0x000000, 0x010002, 0x010000, 0x131313, 0x3e3e40, 0x454545, 0x151714, 0x010100, 0x090708, 0x070506, 0x080808, 0x0c0c0c, 0x060606, 0x050402, 0x040605, 0x040404, 0x040001, 0x000201, 0x020202, 0x050304, 0x0a0a0a, 0x0c0c0c, 0x0e0e0e, 0x141414, 0x121212, 0x111111, 0x0e0e0e, 0x131313, 0x1d1d1d, 0x181818, 0x1b1b1b, 0x252525, 0x2b2b2b, 0x323232, 0x313131, 0x1d1d1d, 0x070707, 0x030303, 0x040404, 0x020202, 0x050505, 0x0f0f0f, 0x111111, 0x040404, 0x000000, 0x000000, 0x000000, 0x0c0c0c, 0x3a3a3a, 0x4f5150, 0x262626, 0x101010, 0x010101, 0x010101, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x000000, 0x010101, 0x020202, 0x040404, 0x060606, 0x060606, 0x050505, 0x060606, 0x080808, 0x080808, 0x070506, 0x060608, 0x070506, 0x070604, 0x060503, 0x050706, 0x040406, 0x040205, 0x050304, 0x050503, 0x080808, 0x090909, 0x070705, 0x070707, 0x040404, 0x030504, 0x060405, 0x050304, 0x050706, 0x040402, 0x050503, 0x040605, 0x080806, 0x060606, 0x000000, 0x000000, 0x242424, 0x505050, 0x4d4d4d, 0x1c1c1c, 0x010101, 0x000000, 0x000000, 0x060606, 0x0e0e0e, 0x111111, 0x151515, 0x191919, 0x262626, 0x1e1e1e, 0x232323, 0x1f1f1f, 0x2b2b2b, 0x242424, 0x0e0e0e, 0x121212, 0x111111, 0x030303, 0x000000, 0x020202, 0x020202, 0x030303, 0x020202, 0x030303, 0x030303, 0x020403, 0x030504, 0x070908, 0x030504, 0x010200, 0x020001, 0x010000, 0x000100, 0x000100, 0x242422, 0x444444, 0x232323, 0x000201, 0x0a0c0b, 0x121214, 0x131114, 0x0c0c0c, 0x0c0a0b, 0x111113, 0x161415, 0x181816, 0x1a1a1c, 0x201f24, 0x2b2d2c, 0x353535, 0x373737, 0x3e3e3e, 0x4a4a4a, 0x505050, 0x545454, 0x59595b, 0x656567, 0x6e6e70, 0x6a6a6c, 0x6a6a6a, 0x707070, 0x686868, 0x535353, 0x434343, 0x2b2d2c, 0x101010, 0x020202, 0x040404, 0x040404, 0x030303, 0x080808, 0x121212, 0x131313, 0x0b0b0b, 0x090909, 0x101010, 0x252525, 0x3a3a3a, 0x262626, 0x171717, 0x141414, 0x070707, 0x020202, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x040404, 0x040404, 0x020202, 0x020202, 0x020202, 0x040404, 0x040404, 0x030303, 0x030502, 0x010302, 0x030504, 0x010504, 0x040406, 0x030303, 0x040301, 0x030102, 0x060604, 0x0a0809, 0x0d0b0c, 0x0c0c0c, 0x060807, 0x060606, 0x070705, 0x050505, 0x060407, 0x060606, 0x060606, 0x060405, 0x070709, 0x08080a, 0x060608, 0x000000, 0x000000, 0x1c1c1c, 0x474747, 0x5b5b5b, 0x292929, 0x000000, 0x010101, 0x000000, 0x000000, 0x0c0c0c, 0x131313, 0x141414, 0x131313, 0x171717, 0x1f1f1f, 0x262626, 0x070707, 0x0e0e0e, 0x121212, 0x171717, 0x252525, 0x1b1b1b, 0x0d0d0d, 0x141414, 0x151515, 0x0a0a0a, 0x010103, 0x000103, 0x020204, 0x020202, 0x020202, 0x020202, 0x040203, 0x050503, 0x060503, 0x090708, 0x050507, 0x030301, 0x000000, 0x010000, 0x010000, 0x010002, 0x0a0a0c, 0x3d3d3f, 0x282828, 0x070705, 0x141613, 0x161817, 0x151716, 0x202020, 0x222224, 0x262827, 0x303433, 0x383838, 0x3b3d3a, 0x414340, 0x454547, 0x515151, 0x585858, 0x626262, 0x6e6e6e, 0x777779, 0x828186, 0x7b7a7f, 0x7f7e83, 0x858587, 0x818183, 0x7a7a7a, 0x6c6c6c, 0x515151, 0x303231, 0x252726, 0x161616, 0x050505, 0x040404, 0x040404, 0x050505, 0x070707, 0x0a0a0a, 0x0e0e0e, 0x101010, 0x0d0d0d, 0x131313, 0x1c1c1c, 0x212121, 0x1d1d1d, 0x1d1d1d, 0x131313, 0x111111, 0x090909, 0x020202, 0x000000, 0x020202, 0x020202, 0x010101, 0x020202, 0x050505, 0x050505, 0x030303, 0x030303, 0x040404, 0x040404, 0x040404, 0x040404, 0x030303, 0x050306, 0x060608, 0x060405, 0x040402, 0x010101, 0x020202, 0x0d0d0b, 0x11110f, 0x0d0e10, 0x0d0e10, 0x0b0b0b, 0x080607, 0x060407, 0x040406, 0x060503, 0x050601, 0x050706, 0x070709, 0x060606, 0x050704, 0x010100, 0x010000, 0x1d1d1d, 0x424242, 0x4c4c4c, 0x2d2d2d, 0x070707, 0x000000, 0x000000, 0x020202, 0x040404, 0x0c0c0c, 0x151515, 0x141414, 0x101010, 0x101010, 0x121212, 0x101010, 0x0f0f0f, 0x020202, 0x010101, 0x040404, 0x040404, 0x090909, 0x111111, 0x111111, 0x0d0d0d, 0x161616, 0x181818, 0x0b0b0b, 0x050505, 0x040404, 0x010101, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x050505, 0x070707, 0x080808, 0x030303, 0x000000, 0x000000, 0x020202, 0x000000, 0x010101, 0x343434, 0x333333, 0x090909, 0x111111, 0x1a1a1a, 0x212121, 0x232323, 0x212121, 0x262626, 0x2a2a2a, 0x232323, 0x242424, 0x2a2a2c, 0x353535, 0x3f3f3f, 0x474747, 0x565656, 0x636363, 0x6f6f6f, 0x707072, 0x6d6b6c, 0x6b6b6d, 0x626763, 0x5b5d5c, 0x535351, 0x3d383c, 0x272528, 0x1a1c1b, 0x121315, 0x0e0e0e, 0x070908, 0x040404, 0x070506, 0x060606, 0x090708, 0x080806, 0x0a0a0a, 0x090b0a, 0x151515, 0x1c1c1c, 0x191b1a, 0x161618, 0x131514, 0x111310, 0x100b0f, 0x080c0b, 0x070707, 0x020204, 0x010101, 0x020200, 0x020401, 0x050306, 0x040404, 0x040404, 0x040404, 0x040404, 0x030303, 0x040404, 0x050505, 0x040404, 0x050505, 0x040404, 0x040404, 0x040404, 0x020202, 0x070707, 0x111111, 0x151515, 0x151515, 0x0f0f0f, 0x0c0c0c, 0x0b0b0b, 0x080808, 0x040404, 0x050505, 0x060606, 0x060606, 0x060606, 0x050505, 0x010101, 0x000000, 0x1b1b1b, 0x484848, 0x515153, 0x282828, 0x010101, 0x000000, 0x000000, 0x030303, 0x040404, 0x070707, 0x0c0c0c, 0x101010, 0x0f0f0f, 0x0b0b0b, 0x060606, 0x050505, 0x050505, 0x040404, 0x010101, 0x020202, 0x020202, 0x020202, 0x000000, 0x000000, 0x030303, 0x070707, 0x080808, 0x0c0c0c, 0x131313, 0x151515, 0x0e0e0e, 0x080808, 0x050505, 0x010101, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x040404, 0x090909, 0x080808, 0x030303, 0x000000, 0x000000, 0x010101, 0x010101, 0x000000, 0x272727, 0x2b2b2b, 0x030303, 0x090909, 0x151515, 0x111111, 0x0f0f0f, 0x121212, 0x121212, 0x131313, 0x0f0f0f, 0x101010, 0x0d0d0d, 0x070707, 0x101010, 0x181818, 0x262626, 0x373737, 0x404040, 0x424242, 0x3c3c3c, 0x343233, 0x3a383b, 0x323232, 0x20201e, 0x171b1a, 0x141414, 0x141416, 0x131311, 0x090b0a, 0x030504, 0x08080a, 0x0c0a0d, 0x0d0d0d, 0x0e0f11, 0x0f0f0f, 0x0d0f0c, 0x151314, 0x171719, 0x11110f, 0x0f0b0c, 0x09070a, 0x0b0708, 0x080a07, 0x080609, 0x090907, 0x070709, 0x020202, 0x030102, 0x060405, 0x040406, 0x040404, 0x040404, 0x030303, 0x040404, 0x030303, 0x040404, 0x040404, 0x040404, 0x050505, 0x040404, 0x050505, 0x020202, 0x090909, 0x181818, 0x161616, 0x141414, 0x121212, 0x101010, 0x0c0c0c, 0x090909, 0x060606, 0x060606, 0x050505, 0x050505, 0x000000, 0x000000, 0x000000, 0x1b1b1b, 0x3e3e3e, 0x4e4e4e, 0x343434, 0x040404, 0x000000, 0x000000, 0x020202, 0x050505, 0x050505, 0x050505, 0x080808, 0x0a0a0a, 0x080808, 0x040404, 0x010101, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x030303, 0x030303, 0x010101, 0x020202, 0x010101, 0x030303, 0x080808, 0x131313, 0x121212, 0x080808, 0x080808, 0x080808, 0x030303, 0x010101, 0x010101, 0x040404, 0x030303, 0x020202, 0x020202, 0x050505, 0x060606, 0x020202, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x1c1c1c, 0x2c2c2c, 0x040404, 0x010101, 0x141414, 0x222222, 0x303030, 0x3b3b3b, 0x414141, 0x434343, 0x3f3f3f, 0x353535, 0x262626, 0x1b1b1b, 0x0c0c0c, 0x020202, 0x090909, 0x151515, 0x1e1e1e, 0x242321, 0x212322, 0x20201e, 0x1d1d1b, 0x181c1d, 0x161616, 0x0e0e10, 0x0f0f0d, 0x171918, 0x15161b, 0x020b12, 0x00010e, 0x00010e, 0x030014, 0x000211, 0x010012, 0x01000e, 0x01000e, 0x00010e, 0x00020f, 0x00060c, 0x0f1314, 0x0c0c0c, 0x040406, 0x050608, 0x050400, 0x0a0a08, 0x09070a, 0x030207, 0x040402, 0x030406, 0x040404, 0x040404, 0x050505, 0x030303, 0x040404, 0x040404, 0x050505, 0x040404, 0x040404, 0x060606, 0x020202, 0x101010, 0x202020, 0x222222, 0x1f1f1f, 0x1d1d1d, 0x151515, 0x0d0d0d, 0x090909, 0x0d0d0d, 0x060606, 0x010101, 0x000000, 0x000000, 0x101010, 0x303030, 0x4b4b4b, 0x4d4d4d, 0x2b2b2b, 0x010101, 0x000000, 0x000000, 0x040404, 0x030303, 0x030303, 0x050505, 0x030303, 0x050505, 0x040404, 0x030303, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x010101, 0x000000, 0x040404, 0x0e0e0e, 0x0c0c0c, 0x070707, 0x060606, 0x050505, 0x040404, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x030303, 0x040404, 0x020202, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x202020, 0x303030, 0x030303, 0x202020, 0x464646, 0x474747, 0x404040, 0x363636, 0x343434, 0x2a2a2a, 0x2b2b2b, 0x2f2f2f, 0x353535, 0x434343, 0x434343, 0x252525, 0x131313, 0x1b1b19, 0x262425, 0x232426, 0x21201e, 0x1e1e1e, 0x0e100f, 0x141416, 0x232728, 0x15212f, 0x051127, 0x070b16, 0x251611, 0x412710, 0x503115, 0x5e3d10, 0x6b4312, 0x724714, 0x6b460f, 0x5e3b11, 0x513416, 0x392210, 0x151112, 0x000317, 0x010119, 0x0c1019, 0x0f0b08, 0x060709, 0x070304, 0x090907, 0x050608, 0x050304, 0x050507, 0x050505, 0x050505, 0x030303, 0x020202, 0x030303, 0x030303, 0x010101, 0x030303, 0x050505, 0x010101, 0x181818, 0x2b2b2b, 0x2b2b2b, 0x222222, 0x1e1e1e, 0x1a1a1a, 0x111111, 0x0b0b0b, 0x020202, 0x000000, 0x040404, 0x181818, 0x343434, 0x3e3e3e, 0x464646, 0x454545, 0x2e2e2e, 0x010101, 0x000000, 0x000000, 0x020202, 0x030303, 0x050505, 0x040404, 0x030303, 0x010101, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x010101, 0x000000, 0x000000, 0x010101, 0x020202, 0x010101, 0x020202, 0x000000, 0x010101, 0x060606, 0x080808, 0x060606, 0x060606, 0x030303, 0x030303, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x030303, 0x020202, 0x000000, 0x000000, 0x000000, 0x020202, 0x020202, 0x000000, 0x212121, 0x303030, 0x020202, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x030303, 0x050505, 0x101010, 0x2a2a2a, 0x444444, 0x3f3f3f, 0x242426, 0x242625, 0x232522, 0x151517, 0x0c0b09, 0x2f3336, 0x121f30, 0x151a2d, 0x422b19, 0x8c5103, 0xcc860c, 0xeb9e1a, 0xfca91b, 0xffaf1b, 0xffb611, 0xfebd19, 0xffb913, 0xffc00e, 0xfdbb1e, 0xfdb71b, 0xfeaa24, 0xf7a71e, 0xbf8313, 0x674917, 0x19181d, 0x01011b, 0x0a0e19, 0x0d0c0a, 0x020605, 0x050608, 0x050402, 0x050304, 0x050505, 0x040404, 0x020202, 0x000000, 0x030303, 0x000000, 0x010101, 0x060606, 0x000000, 0x171717, 0x2f2f2f, 0x252525, 0x242424, 0x202020, 0x151515, 0x070707, 0x000000, 0x121212, 0x2c2c2c, 0x3b3b3b, 0x4a4a4a, 0x4d4d4d, 0x3f3f3f, 0x222222, 0x080808, 0x000000, 0x000000, 0x000000, 0x030303, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x000000, 0x010101, 0x030303, 0x000000, 0x010101, 0x010101, 0x020202, 0x010101, 0x000000, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x040404, 0x050505, 0x040404, 0x030303, 0x010101, 0x010101, 0x030303, 0x020202, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x000000, 0x000000, 0x000000, 0x040404, 0x010101, 0x000000, 0x202020, 0x2f2f2f, 0x000000, 0x010101, 0x121212, 0x121212, 0x191919, 0x202020, 0x212121, 0x212121, 0x1e201f, 0x161817, 0x070707, 0x030303, 0x2e2e2e, 0x3d3d3d, 0x28282a, 0x060606, 0x21201e, 0x4a545e, 0x1a293e, 0x4c2909, 0xbf7200, 0xfecb20, 0xfed138, 0xd9a128, 0xfbb519, 0xfebf1c, 0xfbb812, 0xeec142, 0xffca29, 0xffdb2f, 0xfec746, 0xf3b114, 0xfbb30f, 0xffcd46, 0xd6a13b, 0xfdb60e, 0xffed27, 0xf6af19, 0x755719, 0x0c0e1a, 0x020822, 0x0f0f0f, 0x020202, 0x060606, 0x030301, 0x030303, 0x010101, 0x020202, 0x030303, 0x000000, 0x040404, 0x060606, 0x000000, 0x181617, 0x2d2b2c, 0x272526, 0x1f1d1e, 0x121212, 0x090909, 0x161616, 0x2e2e2e, 0x414141, 0x4e4e4e, 0x444444, 0x2d2d2d, 0x1c1c1c, 0x030303, 0x000000, 0x000000, 0x000000, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x010101, 0x000000, 0x020202, 0x010101, 0x000000, 0x020202, 0x010101, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x000000, 0x000000, 0x010101, 0x010101, 0x000000, 0x020202, 0x000000, 0x010101, 0x010101, 0x000000, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x000000, 0x010101, 0x030303, 0x040404, 0x030303, 0x020202, 0x030303, 0x020202, 0x000000, 0x000000, 0x000000, 0x010101, 0x030303, 0x010101, 0x000000, 0x222222, 0x303030, 0x060606, 0x0e0e0e, 0x1d1d1d, 0x262626, 0x2e2e2e, 0x373737, 0x3c3e3d, 0x3a3c3b, 0x2b2d2c, 0x212322, 0x161616, 0x010101, 0x303030, 0x1b1b1b, 0x50514c, 0x8592a5, 0x38303b, 0x8d4700, 0xffd328, 0xffdb4e, 0x928139, 0x202924, 0x83551a, 0xf7bb1f, 0xf9b923, 0xffbf17, 0xc1a156, 0x7e6431, 0x9d8d42, 0x987b43, 0xfab414, 0xf7b523, 0xfcbb19, 0xc89d2a, 0x282514, 0x78560e, 0xfdb918, 0xffef19, 0xd1a218, 0x2e2516, 0x02031f, 0x101010, 0x040404, 0x040404, 0x010101, 0x020202, 0x010101, 0x010101, 0x060606, 0x0a0a0a, 0x010101, 0x1b1b1b, 0x2f2d2e, 0x252324, 0x161616, 0x191919, 0x343434, 0x454545, 0x484848, 0x414141, 0x323232, 0x101010, 0x000000, 0x000000, 0x000000, 0x000000, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x000000, 0x010101, 0x020202, 0x010101, 0x010101, 0x000000, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x010101, 0x020202, 0x020202, 0x010101, 0x020202, 0x030303, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x000000, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x030303, 0x030303, 0x000000, 0x000000, 0x1c1c1c, 0x1e1e1e, 0x080808, 0x141414, 0x242424, 0x323232, 0x404241, 0x4d4f4e, 0x565855, 0x464845, 0x2c2e2d, 0x1e201f, 0x101010, 0x131313, 0x322e2f, 0xa1aebe, 0x5c534e, 0xba6c00, 0xfef862, 0x9d965f, 0x132330, 0x000100, 0x1e0701, 0xfcba1d, 0xffc11e, 0xf3b31d, 0xffcd1e, 0xb39650, 0x00000c, 0x000000, 0x4e2900, 0xfcc625, 0xf6b920, 0xf3ab19, 0xffdb17, 0x867235, 0x000000, 0x0e0905, 0x90600e, 0xffde1d, 0xffd11b, 0x4d3318, 0x00011a, 0x0b0d0c, 0x020202, 0x020202, 0x020202, 0x000000, 0x080808, 0x060606, 0x000000, 0x212121, 0x303030, 0x1e1c1d, 0x222021, 0x353535, 0x4e4e4e, 0x505050, 0x323232, 0x0d0d0d, 0x000000, 0x000000, 0x000000, 0x020202, 0x030303, 0x010101, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x000000, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x030303, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x020202, 0x010101, 0x000000, 0x010101, 0x030303, 0x010101, 0x000000, 0x010101, 0x000000, 0x080808, 0x131313, 0x0e0e0e, 0x0c0c0c, 0x131313, 0x202020, 0x262626, 0x303030, 0x414141, 0x404040, 0x252525, 0x131313, 0x070508, 0x565d65, 0x323337, 0xbc6601, 0xfffd9c, 0x707e87, 0x000000, 0x000000, 0x000000, 0x1d1101, 0xf5a51a, 0xfedc22, 0xffab0a, 0xffe73c, 0x908359, 0x000100, 0x000100, 0x261209, 0xfdbb1e, 0xfec714, 0xfebe04, 0xffff81, 0x7b7461, 0x000000, 0x010000, 0x000100, 0x4d2c0b, 0xffc71b, 0xfed929, 0x332e1b, 0x00020f, 0x050706, 0x000000, 0x000000, 0x090909, 0x070707, 0x070707, 0x222222, 0x272727, 0x303030, 0x3c3c3c, 0x3d3d3d, 0x373737, 0x1c1c1c, 0x010101, 0x000000, 0x000000, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x030303, 0x010101, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x010101, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x000000, 0x000000, 0x020202, 0x030303, 0x030303, 0x000000, 0x010101, 0x000000, 0x010101, 0x070707, 0x050505, 0x030303, 0x000000, 0x000000, 0x040404, 0x1a1a1a, 0x2f2f2f, 0x272727, 0x0b0b0b, 0x2b2b29, 0x203246, 0x7b3501, 0xfff152, 0x807e71, 0x010300, 0x000002, 0x020003, 0x020001, 0x000002, 0x231709, 0xb28a18, 0xffc51c, 0xe4c666, 0x2b292e, 0x010103, 0x000000, 0x000000, 0x8e5a0e, 0xf2c029, 0xd0b447, 0x6e6f6a, 0x000519, 0x000000, 0x000000, 0x000201, 0x000000, 0x4f2b07, 0xffe526, 0xc99d30, 0x01000e, 0x040308, 0x000000, 0x0a0a0a, 0x050505, 0x0a0a0a, 0x2e2e2e, 0x373737, 0x3b3b3b, 0x3e3e3e, 0x2d2d2d, 0x080808, 0x000000, 0x000000, 0x000000, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x030303, 0x040404, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x030303, 0x030303, 0x040404, 0x010101, 0x000000, 0x000000, 0x000000, 0x010101, 0x030303, 0x0a0a0a, 0x0a0a0a, 0x010101, 0x000000, 0x0b0b0b, 0x212121, 0x0d0d0d, 0x222834, 0x322e2f, 0xec8c04, 0xe1bc52, 0x020109, 0x010002, 0x010204, 0x030301, 0x030104, 0x020202, 0x000002, 0x010100, 0x222617, 0x0e0f13, 0x020001, 0x000100, 0x020100, 0x010002, 0x000100, 0x131114, 0x000316, 0x000000, 0x000200, 0x010002, 0x020003, 0x000002, 0x000100, 0x000000, 0xbd710f, 0xffde39, 0x2c2a1e, 0x000103, 0x000000, 0x000000, 0x1a1a1a, 0x3e3e3e, 0x3f3f3f, 0x383838, 0x292929, 0x030305, 0x000000, 0x000000, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x060606, 0x080808, 0x080808, 0x050505, 0x030303, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x000000, 0x000000, 0x010101, 0x020202, 0x020202, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x030303, 0x070707, 0x040404, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x141414, 0x272727, 0x0b0b0b, 0x010101, 0x0a0a0a, 0x121212, 0x010d1d, 0x4b2f17, 0xffc621, 0x9c7e38, 0x000000, 0x000002, 0x000100, 0x000100, 0x020204, 0x000200, 0x020100, 0x010000, 0x000103, 0x000002, 0x000000, 0x010101, 0x010103, 0x000103, 0x000000, 0x000100, 0x000000, 0x020005, 0x000000, 0x000000, 0x000201, 0x000000, 0x000000, 0x010000, 0x572c00, 0xffe742, 0x676238, 0x010000, 0x0e0e0e, 0x333333, 0x434343, 0x2f2f2f, 0x1c1c1c, 0x050505, 0x000000, 0x000000, 0x020202, 0x030303, 0x020202, 0x030303, 0x010101, 0x010101, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x040404, 0x050505, 0x050505, 0x040404, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x020202, 0x020202, 0x080808, 0x070707, 0x040404, 0x020202, 0x030303, 0x030303, 0x020202, 0x010101, 0x020202, 0x161616, 0x232323, 0x0a0a0a, 0x000000, 0x060606, 0x010415, 0x493115, 0xffcb20, 0x8f7835, 0x000002, 0x000105, 0x160e0c, 0x050001, 0x000102, 0x030200, 0x000201, 0x000105, 0x030303, 0x050503, 0x000000, 0x000002, 0x020202, 0x010100, 0x000103, 0x030102, 0x020001, 0x010100, 0x040404, 0x010101, 0x000002, 0x000100, 0x020003, 0x010002, 0x4d2b00, 0xffe341, 0x7c753f, 0x000000, 0x131313, 0x222222, 0x090909, 0x010101, 0x000000, 0x010101, 0x020202, 0x020202, 0x030303, 0x030303, 0x030303, 0x010101, 0x030303, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x0d0d0d, 0x0d0d0d, 0x060606, 0x040404, 0x000000, 0x030303, 0x020202, 0x030303, 0x010101, 0x000000, 0x050505, 0x0b0b0b, 0x000000, 0x000000, 0x000511, 0x30231a, 0xffb317, 0xc1912b, 0x01010b, 0x3b230b, 0xefa214, 0xd9a22b, 0x292421, 0x010101, 0x000007, 0x020003, 0x000002, 0x090909, 0x050503, 0x000200, 0x010002, 0x000201, 0x040301, 0x010000, 0x000000, 0x000200, 0x000105, 0x000009, 0x56340e, 0xc49016, 0x8b5d10, 0x000103, 0x532900, 0xfee749, 0x51533e, 0x000002, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x000000, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x010101, 0x030303, 0x030303, 0x020202, 0x000000, 0x000000, 0x020202, 0x000000, 0x0c0c0c, 0x141414, 0x0c0c0c, 0x090909, 0x070707, 0x030303, 0x030303, 0x010101, 0x020202, 0x020202, 0x010101, 0x000000, 0x020202, 0x000000, 0x040205, 0x0b0e1d, 0xd58313, 0xffd425, 0x010818, 0x895a12, 0xfecc15, 0xffe029, 0x9b9062, 0x00000c, 0x59330c, 0x513f0d, 0x000000, 0x020204, 0x0d090a, 0x020204, 0x030303, 0x040605, 0x010101, 0x000000, 0x0f0307, 0x543e0c, 0x15100a, 0x28160c, 0xffbd21, 0xffd308, 0xfed641, 0x03051e, 0xac6203, 0xffd55c, 0x060f16, 0x000000, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x000000, 0x020202, 0x010101, 0x010101, 0x000000, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x030303, 0x040404, 0x040404, 0x030303, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x010101, 0x020202, 0x010101, 0x000000, 0x010101, 0x010101, 0x0a0a0a, 0x161616, 0x121212, 0x0d0d0d, 0x0c0c0c, 0x090909, 0x080808, 0x060606, 0x040404, 0x020202, 0x010101, 0x020202, 0x000000, 0x000000, 0x000000, 0x00051b, 0x5a3d1d, 0xffda1b, 0x927a18, 0x512f13, 0xffc121, 0xf8bc1d, 0xd6a838, 0xc58722, 0xffbf1b, 0xfed521, 0xa47e1b, 0x05040a, 0x040507, 0x010302, 0x020403, 0x090506, 0x010000, 0x32200a, 0xe79a18, 0xffc91e, 0xeaac25, 0xce9224, 0xfeb91e, 0xfdc915, 0xa19759, 0x451e00, 0xfced4a, 0x6c654b, 0x010000, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x000000, 0x030303, 0x000000, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x040404, 0x050505, 0x020202, 0x040404, 0x050505, 0x040404, 0x060606, 0x040404, 0x010101, 0x030303, 0x050505, 0x030303, 0x030303, 0x040404, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x020202, 0x000000, 0x090909, 0x1c1c1c, 0x161616, 0x111111, 0x0f0f0f, 0x0d0d0d, 0x0e0e0e, 0x0b0b0b, 0x0a0a0a, 0x090909, 0x070707, 0x040404, 0x010101, 0x020202, 0x020204, 0x000201, 0x030a24, 0x7c4d15, 0xffe220, 0x967317, 0xb47822, 0xf9bf2f, 0xfcbf26, 0xffc525, 0xf5bc2d, 0xffb514, 0xfed94a, 0x16232b, 0x000100, 0x0a0a08, 0x030301, 0x010103, 0x000100, 0x845310, 0xffde2a, 0xf7b523, 0xffc32a, 0xfec627, 0xfab31b, 0xd6bf61, 0x74501c, 0xfece48, 0xb7ad7a, 0x020008, 0x000200, 0x020200, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x040404, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x040404, 0x050505, 0x040404, 0x030303, 0x030303, 0x050505, 0x050505, 0x040404, 0x030303, 0x020202, 0x050505, 0x060606, 0x030303, 0x010101, 0x010101, 0x020202, 0x030303, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x0b0b0b, 0x212121, 0x1f1f1f, 0x181818, 0x161616, 0x121212, 0x111111, 0x0d0d0d, 0x0c0c0c, 0x0d0d0d, 0x0c0c0c, 0x0c0c0c, 0x0c0c0c, 0x0c0c0c, 0x0b0b09, 0x040205, 0x000308, 0x00011a, 0x714812, 0xfdce1e, 0xf0b422, 0xefa925, 0xf2bc3e, 0xefba2e, 0xf2bb2d, 0xfdbf20, 0xdfb142, 0x4f392b, 0x1f100b, 0x010004, 0x000105, 0x010002, 0x3a220a, 0xae7619, 0xf9cc29, 0xf3b929, 0xf4bf31, 0xf1b324, 0xfbb61d, 0xd2a138, 0xffd06e, 0xbec6ae, 0x01000e, 0x000000, 0x020001, 0x020106, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x040404, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x040404, 0x030303, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x040404, 0x030303, 0x030303, 0x050505, 0x040404, 0x040404, 0x050505, 0x050505, 0x050505, 0x030303, 0x040404, 0x050505, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x040404, 0x000000, 0x0a0a0a, 0x252525, 0x2b2b2d, 0x272729, 0x262626, 0x222222, 0x212121, 0x1b1b1b, 0x19191b, 0x19191b, 0x1a1a1a, 0x1b1b1b, 0x1c1c1c, 0x1a1a1c, 0x1a181b, 0x181914, 0x0a0a0a, 0x000004, 0x000005, 0x3a2510, 0xdca01c, 0xfed022, 0xffcb2a, 0xf4b627, 0xeeb424, 0xf2b72d, 0xe8aa21, 0xffb11b, 0xf5b91b, 0x473d1a, 0x09040b, 0xc78318, 0xfdc125, 0xfdb92a, 0xf4b228, 0xf5b327, 0xf2b123, 0xffb812, 0xffda2f, 0xfdd454, 0x787c6e, 0x02000a, 0x000002, 0x010302, 0x010302, 0x020204, 0x020202, 0x020202, 0x030303, 0x040404, 0x050505, 0x040404, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x040404, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x030303, 0x040404, 0x050505, 0x050505, 0x050505, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x040404, 0x030303, 0x050505, 0x050505, 0x040404, 0x050505, 0x040404, 0x040404, 0x040404, 0x030303, 0x030303, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x000000, 0x0a0a0a, 0x29292b, 0x343436, 0x2a2a2c, 0x262628, 0x2b2b2d, 0x272729, 0x252527, 0x262628, 0x29292b, 0x29292b, 0x2a2a2c, 0x2b2b2d, 0x2b2b2d, 0x2b2a2f, 0x28292b, 0x2b2a26, 0x191816, 0x030504, 0x010006, 0x01000c, 0x7c5a1a, 0xd2981a, 0xffbd1e, 0xffd227, 0xfec925, 0xfdbf1e, 0xfebc1d, 0xfdca0d, 0xd7ae44, 0x9a7034, 0xfdcc17, 0xffb71a, 0xfeba19, 0xffbd1e, 0xffcf1d, 0xffd630, 0xf1c54a, 0x99945c, 0x212733, 0x000002, 0x010002, 0x020200, 0x030102, 0x020202, 0x020200, 0x050505, 0x050505, 0x050505, 0x050505, 0x040404, 0x040404, 0x040404, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x040404, 0x040404, 0x030303, 0x030303, 0x040404, 0x060606, 0x050505, 0x030303, 0x030303, 0x070707, 0x0a0a0a, 0x070707, 0x050505, 0x050505, 0x050505, 0x040404, 0x030303, 0x030303, 0x040404, 0x030303, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x000000, 0x040404, 0x242426, 0x363638, 0x2f2f31, 0x2b2b2d, 0x2e2e30, 0x313133, 0x333335, 0x333335, 0x313133, 0x313133, 0x353537, 0x363638, 0x333335, 0x333438, 0x2d3132, 0x292a2c, 0x2a2627, 0x1e201d, 0x0d0c0a, 0x000200, 0x000106, 0x00010d, 0x412c0d, 0x866216, 0xc18c18, 0xe6a418, 0xffb71d, 0xfec01f, 0xffca2c, 0xffcd2c, 0xffca22, 0xffc62e, 0xf9c12e, 0xdfaa28, 0xa7882d, 0x655e32, 0x151e23, 0x000002, 0x000002, 0x010000, 0x000000, 0x000103, 0x030102, 0x060405, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x030303, 0x040404, 0x040404, 0x050505, 0x040404, 0x040404, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x030303, 0x020202, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x030303, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x030303, 0x050505, 0x040404, 0x040404, 0x141414, 0x0f0f0f, 0x090909, 0x040404, 0x030303, 0x040404, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x060606, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x030303, 0x212123, 0x373739, 0x353537, 0x343436, 0x353537, 0x39393b, 0x373739, 0x38383a, 0x3d3d3f, 0x3e3e40, 0x3c3c3e, 0x3c3c3e, 0x3e3e40, 0x414141, 0x35343a, 0x2d2c32, 0x262827, 0x232227, 0x262626, 0x141416, 0x010101, 0x000002, 0x000000, 0x010103, 0x000004, 0x0e0905, 0x322310, 0x4b3716, 0x593e0f, 0x583e0d, 0x513f19, 0x4f3f1e, 0x2a2b1d, 0x050912, 0x010005, 0x010000, 0x000100, 0x000100, 0x010103, 0x000200, 0x050505, 0x020607, 0x040807, 0x09070a, 0x060606, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x030303, 0x030303, 0x040404, 0x0d0d0d, 0x070707, 0x040404, 0x030303, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x030303, 0x030303, 0x040404, 0x050505, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x000000, 0x020202, 0x010101, 0x151515, 0x343436, 0x363638, 0x38383a, 0x404042, 0x424244, 0x464648, 0x48484a, 0x4a4a4c, 0x49494b, 0x464648, 0x464648, 0x48484a, 0x49474c, 0x434047, 0x373739, 0x2a2b2d, 0x202020, 0x292a25, 0x232227, 0x151714, 0x0b0b09, 0x040404, 0x030303, 0x000002, 0x010000, 0x000100, 0x000002, 0x000000, 0x010000, 0x010002, 0x000002, 0x000201, 0x030000, 0x000100, 0x000000, 0x020001, 0x060105, 0x060805, 0x0b0b09, 0x0b0a08, 0x0e090d, 0x070707, 0x070904, 0x060606, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x030303, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x040404, 0x040404, 0x020202, 0x040404, 0x070707, 0x050505, 0x020202, 0x040404, 0x040404, 0x020202, 0x020202, 0x040404, 0x030303, 0x030303, 0x030303, 0x020202, 0x030303, 0x030303, 0x020202, 0x050505, 0x050505, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x0b0b0b, 0x29292b, 0x353537, 0x3c3c3e, 0x424244, 0x48484a, 0x4e4e50, 0x515153, 0x505052, 0x4e4e50, 0x4b4b4d, 0x4a4a4c, 0x4a4a4c, 0x4b4c4e, 0x49484d, 0x3d3b3e, 0x2d2e30, 0x1e1f21, 0x222222, 0x272727, 0x232323, 0x151314, 0x0d0d0f, 0x0a0a08, 0x050706, 0x070508, 0x050505, 0x040301, 0x020202, 0x000201, 0x020202, 0x010101, 0x000000, 0x0f1012, 0x1f2022, 0x20221f, 0x1e1e20, 0x1c1e1d, 0x171717, 0x161614, 0x121214, 0x090909, 0x08080a, 0x070705, 0x070604, 0x050505, 0x050505, 0x050505, 0x050505, 0x040404, 0x040404, 0x040404, 0x040404, 0x030303, 0x040404, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x040404, 0x080808, 0x060606, 0x030303, 0x030303, 0x030303, 0x020202, 0x050505, 0x040404, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x060606, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x050505, 0x161616, 0x2e2e2e, 0x363638, 0x373739, 0x424244, 0x4a4a4c, 0x505052, 0x525254, 0x525254, 0x525254, 0x4e4e50, 0x4c4c4e, 0x4c4c4e, 0x464648, 0x38383a, 0x303030, 0x242424, 0x232323, 0x292929, 0x292929, 0x1b1b1b, 0x0e0e0e, 0x0b0b0b, 0x070707, 0x060606, 0x060606, 0x050505, 0x030303, 0x030303, 0x010101, 0x000002, 0x2d2d2f, 0x5a5a5c, 0x5b5b5d, 0x48484a, 0x3e3e40, 0x333333, 0x1e1e1e, 0x131313, 0x141414, 0x0d0d0d, 0x060606, 0x070707, 0x070707, 0x050505, 0x050505, 0x060606, 0x060606, 0x050505, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x040404, 0x020202, 0x030303, 0x030303, 0x030303, 0x050505, 0x040404, 0x040404, 0x030303, 0x020202, 0x080808, 0x040404, 0x040404, 0x020202, 0x030303, 0x050505, 0x040404, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x030303, 0x050505, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x040404, 0x020202, 0x020202, 0x030303, 0x020202, 0x0a0a0a, 0x181818, 0x292929, 0x323234, 0x373739, 0x434345, 0x48484a, 0x4c4c4e, 0x4f4f51, 0x4f4f51, 0x4c4c4e, 0x4a4a4c, 0x434345, 0x3b3b3d, 0x313133, 0x2d2d2d, 0x2b2b2b, 0x2c2c2c, 0x2c2c2c, 0x282828, 0x141414, 0x090909, 0x050505, 0x060606, 0x070707, 0x050505, 0x050505, 0x050505, 0x020202, 0x020202, 0x272729, 0x505052, 0x4d4d4d, 0x383838, 0x2d2d2f, 0x2f2f31, 0x272727, 0x1c1c1c, 0x121212, 0x111111, 0x0e0e0e, 0x080808, 0x060606, 0x080808, 0x050505, 0x050505, 0x050505, 0x050505, 0x050505, 0x030303, 0x030303, 0x040404, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x030303, 0x060606, 0x060606, 0x030303, 0x030303, 0x070707, 0x070707, 0x030303, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x050505, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x050505, 0x070707, 0x131313, 0x212121, 0x29292b, 0x323234, 0x3a3a3c, 0x3a3a3c, 0x3c3c3e, 0x404042, 0x3d3d3f, 0x3b3b3d, 0x343434, 0x2b2b2b, 0x282828, 0x252525, 0x212121, 0x181818, 0x121212, 0x0c0c0c, 0x040404, 0x040404, 0x040404, 0x040404, 0x050505, 0x050505, 0x050505, 0x030303, 0x010101, 0x131313, 0x3a3a3a, 0x2e2e2e, 0x1e1e1e, 0x131313, 0x131313, 0x161616, 0x171717, 0x131313, 0x0d0d0d, 0x0b0b0b, 0x0b0b0b, 0x080808, 0x070707, 0x080808, 0x060606, 0x050505, 0x050505, 0x050505, 0x050505, 0x040404, 0x030303, 0x040404, 0x040404, 0x040404, 0x040404, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x040404, 0x080808, 0x060606, 0x040404, 0x070707, 0x090909, 0x050505, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x040404, 0x070707, 0x040404, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x050505, 0x0b0b0b, 0x111111, 0x1a1a1a, 0x1c1c1c, 0x1b1b1b, 0x1f1f1f, 0x232323, 0x232323, 0x202020, 0x1b1b1b, 0x191919, 0x121212, 0x090909, 0x060606, 0x010101, 0x010101, 0x010101, 0x040404, 0x050505, 0x030303, 0x020202, 0x030303, 0x040404, 0x040404, 0x040404, 0x070707, 0x111111, 0x141414, 0x101010, 0x0a0a0a, 0x060606, 0x040404, 0x030303, 0x030303, 0x030303, 0x030303, 0x050505, 0x050505, 0x050505, 0x050505, 0x040404, 0x050505, 0x050505, 0x050505, 0x040404, 0x050505, 0x040404, 0x040404, 0x040404, 0x030303, 0x040404, 0x040404, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x020202, 0x0a0a0a, 0x050505, 0x090909, 0x0a0a0a, 0x060606, 0x040404, 0x010101, 0x020202, 0x020202, 0x010101, 0x030303, 0x030303, 0x020202, 0x070707, 0x080808, 0x040404, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x010101, 0x030303, 0x010101, 0x020202, 0x030303, 0x060606, 0x040404, 0x060606, 0x0a0a0a, 0x0b0b0b, 0x0c0c0c, 0x090909, 0x050505, 0x040404, 0x010101, 0x000000, 0x020202, 0x030303, 0x030303, 0x010101, 0x000000, 0x020202, 0x060606, 0x0a0a0a, 0x0b0b0b, 0x080808, 0x040404, 0x040404, 0x0a0a0a, 0x0b0b0b, 0x080808, 0x101010, 0x151515, 0x121212, 0x0e0e0e, 0x040404, 0x030303, 0x030303, 0x030303, 0x040404, 0x040404, 0x040404, 0x040404, 0x030303, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x040404, 0x030303, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x040404, 0x030303, 0x030303, 0x020202, 0x020202, 0x060606, 0x0a0a0a, 0x0b0b0b, 0x070707, 0x040404, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x040404, 0x030303, 0x060606, 0x0d0d0d, 0x090909, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x040404, 0x010101, 0x010101, 0x020202, 0x020202, 0x000000, 0x010101, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x060606, 0x0c0c0c, 0x101010, 0x181818, 0x191919, 0x101010, 0x050505, 0x020202, 0x070707, 0x090909, 0x090909, 0x050505, 0x0c0c0c, 0x0c0c0c, 0x0f0f0f, 0x181818, 0x0d0d0d, 0x040404, 0x040404, 0x030303, 0x030303, 0x030303, 0x030303, 0x030303, 0x040404, 0x040404, 0x030303, 0x030303, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x040404, 0x030303, 0x020202, 0x020202, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x030303, 0x040404, 0x040404, 0x060606, 0x050505, 0x030303, 0x080808, 0x0e0e0e, 0x080808, 0x030303, 0x030303, 0x030303, 0x020202, 0x010101, 0x030303, 0x040404, 0x040404, 0x020202, 0x070707, 0x0d0d0d, 0x070707, 0x010101, 0x010101, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x030303, 0x020202, 0x020202, 0x020202, 0x000000, 0x000000, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x020202, 0x0d0d0d, 0x121212, 0x181818, 0x1a1a1a, 0x1d1d1d, 0x1c1c1c, 0x171717, 0x0d0d0d, 0x030303, 0x010101, 0x050505, 0x070707, 0x060606, 0x060606, 0x060606, 0x030303, 0x060606, 0x070707, 0x040404, 0x060606, 0x0b0b0b, 0x090909, 0x080808, 0x060606, 0x030303, 0x020202, 0x030303, 0x040404, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x010101, 0x020202, 0x030303, 0x030303, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x030303, 0x040404, 0x060606, 0x060606, 0x040404, 0x0d0d0d, 0x080808, 0x030303, 0x020202, 0x030303, 0x030303, 0x020202, 0x030303, 0x030303, 0x030303, 0x030303, 0x030303, 0x080808, 0x080808, 0x040404, 0x030303, 0x020202, 0x030303, 0x030303, 0x040404, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x020202, 0x030303, 0x040404, 0x010101, 0x040404, 0x070707, 0x141414, 0x292929, 0x1e1e1e, 0x070707, 0x000000, 0x020202, 0x050505, 0x0f0f0f, 0x232323, 0x2e2e2e, 0x2d2d2d, 0x282828, 0x292929, 0x212121, 0x101010, 0x040404, 0x000000, 0x000000, 0x0a0a0a, 0x101010, 0x0e0e0e, 0x080808, 0x020202, 0x010101, 0x0e0e0e, 0x151515, 0x111111, 0x0a0a0a, 0x060606, 0x060606, 0x050505, 0x060606, 0x090909, 0x080808, 0x050505, 0x040404, 0x040404, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x030303, 0x020202, 0x020202, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x020202, 0x030303, 0x040404, 0x040404, 0x080808, 0x010101, 0x020202, 0x030303, 0x020202, 0x020202, 0x040404, 0x050505, 0x030303, 0x030303, 0x030303, 0x090909, 0x0b0b0b, 0x040404, 0x010101, 0x030303, 0x040404, 0x020202, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x060606, 0x0a0a0a, 0x252525, 0x2b2b2b, 0x151515, 0x050505, 0x0f0f0f, 0x111111, 0x080808, 0x232323, 0x474747, 0x353535, 0x222222, 0x191919, 0x101010, 0x030303, 0x000000, 0x020202, 0x090909, 0x101010, 0x1a1a1a, 0x171717, 0x0f0f0f, 0x040404, 0x030303, 0x000000, 0x0f0f0f, 0x282828, 0x1e1e1e, 0x111111, 0x070707, 0x040404, 0x050505, 0x040404, 0x050505, 0x050505, 0x050505, 0x040404, 0x030303, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x010101, 0x030303, 0x020202, 0x020202, 0x030303, 0x020202, 0x030303, 0x020202, 0x000000, 0x010101, 0x020202, 0x030303, 0x010101, 0x020202, 0x020202, 0x010101, 0x020202, 0x040404, 0x040404, 0x030303, 0x030303, 0x010101, 0x020202, 0x040404, 0x040404, 0x050505, 0x040404, 0x030303, 0x030303, 0x0b0b0b, 0x090909, 0x030303, 0x020202, 0x010101, 0x030303, 0x030303, 0x030303, 0x040404, 0x030303, 0x030303, 0x030303, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x040404, 0x080808, 0x131313, 0x181818, 0x070707, 0x000000, 0x151515, 0x1e1e1e, 0x1c1c1c, 0x090909, 0x181818, 0x2e2e2e, 0x1d1d1d, 0x101010, 0x070707, 0x000000, 0x000000, 0x0f0f0f, 0x171717, 0x1b1b1b, 0x171717, 0x131313, 0x111111, 0x080808, 0x020202, 0x050505, 0x010101, 0x050505, 0x272727, 0x272727, 0x131313, 0x0c0c0c, 0x060606, 0x040404, 0x030303, 0x030303, 0x030303, 0x030303, 0x030303, 0x030303, 0x030303, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x040404, 0x020202, 0x040404, 0x040404, 0x030303, 0x020202, 0x020202, 0x010101, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x020202, 0x040404, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x020202, 0x010101, 0x040404, 0x040404, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x030303, 0x020202, 0x040404, 0x030303, 0x020202, 0x030303, 0x040404, 0x040404, 0x050505, 0x040404, 0x020202, 0x040404, 0x0b0b0b, 0x060606, 0x030303, 0x030303, 0x020202, 0x010101, 0x010101, 0x020202, 0x050505, 0x040404, 0x020202, 0x020202, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x040404, 0x080808, 0x121212, 0x090909, 0x000000, 0x0a0a0a, 0x171717, 0x1b1b1b, 0x1c1c1c, 0x0d0d0d, 0x0d0d0d, 0x171717, 0x0d0d0d, 0x010101, 0x000000, 0x040404, 0x212121, 0x262626, 0x222222, 0x1e1e1e, 0x181818, 0x111111, 0x090909, 0x030303, 0x030303, 0x010101, 0x020202, 0x040404, 0x212121, 0x272727, 0x151515, 0x0e0e0e, 0x090909, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x060606, 0x050505, 0x020202, 0x020202, 0x030303, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x000000, 0x010101, 0x030303, 0x030303, 0x040404, 0x050505, 0x030303, 0x030303, 0x040404, 0x040404, 0x030303, 0x020202, 0x020202, 0x050505, 0x050505, 0x020202, 0x010101, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x040404, 0x040404, 0x040404, 0x050505, 0x050505, 0x040404, 0x030303, 0x070707, 0x080808, 0x030303, 0x020202, 0x020202, 0x030303, 0x020202, 0x010101, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x030303, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x030303, 0x060606, 0x010101, 0x020202, 0x0a0a0a, 0x0e0e0e, 0x1d1d1d, 0x1f1f1f, 0x0f0f0f, 0x040404, 0x0a0a0a, 0x040404, 0x000000, 0x080808, 0x282828, 0x2f2f2f, 0x242424, 0x232323, 0x1c1c1c, 0x141414, 0x0e0e0e, 0x040404, 0x030303, 0x030303, 0x020202, 0x000000, 0x050505, 0x191919, 0x1e1e1e, 0x161616, 0x0a0a0a, 0x080808, 0x030303, 0x030303, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x030303, 0x020202, 0x020202, 0x090909, 0x090909, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x030303, 0x030303, 0x040404, 0x020202, 0x040404, 0x040404, 0x020202, 0x030303, 0x030303, 0x040404, 0x030303, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x040404, 0x040404, 0x040404, 0x040404, 0x050505, 0x030303, 0x030303, 0x050505, 0x080808, 0x050505, 0x020202, 0x010101, 0x000000, 0x020202, 0x020202, 0x010101, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x000000, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x010101, 0x020202, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x010101, 0x000000, 0x000000, 0x010101, 0x020202, 0x070707, 0x0c0c0c, 0x131313, 0x181818, 0x101010, 0x040404, 0x010101, 0x000000, 0x080808, 0x282828, 0x2e2e2e, 0x242424, 0x1e1e1e, 0x1d1d1d, 0x161616, 0x0f0f0f, 0x0b0b0b, 0x040404, 0x030303, 0x020202, 0x020202, 0x000000, 0x030303, 0x141414, 0x1c1c1c, 0x141414, 0x070707, 0x040404, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x030303, 0x030303, 0x010101, 0x020202, 0x0b0b0b, 0x070707, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x030303, 0x020202, 0x030303, 0x030303, 0x010101, 0x020202, 0x040404, 0x020202, 0x030303, 0x030303, 0x040404, 0x040404, 0x020202, 0x010101, 0x010101, 0x010101, 0x000000, 0x020202, 0x040404, 0x060606, 0x040404, 0x040404, 0x040404, 0x050505, 0x030303, 0x030303, 0x050505, 0x060606, 0x030303, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x020202, 0x010101, 0x010101, 0x020202, 0x020202, 0x000000, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x050505, 0x040404, 0x020202, 0x010101, 0x000000, 0x000000, 0x050505, 0x080808, 0x0a0a0a, 0x111111, 0x0e0e0e, 0x020202, 0x000000, 0x040404, 0x1c1c1c, 0x252525, 0x202020, 0x1d1d1d, 0x181818, 0x181818, 0x101010, 0x0a0a0a, 0x050505, 0x030303, 0x020202, 0x030303, 0x020202, 0x010101, 0x010101, 0x0d0d0d, 0x171717, 0x0e0e0e, 0x050505, 0x030303, 0x030303, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x050505, 0x0c0c0c, 0x030303, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x040404, 0x030303, 0x020202, 0x020202, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x000000, 0x040404, 0x050505, 0x040404, 0x030303, 0x020202, 0x030303, 0x030303, 0x040404, 0x050505, 0x060606, 0x040404, 0x020202, 0x010101, 0x010101, 0x020202, 0x010101, 0x000000, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x030303, 0x050505, 0x060606, 0x060606, 0x060606, 0x030303, 0x000000, 0x020202, 0x040404, 0x060606, 0x090909, 0x0b0b0b, 0x020202, 0x000000, 0x0c0c0c, 0x1b1b1b, 0x181818, 0x181818, 0x151515, 0x141414, 0x0f0f0f, 0x080808, 0x040404, 0x010101, 0x030303, 0x020202, 0x010101, 0x020202, 0x000000, 0x010101, 0x060606, 0x0d0d0d, 0x080808, 0x030303, 0x040404, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x090909, 0x070707, 0x020202, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x010101, 0x020202, 0x030303, 0x020202, 0x030303, 0x020202, 0x030303, 0x030303, 0x020202, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x000000, 0x030303, 0x040404, 0x030303, 0x020202, 0x000000, 0x020202, 0x020202, 0x020202, 0x060606, 0x060606, 0x030303, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x020202, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x030303, 0x050505, 0x080808, 0x080808, 0x060606, 0x010101, 0x000000, 0x010101, 0x020202, 0x040404, 0x090909, 0x060606, 0x000000, 0x040404, 0x0e0e0e, 0x101010, 0x101010, 0x101010, 0x0e0e0e, 0x070707, 0x020202, 0x000000, 0x020202, 0x020202, 0x020202, 0x000000, 0x010101, 0x010101, 0x010101, 0x040404, 0x050505, 0x040404, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x050505, 0x070707, 0x030303, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x010101, 0x000000, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x000000, 0x010101, 0x000000, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x000000, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x030303, 0x030303, 0x030303, 0x020202, 0x020202, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x020202, 0x030303, 0x040404, 0x050505, 0x030303, 0x010101, 0x010101, 0x000000, 0x000000, 0x010101, 0x030303, 0x060606, 0x020202, 0x000000, 0x050505, 0x080808, 0x090909, 0x090909, 0x040404, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x030303, 0x050505, 0x040404, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x020202, 0x020202, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x030303, 0x020202, 0x000000, 0x020202, 0x030303, 0x040404, 0x040404, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x020202, 0x020202, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x010101, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x010101, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000, 0x000000 +}; + +void setup() { + tft.begin(); + tft.writeScreen24bit(image_data_batman_ume); +} + + +void loop(void) { + +} \ No newline at end of file diff --git a/libraries/TFT_ILI9163C-master/examples/bigtest/bigtest.ino b/libraries/TFT_ILI9163C-master/examples/bigtest/bigtest.ino new file mode 100644 index 0000000..763b684 --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/bigtest/bigtest.ino @@ -0,0 +1,353 @@ +#include +#include +#include + +// Color definitions +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF + +/* +Teensy3.x and Arduino's +You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 +Arduino's 8 bit: any +DUE: check arduino site +If you do not use reset, tie it to +3V3 +*/ + + +TFT_ILI9163C display = TFT_ILI9163C(__CS, __DC); + +float p = 3.1415926; + +void setup(void) { + display.begin(); + + + uint16_t time = millis(); + time = millis() - time; + +// lcdTestPattern(); +// delay(1000); + + display.clearScreen(); + display.setCursor(0,0); + display.print("Lorem ipsum dolor sit amet, consectetur adipiscing elit. Curabitur adipiscing ante sed nibh tincidunt feugiat. Maecenas enim massa"); + delay(1000); + + tftPrintTest(); + delay(2000); + + //a single pixel + display.drawPixel(display.width()/2, display.height()/2, GREEN); + delay(500); + + // line draw test + testlines(YELLOW); + delay(500); + + // optimized lines + testfastlines(RED, BLUE); + delay(500); + + testdrawrects(GREEN); + delay(1000); + + testfillrects(BLUE, YELLOW); + delay(1000); + + randomRect(0); + delay(100); + randomCircles(0); + delay(100); + randomLines(); + delay(100); + randomPoints(); + delay(500); + + display.clearScreen(); + testfillcircles(10, BLUE); + testdrawcircles(10, WHITE); + delay(1000); + + testroundrects(); + delay(500); + + testtriangles(); + delay(500); + +} + +void loop() { + testlines(random(0x0010,0xFFFF)); + randomLines(); + //randomCircles(1); + randomCircles(0); + randomRect(1); + randomRect(1); + randomRect(1); + randomRect(1); + randomRect(1); + randomRect(0); + randomRect(0); + randomRect(0); + randomRect(0); + randomRect(0); + randomRect(0); + randomPoints(); +} + +void testlines(uint16_t color) { + display.clearScreen(); + for (int16_t x=0; x < display.width()-1; x+=6) { + display.drawLine(0, 0, x, display.height()-1, color); + } + for (int16_t y=0; y < display.height()-1; y+=6) { + display.drawLine(0, 0, display.width()-1, y, color); + } + display.clearScreen(); + for (int16_t x=0; x < display.width()-1; x+=6) { + display.drawLine(display.width()-1, 0, x, display.height()-1, color); + } + for (int16_t y=0; y < display.height()-1; y+=6) { + display.drawLine(display.width()-1, 0, 0, y, color); + } + + display.clearScreen(); + for (int16_t x=0; x < display.width()-1; x+=6) { + display.drawLine(0, display.height()-1, x, 0, color); + } + for (int16_t y=0; y < display.height()-1; y+=6) { + display.drawLine(0, display.height()-1, display.width()-1, y, color); + } + display.clearScreen(); + for (int16_t x=0; x < display.width()-1; x+=6) { + display.drawLine(display.width()-1, display.height()-1, x, 0, color); + } + for (int16_t y=0; y < display.height()-1; y+=6) { + display.drawLine(display.width()-1, display.height()-1, 0, y, color); + } + delay(500); +} + + +void testdrawtext(char *text, uint16_t color) { + display.setTextSize(1); + display.setTextColor(WHITE); + display.setCursor(0,0); + + for (uint8_t i=0; i < 168; i++) { + if (i == '\n') continue; + display.write(i); + if ((i > 0) && (i % 21 == 0)) + display.println(); + } +} + +void testfastlines(uint16_t color1, uint16_t color2) { + display.clearScreen(); + for (int16_t y=0; y < display.height()-1; y+=5) { + display.drawFastHLine(0, y, display.width()-1, color1); + } + for (int16_t x=0; x < display.width()-1; x+=5) { + display.drawFastVLine(x, 0, display.height()-1, color2); + } +} + +void testdrawrects(uint16_t color) { + display.clearScreen(); + for (int16_t x=0; x < display.height()-1; x+=6) { + display.drawRect((display.width()-1)/2 -x/2, (display.height()-1)/2 -x/2 , x, x, color); + } +} + +void testfillrects(uint16_t color1, uint16_t color2) { + display.clearScreen(); + for (int16_t x=display.height()-1; x > 6; x-=6) { + display.fillRect((display.width()-1)/2 -x/2, (display.height()-1)/2 -x/2 , x, x, color1); + display.drawRect((display.width()-1)/2 -x/2, (display.height()-1)/2 -x/2 , x, x, color2); + } +} + +void testfillcircles(uint8_t radius, uint16_t color) { + for (uint8_t x=radius; x < display.width()-1; x+=radius*2) { + for (uint8_t y=radius; y < display.height()-1; y+=radius*2) { + display.fillCircle(x, y, radius, color); + } + } +} + +void testdrawcircles(uint8_t radius, uint16_t color) { + for (int16_t x=0; x < (display.width()-1)+radius; x+=radius*2) { + for (int16_t y=0; y < (display.height())-1+radius; y+=radius*2) { + display.drawCircle(x, y, radius, color); + } + } +} + +void testtriangles() { + display.clearScreen(); + int color = 0xF800; + int t; + int w = display.width()/2; + int x = display.height(); + int y = 0; + int z = display.width(); + for(t = 0 ; t <= 15; t+=1) { + display.drawTriangle(w, y, y, x, z, x, color); + x-=4; + y+=4; + z-=4; + color+=100; + } +} + +void testroundrects() { + display.clearScreen(); + int color = 100; + int i; + int t; + for(t = 0 ; t <= 4; t+=1) { + int x = 0; + int y = 0; + int w = display.width(); + int h = display.height(); + for(i = 0 ; i <= 24; i+=1) { + display.drawRoundRect(x, y, w, h, 5, color); + x+=2; + y+=3; + w-=4; + h-=6; + color+=1100; + } + color+=100; + } +} + +void tftPrintTest() { + display.clearScreen(); + display.setCursor(0, 5); + display.setTextColor(RED); + display.setTextSize(1); + display.println("Hello World!"); + display.setTextColor(YELLOW, GREEN); + display.setTextSize(2); + display.print("Hello Wo"); + display.setTextColor(BLUE); + display.setTextSize(3); + display.print(12.57); + delay(1500); + display.setCursor(0, 5); + display.clearScreen(); + display.setTextColor(WHITE); + display.setTextSize(0); + display.println("Hello World!"); + display.setTextSize(1); + display.setTextColor(GREEN); + display.print(p, 5); + display.println(" Want pi?"); + display.print(8675309, HEX); + display.print(" Print HEX"); + display.setTextColor(WHITE); + display.println("Sketch has been"); + display.println("running for: "); + display.setTextColor(MAGENTA); + display.print(millis() / 1000); + display.setTextColor(WHITE); + display.print(" sec."); +} + + +void randomRect(bool fill){ + display.clearScreen(); + uint8_t k,c; + for (k = 0; k < 16; k++) { + for (c = 0; c < 32; c++) { + uint8_t cx, cy, x, y, w, h; + // center + cx = random(0,display.width()); + cy = random(0,display.height()); + // size + w = random(0,30 + 6); + h = random(0,20 + 4); + // upper-left + x = cx - w / 2; + y = cy - h / 2; + if (x < 0) x = 0; + if (y < 0) y = 0; + // adjust size + if (x + w > display.width()) w = display.width() - x; + if (y + h > display.height()) h = display.height() - y; + if (fill){ + display.fillRect(x, y, w, h,random(0x0010,0xFFFF)); + } + else { + display.drawRect(x, y, w, h,random(0x0010,0xFFFF)); + } + + } + display.clearScreen(); + } +} + +void randomCircles(bool fill){ + display.clearScreen(); + uint8_t k,c; + for (k = 0; k < display.height(); k++) { + for (c = 0; c < display.height()/2; c++) { + // coordinates + uint8_t x = random(0,120 + 3), y = random(0,90 + 2), r = random(0,40 + 1); + if (x - r < 0) r = x; + if (x + r > (display.width()-1)) r = (display.width() - 1) - x; + if (y - r < 0) r = y; + if (y + r > (display.height()-1)) r = (display.height() - 1) - y; + if (fill){ + display.fillCircle(x, y, r,random(0x0010,0xFFFF)); + } + else { + display.drawCircle(x, y, r,random(0x0010,0xFFFF)); + } + } + if (!fill)display.clearScreen(); + } +} + + +void randomLines(){ + display.clearScreen(); + uint8_t k,c; + for (k = 0; k < display.height(); k++) { + for (c = 0; c < display.height()/2; c++) { + uint8_t x1 = random(0,display.width()), y1 = random(0,display.height()), x2 = random(0,display.width()), y2 = random(0,display.height()); + display.drawLine(x1, y1, x2, y2,random(0x0010,0xFFFF)); + } + display.clearScreen(); + } +} + + +void randomPoints(){ + display.clearScreen(); + int k,c; + for (k = 0; k < 128; k++) { + for (c = 0; c < 1000; c++) { + uint8_t x = random(0,display.width()), y = random(0,display.height()); + display.drawPixel(x, y,random(0x0010,0xFFFF)); + } + display.clearScreen(); + } +} diff --git a/libraries/TFT_ILI9163C-master/examples/bubbles/bubbles.ino b/libraries/TFT_ILI9163C-master/examples/bubbles/bubbles.ino new file mode 100644 index 0000000..88b7d12 --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/bubbles/bubbles.ino @@ -0,0 +1,182 @@ +/* + This example was adapted from ugfx http://ugfx.org + It's a great example of many 2d objects in a 3d space (matrix transformations) + and show the capabilities of RA8875 chip. + Tested and worked with: + Teensy3,Teensy3.1,Arduino UNO,Arduino YUN,Arduino Leonardo,Stellaris + Works with Arduino 1.0.6 IDE, Arduino 1.5.8 IDE, Energia 0013 IDE +*/ +#ifdef __AVR__ +#define sinf sin +#endif + +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF +#define NDOTS 512 // Number of dots 512 +#define SCALE 4096//4096 +#define INCREMENT 512//512 +#define PI2 6.283185307179586476925286766559 +#define RED_COLORS (32) +#define GREEN_COLORS (64) +#define BLUE_COLORS (32) + +#include +#include +#include + +/* +Teensy3.x and Arduino's +You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +TFT_ILI9163C tft = TFT_ILI9163C(10, 9); + +int16_t sine[SCALE+(SCALE/4)]; +int16_t *cosi = &sine[SCALE/4]; +int16_t angleX = 0, angleY = 0, angleZ = 0; +int16_t speedX = 0, speedY = 0, speedZ = 0; + +int16_t xyz[3][NDOTS]; +uint16_t col[NDOTS]; +int pass = 0; + + +void initialize (void){ + uint16_t i; + /* if you change the SCALE*1.25 back to SCALE, the program will + * occassionally overrun the cosi array -- however this actually + * produces some interesting effects as the BUBBLES LOSE CONTROL!!!! + */ + for (i = 0; i < SCALE+(SCALE/4); i++) + //sine[i] = (-SCALE/2) + (int)(sinf(PI2 * i / SCALE) * sinf(PI2 * i / SCALE) * SCALE); + sine[i] = (int)(sinf(PI2 * i / SCALE) * SCALE); +} + +void setup() +{ + + tft.begin(); + + initialize(); +} + + + +void matrix (int16_t xyz[3][NDOTS], uint16_t col[NDOTS]){ + static uint32_t t = 0; + int16_t x = -SCALE, y = -SCALE; + uint16_t i, s, d; + uint8_t red,grn,blu; + + for (i = 0; i < NDOTS; i++) + { + xyz[0][i] = x; + xyz[1][i] = y; + + d = sqrt(x * x + y * y); /* originally a fastsqrt() call */ + s = sine[(t * 30) % SCALE] + SCALE; + + xyz[2][i] = sine[(d + s) % SCALE] * sine[(t * 10) % SCALE] / SCALE / 2; + + red = (cosi[xyz[2][i] + SCALE / 2] + SCALE) * (RED_COLORS - 1) / SCALE / 2; + grn = (cosi[(xyz[2][i] + SCALE / 2 + 2 * SCALE / 3) % SCALE] + SCALE) * (GREEN_COLORS - 1) / SCALE / 2; + blu = (cosi[(xyz[2][i] + SCALE / 2 + SCALE / 3) % SCALE] + SCALE) * (BLUE_COLORS - 1) / SCALE / 2; + col[i] = ((red << 11) + (grn << 5) + blu); + x += INCREMENT; + if (x >= SCALE) x = -SCALE, y += INCREMENT; + } + t++; +} + +void rotate (int16_t xyz[3][NDOTS], uint16_t angleX, uint16_t angleY, uint16_t angleZ){ + uint16_t i; + int16_t tmpX, tmpY; + int16_t sinx = sine[angleX], cosx = cosi[angleX]; + int16_t siny = sine[angleY], cosy = cosi[angleY]; + int16_t sinz = sine[angleZ], cosz = cosi[angleZ]; + + for (i = 0; i < NDOTS; i++) + { + tmpX = (xyz[0][i] * cosx - xyz[2][i] * sinx) / SCALE; + xyz[2][i] = (xyz[0][i] * sinx + xyz[2][i] * cosx) / SCALE; + xyz[0][i] = tmpX; + tmpY = (xyz[1][i] * cosy - xyz[2][i] * siny) / SCALE; + xyz[2][i] = (xyz[1][i] * siny + xyz[2][i] * cosy) / SCALE; + xyz[1][i] = tmpY; + tmpX = (xyz[0][i] * cosz - xyz[1][i] * sinz) / SCALE; + xyz[1][i] = (xyz[0][i] * sinz + xyz[1][i] * cosz) / SCALE; + xyz[0][i] = tmpX; + } +} + + +void draw(int16_t xyz[3][NDOTS], uint16_t col[NDOTS]){ + static uint16_t oldProjX[NDOTS] = { 0 }; + static uint16_t oldProjY[NDOTS] = { 0 }; + static uint8_t oldDotSize[NDOTS] = { 0 }; + uint16_t i, projX, projY, projZ, dotSize; + + for (i = 0; i < NDOTS; i++) + { + projZ = SCALE - (xyz[2][i] + SCALE) / 4; + projX = tft.width() / 2 + (xyz[0][i] * projZ / SCALE) / 25; + projY = tft.height() / 2 + (xyz[1][i] * projZ / SCALE) / 25; + dotSize = 3 - (xyz[2][i] + SCALE) * 2 / SCALE; + + tft.drawCircle (oldProjX[i], oldProjY[i], oldDotSize[i], BLACK); + + if (projX > dotSize && projY > dotSize && projX < tft.width() - dotSize && projY < tft.height() - dotSize) + { + tft.drawCircle (projX, projY, dotSize, col[i]); + oldProjX[i] = projX; + oldProjY[i] = projY; + oldDotSize[i] = dotSize; + } + } +} + +void loop() +{ + matrix(xyz, col); + rotate(xyz, angleX, angleY, angleZ); + draw(xyz, col); + + angleX += speedX; + angleY += speedY; + angleZ += speedZ; + + if (pass > 400) speedY = 1; + if (pass > 800) speedX = 1; + if (pass > 1200) speedZ = 1; + pass++; + + if (angleX >= SCALE) { + angleX -= SCALE; + } + else if (angleX < 0) { + angleX += SCALE; + } + + if (angleY >= SCALE) { + angleY -= SCALE; + } + else if (angleY < 0) { + angleY += SCALE; + } + + if (angleZ >= SCALE) { + angleZ -= SCALE; + } + else if (angleZ < 0) { + angleZ += SCALE; + } +} diff --git a/libraries/TFT_ILI9163C-master/examples/clock/clock.ino b/libraries/TFT_ILI9163C-master/examples/clock/clock.ino new file mode 100644 index 0000000..bfa0f4b --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/clock/clock.ino @@ -0,0 +1,137 @@ +#include +#include +#include + +// Color definitions +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF + +/* +Teensy3.x and Arduino's +You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 +Arduino's 8 bit: any +DUE: check arduino site +If you do not use reset, tie it to +3V3 +*/ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + +uint16_t ccenterx,ccentery;//center x,y of the clock +const uint16_t cradius = 63;//radius of the clock +const float scosConst = 0.0174532925; +float sx = 0, sy = 1, mx = 1, my = 0, hx = -1, hy = 0; +float sdeg=0, mdeg=0, hdeg=0; +uint16_t osx,osy,omx,omy,ohx,ohy; +uint16_t x0 = 0, x1 = 0, yy0 = 0, yy1 = 0; +uint32_t targetTime = 0;// for next 1 second timeout +uint8_t hh,mm,ss; //containers for current time + + +void drawClockFace(){ + tft.fillCircle(ccenterx, ccentery, cradius, BLUE); + tft.fillCircle(ccenterx, ccentery, cradius-4, BLACK); + // Draw 12 lines + for(int i = 0; i<360; i+= 30) { + sx = cos((i-90)*scosConst); + sy = sin((i-90)*scosConst); + x0 = sx*(cradius-4)+ccenterx; + yy0 = sy*(cradius-4)+ccentery; + x1 = sx*(cradius-11)+ccenterx; + yy1 = sy*(cradius-11)+ccentery; + tft.drawLine(x0, yy0, x1, yy1, BLUE); + } +} + +static uint8_t conv2d(const char* p) { + uint8_t v = 0; + if ('0' <= *p && *p <= '9') v = *p - '0'; + return 10 * v + *++p - '0'; +} + +void setup(void) { + tft.begin(); + + tft.setTextColor(WHITE, BLACK); + ccenterx = tft.width()/2; + ccentery = tft.height()/2; + osx = ccenterx; + osy = ccentery; + omx = ccenterx; + omy = ccentery; + ohx = ccenterx; + ohy = ccentery; + drawClockFace();// Draw clock face + //get current time from compiler + hh = conv2d(__TIME__); + mm = conv2d(__TIME__+3); + ss = conv2d(__TIME__+6); + targetTime = millis() + 1000; +} + +void drawClockHands(uint8_t h,uint8_t m,uint8_t s){ + // Pre-compute hand degrees, x & y coords for a fast screen update + sdeg = s * 6; // 0-59 -> 0-354 + mdeg = m * 6 + sdeg * 0.01666667; // 0-59 -> 0-360 - includes seconds + hdeg = h * 30 + mdeg * 0.0833333; // 0-11 -> 0-360 - includes minutes and seconds + hx = cos((hdeg-90)*scosConst); + hy = sin((hdeg-90)*scosConst); + mx = cos((mdeg-90)*scosConst); + my = sin((mdeg-90)*scosConst); + sx = cos((sdeg-90)*scosConst); + sy = sin((sdeg-90)*scosConst); + + // Erase just old hand positions + tft.drawLine(ohx, ohy, ccenterx+1, ccentery+1, BLACK); + tft.drawLine(omx, omy, ccenterx+1, ccentery+1, BLACK); + tft.drawLine(osx, osy, ccenterx+1, ccentery+1, BLACK); + // Draw new hand positions + tft.drawLine(hx*(cradius-28)+ccenterx+1, hy*(cradius-28)+ccentery+1, ccenterx+1, ccentery+1, WHITE); + tft.drawLine(mx*(cradius-17)+ccenterx+1, my*(cradius-17)+ccentery+1, ccenterx+1, ccentery+1, WHITE); + tft.drawLine(sx*(cradius-14)+ccenterx+1, sy*(cradius-14)+ccentery+1, ccenterx+1, ccentery+1, RED); + tft.fillCircle(ccenterx+1, ccentery+1, 3, RED); + + // Update old x&y coords + osx = sx*(cradius-14)+ccenterx+1; + osy = sy*(cradius-14)+ccentery+1; + omx = mx*(cradius-17)+ccenterx+1; + omy = my*(cradius-17)+ccentery+1; + ohx = hx*(cradius-28)+ccenterx+1; + ohy = hy*(cradius-28)+ccentery+1; +} + + +void loop() { + if (targetTime < millis()) { + targetTime = millis()+1000; + ss++; + if (ss == 60) { + ss = 0; + mm++; + if(mm > 59) { + mm = 0; + hh++; + if (hh > 23) hh = 0; + } + } + drawClockHands(hh,mm,ss); + + } +} + + diff --git a/libraries/TFT_ILI9163C-master/examples/cube/cube.ino b/libraries/TFT_ILI9163C-master/examples/cube/cube.ino new file mode 100644 index 0000000..35de8d6 --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/cube/cube.ino @@ -0,0 +1,99 @@ +#include +#include +#include + + +// Color definitions +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF + +const float sin_d[] = { + 0,0.17,0.34,0.5,0.64,0.77,0.87,0.94,0.98,1,0.98,0.94, + 0.87,0.77,0.64,0.5,0.34,0.17,0,-0.17,-0.34,-0.5,-0.64, + -0.77,-0.87,-0.94,-0.98,-1,-0.98,-0.94,-0.87,-0.77, + -0.64,-0.5,-0.34,-0.17 }; +const float cos_d[] = { + 1,0.98,0.94,0.87,0.77,0.64,0.5,0.34,0.17,0,-0.17,-0.34, + -0.5,-0.64,-0.77,-0.87,-0.94,-0.98,-1,-0.98,-0.94,-0.87, + -0.77,-0.64,-0.5,-0.34,-0.17,0,0.17,0.34,0.5,0.64,0.77, + 0.87,0.94,0.98}; +const float d = 10; +float px[] = { + -d, d, d, -d, -d, d, d, -d }; +float py[] = { + -d, -d, d, d, -d, -d, d, d }; +float pz[] = { + -d, -d, -d, -d, d, d, d, d }; + +float p2x[] = { + 0,0,0,0,0,0,0,0}; +float p2y[] = { + 0,0,0,0,0,0,0,0}; + +int r[] = { + 0,0,0}; + +/* +Teensy3.x and Arduino's +You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 +Arduino's 8 bit: any +DUE: check arduino site +If you do not use reset, tie it to +3V3 +*/ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + +void setup() { + tft.begin(); +} + +void loop(){ + tft.fillScreen(WHITE); + r[0]=r[0]+1; + r[1]=r[1]+1; + if (r[0] == 36) r[0] = 0; + if (r[1] == 36) r[1] = 0; + if (r[2] == 36) r[2] = 0; + for (int i=0;i<8;i++) + { + float px2 = px[i]; + float py2 = cos_d[r[0]]*py[i] - sin_d[r[0]]*pz[i]; + float pz2 = sin_d[r[0]]*py[i] + cos_d[r[0]]*pz[i]; + + float px3 = cos_d[r[1]]*px2 + sin_d[r[1]]*pz2; + float py3 = py2; + float pz3 = -sin_d[r[1]]*px2 + cos_d[r[1]]*pz2; + + float ax = cos_d[r[2]]*px3 - sin_d[r[2]]*py3; + float ay = sin_d[r[2]]*px3 + cos_d[r[2]]*py3; + float az = pz3-190; + + p2x[i] = ((tft.width())/2)+ax*500/az; + p2y[i] = ((tft.height())/2)+ay*500/az; + } + for (int i=0;i<3;i++) { + tft.drawLine(p2x[i],p2y[i],p2x[i+1],p2y[i+1],BLACK); + tft.drawLine(p2x[i+4],p2y[i+4],p2x[i+5],p2y[i+5],BLACK); + tft.drawLine(p2x[i],p2y[i],p2x[i+4],p2y[i+4],BLACK); + } + tft.drawLine(p2x[3],p2y[3],p2x[0],p2y[0],BLACK); + tft.drawLine(p2x[7],p2y[7],p2x[4],p2y[4],BLACK); + tft.drawLine(p2x[3],p2y[3],p2x[7],p2y[7],BLACK); + delay(15); +} \ No newline at end of file diff --git a/libraries/TFT_ILI9163C-master/examples/display_command/display_command.ino b/libraries/TFT_ILI9163C-master/examples/display_command/display_command.ino new file mode 100644 index 0000000..279b113 --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/display_command/display_command.ino @@ -0,0 +1,51 @@ +/* +Turn display ON/OFF - this command it's almost unusable since it doesn't control the backligh +It result in a white screen! +*/ + + +#include +#include +#include + +// Color definitions +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF + +/* +Teensy3.x and Arduino's + You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 + Arduino's 8 bit: any + DUE: check arduino site + If you do not use reset, tie it to +3V3 + */ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + +void setup() { + tft.begin(); + tft.fillScreen(0xF81F); +} + +void loop(void) { + tft.display(false); + delay(1000); + tft.display(true); + delay(1000); +} diff --git a/libraries/TFT_ILI9163C-master/examples/easyScroll/easyScroll.ino b/libraries/TFT_ILI9163C-master/examples/easyScroll/easyScroll.ino new file mode 100644 index 0000000..dc8be80 --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/easyScroll/easyScroll.ino @@ -0,0 +1,98 @@ +/* +Rudimentary scroll! + */ + + +#include +#include +#include + +// Color definitions +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF + +/* +Teensy3.x and Arduino's + You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 + Arduino's 8 bit: any + DUE: check arduino site + If you do not use reset, tie it to +3V3 + */ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + +void setup() { + tft.begin(); + tft.setRotation(0); + tft.setCursor(0, 0); + tft.setTextColor(WHITE); + tft.setTextSize(1); + tft.println("Hello World!"); + tft.setTextColor(YELLOW); + tft.setTextSize(2); + tft.println(1234.56); + tft.setTextColor(RED); + tft.setTextSize(3); + tft.println(0xDEAD, HEX); + tft.println(); + tft.setTextColor(GREEN); + tft.setTextSize(4); + tft.println("Hello"); + tft.setTextSize(2); + tft.println("I implore thee,"); + tft.setTextSize(1); + tft.println("my foonting turlingdromes."); + tft.println("And hooptiously drangle me"); + tft.println("with crinkly bindlewurdles,"); + tft.println("Or I will rend thee"); + tft.println("in the gobberwarts"); + tft.println("with my blurglecruncheon,"); + tft.println("see if I don't!"); + tft.defineScrollArea(23,50); + //try load again with this commented out! +} + + +int t = 0; + + +void loop(void) { + tft.scroll(t); + if (t > 160) { + t = 0; + } + else { + t++; + } + + delay(10); +} + + +void testFilledRects() { + int n, i, i2, + cx = (tft.width() / 2), + cy = (tft.height() / 2); + n = min(tft.width(), tft.height()); + for(i=n; i>0; i-=6) { + i2 = i / 2; + tft.fillRect(cx-i2, cy-i2, i, i, random(0x0000,0xFFFF)); + tft.drawRect(cx-i2, cy-i2, i, i, random(0x0000,0xFFFF)); + } +} \ No newline at end of file diff --git a/libraries/TFT_ILI9163C-master/examples/minimal/minimal.ino b/libraries/TFT_ILI9163C-master/examples/minimal/minimal.ino new file mode 100644 index 0000000..13ddb64 --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/minimal/minimal.ino @@ -0,0 +1,40 @@ +#include +#include +#include + +// Color definitions +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF + +/* +Teensy3.x and Arduino's +You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 +Arduino's 8 bit: any +DUE: check arduino site +If you do not use reset, tie it to +3V3 +*/ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + +void setup() { + tft.begin(); +} + +void loop(void) { +} \ No newline at end of file diff --git a/libraries/TFT_ILI9163C-master/examples/mood/mood.ino b/libraries/TFT_ILI9163C-master/examples/mood/mood.ino new file mode 100644 index 0000000..9a31d13 --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/mood/mood.ino @@ -0,0 +1,62 @@ +#include +#include +#include + + +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF +#define TRANSPARENT -1 +/* +Teensy3.x and Arduino's +You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 +Arduino's 8 bit: any +DUE: check arduino site +If you do not use reset, tie it to +3V3 +*/ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + + +float angle; + +void setup() +{ + tft.begin(); + +} + +// Translate a hue "angle" -120 to 120 degrees (ie -2PI/3 to 2PI/3) to +// a 6-bit R channel value +// +// This is very slow on a microcontroller, not a great example! +inline int angle_to_channel(float a) { + if (a < -PI) a += 2*PI; + if (a < -2*PI/3 || a > 2*PI/3) return 0; + float f_channel = cos(a*3/4); // remap 120-degree 0-1.0 to 90 ?? + return ceil(f_channel * 255);//63 +} + +void loop() { + uint16_t clr = (((angle_to_channel(angle-4*PI/3)>>1) & 0xF8) << 8) | (((angle_to_channel(angle-2*PI/3)) & 0xFC) << 3) | ((angle_to_channel(angle)>>1) >> 3); + tft.fillScreen(clr); + + angle += 0.01; + if(angle > PI) + angle -= 2*PI; +} \ No newline at end of file diff --git a/libraries/TFT_ILI9163C-master/examples/roundGaugeWithBallistic/roundGaugeWithBallistic.ino b/libraries/TFT_ILI9163C-master/examples/roundGaugeWithBallistic/roundGaugeWithBallistic.ino new file mode 100644 index 0000000..8170e73 --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/roundGaugeWithBallistic/roundGaugeWithBallistic.ino @@ -0,0 +1,120 @@ +/* +ROUND GAUGE EXAMPLE with ballistic! +This example show how to create a round gauge that react like the real one with (almost) correct ballistic +Created by S.U.M.O.T.O.Y - Max MC Costa +If you modify or get better result please let me know +*/ +#include +#include +#include + + + +// Color definitions +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF + + +volatile int16_t curVal1 = 0; +volatile int16_t oldVal1 = 0; + +/* +Teensy3.x and Arduino's +You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 +Arduino's 8 bit: any +DUE: check arduino site +If you do not use reset, tie it to +3V3 +*/ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + + +void setup() { + Serial.begin(9600); + tft.begin(); + drawGauge(63,63,63); +} + +void loop(void) { + curVal1 = random(1,254); + if (oldVal1 != curVal1){ + drawNeedle(curVal1,63,63,63,GREEN,BLACK); + oldVal1 = curVal1; + } +} + +void drawGauge(uint8_t x,uint8_t y,uint8_t r) { + tft.drawCircle(x, y, r,WHITE);//draw instrument container + faceHelper(x,y,r,150,390,1.3);//draw major ticks + if (r > 15) faceHelper(x,y,r,165,375,1.1);//draw minor ticks + +} + +void faceHelper(uint8_t x,uint8_t y,uint8_t r,int from,int to,float dev){ + float dsec,fromSecX,fromSecY,toSecX,toSecY; + int i; + for (i = from;i <= to;i += 30) { + dsec = i * (PI / 180); + fromSecX = cos(dsec) * (r / dev); + fromSecY = sin(dsec) * (r / dev); + toSecX = cos(dsec) * r; + toSecY = sin(dsec) * r; + tft.drawLine(1 + x + fromSecX,1 + y + fromSecY,1 + x + toSecX,1 + y + toSecY,WHITE); + } +} + +void drawNeedle(int16_t val,uint8_t x,uint8_t y,uint8_t r,uint16_t color,uint16_t bcolor){ + uint8_t i; + if (curVal1 > oldVal1){ + for (i = oldVal1; i <= curVal1; i++){ + drawPointerHelper(i-1,63,63,63,bcolor); + drawPointerHelper(i,63,63,63,color); + if ((curVal1 - oldVal1) < (128)) delay(1);//ballistic + } + } + else { + for (i = oldVal1; i >= curVal1; i--){ + drawPointerHelper(i+1,63,63,63,bcolor); + drawPointerHelper(i,63,63,63,color); + //ballistic + if ((oldVal1 - curVal1) >= 128){ + delay(1); + } else { + delay(3); + } + } + } +} + +void drawPointerHelper(int16_t val,uint8_t x,uint8_t y,uint8_t r,uint16_t color) { + float dsec, toSecX, toSecY; + int16_t minValue = 0; + int16_t maxValue = 255; + int fromDegree = 150;//start + int toDegree = 240;//end + if (val > maxValue) val = maxValue; + if (val < minValue) val = minValue; + dsec = (((float)(uint16_t)(val - minValue) / (float)(uint16_t)(maxValue - minValue) * toDegree) + fromDegree) * (PI / 180); + toSecX = cos(dsec) * (r / 1.35); + toSecY = sin(dsec) * (r / 1.35); + tft.drawLine(x, y, 1 + x + toSecX, 1 + y + toSecY, color); + tft.fillCircle(x,y,2,color); +} + + diff --git a/libraries/TFT_ILI9163C-master/examples/simpleBars/simpleBars.ino b/libraries/TFT_ILI9163C-master/examples/simpleBars/simpleBars.ino new file mode 100644 index 0000000..e45677c --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/simpleBars/simpleBars.ino @@ -0,0 +1,82 @@ +#include +#include +#include + +// Color definitions +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF + +#define NBINS 12 +const uint8_t bar_Width = 3; + +uint32_t avrg_TmrF = 0; +uint16_t t_b[NBINS]; + +uint16_t datax_[NBINS]; + +/* +Teensy3.x and Arduino's +You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 +Arduino's 8 bit: any +DUE: check arduino site +If you do not use reset, tie it to +3V3 +*/ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + +void setup(void) { + Serial.begin(38400); + //while(!Serial); + tft.begin(); + tft.setRotation(1); + tft.fillScreen(BLACK); + tft.setTextWrap(true); + tft.setTextColor(WHITE, BLACK); + tft.setCursor(0,0); +} + + +void loop(){ + for (int i=0;i> 3); + tft.fillRect(startX,(vOrigin+1),(bar_Width+3),dataToWidth,BLACK);//mask ok + tft.fillRect(startX,(dataToWidth+vOrigin)+1,(bar_Width+3),((barHeight-2)-dataToWidth),color);//fillRect(X,Y,width,height,color) + } +} diff --git a/libraries/TFT_ILI9163C-master/examples/sleep/sleep.ino b/libraries/TFT_ILI9163C-master/examples/sleep/sleep.ino new file mode 100644 index 0000000..c9802b1 --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/sleep/sleep.ino @@ -0,0 +1,55 @@ +/* +Sleep Command example +Very simple, when sleep on DC/DC converter is stopped, Internal oscillator is stopped, and panel scanning is stopped +MCU interface and memory are still working and the memory keeps its contents. +NOTE: +The led background still active since it's NOT controlled by chip so the result it's a white screen until you turn off +the backlight! +*/ + +#include +#include +#include + +// Color definitions +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF + +/* +Teensy3.x and Arduino's + You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 + Arduino's 8 bit: any + DUE: check arduino site + If you do not use reset, tie it to +3V3 + */ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + +void setup() { + tft.begin(); + tft.fillScreen(0xF800); + delay(500); +} + +void loop(void) { + tft.sleepMode(true); + delay(1000); + tft.sleepMode(false); + delay(1000); +} diff --git a/libraries/TFT_ILI9163C-master/examples/solid3D/solid3D.ino b/libraries/TFT_ILI9163C-master/examples/solid3D/solid3D.ino new file mode 100644 index 0000000..883247e --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/solid3D/solid3D.ino @@ -0,0 +1,306 @@ +/* +From ucg, modified for use with all my libraries. +IMPORTANT! You need my modified Adafruit_GFX library! +https://github.com/sumotoy/Adafruit_GFX/ +*/ + + + +#include +#include +#include + +#ifndef _ADAFRUIT_GFX_VARIANT +#error you need the modified Adafruit_GFX library! +#endif + +#define __CS 10 +#define __DC 6 + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + +struct pt3d +{ + int x, y, z; +}; + +struct surface +{ + uint8_t p[4]; + int16_t z; +}; + +struct pt2d +{ + int x, y; + unsigned is_visible; +}; + + +// define the point at which the observer looks, 3d box will be centered there +#define MX (tft.width()/2) +#define MY (tft.height()/2) + +// define a value that corresponds to "1" +#define U 100 + +// eye to screen distance (fixed) +#define ZS U + +// cube edge length is 2*U +struct pt3d cube[8] = +{ + { -U, -U, U}, + { U, -U, U}, + { U, -U, -U}, + { -U, -U, -U}, + { -U, U, U}, + { U, U, U}, + { U, U, -U}, + { -U, U, -U}, +}; + +// define the surfaces +struct surface cube_surface[6] = +{ + { {0, 1, 2, 3}, 0 }, // bottom + { {4, 5, 6, 7}, 0 }, // top + { {0, 1, 5, 4}, 0 }, // back + + { {3, 7, 6, 2}, 0 }, // front + { {1, 2, 6, 5}, 0 }, // right + { {0, 3, 7, 4}, 0 }, // left +}; + +// define some structures for the copy of the box, calculation will be done there +struct pt3d cube2[8]; +struct pt2d cube_pt[8]; + +// will contain a rectangle border of the box projection into 2d plane +int x_min, x_max; +int y_min, y_max; + +const int16_t sin_tbl[65] = { + 0, 1606, 3196, 4756, 6270, 7723, 9102, 10394, 11585, 12665, 13623, 14449, 15137, 15679, 16069, 16305, 16384, 16305, 16069, 15679, + 15137, 14449, 13623, 12665, 11585, 10394, 9102, 7723, 6270, 4756, 3196, 1606, 0, -1605, -3195, -4755, -6269, -7722, -9101, -10393, + -11584, -12664, -13622, -14448, -15136, -15678, -16068, -16304, -16383, -16304, -16068, -15678, -15136, -14448, -13622, -12664, -11584, -10393, -9101, -7722, + -6269, -4755, -3195, -1605, 0 +}; + +const int16_t cos_tbl[65] = { + 16384, 16305, 16069, 15679, 15137, 14449, 13623, 12665, 11585, 10394, 9102, 7723, 6270, 4756, 3196, 1606, 0, -1605, -3195, -4755, + -6269, -7722, -9101, -10393, -11584, -12664, -13622, -14448, -15136, -15678, -16068, -16304, -16383, -16304, -16068, -15678, -15136, -14448, -13622, -12664, + -11584, -10393, -9101, -7722, -6269, -4755, -3195, -1605, 0, 1606, 3196, 4756, 6270, 7723, 9102, 10394, 11585, 12665, 13623, 14449, + 15137, 15679, 16069, 16305, 16384 +}; + + +void copy_cube(void) +{ + uint8_t i; + for (i = 0; i < 8; i++) + { + cube2[i] = cube[i]; + } +} + +void rotate_cube_y(uint16_t w) +{ + uint8_t i; + int16_t x, z; + /* + x' = x * cos(w) + z * sin(w) + z' = - x * sin(w) + z * cos(w) + */ + for (i = 0; i < 8; i++) + { + x = ((int32_t)cube2[i].x * (int32_t)cos_tbl[w] + (int32_t)cube2[i].z * (int32_t)sin_tbl[w]) >> 14; + z = (-(int32_t)cube2[i].x * (int32_t)sin_tbl[w] + (int32_t)cube2[i].z * (int32_t)cos_tbl[w]) >> 14; + //printf("%d: %d %d --> %d %d\n", i, cube2[i].x, cube2[i].z, x, z); + cube2[i].x = x; + cube2[i].z = z; + } +} + +void rotate_cube_x(uint16_t w) +{ + uint8_t i; + int16_t y, z; + for (i = 0; i < 8; i++) + { + y = ((int32_t)cube2[i].y * (int32_t)cos_tbl[w] + (int32_t)cube2[i].z * (int32_t)sin_tbl[w]) >> 14; + z = (-(int32_t)cube2[i].y * (int32_t)sin_tbl[w] + (int32_t)cube2[i].z * (int32_t)cos_tbl[w]) >> 14; + cube2[i].y = y; + cube2[i].z = z; + } +} + +void trans_cube(uint16_t z) +{ + uint8_t i; + for (i = 0; i < 8; i++) + { + cube2[i].z += z; + } +} + +void reset_min_max(void) +{ + x_min = 0x07fff; + y_min = 0x07fff; + x_max = -0x07fff; + y_max = -0x07fff; +} + +// calculate xs and ys from a 3d value +void convert_3d_to_2d(struct pt3d *p3, struct pt2d *p2) +{ + int32_t t; + p2->is_visible = 1; + if (p3->z >= ZS) + { + t = ZS; + t *= p3->x; + t <<= 1; + t /= p3->z; + if (t >= -MX && t <= MX - 1) + { + t += MX; + p2->x = t; + + if (x_min > t) x_min = t; + if (x_max < t) x_max = t; + + t = ZS; + t *= p3->y; + t <<= 1; + t /= p3->z; + if (t >= -MY && t <= MY - 1) + { + t += MY; + p2->y = t; + if (y_min > t) y_min = t; + if (y_max < t) y_max = t; + } + else + { + p2->is_visible = 0; + } + } + else + { + p2->is_visible = 0; + } + } + else + { + p2->is_visible = 0; + } +} + +void convert_cube(void) +{ + uint8_t i; + reset_min_max(); + for (i = 0; i < 8; i++) + { + convert_3d_to_2d(cube2 + i, cube_pt + i); + } +} + +void calculate_z(void) +{ + uint8_t i, j; + uint16_t z; + for (i = 0; i < 6; i++) + { + z = 0; + for (j = 0; j < 4; j++) + { + z += cube2[cube_surface[i].p[j]].z; + } + z /= 4; + cube_surface[i].z = z; + //printf("%d: z=%d\n", i, z); + } +} + +void draw_cube(void) +{ + uint8_t i, ii; + uint8_t skip_cnt = 3; /* it is known, that the first 3 surfaces are invisible */ + int16_t z, z_upper; + uint16_t color; + + z_upper = 32767; + for (;;) + { + ii = 6; + z = -32767; + for (i = 0; i < 6; i++) + { + if (cube_surface[i].z <= z_upper) + { + if (z < cube_surface[i].z) + { + z = cube_surface[i].z; + ii = i; + } + } + } + + if (ii >= 6) break; + z_upper = cube_surface[ii].z; + cube_surface[ii].z++; + + if (skip_cnt > 0) + { + skip_cnt--; + } + else + { + color = tft.Color565(((ii + 1) & 1) * 255, (((ii + 1) >> 1) & 1) * 255, (((ii + 1) >> 2) & 1) * 255); + tft.fillQuad( + cube_pt[cube_surface[ii].p[0]].x, cube_pt[cube_surface[ii].p[0]].y, + cube_pt[cube_surface[ii].p[1]].x, cube_pt[cube_surface[ii].p[1]].y, + cube_pt[cube_surface[ii].p[2]].x, cube_pt[cube_surface[ii].p[2]].y, + cube_pt[cube_surface[ii].p[3]].x, cube_pt[cube_surface[ii].p[3]].y, color); + + } + } +} + + + +void calc_and_draw(uint16_t w, uint16_t v) +{ + + copy_cube(); + rotate_cube_y(w); + rotate_cube_x(v); + trans_cube(U * 8); + convert_cube(); + calculate_z(); + draw_cube(); +} + + +void setup(void) +{ + tft.begin(); +} + +uint16_t w = 0; +uint16_t v = 0; + +void loop(void) +{ + calc_and_draw(w, v >> 3); + v += 3; + v &= 511; + w++; + w &= 63; + delay(10); + tft.fillRect(x_min, y_min, x_max - x_min + 3, y_max - y_min + 3, 0x0000); +} + diff --git a/libraries/TFT_ILI9163C-master/examples/test/test.ino b/libraries/TFT_ILI9163C-master/examples/test/test.ino new file mode 100644 index 0000000..b03b5be --- /dev/null +++ b/libraries/TFT_ILI9163C-master/examples/test/test.ino @@ -0,0 +1,109 @@ +#include +#include +#include + + +// Color definitions +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF + +/* +Teensy3.x and Arduino's +You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 +Arduino's 8 bit: any +DUE: check arduino site +If you do not use reset, tie it to +3V3 +*/ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + +void setup() { + tft.begin(); +} + +void loop(){ + testLines(random(0x00ff,0xffff)); + delay(100); + testText(); + delay(500); +} + + +unsigned long testText() { + tft.fillScreen(); + unsigned long start = micros(); + tft.setCursor(0, 0); + tft.setTextColor(WHITE); + tft.setTextSize(1); + tft.println("Hello World!"); + tft.setTextColor(YELLOW); + tft.setTextSize(2); + tft.println(1234.56); + tft.setTextColor(RED); + tft.setTextSize(3); + tft.println(0xDEAD, HEX); + tft.println(); + tft.setTextColor(GREEN); + tft.setTextSize(4); + tft.println("Hello"); + return micros() - start; +} + +unsigned long testLines(uint16_t color) { + tft.fillScreen(); + unsigned long start, t; + int x1, y1, x2, y2, + w = tft.width(), + h = tft.height(); + tft.fillScreen(); + x1 = y1 = 0; + y2 = h - 1; + start = micros(); + for(x2=0; x2 +#include +#include + +// Color definitions +#define BLACK 0x0000 +#define BLUE 0x001F +#define RED 0xF800 +#define GREEN 0x07E0 +#define CYAN 0x07FF +#define MAGENTA 0xF81F +#define YELLOW 0xFFE0 +#define WHITE 0xFFFF + +#define NBINS 8 +const uint8_t bar_Width = 7; +uint32_t avrg_TmrF = 0; +uint16_t t_b[NBINS]; + +/* +Teensy3.x and Arduino's +You are using 4 wire SPI here, so: + MOSI: 11//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + MISO: 12//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + SCK: 13//Teensy3.x/Arduino UNO (for MEGA/DUE refere to arduino site) + the rest of pin below: + */ +#define __CS 10 +#define __DC 9 +/* +Teensy 3.x can use: 2,6,9,10,15,20,21,22,23 +Arduino's 8 bit: any +DUE: check arduino site +If you do not use reset, tie it to +3V3 +*/ + + +TFT_ILI9163C tft = TFT_ILI9163C(__CS, __DC); + + +void setup(void) { + Serial.begin(38400); + tft.begin(); + tft.setRotation(1); + tft.fillScreen(BLACK); + tft.setTextWrap(true); + tft.setTextColor(WHITE,BLACK); + tft.setCursor(0,0); + Draw_Table(); +} + + +void loop(){ + for (int i=0;i>= 4; + if (avrg_TmrF != 0) frequency = (8.0 * 16000000.0) / avrg_TmrF; + avrg_TmrF = 0; + //--------------------- FREQ --------------- + tft.setCursor(96,33); + if (frequency < 99) { + tft.print(frequency,2); + } + else{ + tft.print("..."); + } + +/*THD: Total Harmonic Distortion. The harmonic distortion characterises the ratio of the sum of the +harmonics to the fundamental signal. Normally there are the first 6 harmonics used for the +characterisation. +THD = 20 * log (SQRT (SUM (SQR ([Harmonics]))) / [Fundamental])*/ +// ---------------- Vertical VU's ------------------------------------------ + uint32_t total1 = 0; // ALL + uint32_t total2 = 0; // All, Except Fundamental (1). + uint16_t fnd = 0; // Fundamental + + for (int i = 1; i < NBINS; i++) { + int st1 = (i * 10) + 15; // k = 70 / (NBINS -1) + tft.drawRect((st1-1),0,bar_Width,128,WHITE); // Volume + uint32_t vremn1 = t_b[i] >> 4; // V(i) / updt_Rate + uint32_t vremn2 = vremn1 * vremn1; // V(i) ^ 2. + total1 += vremn2; // Total1 = V1^2 + V2^2 + V3^2 + V4^2 + V5^2 + if (i != 1) + total2 += vremn2; // Total2 = V2^2 + V3^2 + V4^2 + V5^2 + else + fnd = vremn1; // Fundamental = V1 + vremn2 = 20 * log10(vremn1+1); // !!! +1 MUST, + int st2 = map(vremn2,0,73,(128-2),0); // 73 dB + tft.fillRect(st1,1,(bar_Width-2),st2,BLACK); // Empty + tft.fillRect(st1,(st2 + 2),(bar_Width-2),(128-2-st2),GREEN); // Fill Up + t_b[i] = 0; +} + + voltag_ac = sqrt(total1) / 20.27; // Hardware Calibration Coefficient /0.39752907 + //-------------RMS-------------------- + tft.setCursor(96,55); + if (voltag_ac < 999) { + tft.print(voltag_ac,1); + } + else{ + tft.print( "..."); + } + + total_thd = 100.0 * sqrt(total2) / fnd; + //-------------THD ------------------------ + tft.setCursor(96,11); + if (total_thd < 9) { + tft.print(total_thd,3); + } + else{ + tft.print( "..."); + } +} \ No newline at end of file diff --git a/libraries/TFT_ILI9163C-master/keywords.txt b/libraries/TFT_ILI9163C-master/keywords.txt new file mode 100644 index 0000000..91d5974 --- /dev/null +++ b/libraries/TFT_ILI9163C-master/keywords.txt @@ -0,0 +1,21 @@ +TFT_ILI9163C KEYWORD1 +begin KEYWORD2 +setAddrWindow KEYWORD2 +pushColor KEYWORD2 +setBrightness KEYWORD2 +writeData KEYWORD2 +setBitrate KEYWORD2 +Color565 KEYWORD2 +setBitrate KEYWORD2 +clearScreen KEYWORD2 +Color24To565 KEYWORD2 +sleepMode KEYWORD2 +display KEYWORD2 +startPushData KEYWORD2 +pushData KEYWORD2 +endPushData KEYWORD2 +defineScrollArea KEYWORD2 +writeScreen24 KEYWORD2 +idleMode KEYWORD2 +errorCode KEYWORD2 + diff --git a/libraries/TFT_ILI9163C-master/library.json b/libraries/TFT_ILI9163C-master/library.json new file mode 100644 index 0000000..724b9ab --- /dev/null +++ b/libraries/TFT_ILI9163C-master/library.json @@ -0,0 +1,18 @@ +{ + "name": "TFT_ILI9163", + "keywords": "display, tft, graphics, spi", + "description": "A fast SPI driver for TFT drived by ILI9163C, fully SPI Transaction compatible and very fast with Teensy 3", + "repository": + { + "type": "git", + "url": "https://github.com/sumotoy/TFT_ILI9163C.git" + }, + "exclude": "_utility", + "frameworks": "arduino", + "platforms": + [ + "atmelavr", + "atmelsam", + "teensy" + ] +} diff --git a/libraries/TFT_ILI9163C-master/library.properties b/libraries/TFT_ILI9163C-master/library.properties new file mode 100644 index 0000000..0947fba --- /dev/null +++ b/libraries/TFT_ILI9163C-master/library.properties @@ -0,0 +1,9 @@ +name=TFT_ILI9163C +version=0.9 +author=Max MC Costa +maintainer=sumotoy +sentence=A fast SPI driver for TFT drived by ILI9163C, fully SPI Transaction compatible and very fast with Teensy 3 +paragraph=This library works with many MCU's included Arduino's but it's particular fast with Teensy 3, Teensy 3.1. +category=Display +url=https://github.com/sumotoy/TFT_ILI9163C +architectures=* diff --git a/libraries/Tone-master/.gitignore b/libraries/Tone-master/.gitignore new file mode 100644 index 0000000..d55065f --- /dev/null +++ b/libraries/Tone-master/.gitignore @@ -0,0 +1,6 @@ +# Wiring .gitignore +# For Libraries and Sketches + +*.bak +*~ +build/ diff --git a/libraries/Tone-master/README.md b/libraries/Tone-master/README.md new file mode 100644 index 0000000..edae538 --- /dev/null +++ b/libraries/Tone-master/README.md @@ -0,0 +1,253 @@ +# Tone Library # + +---- + +## Description ## + +This is an Arduino Library to produce square-wave of the specified frequency (and 50% duty cycle) on any Arduino pin. + +A duration can optionally be specified, otherwise the wave continues until `stop()` is called. + +The pin can be connected to a piezo buzzer or other speaker to play tones. + +Be sure to try out the RTTTL (RingTone Text Transfer Language) example! + +### Arduino Core Version ### + +A simplified version of the Tone library has been incorporated into the Arduino core since 0018. It only provides a single tone (since only one timer is used). You can find the core documentation [here](http://arduino.cc/en/Reference/Tone). + +Check out the [tutorial](http://itp.nyu.edu/physcomp/labs/labs-arduino-digital-and-analog/tone-output-using-an-arduino/) by Tom Igoe at NYU's Interactive Telecommunications Program (ITP). It demonstrates how to use the core `tone()` and `noTone()` commands. + +### _WARNING_ ### +*_Do not connect the pin directly to some sort of audio input. The voltage is considerably higher than a standard [line level voltages](http://en.wikipedia.org/wiki/Line_level), and can damage sound card inputs, etc. You could use a voltage divider to bring the voltage down, but you have been warned._* + +*_You MUST have a resistor in line with the speaker, or you WILL damage your controller._* + +---- + +## Download and Installation ## + +* [Tone Library - Latest Version](https://github.com/bhagman/Tone/archive/master.zip) + +Unzip the folder and rename it to `Tone`, then move it to your `arduinosketchfolder/libraries/` folder. + +---- + +## Hardware Connections/Requirements ## + + * Just connect the digital pin to a speaker (with a resistor - say 1K - in line), and the other side of the speaker to ground (GND). + + + + +
+Tone-Arduino-Connections + +Tone-Wiring-Connections
+ + * You can use a potentiometer to control the volume. Use a 10K Ohm potentiometer (variable resistor) in line with the 1K Ohm resistor connected to the speaker. + + * Using this library will affect usage of the PWM outputs, so be aware. + + * Also, although it's the last timer to be allocated, timer 0 (which is used for `millis()` among other things) will be affected if used. + +---- + +## Library Usage ## + +### Instantiation/Creation ### + +```arduino +Tone tone1; + +void setup(void) +{ + tone1.begin(13); +} + +``` + + +### Properties ### + * No properties. + +### Methods ### + * `begin(`_*`pin`*_`)` - prepares a pin for playing a tone. + * `isPlaying()` - returns `true` if tone is playing, `false` if not. + * `play(`_*`frequency`*_` [, `_*`duration`*_`])` - play a tone. + * _*`frequency`*_ is in Hertz, and the _*`duration`*_ is in milliseconds. + * _*`duration`*_ is optional. If _*`duration`*_ is not given, tone will play continuously until _*`stop()`*_ is called. + * `play()` is [non-blocking](http://en.wikipedia.org/wiki/Non-blocking_synchronization). Once called, `play()` will return immediately. If _*`duration`*_ is given, the tone will play for that amount of time, and then stop automatically. + * `stop()` - stop playing a tone. + +### Constants ### + +Below is a list of constant values of frequencies for notes. (These are included in the library). + +e.g. + +```arduino + tone1.play(NOTE_B3); +``` + +#### Musical Notes #### + +| *Constant Name* | *Frequency (Hz)* | +|-----------------|------------------| +| NOTE_B0 | 31 | +| NOTE_C1 | 33 | +| NOTE_CS1 | 35 | +| NOTE_D1 | 37 | +| NOTE_DS1 | 39 | +| NOTE_E1 | 41 | +| NOTE_F1 | 44 | +| NOTE_FS1 | 46 | +| NOTE_G1 | 49 | +| NOTE_GS1 | 52 | +| NOTE_A1 | 55 | +| NOTE_AS1 | 58 | +| NOTE_B1 | 62 | +| NOTE_C2 | 65 | +| NOTE_CS2 | 69 | +| NOTE_D2 | 73 | +| NOTE_DS2 | 78 | +| NOTE_E2 | 82 | +| NOTE_F2 | 87 | +| NOTE_FS2 | 93 | +| NOTE_G2 | 98 | +| NOTE_GS2 | 104 | +| NOTE_A2 | 110 | +| NOTE_AS2 | 117 | +| NOTE_B2 | 123 | +| NOTE_C3 | 131 | +| NOTE_CS3 | 139 | +| NOTE_D3 | 147 | +| NOTE_DS3 | 156 | +| NOTE_E3 | 165 | +| NOTE_F3 | 175 | +| NOTE_FS3 | 185 | +| NOTE_G3 | 196 | +| NOTE_GS3 | 208 | +| NOTE_A3 | 220 | +| NOTE_AS3 | 233 | +| NOTE_B3 | 247 | +| NOTE_C4 | 262 | +| NOTE_CS4 | 277 | +| NOTE_D4 | 294 | +| NOTE_DS4 | 311 | +| NOTE_E4 | 330 | +| NOTE_F4 | 349 | +| NOTE_FS4 | 370 | +| NOTE_G4 | 392 | +| NOTE_GS4 | 415 | +| NOTE_A4 | 440 | +| NOTE_AS4 | 466 | +| NOTE_B4 | 494 | +| NOTE_C5 | 523 | +| NOTE_CS5 | 554 | +| NOTE_D5 | 587 | +| NOTE_DS5 | 622 | +| NOTE_E5 | 659 | +| NOTE_F5 | 698 | +| NOTE_FS5 | 740 | +| NOTE_G5 | 784 | +| NOTE_GS5 | 831 | +| NOTE_A5 | 880 | +| NOTE_AS5 | 932 | +| NOTE_B5 | 988 | +| NOTE_C6 | 1047 | +| NOTE_CS6 | 1109 | +| NOTE_D6 | 1175 | +| NOTE_DS6 | 1245 | +| NOTE_E6 | 1319 | +| NOTE_F6 | 1397 | +| NOTE_FS6 | 1480 | +| NOTE_G6 | 1568 | +| NOTE_GS6 | 1661 | +| NOTE_A6 | 1760 | +| NOTE_AS6 | 1865 | +| NOTE_B6 | 1976 | +| NOTE_C7 | 2093 | +| NOTE_CS7 | 2217 | +| NOTE_D7 | 2349 | +| NOTE_DS7 | 2489 | +| NOTE_E7 | 2637 | +| NOTE_F7 | 2794 | +| NOTE_FS7 | 2960 | +| NOTE_G7 | 3136 | +| NOTE_GS7 | 3322 | +| NOTE_A7 | 3520 | +| NOTE_AS7 | 3729 | +| NOTE_B7 | 3951 | +| NOTE_C8 | 4186 | +| NOTE_CS8 | 4435 | +| NOTE_D8 | 4699 | +| NOTE_DS8 | 4978 | + + +### Quick example ### + +Play a 440 Hz - musical note of 4^th^ octave A - on pin 13: +```arduino +#include + +Tone tone1; + +void setup() +{ + tone1.begin(13); + tone1.play(NOTE_A4); +} + +void loop() +{ +} +``` + +---- + +## Ugly Details ## + +The library uses the hardware timers on the microcontroller to generate square-wave tones in the audible range. + +You can output the tones on any pin (arbitrary). The number of tones that can be played simultaneously depends on the number of hardware timers (with CTC capability) available on the microcontroller. + + * ATmega8: 2 (timers 2, and 1) + * ATmega168/328: 3 (timers 2, 1, and 0) + * ATmega1280: 6 (timers 2, 3, 4, 5, 1, 0) + +The timer order given above is the order in which the timers are allocated. Timer 0 is a sensitive timer on the Arduino since it provides `millis()` and PWM functionality. + +The range of frequencies that can be produced depends on the microcontroller clock frequency and the timer which is being used: + +|*MCU clock*|*8 bit timer Flow*|*16 bit timer Flow*|*Fhigh*| +|-----------|--------------------|---------------------|---------| +|8 MHz |16 Hz |1 Hz (1/16 Hz) |4 MHz | +|16 MHz |31 Hz |1 Hz (1/8 Hz) |8 MHz | + +Although Fhigh can go as high as 8 MHz, the [human hearing range](http://en.wikipedia.org/wiki/Hearing_range#Humans) is typically as high as 20 kHz. + +Tone accuracy is dependent on the timer prescalar. Frequency quantization occurs as the frequencies increase per prescalar. + +If you used a 16 bit timer (e.g. timer 1, or timers 3,4,5 on '1280), you could generate "tones" down to 1/8 Hz (one cycle every 8 seconds), although the library only accepts integers for frequency. + +After all is said and done, because `play()` only accepts unsigned integers for frequency, the maximum frequency that can be produced is 65535 Hz - which, after rounding, results in a 65573.77 Hz "tone" on a 16 MHz part. Even if play accepted larger values for frequency, you couldn't achieve better than around 80KHz with the Tone library because the pin toggling is done in software. Each toggle, in software, requires _AT LEAST_ 50+ cycles. + +---- + +## Links ## + +### Projects/Examples Using Tone Library and Wiring Framework Version of `tone()` ### + + * [Tom Igoe - Tone Output using an Arduino](http://itp.nyu.edu/physcomp/labs/labs-arduino-digital-and-analog/tone-output-using-an-arduino/) + * [Evan Kale - Build Your Own Metal Detector with an Arduino](http://www.allaboutcircuits.com/projects/metal-detector-with-arduino/) + +### RTTTL Sites ### + + * http://merwin.bespin.org/db/rts/index.php + * http://www.cellringtones.com/ + * http://arcadetones.emuunlim.com/ + +### Other ### + + * [Arduino sketch for high frequency precision sine wave tone sound synthesis](http://www.adrianfreed.com/content/arduino-sketch-high-frequency-precision-sine-wave-tone-sound-synthesis) diff --git a/libraries/Tone-master/Tone.cpp b/libraries/Tone-master/Tone.cpp new file mode 100644 index 0000000..6de2ae9 --- /dev/null +++ b/libraries/Tone-master/Tone.cpp @@ -0,0 +1,579 @@ +/* +|| @author Brett Hagman +|| @contribution Fotis Papadopoulos +|| @url http://wiring.org.co/ +|| @url http://roguerobotics.com/ +|| +|| @description +|| | A Software Digital Square Wave Tone Generation Library +|| | +|| | Written by Brett Hagman +|| | http://www.roguerobotics.com/ +|| | bhagman@roguerobotics.com, bhagman@wiring.org.co +|| | +|| | This is a Wiring Framework (Arduino) library to produce square-wave +|| | tones on an arbitrary pin. +|| | +|| | You can make multiple instances of the Tone object, to create tones on +|| | different pins. +|| | +|| | The number of tones that can be generated at the same time is limited +|| | by the number of hardware timers available on the hardware. +|| | (e.g. ATmega328 has 3 available timers, and the ATmega1280 has 6 timers) +|| | +|| | A simplified (single tone) version of this library has been included +|| | in the Wiring Framework since Wiring 0025 and in the Arduino distribution +|| | since Arduino 0018. +|| | +|| # +|| +|| @license Please see the accompanying LICENSE.txt file for this project. +|| +|| @name Software PWM Library +|| @type Library +|| @target Atmel AVR 8 Bit +|| +|| @version 1.0.0 +|| +*/ + +#if defined(WIRING) + #include +#elif ARDUINO >= 100 + #include +#else + #include +#endif + +#include "Tone.h" + +#if defined(__AVR_ATmega8__) +#define TCCR2A TCCR2 +#define TCCR2B TCCR2 +#define COM2A1 COM21 +#define COM2A0 COM20 +#define OCR2A OCR2 +#define TIMSK2 TIMSK +#define OCIE2A OCIE2 +#define TIMER2_COMPA_vect TIMER2_COMP_vect +#define TIMSK1 TIMSK +#endif + +// timerx_toggle_count: +// > 0 - duration specified +// = 0 - stopped +// < 0 - infinitely (until stop() method called, or new play() called) + +#if !defined(__AVR_ATmega8__) +volatile int32_t timer0_toggle_count; +volatile uint8_t *timer0_pin_port; +volatile uint8_t timer0_pin_mask; +#endif + +volatile int32_t timer1_toggle_count; +volatile uint8_t *timer1_pin_port; +volatile uint8_t timer1_pin_mask; +volatile int32_t timer2_toggle_count; +volatile uint8_t *timer2_pin_port; +volatile uint8_t timer2_pin_mask; + +#if defined(__AVR_ATmega1280__) +volatile int32_t timer3_toggle_count; +volatile uint8_t *timer3_pin_port; +volatile uint8_t timer3_pin_mask; +volatile int32_t timer4_toggle_count; +volatile uint8_t *timer4_pin_port; +volatile uint8_t timer4_pin_mask; +volatile int32_t timer5_toggle_count; +volatile uint8_t *timer5_pin_port; +volatile uint8_t timer5_pin_mask; +#endif + + +#if defined(__AVR_ATmega1280__) + +#define AVAILABLE_TONE_PINS 6 + +// Leave timers 1, and zero to last. +const uint8_t PROGMEM tone_pin_to_timer_PGM[] = { 2, 3, 4, 5, 1, 0 }; + +#elif defined(__AVR_ATmega8__) + +#define AVAILABLE_TONE_PINS 2 + +const uint8_t PROGMEM tone_pin_to_timer_PGM[] = { 2, 1 }; + +#else + +#define AVAILABLE_TONE_PINS 3 + +// Leave timer 0 to last. +const uint8_t PROGMEM tone_pin_to_timer_PGM[] = { 2, 1, 0 }; + +#endif + + +// Initialize our pin count + +uint8_t Tone::_tone_pin_count = 0; + + +// Interrupt routines +#if !defined(__AVR_ATmega8__) +#ifdef WIRING +void Tone_Timer0_Interrupt(void) +#else +ISR(TIMER0_COMPA_vect) +#endif +{ + if (timer0_toggle_count != 0) + { + // toggle the pin + *timer0_pin_port ^= timer0_pin_mask; + + if (timer0_toggle_count > 0) + timer0_toggle_count--; + } + else + { + TIMSK0 &= ~(1 << OCIE0A); // disable the interrupt + *timer0_pin_port &= ~(timer0_pin_mask); // keep pin low after stop + } +} +#endif + + +#ifdef WIRING +void Tone_Timer1_Interrupt(void) +#else +ISR(TIMER1_COMPA_vect) +#endif +{ + if (timer1_toggle_count != 0) + { + // toggle the pin + *timer1_pin_port ^= timer1_pin_mask; + + if (timer1_toggle_count > 0) + timer1_toggle_count--; + } + else + { + TIMSK1 &= ~(1 << OCIE1A); // disable the interrupt + *timer1_pin_port &= ~(timer1_pin_mask); // keep pin low after stop + } +} + + +#ifdef WIRING +void Tone_Timer2_Interrupt(void) +#else +ISR(TIMER2_COMPA_vect) +#endif +{ + int32_t temp_toggle_count = timer2_toggle_count; + + if (temp_toggle_count != 0) + { + // toggle the pin + *timer2_pin_port ^= timer2_pin_mask; + + if (temp_toggle_count > 0) + temp_toggle_count--; + } + else + { + TIMSK2 &= ~(1 << OCIE2A); // disable the interrupt + *timer2_pin_port &= ~(timer2_pin_mask); // keep pin low after stop + } + + timer2_toggle_count = temp_toggle_count; +} + + + +#if defined(__AVR_ATmega1280__) + +#ifdef WIRING +void Tone_Timer3_Interrupt(void) +#else +ISR(TIMER3_COMPA_vect) +#endif +{ + if (timer3_toggle_count != 0) + { + // toggle the pin + *timer3_pin_port ^= timer3_pin_mask; + + if (timer3_toggle_count > 0) + timer3_toggle_count--; + } + else + { + TIMSK3 &= ~(1 << OCIE3A); // disable the interrupt + *timer3_pin_port &= ~(timer3_pin_mask); // keep pin low after stop + } +} + +#ifdef WIRING +void Tone_Timer4_Interrupt(void) +#else +ISR(TIMER4_COMPA_vect) +#endif +{ + if (timer4_toggle_count != 0) + { + // toggle the pin + *timer4_pin_port ^= timer4_pin_mask; + + if (timer4_toggle_count > 0) + timer4_toggle_count--; + } + else + { + TIMSK4 &= ~(1 << OCIE4A); // disable the interrupt + *timer4_pin_port &= ~(timer4_pin_mask); // keep pin low after stop + } +} + +#ifdef WIRING +void Tone_Timer5_Interrupt(void) +#else +ISR(TIMER5_COMPA_vect) +#endif +{ + if (timer5_toggle_count != 0) + { + // toggle the pin + *timer5_pin_port ^= timer5_pin_mask; + + if (timer5_toggle_count > 0) + timer5_toggle_count--; + } + else + { + TIMSK5 &= ~(1 << OCIE5A); // disable the interrupt + *timer5_pin_port &= ~(timer5_pin_mask); // keep pin low after stop + } +} + +#endif + + +void Tone::begin(uint8_t tonePin) +{ + if (_tone_pin_count < AVAILABLE_TONE_PINS) + { + _pin = tonePin; + _timer = pgm_read_byte(tone_pin_to_timer_PGM + _tone_pin_count); + _tone_pin_count++; + + // Set timer specific stuff + // All timers in CTC mode + // 8 bit timers will require changing prescalar values, + // whereas 16 bit timers are set to either ck/1 or ck/64 prescalar + switch (_timer) + { +#if !defined(__AVR_ATmega8__) + case 0: + // 8 bit timer + TCCR0A = 0; + TCCR0B = 0; + bitWrite(TCCR0A, WGM01, 1); + bitWrite(TCCR0B, CS00, 1); + timer0_pin_port = portOutputRegister(digitalPinToPort(_pin)); + timer0_pin_mask = digitalPinToBitMask(_pin); +#ifdef WIRING + Timer0.attachInterrupt(INTERRUPT_COMPARE_MATCH_A, Tone_Timer0_Interrupt); +#endif + break; +#endif + + case 1: + // 16 bit timer + TCCR1A = 0; + TCCR1B = 0; + bitWrite(TCCR1B, WGM12, 1); + bitWrite(TCCR1B, CS10, 1); + timer1_pin_port = portOutputRegister(digitalPinToPort(_pin)); + timer1_pin_mask = digitalPinToBitMask(_pin); +#ifdef WIRING + Timer1.attachInterrupt(INTERRUPT_COMPARE_MATCH_A, Tone_Timer1_Interrupt); +#endif + break; + case 2: + // 8 bit timer + TCCR2A = 0; + TCCR2B = 0; + bitWrite(TCCR2A, WGM21, 1); + bitWrite(TCCR2B, CS20, 1); + timer2_pin_port = portOutputRegister(digitalPinToPort(_pin)); + timer2_pin_mask = digitalPinToBitMask(_pin); +#ifdef WIRING + Timer2.attachInterrupt(INTERRUPT_COMPARE_MATCH_A, Tone_Timer2_Interrupt); +#endif + break; + +#if defined(__AVR_ATmega1280__) + case 3: + // 16 bit timer + TCCR3A = 0; + TCCR3B = 0; + bitWrite(TCCR3B, WGM32, 1); + bitWrite(TCCR3B, CS30, 1); + timer3_pin_port = portOutputRegister(digitalPinToPort(_pin)); + timer3_pin_mask = digitalPinToBitMask(_pin); +#ifdef WIRING + Timer3.attachInterrupt(INTERRUPT_COMPARE_MATCH_A, Tone_Timer3_Interrupt); +#endif + break; + case 4: + // 16 bit timer + TCCR4A = 0; + TCCR4B = 0; + bitWrite(TCCR4B, WGM42, 1); + bitWrite(TCCR4B, CS40, 1); + timer4_pin_port = portOutputRegister(digitalPinToPort(_pin)); + timer4_pin_mask = digitalPinToBitMask(_pin); +#ifdef WIRING + Timer4.attachInterrupt(INTERRUPT_COMPARE_MATCH_A, Tone_Timer4_Interrupt); +#endif + break; + case 5: + // 16 bit timer + TCCR5A = 0; + TCCR5B = 0; + bitWrite(TCCR5B, WGM52, 1); + bitWrite(TCCR5B, CS50, 1); + timer5_pin_port = portOutputRegister(digitalPinToPort(_pin)); + timer5_pin_mask = digitalPinToBitMask(_pin); +#ifdef WIRING + Timer5.attachInterrupt(INTERRUPT_COMPARE_MATCH_A, Tone_Timer5_Interrupt); +#endif + break; +#endif + } + } + else + { + // disabled + _timer = -1; + } +} + + + +// frequency (in hertz) and duration (in milliseconds). + +void Tone::play(uint16_t frequency, uint32_t duration) +{ + uint8_t prescalarbits = 0b001; + int32_t toggle_count = 0; + uint32_t ocr = 0; + + if (_timer >= 0) + { + // Set the pinMode as OUTPUT + pinMode(_pin, OUTPUT); + + // if we are using an 8 bit timer, scan through prescalars to find the best fit + if (_timer == 0 || _timer == 2) + { + ocr = F_CPU / frequency / 2 - 1; + prescalarbits = 0b001; // ck/1: same for both timers + if (ocr > 255) + { + ocr = F_CPU / frequency / 2 / 8 - 1; + prescalarbits = 0b010; // ck/8: same for both timers + + if (_timer == 2 && ocr > 255) + { + ocr = F_CPU / frequency / 2 / 32 - 1; + prescalarbits = 0b011; + } + + if (ocr > 255) + { + ocr = F_CPU / frequency / 2 / 64 - 1; + prescalarbits = _timer == 0 ? 0b011 : 0b100; + + if (_timer == 2 && ocr > 255) + { + ocr = F_CPU / frequency / 2 / 128 - 1; + prescalarbits = 0b101; + } + + if (ocr > 255) + { + ocr = F_CPU / frequency / 2 / 256 - 1; + prescalarbits = _timer == 0 ? 0b100 : 0b110; + if (ocr > 255) + { + // can't do any better than /1024 + ocr = F_CPU / frequency / 2 / 1024 - 1; + prescalarbits = _timer == 0 ? 0b101 : 0b111; + } + } + } + } + +#if !defined(__AVR_ATmega8__) + if (_timer == 0) + TCCR0B = (TCCR0B & 0b11111000) | prescalarbits; + else +#endif + TCCR2B = (TCCR2B & 0b11111000) | prescalarbits; + } + else + { + // two choices for the 16 bit timers: ck/1 or ck/64 + ocr = F_CPU / frequency / 2 - 1; + + prescalarbits = 0b001; + if (ocr > 0xffff) + { + ocr = F_CPU / frequency / 2 / 64 - 1; + prescalarbits = 0b011; + } + + if (_timer == 1) + TCCR1B = (TCCR1B & 0b11111000) | prescalarbits; +#if defined(__AVR_ATmega1280__) + else if (_timer == 3) + TCCR3B = (TCCR3B & 0b11111000) | prescalarbits; + else if (_timer == 4) + TCCR4B = (TCCR4B & 0b11111000) | prescalarbits; + else if (_timer == 5) + TCCR5B = (TCCR5B & 0b11111000) | prescalarbits; +#endif + + } + + + // Calculate the toggle count + if (duration > 0) + { + toggle_count = 2 * frequency * duration / 1000; + } + else + { + toggle_count = -1; + } + + // Set the OCR for the given timer, + // set the toggle count, + // then turn on the interrupts + switch (_timer) + { + +#if !defined(__AVR_ATmega8__) + case 0: + OCR0A = ocr; + timer0_toggle_count = toggle_count; + bitWrite(TIMSK0, OCIE0A, 1); + break; +#endif + + case 1: + OCR1A = ocr; + timer1_toggle_count = toggle_count; + bitWrite(TIMSK1, OCIE1A, 1); + break; + case 2: + OCR2A = ocr; + timer2_toggle_count = toggle_count; + bitWrite(TIMSK2, OCIE2A, 1); + break; + +#if defined(__AVR_ATmega1280__) + case 3: + OCR3A = ocr; + timer3_toggle_count = toggle_count; + bitWrite(TIMSK3, OCIE3A, 1); + break; + case 4: + OCR4A = ocr; + timer4_toggle_count = toggle_count; + bitWrite(TIMSK4, OCIE4A, 1); + break; + case 5: + OCR5A = ocr; + timer5_toggle_count = toggle_count; + bitWrite(TIMSK5, OCIE5A, 1); + break; +#endif + + } + } +} + + +void Tone::stop() +{ + switch (_timer) + { +#if !defined(__AVR_ATmega8__) + case 0: + TIMSK0 &= ~(1 << OCIE0A); + break; +#endif + case 1: + TIMSK1 &= ~(1 << OCIE1A); + break; + case 2: + TIMSK2 &= ~(1 << OCIE2A); + break; + +#if defined(__AVR_ATmega1280__) + case 3: + TIMSK3 &= ~(1 << OCIE3A); + break; + case 4: + TIMSK4 &= ~(1 << OCIE4A); + break; + case 5: + TIMSK5 &= ~(1 << OCIE5A); + break; +#endif + } + + digitalWrite(_pin, 0); +} + + +bool Tone::isPlaying(void) +{ + bool returnvalue = false; + + switch (_timer) + { +#if !defined(__AVR_ATmega8__) + case 0: + returnvalue = (TIMSK0 & (1 << OCIE0A)); + break; +#endif + + case 1: + returnvalue = (TIMSK1 & (1 << OCIE1A)); + break; + case 2: + returnvalue = (TIMSK2 & (1 << OCIE2A)); + break; + +#if defined(__AVR_ATmega1280__) + case 3: + returnvalue = (TIMSK3 & (1 << OCIE3A)); + break; + case 4: + returnvalue = (TIMSK4 & (1 << OCIE4A)); + break; + case 5: + returnvalue = (TIMSK5 & (1 << OCIE5A)); + break; +#endif + + } + return returnvalue; +} + + diff --git a/libraries/Tone-master/Tone.h b/libraries/Tone-master/Tone.h new file mode 100644 index 0000000..c20cb27 --- /dev/null +++ b/libraries/Tone-master/Tone.h @@ -0,0 +1,159 @@ +/* +|| @author Brett Hagman +|| @contribution Fotis Papadopoulos +|| @url http://wiring.org.co/ +|| @url http://roguerobotics.com/ +|| +|| @description +|| | A Software Digital Square Wave Tone Generation Library +|| | +|| | Written by Brett Hagman +|| | http://www.roguerobotics.com/ +|| | bhagman@roguerobotics.com, bhagman@wiring.org.co +|| | +|| | This is a Wiring Framework (Arduino) library to produce square-wave +|| | tones on an arbitrary pin. +|| | +|| | You can make multiple instances of the Tone object, to create tones on +|| | different pins. +|| | +|| | The number of tones that can be generated at the same time is limited +|| | by the number of hardware timers available on the hardware. +|| | (e.g. ATmega328 has 3 available timers, and the ATmega1280 has 6 timers) +|| | +|| | A simplified (single tone) version of this library has been included +|| | in the Wiring Framework since Wiring 0025 and in the Arduino distribution +|| | since Arduino 0018. +|| | +|| # +|| +|| @license Please see the accompanying LICENSE.txt file for this project. +|| +|| @name Software PWM Library +|| @type Library +|| @target Atmel AVR 8 Bit +|| +|| @version 1.0.0 +|| +*/ + +#ifndef _Tone_h +#define _Tone_h + +#include + +/* +|| Public Constants +*/ + +#define NOTE_B0 31 +#define NOTE_C1 33 +#define NOTE_CS1 35 +#define NOTE_D1 37 +#define NOTE_DS1 39 +#define NOTE_E1 41 +#define NOTE_F1 44 +#define NOTE_FS1 46 +#define NOTE_G1 49 +#define NOTE_GS1 52 +#define NOTE_A1 55 +#define NOTE_AS1 58 +#define NOTE_B1 62 +#define NOTE_C2 65 +#define NOTE_CS2 69 +#define NOTE_D2 73 +#define NOTE_DS2 78 +#define NOTE_E2 82 +#define NOTE_F2 87 +#define NOTE_FS2 93 +#define NOTE_G2 98 +#define NOTE_GS2 104 +#define NOTE_A2 110 +#define NOTE_AS2 117 +#define NOTE_B2 123 +#define NOTE_C3 131 +#define NOTE_CS3 139 +#define NOTE_D3 147 +#define NOTE_DS3 156 +#define NOTE_E3 165 +#define NOTE_F3 175 +#define NOTE_FS3 185 +#define NOTE_G3 196 +#define NOTE_GS3 208 +#define NOTE_A3 220 +#define NOTE_AS3 233 +#define NOTE_B3 247 +#define NOTE_C4 262 +#define NOTE_CS4 277 +#define NOTE_D4 294 +#define NOTE_DS4 311 +#define NOTE_E4 330 +#define NOTE_F4 349 +#define NOTE_FS4 370 +#define NOTE_G4 392 +#define NOTE_GS4 415 +#define NOTE_A4 440 +#define NOTE_AS4 466 +#define NOTE_B4 494 +#define NOTE_C5 523 +#define NOTE_CS5 554 +#define NOTE_D5 587 +#define NOTE_DS5 622 +#define NOTE_E5 659 +#define NOTE_F5 698 +#define NOTE_FS5 740 +#define NOTE_G5 784 +#define NOTE_GS5 831 +#define NOTE_A5 880 +#define NOTE_AS5 932 +#define NOTE_B5 988 +#define NOTE_C6 1047 +#define NOTE_CS6 1109 +#define NOTE_D6 1175 +#define NOTE_DS6 1245 +#define NOTE_E6 1319 +#define NOTE_F6 1397 +#define NOTE_FS6 1480 +#define NOTE_G6 1568 +#define NOTE_GS6 1661 +#define NOTE_A6 1760 +#define NOTE_AS6 1865 +#define NOTE_B6 1976 +#define NOTE_C7 2093 +#define NOTE_CS7 2217 +#define NOTE_D7 2349 +#define NOTE_DS7 2489 +#define NOTE_E7 2637 +#define NOTE_F7 2794 +#define NOTE_FS7 2960 +#define NOTE_G7 3136 +#define NOTE_GS7 3322 +#define NOTE_A7 3520 +#define NOTE_AS7 3729 +#define NOTE_B7 3951 +#define NOTE_C8 4186 +#define NOTE_CS8 4435 +#define NOTE_D8 4699 +#define NOTE_DS8 4978 + + +/* +|| Definitions +*/ + +class Tone +{ + public: + void begin(uint8_t tonePin); + bool isPlaying(); + void play(uint16_t frequency, uint32_t duration = 0); + void stop(); + + private: + static uint8_t _tone_pin_count; + uint8_t _pin; + int8_t _timer; +}; + +#endif + diff --git a/libraries/Tone-master/changelog.txt b/libraries/Tone-master/changelog.txt new file mode 100644 index 0000000..533d91c --- /dev/null +++ b/libraries/Tone-master/changelog.txt @@ -0,0 +1,16 @@ +Tone Library Changelog + +Version Modified By Date Comments +------- ----------- -------- -------- +0001 B Hagman 09/08/02 Initial coding +0002 B Hagman 09/08/18 Fixed: Multiple pins. +0003 B Hagman 09/08/18 Fixed: Moved initialization from constructor to + begin(). +0004 B Hagman 09/09/26 Fixed: Problems with ATmega8. +0005 B Hagman 09/11/23 Fixed: Scanned prescalars for best fit on 8 bit + timers + 09/11/25 Fixed: Pin toggle method to XOR. + 09/11/25 Fixed: timer0 from being excluded. +0006 B Hagman 10/03/21 Fixed: License updates, minor fixes. + B Hagman 10/07/17 Fixed: (more) problems with ATmega8 (thanks to Pete62) +1.0.0 B Hagman 15/04/14 Migration to GitHub, including fixes for Wiring and Arduino. diff --git a/libraries/Tone-master/examples/DTMFTest/DTMFTest.pde b/libraries/Tone-master/examples/DTMFTest/DTMFTest.pde new file mode 100644 index 0000000..3d31569 --- /dev/null +++ b/libraries/Tone-master/examples/DTMFTest/DTMFTest.pde @@ -0,0 +1,46 @@ +// DTMF (Dual Tone Multiple Frequency) Demonstration + +// http://en.wikipedia.org/wiki/Dual-tone_multi-frequency + +// To mix the output of the signals to output to a small speaker (i.e. 8 Ohms or higher), +// simply use 1K Ohm resistors from each output pin and tie them together at the speaker. +// Don't forget to connect the other side of the speaker to ground! + +#include + +Tone freq1; +Tone freq2; + +const int DTMF_freq1[] = { 1336, 1209, 1336, 1477, 1209, 1336, 1477, 1209, 1336, 1477 }; +const int DTMF_freq2[] = { 941, 697, 697, 697, 770, 770, 770, 852, 852, 852 }; + +void setup() +{ + Serial.begin(9600); + freq1.begin(11); + freq2.begin(12); +} + +void playDTMF(uint8_t number, long duration) +{ + freq1.play(DTMF_freq1[number], duration); + freq2.play(DTMF_freq2[number], duration); +} + + +void loop() +{ + int i; + uint8_t phone_number[] = { 8, 6, 7, 5, 3, 0 ,9 }; + + for(i = 0; i < sizeof(phone_number); i ++) + { + Serial.print(phone_number[i], 10); + Serial.print(' '); + playDTMF(phone_number[i], 500); + delay(600); + } + + Serial.println(); + delay(4000); +} diff --git a/libraries/Tone-master/examples/RTTTL/RTTTL.pde b/libraries/Tone-master/examples/RTTTL/RTTTL.pde new file mode 100644 index 0000000..05feb87 --- /dev/null +++ b/libraries/Tone-master/examples/RTTTL/RTTTL.pde @@ -0,0 +1,222 @@ +// A fun sketch to demonstrate the use of the Tone library. + +// To mix the output of the signals to output to a small speaker (i.e. 8 Ohms or higher), +// simply use 1K Ohm resistors from each output pin and tie them together at the speaker. +// Don't forget to connect the other side of the speaker to ground! + +// You can get more RTTTL (RingTone Text Transfer Language) songs from +// http://code.google.com/p/rogue-code/wiki/ToneLibraryDocumentation + +#include + +Tone tone1; + +#define OCTAVE_OFFSET 0 + +int notes[] = { 0, +NOTE_C4, NOTE_CS4, NOTE_D4, NOTE_DS4, NOTE_E4, NOTE_F4, NOTE_FS4, NOTE_G4, NOTE_GS4, NOTE_A4, NOTE_AS4, NOTE_B4, +NOTE_C5, NOTE_CS5, NOTE_D5, NOTE_DS5, NOTE_E5, NOTE_F5, NOTE_FS5, NOTE_G5, NOTE_GS5, NOTE_A5, NOTE_AS5, NOTE_B5, +NOTE_C6, NOTE_CS6, NOTE_D6, NOTE_DS6, NOTE_E6, NOTE_F6, NOTE_FS6, NOTE_G6, NOTE_GS6, NOTE_A6, NOTE_AS6, NOTE_B6, +NOTE_C7, NOTE_CS7, NOTE_D7, NOTE_DS7, NOTE_E7, NOTE_F7, NOTE_FS7, NOTE_G7, NOTE_GS7, NOTE_A7, NOTE_AS7, NOTE_B7 +}; + +//char *song = "The Simpsons:d=4,o=5,b=160:c.6,e6,f#6,8a6,g.6,e6,c6,8a,8f#,8f#,8f#,2g,8p,8p,8f#,8f#,8f#,8g,a#.,8c6,8c6,8c6,c6"; +//char *song = "Indiana:d=4,o=5,b=250:e,8p,8f,8g,8p,1c6,8p.,d,8p,8e,1f,p.,g,8p,8a,8b,8p,1f6,p,a,8p,8b,2c6,2d6,2e6,e,8p,8f,8g,8p,1c6,p,d6,8p,8e6,1f.6,g,8p,8g,e.6,8p,d6,8p,8g,e.6,8p,d6,8p,8g,f.6,8p,e6,8p,8d6,2c6"; +//char *song = "TakeOnMe:d=4,o=4,b=160:8f#5,8f#5,8f#5,8d5,8p,8b,8p,8e5,8p,8e5,8p,8e5,8g#5,8g#5,8a5,8b5,8a5,8a5,8a5,8e5,8p,8d5,8p,8f#5,8p,8f#5,8p,8f#5,8e5,8e5,8f#5,8e5,8f#5,8f#5,8f#5,8d5,8p,8b,8p,8e5,8p,8e5,8p,8e5,8g#5,8g#5,8a5,8b5,8a5,8a5,8a5,8e5,8p,8d5,8p,8f#5,8p,8f#5,8p,8f#5,8e5,8e5"; +//char *song = "Entertainer:d=4,o=5,b=140:8d,8d#,8e,c6,8e,c6,8e,2c.6,8c6,8d6,8d#6,8e6,8c6,8d6,e6,8b,d6,2c6,p,8d,8d#,8e,c6,8e,c6,8e,2c.6,8p,8a,8g,8f#,8a,8c6,e6,8d6,8c6,8a,2d6"; +//char *song = "Muppets:d=4,o=5,b=250:c6,c6,a,b,8a,b,g,p,c6,c6,a,8b,8a,8p,g.,p,e,e,g,f,8e,f,8c6,8c,8d,e,8e,8e,8p,8e,g,2p,c6,c6,a,b,8a,b,g,p,c6,c6,a,8b,a,g.,p,e,e,g,f,8e,f,8c6,8c,8d,e,8e,d,8d,c"; +//char *song = "Xfiles:d=4,o=5,b=125:e,b,a,b,d6,2b.,1p,e,b,a,b,e6,2b.,1p,g6,f#6,e6,d6,e6,2b.,1p,g6,f#6,e6,d6,f#6,2b.,1p,e,b,a,b,d6,2b.,1p,e,b,a,b,e6,2b.,1p,e6,2b."; +//char *song = "Looney:d=4,o=5,b=140:32p,c6,8f6,8e6,8d6,8c6,a.,8c6,8f6,8e6,8d6,8d#6,e.6,8e6,8e6,8c6,8d6,8c6,8e6,8c6,8d6,8a,8c6,8g,8a#,8a,8f"; +//char *song = "20thCenFox:d=16,o=5,b=140:b,8p,b,b,2b,p,c6,32p,b,32p,c6,32p,b,32p,c6,32p,b,8p,b,b,b,32p,b,32p,b,32p,b,32p,b,32p,b,32p,b,32p,g#,32p,a,32p,b,8p,b,b,2b,4p,8e,8g#,8b,1c#6,8f#,8a,8c#6,1e6,8a,8c#6,8e6,1e6,8b,8g#,8a,2b"; +//char *song = "Bond:d=4,o=5,b=80:32p,16c#6,32d#6,32d#6,16d#6,8d#6,16c#6,16c#6,16c#6,16c#6,32e6,32e6,16e6,8e6,16d#6,16d#6,16d#6,16c#6,32d#6,32d#6,16d#6,8d#6,16c#6,16c#6,16c#6,16c#6,32e6,32e6,16e6,8e6,16d#6,16d6,16c#6,16c#7,c.7,16g#6,16f#6,g#.6"; +//char *song = "MASH:d=8,o=5,b=140:4a,4g,f#,g,p,f#,p,g,p,f#,p,2e.,p,f#,e,4f#,e,f#,p,e,p,4d.,p,f#,4e,d,e,p,d,p,e,p,d,p,2c#.,p,d,c#,4d,c#,d,p,e,p,4f#,p,a,p,4b,a,b,p,a,p,b,p,2a.,4p,a,b,a,4b,a,b,p,2a.,a,4f#,a,b,p,d6,p,4e.6,d6,b,p,a,p,2b"; +//char *song = "StarWars:d=4,o=5,b=45:32p,32f#,32f#,32f#,8b.,8f#.6,32e6,32d#6,32c#6,8b.6,16f#.6,32e6,32d#6,32c#6,8b.6,16f#.6,32e6,32d#6,32e6,8c#.6,32f#,32f#,32f#,8b.,8f#.6,32e6,32d#6,32c#6,8b.6,16f#.6,32e6,32d#6,32c#6,8b.6,16f#.6,32e6,32d#6,32e6,8c#6"; +//char *song = "GoodBad:d=4,o=5,b=56:32p,32a#,32d#6,32a#,32d#6,8a#.,16f#.,16g#.,d#,32a#,32d#6,32a#,32d#6,8a#.,16f#.,16g#.,c#6,32a#,32d#6,32a#,32d#6,8a#.,16f#.,32f.,32d#.,c#,32a#,32d#6,32a#,32d#6,8a#.,16g#.,d#"; +//char *song = "TopGun:d=4,o=4,b=31:32p,16c#,16g#,16g#,32f#,32f,32f#,32f,16d#,16d#,32c#,32d#,16f,32d#,32f,16f#,32f,32c#,16f,d#,16c#,16g#,16g#,32f#,32f,32f#,32f,16d#,16d#,32c#,32d#,16f,32d#,32f,16f#,32f,32c#,g#"; +//char *song = "A-Team:d=8,o=5,b=125:4d#6,a#,2d#6,16p,g#,4a#,4d#.,p,16g,16a#,d#6,a#,f6,2d#6,16p,c#.6,16c6,16a#,g#.,2a#"; +//char *song = "Flinstones:d=4,o=5,b=40:32p,16f6,16a#,16a#6,32g6,16f6,16a#.,16f6,32d#6,32d6,32d6,32d#6,32f6,16a#,16c6,d6,16f6,16a#.,16a#6,32g6,16f6,16a#.,32f6,32f6,32d#6,32d6,32d6,32d#6,32f6,16a#,16c6,a#,16a6,16d.6,16a#6,32a6,32a6,32g6,32f#6,32a6,8g6,16g6,16c.6,32a6,32a6,32g6,32g6,32f6,32e6,32g6,8f6,16f6,16a#.,16a#6,32g6,16f6,16a#.,16f6,32d#6,32d6,32d6,32d#6,32f6,16a#,16c.6,32d6,32d#6,32f6,16a#,16c.6,32d6,32d#6,32f6,16a#6,16c7,8a#.6"; +//char *song = "Jeopardy:d=4,o=6,b=125:c,f,c,f5,c,f,2c,c,f,c,f,a.,8g,8f,8e,8d,8c#,c,f,c,f5,c,f,2c,f.,8d,c,a#5,a5,g5,f5,p,d#,g#,d#,g#5,d#,g#,2d#,d#,g#,d#,g#,c.7,8a#,8g#,8g,8f,8e,d#,g#,d#,g#5,d#,g#,2d#,g#.,8f,d#,c#,c,p,a#5,p,g#.5,d#,g#"; +//char *song = "Gadget:d=16,o=5,b=50:32d#,32f,32f#,32g#,a#,f#,a,f,g#,f#,32d#,32f,32f#,32g#,a#,d#6,4d6,32d#,32f,32f#,32g#,a#,f#,a,f,g#,f#,8d#"; +//char *song = "Smurfs:d=32,o=5,b=200:4c#6,16p,4f#6,p,16c#6,p,8d#6,p,8b,p,4g#,16p,4c#6,p,16a#,p,8f#,p,8a#,p,4g#,4p,g#,p,a#,p,b,p,c6,p,4c#6,16p,4f#6,p,16c#6,p,8d#6,p,8b,p,4g#,16p,4c#6,p,16a#,p,8b,p,8f,p,4f#"; +//char *song = "MahnaMahna:d=16,o=6,b=125:c#,c.,b5,8a#.5,8f.,4g#,a#,g.,4d#,8p,c#,c.,b5,8a#.5,8f.,g#.,8a#.,4g,8p,c#,c.,b5,8a#.5,8f.,4g#,f,g.,8d#.,f,g.,8d#.,f,8g,8d#.,f,8g,d#,8c,a#5,8d#.,8d#.,4d#,8d#."; +//char *song = "LeisureSuit:d=16,o=6,b=56:f.5,f#.5,g.5,g#5,32a#5,f5,g#.5,a#.5,32f5,g#5,32a#5,g#5,8c#.,a#5,32c#,a5,a#.5,c#.,32a5,a#5,32c#,d#,8e,c#.,f.,f.,f.,f.,f,32e,d#,8d,a#.5,e,32f,e,32f,c#,d#.,c#"; +char *song = "MissionImp:d=16,o=6,b=95:32d,32d#,32d,32d#,32d,32d#,32d,32d#,32d,32d,32d#,32e,32f,32f#,32g,g,8p,g,8p,a#,p,c7,p,g,8p,g,8p,f,p,f#,p,g,8p,g,8p,a#,p,c7,p,g,8p,g,8p,f,p,f#,p,a#,g,2d,32p,a#,g,2c#,32p,a#,g,2c,a#5,8c,2p,32p,a#5,g5,2f#,32p,a#5,g5,2f,32p,a#5,g5,2e,d#,8d"; + +void setup(void) +{ + Serial.begin(9600); + tone1.begin(13); +} + +#define isdigit(n) (n >= '0' && n <= '9') + +void play_rtttl(char *p) +{ + // Absolutely no error checking in here + + byte default_dur = 4; + byte default_oct = 6; + int bpm = 63; + int num; + long wholenote; + long duration; + byte note; + byte scale; + + // format: d=N,o=N,b=NNN: + // find the start (skip name, etc) + + while(*p != ':') p++; // ignore name + p++; // skip ':' + + // get default duration + if(*p == 'd') + { + p++; p++; // skip "d=" + num = 0; + while(isdigit(*p)) + { + num = (num * 10) + (*p++ - '0'); + } + if(num > 0) default_dur = num; + p++; // skip comma + } + + Serial.print("ddur: "); Serial.println(default_dur, 10); + + // get default octave + if(*p == 'o') + { + p++; p++; // skip "o=" + num = *p++ - '0'; + if(num >= 3 && num <=7) default_oct = num; + p++; // skip comma + } + + Serial.print("doct: "); Serial.println(default_oct, 10); + + // get BPM + if(*p == 'b') + { + p++; p++; // skip "b=" + num = 0; + while(isdigit(*p)) + { + num = (num * 10) + (*p++ - '0'); + } + bpm = num; + p++; // skip colon + } + + Serial.print("bpm: "); Serial.println(bpm, 10); + + // BPM usually expresses the number of quarter notes per minute + wholenote = (60 * 1000L / bpm) * 4; // this is the time for whole note (in milliseconds) + + Serial.print("wn: "); Serial.println(wholenote, 10); + + + // now begin note loop + while(*p) + { + // first, get note duration, if available + num = 0; + while(isdigit(*p)) + { + num = (num * 10) + (*p++ - '0'); + } + + if(num) duration = wholenote / num; + else duration = wholenote / default_dur; // we will need to check if we are a dotted note after + + // now get the note + note = 0; + + switch(*p) + { + case 'c': + note = 1; + break; + case 'd': + note = 3; + break; + case 'e': + note = 5; + break; + case 'f': + note = 6; + break; + case 'g': + note = 8; + break; + case 'a': + note = 10; + break; + case 'b': + note = 12; + break; + case 'p': + default: + note = 0; + } + p++; + + // now, get optional '#' sharp + if(*p == '#') + { + note++; + p++; + } + + // now, get optional '.' dotted note + if(*p == '.') + { + duration += duration/2; + p++; + } + + // now, get scale + if(isdigit(*p)) + { + scale = *p - '0'; + p++; + } + else + { + scale = default_oct; + } + + scale += OCTAVE_OFFSET; + + if(*p == ',') + p++; // skip comma for next note (or we may be at the end) + + // now play the note + + if(note) + { + Serial.print("Playing: "); + Serial.print(scale, 10); Serial.print(' '); + Serial.print(note, 10); Serial.print(" ("); + Serial.print(notes[(scale - 4) * 12 + note], 10); + Serial.print(") "); + Serial.println(duration, 10); + tone1.play(notes[(scale - 4) * 12 + note]); + delay(duration); + tone1.stop(); + } + else + { + Serial.print("Pausing: "); + Serial.println(duration, 10); + delay(duration); + } + } +} + +void loop(void) +{ + play_rtttl(song); + Serial.println("Done."); + while(1); +} diff --git a/libraries/Tone-master/examples/ToneTest/ToneTest.pde b/libraries/Tone-master/examples/ToneTest/ToneTest.pde new file mode 100644 index 0000000..67920b7 --- /dev/null +++ b/libraries/Tone-master/examples/ToneTest/ToneTest.pde @@ -0,0 +1,67 @@ +// Duelling Tones - Simultaneous tone generation. +// To mix the output of the signals to output to a small speaker (i.e. 8 Ohms or higher), +// simply use 1K Ohm resistors from each output pin and tie them together at the speaker. +// Don't forget to connect the other side of the speaker to ground! + +// This example plays notes 'a' through 'g' sent over the Serial Monitor. +// 's' stops the current playing tone. Use uppercase letters for the second. + +#include + +int notes[] = { NOTE_A3, + NOTE_B3, + NOTE_C4, + NOTE_D4, + NOTE_E4, + NOTE_F4, + NOTE_G4 }; + +// You can declare the tones as an array +Tone notePlayer[2]; + +void setup(void) +{ + Serial.begin(9600); + notePlayer[0].begin(11); + notePlayer[1].begin(12); +} + +void loop(void) +{ + char c; + + if(Serial.available()) + { + c = Serial.read(); + + switch(c) + { + case 'a'...'g': + notePlayer[0].play(notes[c - 'a']); + Serial.println(notes[c - 'a']); + break; + case 's': + notePlayer[0].stop(); + break; + + case 'A'...'G': + notePlayer[1].play(notes[c - 'A']); + Serial.println(notes[c - 'A']); + break; + case 'S': + notePlayer[1].stop(); + break; + + default: + notePlayer[1].stop(); + notePlayer[0].play(NOTE_B2); + delay(300); + notePlayer[0].stop(); + delay(100); + notePlayer[1].play(NOTE_B2); + delay(300); + notePlayer[1].stop(); + break; + } + } +} diff --git a/libraries/Tone-master/keywords.txt b/libraries/Tone-master/keywords.txt new file mode 100644 index 0000000..b8cbbd8 --- /dev/null +++ b/libraries/Tone-master/keywords.txt @@ -0,0 +1,112 @@ +####################################### +# Syntax Coloring Map For Tone +####################################### + +####################################### +# Datatypes (KEYWORD1) +####################################### + +Tone KEYWORD1 + +####################################### +# Methods and Functions (KEYWORD2) +####################################### + +play KEYWORD2 +stop KEYWORD2 +begin KEYWORD2 +isPlaying KEYWORD2 + +####################################### +# Constants (LITERAL1) +####################################### + +NOTE_B0 LITERAL1 +NOTE_C1 LITERAL1 +NOTE_CS1 LITERAL1 +NOTE_D1 LITERAL1 +NOTE_DS1 LITERAL1 +NOTE_E1 LITERAL1 +NOTE_F1 LITERAL1 +NOTE_FS1 LITERAL1 +NOTE_G1 LITERAL1 +NOTE_GS1 LITERAL1 +NOTE_A1 LITERAL1 +NOTE_AS1 LITERAL1 +NOTE_B1 LITERAL1 +NOTE_C2 LITERAL1 +NOTE_CS2 LITERAL1 +NOTE_D2 LITERAL1 +NOTE_DS2 LITERAL1 +NOTE_E2 LITERAL1 +NOTE_F2 LITERAL1 +NOTE_FS2 LITERAL1 +NOTE_G2 LITERAL1 +NOTE_GS2 LITERAL1 +NOTE_A2 LITERAL1 +NOTE_AS2 LITERAL1 +NOTE_B2 LITERAL1 +NOTE_C3 LITERAL1 +NOTE_CS3 LITERAL1 +NOTE_D3 LITERAL1 +NOTE_DS3 LITERAL1 +NOTE_E3 LITERAL1 +NOTE_F3 LITERAL1 +NOTE_FS3 LITERAL1 +NOTE_G3 LITERAL1 +NOTE_GS3 LITERAL1 +NOTE_A3 LITERAL1 +NOTE_AS3 LITERAL1 +NOTE_B3 LITERAL1 +NOTE_C4 LITERAL1 +NOTE_CS4 LITERAL1 +NOTE_D4 LITERAL1 +NOTE_DS4 LITERAL1 +NOTE_E4 LITERAL1 +NOTE_F4 LITERAL1 +NOTE_FS4 LITERAL1 +NOTE_G4 LITERAL1 +NOTE_GS4 LITERAL1 +NOTE_A4 LITERAL1 +NOTE_AS4 LITERAL1 +NOTE_B4 LITERAL1 +NOTE_C5 LITERAL1 +NOTE_CS5 LITERAL1 +NOTE_D5 LITERAL1 +NOTE_DS5 LITERAL1 +NOTE_E5 LITERAL1 +NOTE_F5 LITERAL1 +NOTE_FS5 LITERAL1 +NOTE_G5 LITERAL1 +NOTE_GS5 LITERAL1 +NOTE_A5 LITERAL1 +NOTE_AS5 LITERAL1 +NOTE_B5 LITERAL1 +NOTE_C6 LITERAL1 +NOTE_CS6 LITERAL1 +NOTE_D6 LITERAL1 +NOTE_DS6 LITERAL1 +NOTE_E6 LITERAL1 +NOTE_F6 LITERAL1 +NOTE_FS6 LITERAL1 +NOTE_G6 LITERAL1 +NOTE_GS6 LITERAL1 +NOTE_A6 LITERAL1 +NOTE_AS6 LITERAL1 +NOTE_B6 LITERAL1 +NOTE_C7 LITERAL1 +NOTE_CS7 LITERAL1 +NOTE_D7 LITERAL1 +NOTE_DS7 LITERAL1 +NOTE_E7 LITERAL1 +NOTE_F7 LITERAL1 +NOTE_FS7 LITERAL1 +NOTE_G7 LITERAL1 +NOTE_GS7 LITERAL1 +NOTE_A7 LITERAL1 +NOTE_AS7 LITERAL1 +NOTE_B7 LITERAL1 +NOTE_C8 LITERAL1 +NOTE_CS8 LITERAL1 +NOTE_D8 LITERAL1 +NOTE_DS8 LITERAL1 diff --git a/libraries/Tone-master/library.properties b/libraries/Tone-master/library.properties new file mode 100644 index 0000000..0850b12 --- /dev/null +++ b/libraries/Tone-master/library.properties @@ -0,0 +1,9 @@ +name=Tone +version=1.0.0 +author=Brett Hagman +maintainer=Brett Hagman +sentence=A software digital square wave tone generation library.
+paragraph=This is a Wiring Framework (Arduino) library to produce square-wave tones on an arbitrary pin.
You can make multiple instances of the Tone object, to create tones on different pins.

Issues or questions: https://github.com/bhagman/Tone/issues
+category=Signal Input/Output +url=https://github.com/bhagman/Tone +architectures=avr diff --git a/libraries/Tone-master/license.txt b/libraries/Tone-master/license.txt new file mode 100644 index 0000000..534214b --- /dev/null +++ b/libraries/Tone-master/license.txt @@ -0,0 +1,21 @@ +The MIT License (MIT) + +Copyright (c) 2016 Brett Hagman + +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. + diff --git a/libraries/_Stub/_Stub.cpp b/libraries/_Stub/_Stub.cpp new file mode 100644 index 0000000..3fb9ebb --- /dev/null +++ b/libraries/_Stub/_Stub.cpp @@ -0,0 +1,288 @@ +// I2Cdev library collection - MYDEVSTUB I2C device class +// Based on [Manufacturer Name] MYDEVSTUB datasheet, [datasheet date] +// [current release date] by [Author Name] <[Author Email]> +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// [YYYY-mm-dd] - updated some broken thing +// [YYYY-mm-dd] - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 [Author Name], 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 "MYDEVSTUB.h" + +// ============================================================================ +// DEVICE LIBRARY CONVENTIONS: +// +// 1. The class name should be the same as the device model if at all possible. +// No spaces or hyphens, and ideally no underlines unless they're absolutely +// necessary for clarity. ALL CAPS for model numbers, or FirstInitial caps +// for full names. For example: +// - ADXL345 +// - MPU6050 +// - TCA6424A +// - PanelPilot +// +// 2. All #defines should use a device-specific prefix that is the same as the +// all-caps version of the class name ("MYDEVSTUB_" in this example). +// +// 3. All #defines should be ALL CAPS, no matter what. This makes them clearly +// distinctive from variables, classes, and functions. +// +// 4. Class methods and member variables should be named using camelCaps. +// +// 5. Every device class should contain an "initialize()" method which takes +// no parameters and resets any important settings back to a known state, +// ideally the defaults outlined in the datasheet. Some devices have a +// RESET command available, which may be suitable. Some devices may not +// require any specific initialization, but an empty method should be +// created for consistency anyway. +// +// 6. Every device class should contain a "testConnection()" method which +// returns TRUE if the device appears to be connected, or FALSE otherwise. +// If a known ID register or device code is available, check for that. Since +// such an ID register is not always available, at least check to make sure +// that an I2C read may be performed on a specific register and that data +// does actually come back (the I2Cdev class returns a "bytes read" value +// for all read operations). +// +// 7. All class methods should be documented with useful information in Doxygen +// format. You can take the info right out of the datasheet if you want to, +// since that's likely to be helpful. Writing your own info is fine as well. +// The goal is to have enough clear documentation right in the code that +// someone can determine how the device works by studying the code alone. +// +// ============================================================================ + +/* ============================================================================ + I2Cdev Class Quick Primer: + + The I2Cdev class provides simple methods for reading and writing from I2C + device registers without messing with the underlying TWI/I2C functions. You + just specify the device address, register address, and source or destination + data according to which action you are doing. Here is the list of relevant + function prototypes from the I2Cdev class (more info in the .cpp/.h files): + + static int8_t readBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readByte(uint8_t devAddr, uint8_t regAddr, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readWord(uint8_t devAddr, uint8_t regAddr, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data, uint16_t timeout=I2Cdev::readTimeout); + static int8_t readWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data, uint16_t timeout=I2Cdev::readTimeout); + + static bool writeBit(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint8_t data); + static bool writeBitW(uint8_t devAddr, uint8_t regAddr, uint8_t bitNum, uint16_t data); + static bool writeBits(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint8_t data); + static bool writeBitsW(uint8_t devAddr, uint8_t regAddr, uint8_t bitStart, uint8_t length, uint16_t data); + static bool writeByte(uint8_t devAddr, uint8_t regAddr, uint8_t data); + static bool writeWord(uint8_t devAddr, uint8_t regAddr, uint16_t data); + static bool writeBytes(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint8_t *data); + static bool writeWords(uint8_t devAddr, uint8_t regAddr, uint8_t length, uint16_t *data); + + Note that ALL OF THESE METHODS ARE STATIC. No I2Cdev object is needed; just + use the static class methods. + + Also note that the first two parameters of every one of these methods are + the same: "devAddr" and "regAddr". For every method, you need to specify the + target/slave address and the register address. + + If your device uses 8-bit registers, you will want to use the following: + readBit, readBits, readByte, readBytes + writeBit, writeBits, writeByte, writeBytes + + ...but if it uses 16-bit registers, you will want to use these instead: + readBitW, readBitsW, readWord, readWords + writeBitW, writeBitsW, writeWord, writeWords + + Here's a sample of how to use a few of the methods. Note that in each case, + the "buffer" variable is a uint8_t array or pointer, and the "value" variable + (in three of the write examples) is a uint8_t single byte. The multi-byte + write methods still require an array or pointer. + + READ 1 BIT FROM DEVICE 0x68, REGISTER 0x02, BIT POSITION 4 + bytesRead = I2Cdev::readBit(0x68, 0x02, 4, buffer); + + READ 3 BITS FROM DEVICE 0x68, REGISTER 0x02, BIT POSITION 4 + bytesRead = I2Cdev::readBits(0x68, 0x02, 4, 3, buffer); + + READ 1 BYTE FROM DEVICE 0x68, REGISTER 0x02 + bytesRead = I2Cdev::readByte(0x68, 0x02, buffer); + + READ 2 BYTES FROM DEVICE 0x68, REGISTER 0x02 (AND 0x03 FOR 2ND BYTE) + bytesRead = I2Cdev::readBytes(0x68, 0x02, 2, buffer); + + WRITE 1 BIT TO DEVICE 0x68, REGISTER 0x02, BIT POSITION 4 + status = I2Cdev::writeBit(0x68, 0x02, 4, value); + + WRITE 3 BITS TO DEVICE 0x68, REGISTER 0x02, BIT POSITION 4 + status = I2Cdev::writeBits(0x68, 0x02, 4, 3, value); + + WRITE 1 BYTE TO DEVICE 0x68, REGISTER 0x02 + status = I2Cdev::writeByte(0x68, 0x02, value); + + WRITE 2 BYTES TO DEVICE 0x68, REGISTER 0x02 (AND 0x03 FOR 2ND BYTE) + status = I2Cdev::writeBytes(0x68, 0x02, 2, buffer); + + The word-based methods are exactly the same, except they use 16-bit variables + instead of 8-bit ones. + + ============================================================================ */ + +/** Default constructor, uses default I2C address. + * @see MYDEVSTUB_DEFAULT_ADDRESS + */ +MYDEVSTUB::MYDEVSTUB() { + devAddr = MYDEVSTUB_DEFAULT_ADDRESS; +} + +/** Specific address constructor. + * @param address I2C address + * @see MYDEVSTUB_DEFAULT_ADDRESS + * @see MYDEVSTUB_ADDRESS + */ +MYDEVSTUB::MYDEVSTUB(uint8_t address) { + devAddr = address; +} + +/** Power on and prepare for general usage. + */ +void MYDEVSTUB::initialize() { + // ---------------------------------------------------------------------------- + // STUB TODO: + // Perform any important initialization here. Maybe nothing is required, but + // the method should exist anyway. + // ---------------------------------------------------------------------------- +} + +/** Verify the I2C connection. + * Make sure the device is connected and responds as expected. + * @return True if connection is valid, false otherwise + */ +bool MYDEVSTUB::testConnection() { + if (I2Cdev::readByte(devAddr, MYDEVSTUB_RA_WHO_AM_I, buffer) == 1) { + return true; + } + return false; +} + +// ---------------------------------------------------------------------------- +// STUB TODO: +// Define methods to fully cover all available functionality provided by the +// device, according to the datasheet and/or register map. Unless there is very +// clear reason not to, try to follow the get/set naming convention for all +// values, for instance: +// - uint8_t getThreshold() +// - void setThreshold(uint8_t threshold) +// - uint8_t getRate() +// - void setRate(uint8_t rate) +// +// Some methods may be named differently if it makes sense. As long as all +// functionality is covered, that's the important part. The methods here are +// only examples and should not be kept for your real device. +// ---------------------------------------------------------------------------- + +// MEASURE1 register, read-only + +uint8_t MYDEVSTUB::getMeasurement1() { + // read a single byte and return it + I2Cdev::readByte(devAddr, MYDEVSTUB_RA_MEASURE1, buffer); + return buffer[0]; +} + +// MEASURE2 register, read-only + +uint8_t MYDEVSTUB::getMeasurement2() { + // read a single byte and return it + I2Cdev::readByte(devAddr, MYDEVSTUB_RA_MEASURE2, buffer); + return buffer[0]; +} + +// MEASURE3 register, read-only + +uint8_t MYDEVSTUB::getMeasurement3() { + // read a single byte and return it + I2Cdev::readByte(devAddr, MYDEVSTUB_RA_MEASURE3, buffer); + return buffer[0]; +} + +// CONFIG1 register, r/w + +void MYDEVSTUB::reset() { + // write a single bit to the RESET position in the CONFIG1 register + I2Cdev::writeBit(devAddr, MYDEVSTUB_RA_CONFIG1, MYDEVSTUB_CONFIG1_RESET_BIT, 1); +} +bool MYDEVSTUB::getFIFOEnabled() { + // read a single bit from the FIFO_EN position in the CONFIG1 regsiter + I2Cdev::readBit(devAddr, MYDEVSTUB_RA_CONFIG1, MYDEVSTUB_CONFIG1_FIFO_EN_BIT, buffer); + return buffer[0]; +} +void MYDEVSTUB::setFIFOEnabled(bool enabled) { + // write a single bit to the FIFO_EN position in the CONFIG1 regsiter + I2Cdev::writeBit(devAddr, MYDEVSTUB_RA_CONFIG1, MYDEVSTUB_CONFIG1_FIFO_EN_BIT, enabled); +} + +// CONFIG2 register, r/w + +uint8_t MYDEVSTUB::getInterruptMode() { + // reading a single bit from a register + I2Cdev::readBit(devAddr, MYDEVSTUB_RA_CONFIG2, MYDEVSTUB_CONFIG2_INTMODE_BIT, buffer); + return buffer[0]; +} +void MYDEVSTUB::setInterruptMode(uint8_t mode) { + // writing a single bit into a register +} +uint8_t MYDEVSTUB::getRate() { + // reading multiple single bit from a register + I2Cdev::readBits(devAddr, MYDEVSTUB_RA_CONFIG2, MYDEVSTUB_CONFIG2_RATE_BIT, MYDEVSTUB_CONFIG2_RATE_LENGTH, buffer); + return buffer[0]; +} +void MYDEVSTUB::setRate(uint8_t rate) { + // writing multiple bits into a register + I2Cdev::writeBits(devAddr, MYDEVSTUB_RA_CONFIG2, MYDEVSTUB_CONFIG2_RATE_BIT, MYDEVSTUB_CONFIG2_RATE_LENGTH, rate); +} + +// DATA_* registers, r/w + +uint16_t MYDEVSTUB::getData() { + // reading two H/L bytes and bit-shifting them into a 16-bit value + I2Cdev::readBytes(devAddr, MYDEVSTUB_RA_DATA_H, 2, buffer); + return (buffer[0] << 8) + buffer[1]; +} +void MYDEVSTUB::setData(uint16_t value) { + // splitting a 16-bit value into two H/L bytes and writing them + buffer[0] = value >> 8; + buffer[1] = value & 0xFF; + I2Cdev::writeBytes(devAddr, MYDEVSTUB_RA_DATA_H, 2, buffer); +} + +// WHO_AM_I register, read-only + +uint8_t MYDEVSTUB::getDeviceID() { + // read a single byte and return it + I2Cdev::readByte(devAddr, MYDEVSTUB_RA_WHO_AM_I, buffer); + return buffer[0]; +} diff --git a/libraries/_Stub/_Stub.h b/libraries/_Stub/_Stub.h new file mode 100644 index 0000000..5db149e --- /dev/null +++ b/libraries/_Stub/_Stub.h @@ -0,0 +1,209 @@ +// I2Cdev library collection - MYDEVSTUB I2C device class header file +// Based on [Manufacturer Name] MYDEVSTUB datasheet, [datasheet date] +// [current release date] by [Author Name] <[Author Email]> +// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib +// +// Changelog: +// [YYYY-mm-dd] - updated some broken thing +// [YYYY-mm-dd] - initial release + +/* ============================================ +I2Cdev device library code is placed under the MIT license +Copyright (c) 2011 [Author Name], 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 _MYDEVSTUB_H_ +#define _MYDEVSTUB_H_ + +#include "I2Cdev.h" + +// ============================================================================ +// DEVICE LIBRARY CONVENTIONS: +// +// 1. The class name should be the same as the device model if at all possible. +// No spaces or hyphens, and ideally no underlines unless they're absolutely +// necessary for clarity. ALL CAPS for model numbers, or FirstInitial caps +// for full names. For example: +// - ADXL345 +// - MPU6050 +// - TCA6424A +// - PanelPilot +// +// 2. All #defines should use a device-specific prefix that is the same as the +// all-caps version of the class name ("MYDEVSTUB_" in this example). +// +// 3. All #defines should be ALL CAPS, no matter what. This makes them clearly +// distinctive from variables, classes, and functions. +// +// 4. Class methods and member variables should be named using camelCaps. +// +// 5. Every device class should contain an "initialize()" method which takes +// no parameters and resets any important settings back to a known state, +// ideally the defaults outlined in the datasheet. Some devices have a +// RESET command available, which may be suitable. Some devices may not +// require any specific initialization, but an empty method should be +// created for consistency anyway. +// +// 6. Every device class should contain a "testConnection()" method which +// returns TRUE if the device appears to be connected, or FALSE otherwise. +// If a known ID register or device code is available, check for that. Since +// such an ID register is not always available, at least check to make sure +// that an I2C read may be performed on a specific register and that data +// does actually come back (the I2Cdev class returns a "bytes read" value +// for all read operations). +// +// 7. All class methods should be documented with useful information in Doxygen +// format. You can take the info right out of the datasheet if you want to, +// since that's likely to be helpful. Writing your own info is fine as well. +// The goal is to have enough clear documentation right in the code that +// someone can determine how the device works by studying the code alone. +// +// ============================================================================ + +// ---------------------------------------------------------------------------- +// STUB TODO: +// List all possible device I2C addresses here, if they are predefined. Some +// devices only have one possible address, in which case that one should be +// defined as both [MYDEVSTUB]_ADDRESS and [MYDEVSTUB]_DEFAULT_ADDRESS for +// consistency. The *_DEFAULT address will be used if a device object is +// created without an address provided in the constructor. Note that I2C +// devices conventionally use 7-bit addresses, so these will generally be +// between 0x00 and 0x7F. +// ---------------------------------------------------------------------------- +#define MYDEVSTUB_ADDRESS_AD0_LOW 0x20 +#define MYDEVSTUB_ADDRESS_AD0_HIGH 0x21 +#define MYDEVSTUB_DEFAULT_ADDRESS 0x20 + +// ---------------------------------------------------------------------------- +// STUB TODO: +// List all registers that this device has. The goal for all device libraries +// is to have complete coverage of all possible functions, so be sure to add +// everything in the datasheet. Register address constants should use the extra +// prefix "RA_", followed by the datasheet's given name for each register. +// ---------------------------------------------------------------------------- +#define MYDEVSTUB_RA_MEASURE1 0x00 +#define MYDEVSTUB_RA_MEASURE2 0x01 +#define MYDEVSTUB_RA_MEASURE3 0x02 +#define MYDEVSTUB_RA_CONFIG1 0x03 +#define MYDEVSTUB_RA_CONFIG2 0x04 +#define MYDEVSTUB_RA_DATA_H 0x05 +#define MYDEVSTUB_RA_DATA_L 0x06 +#define MYDEVSTUB_RA_WHO_AM_I 0x07 + +// ---------------------------------------------------------------------------- +// STUB TODO: +// List register structures wherever necessary. Bit position constants should +// end in "_BIT", and are defined from 7 to 0, with 7 being the left/MSB and +// 0 being the right/LSB. If the device uses 16-bit registers instead of the +// more common 8-bit registers, the range is 15 to 0. Field length constants +// should end in "_LENGTH", but otherwise match the name of bit position +// constant that it complements. Fields that are a single bit in length don't +// need a separate field length constant. +// ---------------------------------------------------------------------------- +#define MYDEVSTUB_MEASURE1_RATE_BIT 4 +#define MYDEVSTUB_MEASURE1_RATE_LENGTH 3 + +#define MYDEVSTUB_CONFIG1_FIFO_BIT 1 +#define MYDEVSTUB_CONFIG1_RESET_BIT 0 + +// ---------------------------------------------------------------------------- +// STUB TODO: +// List any special predefined values for each register according to the +// datasheet. For example, MEMS devices often provide different options for +// measurement rates, say 25Hz, 50Hz, 100Hz, and 200Hz. These are typically +// represented by arbitrary bit values, say 0b00, 0b01, 0b10, and 0b11 (or 0x0, +// 0x1, 0x2, and 0x3). Defining them here makes it easy to know which options +// are available. +// ---------------------------------------------------------------------------- +#define MYDEVSTUB_RATE_10 0x00 +#define MYDEVSTUB_RATE_20 0x01 +#define MYDEVSTUB_RATE_40 0x02 +#define MYDEVSTUB_RATE_80 0x03 +#define MYDEVSTUB_RATE_160 0x04 + +class MYDEVSTUB { + public: + MYDEVSTUB(); + MYDEVSTUB(uint8_t address); + + void initialize(); + bool testConnection(); + +// ---------------------------------------------------------------------------- +// STUB TODO: +// Declare methods to fully cover all available functionality provided by the +// device, according to the datasheet and/or register map. Unless there is very +// clear reason not to, try to follow the get/set naming convention for all +// values, for instance: +// - uint8_t getThreshold() +// - void setThreshold(uint8_t threshold) +// - uint8_t getRate() +// - void setRate(uint8_t rate) +// +// Some methods may be named differently if it makes sense. As long as all +// functionality is covered, that's the important part. The methods here are +// only examples and should not be kept for your real device. +// ---------------------------------------------------------------------------- + + // MEASURE1 register, read-only + uint8_t getMeasurement1(); + + // MEASURE2 register, read-only + uint8_t getMeasurement2(); + + // MEASURE3 register, read-only + uint8_t getMeasurement3(); + + // CONFIG1 register, r/w + void reset(); // <-- special method that resets entire device + bool getFIFOEnabled(); + void setFIFOEnabled(bool enabled); + + // CONFIG2 register, r/w + uint8_t getInterruptMode(); + void setInterruptMode(uint8_t mode); + uint8_t getRate(); + void setRate(uint8_t rate); + + // DATA_* registers, r/w + uint16_t getData(); + void setData(uint16_t value); + + // WHO_AM_I register, read-only + uint8_t getDeviceID(); + +// ---------------------------------------------------------------------------- +// STUB TODO: +// Declare private object helper variables or local storage for particular +// device settings, if required. All devices need a "devAddr" variable to store +// the I2C slave address for easy access. Most devices also need a buffer for +// reads (the I2Cdev class' read methods use a pointer for the storage location +// of any read data). The buffer should be of type "uint8_t" if the device uses +// 8-bit registers, or type "uint16_t" if the device uses 16-bit registers. +// Many devices will not require more member variables than this. +// ---------------------------------------------------------------------------- + private: + uint8_t devAddr; + uint8_t buffer[6]; +}; + +#endif /* _MYDEVSTUB_H_ */ diff --git a/libraries/ethercard-master/.gitignore b/libraries/ethercard-master/.gitignore new file mode 100644 index 0000000..a0c1726 --- /dev/null +++ b/libraries/ethercard-master/.gitignore @@ -0,0 +1,3 @@ +.DS_Store +*.esproj +/html diff --git a/libraries/ethercard-master/.travis.yml b/libraries/ethercard-master/.travis.yml new file mode 100644 index 0000000..dcbe057 --- /dev/null +++ b/libraries/ethercard-master/.travis.yml @@ -0,0 +1,45 @@ +language: python +python: + - "2.7" + +# Cache PlatformIO packages using Travis CI container-based infrastructure +sudo: false +cache: + directories: + - "~/.platformio" + +env: + - PLATFORMIO_CI_SRC=examples/backSoon/backSoon.ino + - PLATFORMIO_CI_SRC=examples/etherNode/etherNode.ino + - PLATFORMIO_CI_SRC=examples/getDHCPandDNS/getDHCPandDNS.ino + - PLATFORMIO_CI_SRC=examples/getStaticIP/getStaticIP.ino + - PLATFORMIO_CI_SRC=examples/getViaDNS/getViaDNS.ino + - PLATFORMIO_CI_SRC=examples/JeeUdp/JeeUdp.ino + - PLATFORMIO_CI_SRC=examples/multipacket/multipacket.ino + - PLATFORMIO_CI_SRC=examples/multipacketSD/multipacketSD.ino + - PLATFORMIO_CI_SRC=examples/nanether/nanether.ino + - PLATFORMIO_CI_SRC=examples/noipClient/noipClient.ino + - PLATFORMIO_CI_SRC=examples/notifyMyAndroid/notifyMyAndroid.ino + - PLATFORMIO_CI_SRC=examples/pings/pings.ino + - PLATFORMIO_CI_SRC=examples/rbbb_server/rbbb_server.ino + - PLATFORMIO_CI_SRC=examples/SSDP/SSDP.ino + - PLATFORMIO_CI_SRC=examples/stashTest/stashTest.ino + - PLATFORMIO_CI_SRC=examples/testDHCP/testDHCP.ino + - PLATFORMIO_CI_SRC=examples/thingspeak/thingspeak.ino + - PLATFORMIO_CI_SRC=examples/twitter/twitter.ino + - PLATFORMIO_CI_SRC=examples/udpClientSendOnly/udpClientSendOnly.ino +# - PLATFORMIO_CI_SRC=examples/udpListener/udpListener.ino + - PLATFORMIO_CI_SRC=examples/webClient/webClient.ino + - PLATFORMIO_CI_SRC=examples/xively/xively.ino + +install: + - pip install -U platformio + + - wget https://github.com/jcw/jeelib/archive/master.zip -O /tmp/jeelib.zip + - unzip /tmp/jeelib.zip -d /tmp + + - wget https://github.com/Rodot/Gamebuino/archive/master.zip -O /tmp/gamebuino.zip + - unzip /tmp/gamebuino.zip -d /tmp + +script: + - platformio ci --lib="." --lib="/tmp/jeelib-master" --lib="/tmp/Gamebuino-master/libraries/tinyFAT" --board=uno --board=megaatmega2560 diff --git a/libraries/ethercard-master/CONTRIBUTING.md b/libraries/ethercard-master/CONTRIBUTING.md new file mode 100644 index 0000000..1f12897 --- /dev/null +++ b/libraries/ethercard-master/CONTRIBUTING.md @@ -0,0 +1,22 @@ +Contributing to EtherCard +========================= + +Contributions to the EtherCard codebase are welcome using the usual Github pull request workflow. + +Please remember that memory, particularly RAM, is often limited on Arduino, so try and be efficient when adding new features. + + +Code Style +---------- + +When making contributions, please use the following code style to keep the codebase consistent: + +* Indent using *4 spaces* not tabs +* When placing an opening brace on the same line, there should be one space before it +* Closing braces should be broken from the preceding line + +If in doubt, this is the same as the default [astyle] settings, so use the astyle tool to check your code. + + + +[astyle]: http://astyle.sourceforge.net/ diff --git a/libraries/ethercard-master/Doxyfile b/libraries/ethercard-master/Doxyfile new file mode 100644 index 0000000..9dc52f4 --- /dev/null +++ b/libraries/ethercard-master/Doxyfile @@ -0,0 +1,1923 @@ +# Doxyfile 1.8.4 + +# This file describes the settings to be used by the documentation system +# doxygen (www.doxygen.org) for a project. +# +# All text after a double hash (##) is considered a comment and is placed +# in front of the TAG it is preceding . +# All text after a hash (#) is considered a comment and will be ignored. +# The format is: +# TAG = value [value, ...] +# For lists items can also be appended using: +# TAG += value [value, ...] +# Values that contain spaces should be placed between quotes (" "). + +#--------------------------------------------------------------------------- +# Project related configuration options +#--------------------------------------------------------------------------- + +# This tag specifies the encoding used for all characters in the config file +# that follow. The default is UTF-8 which is also the encoding used for all +# text before the first occurrence of this tag. Doxygen uses libiconv (or the +# iconv built into libc) for the transcoding. See +# http://www.gnu.org/software/libiconv for the list of possible encodings. + +DOXYFILE_ENCODING = UTF-8 + +# The PROJECT_NAME tag is a single word (or sequence of words) that should +# identify the project. Note that if you do not use Doxywizard you need +# to put quotes around the project name if it contains spaces. + +PROJECT_NAME = "EtherCard" + +# The PROJECT_NUMBER tag can be used to enter a project or revision number. +# This could be handy for archiving the generated documentation or +# if some version control system is used. + +PROJECT_NUMBER = + +# Using the PROJECT_BRIEF tag one can provide an optional one line description +# for a project that appears at the top of each page and should give viewer +# a quick idea about the purpose of the project. Keep the description short. + +PROJECT_BRIEF = "Ardino interface library for the ENC28J60 Ethernet controller chip (GPL)." + +# With the PROJECT_LOGO tag one can specify an logo or icon that is +# included in the documentation. The maximum height of the logo should not +# exceed 55 pixels and the maximum width should not exceed 200 pixels. +# Doxygen will copy the logo to the output directory. + +PROJECT_LOGO = Doxylogo.png + +# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) +# base path where the generated documentation will be put. +# If a relative path is entered, it will be relative to the location +# where doxygen was started. If left blank the current directory will be used. + +OUTPUT_DIRECTORY = + +# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create +# 4096 sub-directories (in 2 levels) under the output directory of each output +# format and will distribute the generated files over these directories. +# Enabling this option can be useful when feeding doxygen a huge amount of +# source files, where putting all generated files in the same directory would +# otherwise cause performance problems for the file system. + +CREATE_SUBDIRS = NO + +# The OUTPUT_LANGUAGE tag is used to specify the language in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all constant output in the proper language. +# The default language is English, other supported languages are: +# Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional, +# Croatian, Czech, Danish, Dutch, Esperanto, Farsi, Finnish, French, German, +# Greek, Hungarian, Italian, Japanese, Japanese-en (Japanese with English +# messages), Korean, Korean-en, Latvian, Lithuanian, Norwegian, Macedonian, +# Persian, Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrillic, +# Slovak, Slovene, Spanish, Swedish, Ukrainian, and Vietnamese. + +OUTPUT_LANGUAGE = English + +# If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will +# include brief member descriptions after the members that are listed in +# the file and class documentation (similar to JavaDoc). +# Set to NO to disable this. + +BRIEF_MEMBER_DESC = YES + +# If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend +# the brief description of a member or function before the detailed description. +# Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the +# brief descriptions will be completely suppressed. + +REPEAT_BRIEF = YES + +# This tag implements a quasi-intelligent brief description abbreviator +# that is used to form the text in various listings. Each string +# in this list, if found as the leading text of the brief description, will be +# stripped from the text and the result after processing the whole list, is +# used as the annotated text. Otherwise, the brief description is used as-is. +# If left blank, the following values are used ("$name" is automatically +# replaced with the name of the entity): "The $name class" "The $name widget" +# "The $name file" "is" "provides" "specifies" "contains" +# "represents" "a" "an" "the" + +ABBREVIATE_BRIEF = + +# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then +# Doxygen will generate a detailed section even if there is only a brief +# description. + +ALWAYS_DETAILED_SEC = NO + +# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all +# inherited members of a class in the documentation of that class as if those +# members were ordinary class members. Constructors, destructors and assignment +# operators of the base classes will not be shown. + +INLINE_INHERITED_MEMB = NO + +# If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full +# path before files name in the file list and in the header files. If set +# to NO the shortest path that makes the file name unique will be used. + +FULL_PATH_NAMES = YES + +# If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag +# can be used to strip a user-defined part of the path. Stripping is +# only done if one of the specified strings matches the left-hand part of +# the path. The tag can be used to show relative paths in the file list. +# If left blank the directory from which doxygen is run is used as the +# path to strip. Note that you specify absolute paths here, but also +# relative paths, which will be relative from the directory where doxygen is +# started. + +STRIP_FROM_PATH = + +# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of +# the path mentioned in the documentation of a class, which tells +# the reader which header file to include in order to use a class. +# If left blank only the name of the header file containing the class +# definition is used. Otherwise one should specify the include paths that +# are normally passed to the compiler using the -I flag. + +STRIP_FROM_INC_PATH = + +# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter +# (but less readable) file names. This can be useful if your file system +# doesn't support long names like on DOS, Mac, or CD-ROM. + +SHORT_NAMES = NO + +# If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen +# will interpret the first line (until the first dot) of a JavaDoc-style +# comment as the brief description. If set to NO, the JavaDoc +# comments will behave just like regular Qt-style comments +# (thus requiring an explicit @brief command for a brief description.) + +JAVADOC_AUTOBRIEF = YES + +# If the QT_AUTOBRIEF tag is set to YES then Doxygen will +# interpret the first line (until the first dot) of a Qt-style +# comment as the brief description. If set to NO, the comments +# will behave just like regular Qt-style comments (thus requiring +# an explicit \brief command for a brief description.) + +QT_AUTOBRIEF = NO + +# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen +# treat a multi-line C++ special comment block (i.e. a block of //! or /// +# comments) as a brief description. This used to be the default behaviour. +# The new default is to treat a multi-line C++ comment block as a detailed +# description. Set this tag to YES if you prefer the old behaviour instead. + +MULTILINE_CPP_IS_BRIEF = NO + +# If the INHERIT_DOCS tag is set to YES (the default) then an undocumented +# member inherits the documentation from any documented member that it +# re-implements. + +INHERIT_DOCS = YES + +# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce +# a new page for each member. If set to NO, the documentation of a member will +# be part of the file/class/namespace that contains it. + +SEPARATE_MEMBER_PAGES = NO + +# The TAB_SIZE tag can be used to set the number of spaces in a tab. +# Doxygen uses this value to replace tabs by spaces in code fragments. + +TAB_SIZE = 8 + +# This tag can be used to specify a number of aliases that acts +# as commands in the documentation. An alias has the form "name=value". +# For example adding "sideeffect=\par Side Effects:\n" will allow you to +# put the command \sideeffect (or @sideeffect) in the documentation, which +# will result in a user-defined paragraph with heading "Side Effects:". +# You can put \n's in the value part of an alias to insert newlines. + +ALIASES = + +# This tag can be used to specify a number of word-keyword mappings (TCL only). +# A mapping has the form "name=value". For example adding +# "class=itcl::class" will allow you to use the command class in the +# itcl::class meaning. + +TCL_SUBST = + +# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C +# sources only. Doxygen will then generate output that is more tailored for C. +# For instance, some of the names that are used will be different. The list +# of all members will be omitted, etc. + +OPTIMIZE_OUTPUT_FOR_C = NO + +# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java +# sources only. Doxygen will then generate output that is more tailored for +# Java. For instance, namespaces will be presented as packages, qualified +# scopes will look different, etc. + +OPTIMIZE_OUTPUT_JAVA = NO + +# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran +# sources only. Doxygen will then generate output that is more tailored for +# Fortran. + +OPTIMIZE_FOR_FORTRAN = NO + +# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL +# sources. Doxygen will then generate output that is tailored for +# VHDL. + +OPTIMIZE_OUTPUT_VHDL = NO + +# Doxygen selects the parser to use depending on the extension of the files it +# parses. With this tag you can assign which parser to use for a given +# extension. Doxygen has a built-in mapping, but you can override or extend it +# using this tag. The format is ext=language, where ext is a file extension, +# and language is one of the parsers supported by doxygen: IDL, Java, +# Javascript, CSharp, C, C++, D, PHP, Objective-C, Python, Fortran, VHDL, C, +# C++. For instance to make doxygen treat .inc files as Fortran files (default +# is PHP), and .f files as C (default is Fortran), use: inc=Fortran f=C. Note +# that for custom extensions you also need to set FILE_PATTERNS otherwise the +# files are not read by doxygen. + +EXTENSION_MAPPING = Markdown=md + +# If MARKDOWN_SUPPORT is enabled (the default) then doxygen pre-processes all +# comments according to the Markdown format, which allows for more readable +# documentation. See http://daringfireball.net/projects/markdown/ for details. +# The output of markdown processing is further processed by doxygen, so you +# can mix doxygen, HTML, and XML commands with Markdown formatting. +# Disable only in case of backward compatibilities issues. + +MARKDOWN_SUPPORT = YES + +# When enabled doxygen tries to link words that correspond to documented +# classes, or namespaces to their corresponding documentation. Such a link can +# be prevented in individual cases by by putting a % sign in front of the word +# or globally by setting AUTOLINK_SUPPORT to NO. + +AUTOLINK_SUPPORT = YES + +# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want +# to include (a tag file for) the STL sources as input, then you should +# set this tag to YES in order to let doxygen match functions declarations and +# definitions whose arguments contain STL classes (e.g. func(std::string); v.s. +# func(std::string) {}). This also makes the inheritance and collaboration +# diagrams that involve STL classes more complete and accurate. + +BUILTIN_STL_SUPPORT = NO + +# If you use Microsoft's C++/CLI language, you should set this option to YES to +# enable parsing support. + +CPP_CLI_SUPPORT = NO + +# Set the SIP_SUPPORT tag to YES if your project consists of sip sources only. +# Doxygen will parse them like normal C++ but will assume all classes use public +# instead of private inheritance when no explicit protection keyword is present. + +SIP_SUPPORT = NO + +# For Microsoft's IDL there are propget and propput attributes to indicate +# getter and setter methods for a property. Setting this option to YES (the +# default) will make doxygen replace the get and set methods by a property in +# the documentation. This will only work if the methods are indeed getting or +# setting a simple type. If this is not the case, or you want to show the +# methods anyway, you should set this option to NO. + +IDL_PROPERTY_SUPPORT = YES + +# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC +# tag is set to YES, then doxygen will reuse the documentation of the first +# member in the group (if any) for the other members of the group. By default +# all members of a group must be documented explicitly. + +DISTRIBUTE_GROUP_DOC = NO + +# Set the SUBGROUPING tag to YES (the default) to allow class member groups of +# the same type (for instance a group of public functions) to be put as a +# subgroup of that type (e.g. under the Public Functions section). Set it to +# NO to prevent subgrouping. Alternatively, this can be done per class using +# the \nosubgrouping command. + +SUBGROUPING = YES + +# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and +# unions are shown inside the group in which they are included (e.g. using +# @ingroup) instead of on a separate page (for HTML and Man pages) or +# section (for LaTeX and RTF). + +INLINE_GROUPED_CLASSES = NO + +# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and +# unions with only public data fields or simple typedef fields will be shown +# inline in the documentation of the scope in which they are defined (i.e. file, +# namespace, or group documentation), provided this scope is documented. If set +# to NO (the default), structs, classes, and unions are shown on a separate +# page (for HTML and Man pages) or section (for LaTeX and RTF). + +INLINE_SIMPLE_STRUCTS = NO + +# When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct, union, or enum +# is documented as struct, union, or enum with the name of the typedef. So +# typedef struct TypeS {} TypeT, will appear in the documentation as a struct +# with name TypeT. When disabled the typedef will appear as a member of a file, +# namespace, or class. And the struct will be named TypeS. This can typically +# be useful for C code in case the coding convention dictates that all compound +# types are typedef'ed and only the typedef is referenced, never the tag name. + +TYPEDEF_HIDES_STRUCT = NO + +# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This +# cache is used to resolve symbols given their name and scope. Since this can +# be an expensive process and often the same symbol appear multiple times in +# the code, doxygen keeps a cache of pre-resolved symbols. If the cache is too +# small doxygen will become slower. If the cache is too large, memory is wasted. +# The cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid +# range is 0..9, the default is 0, corresponding to a cache size of 2^16 = 65536 +# symbols. + +LOOKUP_CACHE_SIZE = 0 + +#--------------------------------------------------------------------------- +# Build related configuration options +#--------------------------------------------------------------------------- + +# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in +# documentation are documented, even if no documentation was available. +# Private class members and static file members will be hidden unless +# the EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES + +EXTRACT_ALL = NO + +# If the EXTRACT_PRIVATE tag is set to YES all private members of a class +# will be included in the documentation. + +EXTRACT_PRIVATE = NO + +# If the EXTRACT_PACKAGE tag is set to YES all members with package or internal +# scope will be included in the documentation. + +EXTRACT_PACKAGE = NO + +# If the EXTRACT_STATIC tag is set to YES all static members of a file +# will be included in the documentation. + +EXTRACT_STATIC = NO + +# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) +# defined locally in source files will be included in the documentation. +# If set to NO only classes defined in header files are included. + +EXTRACT_LOCAL_CLASSES = NO + +# This flag is only useful for Objective-C code. When set to YES local +# methods, which are defined in the implementation section but not in +# the interface are included in the documentation. +# If set to NO (the default) only methods in the interface are included. + +EXTRACT_LOCAL_METHODS = NO + +# If this flag is set to YES, the members of anonymous namespaces will be +# extracted and appear in the documentation as a namespace called +# 'anonymous_namespace{file}', where file will be replaced with the base +# name of the file that contains the anonymous namespace. By default +# anonymous namespaces are hidden. + +EXTRACT_ANON_NSPACES = YES + +# If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all +# undocumented members of documented classes, files or namespaces. +# If set to NO (the default) these members will be included in the +# various overviews, but no documentation section is generated. +# This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_MEMBERS = NO + +# If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all +# undocumented classes that are normally visible in the class hierarchy. +# If set to NO (the default) these classes will be included in the various +# overviews. This option has no effect if EXTRACT_ALL is enabled. + +HIDE_UNDOC_CLASSES = NO + +# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all +# friend (class|struct|union) declarations. +# If set to NO (the default) these declarations will be included in the +# documentation. + +HIDE_FRIEND_COMPOUNDS = NO + +# If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any +# documentation blocks found inside the body of a function. +# If set to NO (the default) these blocks will be appended to the +# function's detailed documentation block. + +HIDE_IN_BODY_DOCS = NO + +# The INTERNAL_DOCS tag determines if documentation +# that is typed after a \internal command is included. If the tag is set +# to NO (the default) then the documentation will be excluded. +# Set it to YES to include the internal documentation. + +INTERNAL_DOCS = NO + +# If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate +# file names in lower-case letters. If set to YES upper-case letters are also +# allowed. This is useful if you have classes or files whose names only differ +# in case and if your file system supports case sensitive file names. Windows +# and Mac users are advised to set this option to NO. + +CASE_SENSE_NAMES = YES + +# If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen +# will show members with their full class and namespace scopes in the +# documentation. If set to YES the scope will be hidden. + +HIDE_SCOPE_NAMES = NO + +# If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen +# will put a list of the files that are included by a file in the documentation +# of that file. + +SHOW_INCLUDE_FILES = YES + +# If the FORCE_LOCAL_INCLUDES tag is set to YES then Doxygen +# will list include files with double quotes in the documentation +# rather than with sharp brackets. + +FORCE_LOCAL_INCLUDES = NO + +# If the INLINE_INFO tag is set to YES (the default) then a tag [inline] +# is inserted in the documentation for inline members. + +INLINE_INFO = YES + +# If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen +# will sort the (detailed) documentation of file and class members +# alphabetically by member name. If set to NO the members will appear in +# declaration order. + +SORT_MEMBER_DOCS = YES + +# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the +# brief documentation of file, namespace and class members alphabetically +# by member name. If set to NO (the default) the members will appear in +# declaration order. + +SORT_BRIEF_DOCS = NO + +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen +# will sort the (brief and detailed) documentation of class members so that +# constructors and destructors are listed first. If set to NO (the default) +# the constructors will appear in the respective orders defined by +# SORT_MEMBER_DOCS and SORT_BRIEF_DOCS. +# This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO +# and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO. + +SORT_MEMBERS_CTORS_1ST = NO + +# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the +# hierarchy of group names into alphabetical order. If set to NO (the default) +# the group names will appear in their defined order. + +SORT_GROUP_NAMES = NO + +# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be +# sorted by fully-qualified names, including namespaces. If set to +# NO (the default), the class list will be sorted only by class name, +# not including the namespace part. +# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES. +# Note: This option applies only to the class list, not to the +# alphabetical list. + +SORT_BY_SCOPE_NAME = NO + +# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to +# do proper type resolution of all parameters of a function it will reject a +# match between the prototype and the implementation of a member function even +# if there is only one candidate or it is obvious which candidate to choose +# by doing a simple string match. By disabling STRICT_PROTO_MATCHING doxygen +# will still accept a match between prototype and implementation in such cases. + +STRICT_PROTO_MATCHING = NO + +# The GENERATE_TODOLIST tag can be used to enable (YES) or +# disable (NO) the todo list. This list is created by putting \todo +# commands in the documentation. + +GENERATE_TODOLIST = YES + +# The GENERATE_TESTLIST tag can be used to enable (YES) or +# disable (NO) the test list. This list is created by putting \test +# commands in the documentation. + +GENERATE_TESTLIST = YES + +# The GENERATE_BUGLIST tag can be used to enable (YES) or +# disable (NO) the bug list. This list is created by putting \bug +# commands in the documentation. + +GENERATE_BUGLIST = YES + +# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or +# disable (NO) the deprecated list. This list is created by putting +# \deprecated commands in the documentation. + +GENERATE_DEPRECATEDLIST= YES + +# The ENABLED_SECTIONS tag can be used to enable conditional +# documentation sections, marked by \if section-label ... \endif +# and \cond section-label ... \endcond blocks. + +ENABLED_SECTIONS = + +# The MAX_INITIALIZER_LINES tag determines the maximum number of lines +# the initial value of a variable or macro consists of for it to appear in +# the documentation. If the initializer consists of more lines than specified +# here it will be hidden. Use a value of 0 to hide initializers completely. +# The appearance of the initializer of individual variables and macros in the +# documentation can be controlled using \showinitializer or \hideinitializer +# command in the documentation regardless of this setting. + +MAX_INITIALIZER_LINES = 30 + +# Set the SHOW_USED_FILES tag to NO to disable the list of files generated +# at the bottom of the documentation of classes and structs. If set to YES the +# list will mention the files that were used to generate the documentation. + +SHOW_USED_FILES = YES + +# Set the SHOW_FILES tag to NO to disable the generation of the Files page. +# This will remove the Files entry from the Quick Index and from the +# Folder Tree View (if specified). The default is YES. + +SHOW_FILES = YES + +# Set the SHOW_NAMESPACES tag to NO to disable the generation of the +# Namespaces page. +# This will remove the Namespaces entry from the Quick Index +# and from the Folder Tree View (if specified). The default is YES. + +SHOW_NAMESPACES = YES + +# The FILE_VERSION_FILTER tag can be used to specify a program or script that +# doxygen should invoke to get the current version for each file (typically from +# the version control system). Doxygen will invoke the program by executing (via +# popen()) the command , where is the value of +# the FILE_VERSION_FILTER tag, and is the name of an input file +# provided by doxygen. Whatever the program writes to standard output +# is used as the file version. See the manual for examples. + +FILE_VERSION_FILTER = + +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed +# by doxygen. The layout file controls the global structure of the generated +# output files in an output format independent way. To create the layout file +# that represents doxygen's defaults, run doxygen with the -l option. +# You can optionally specify a file name after the option, if omitted +# DoxygenLayout.xml will be used as the name of the layout file. + +LAYOUT_FILE = + +# The CITE_BIB_FILES tag can be used to specify one or more bib files +# containing the references data. This must be a list of .bib files. The +# .bib extension is automatically appended if omitted. Using this command +# requires the bibtex tool to be installed. See also +# http://en.wikipedia.org/wiki/BibTeX for more info. For LaTeX the style +# of the bibliography can be controlled using LATEX_BIB_STYLE. To use this +# feature you need bibtex and perl available in the search path. Do not use +# file names with spaces, bibtex cannot handle them. + +CITE_BIB_FILES = + +#--------------------------------------------------------------------------- +# configuration options related to warning and progress messages +#--------------------------------------------------------------------------- + +# The QUIET tag can be used to turn on/off the messages that are generated +# by doxygen. Possible values are YES and NO. If left blank NO is used. + +QUIET = YES + +# The WARNINGS tag can be used to turn on/off the warning messages that are +# generated by doxygen. Possible values are YES and NO. If left blank +# NO is used. + +WARNINGS = YES + +# If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings +# for undocumented members. If EXTRACT_ALL is set to YES then this flag will +# automatically be disabled. + +WARN_IF_UNDOCUMENTED = NO + +# If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for +# potential errors in the documentation, such as not documenting some +# parameters in a documented function, or documenting parameters that +# don't exist or using markup commands wrongly. + +WARN_IF_DOC_ERROR = YES + +# The WARN_NO_PARAMDOC option can be enabled to get warnings for +# functions that are documented, but have no documentation for their parameters +# or return value. If set to NO (the default) doxygen will only warn about +# wrong or incomplete parameter documentation, but not about the absence of +# documentation. + +WARN_NO_PARAMDOC = NO + +# The WARN_FORMAT tag determines the format of the warning messages that +# doxygen can produce. The string should contain the $file, $line, and $text +# tags, which will be replaced by the file and line number from which the +# warning originated and the warning text. Optionally the format may contain +# $version, which will be replaced by the version of the file (if it could +# be obtained via FILE_VERSION_FILTER) + +WARN_FORMAT = "$file:$line: $text" + +# The WARN_LOGFILE tag can be used to specify a file to which warning +# and error messages should be written. If left blank the output is written +# to stderr. + +WARN_LOGFILE = + +#--------------------------------------------------------------------------- +# configuration options related to the input files +#--------------------------------------------------------------------------- + +# The INPUT tag can be used to specify the files and/or directories that contain +# documented source files. You may enter file names like "myfile.cpp" or +# directories like "/usr/src/myproject". Separate the files or directories +# with spaces. + +INPUT = + +# This tag can be used to specify the character encoding of the source files +# that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is +# also the default input encoding. Doxygen uses libiconv (or the iconv built +# into libc) for the transcoding. See http://www.gnu.org/software/libiconv for +# the list of possible encodings. + +INPUT_ENCODING = UTF-8 + +# If the value of the INPUT tag contains directories, you can use the +# FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank the following patterns are tested: +# *.c *.cc *.cxx *.cpp *.c++ *.d *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh +# *.hxx *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.dox *.py +# *.f90 *.f *.for *.vhd *.vhdl + +FILE_PATTERNS = *.c \ + *.cc \ + *.cxx \ + *.cpp \ + *.c++ \ + *.d \ + *.java \ + *.ii \ + *.ixx \ + *.ipp \ + *.i++ \ + *.inl \ + *.h \ + *.hh \ + *.hxx \ + *.hpp \ + *.h++ \ + *.idl \ + *.odl \ + *.cs \ + *.php \ + *.php3 \ + *.inc \ + *.m \ + *.md \ + *.mm \ + *.dox \ + *.py \ + *.f90 \ + *.f \ + *.for \ + *.vhd \ + *.vhdl \ + *.ino + +# The RECURSIVE tag can be used to turn specify whether or not subdirectories +# should be searched for input files as well. Possible values are YES and NO. +# If left blank NO is used. + +RECURSIVE = YES + +# The EXCLUDE tag can be used to specify files and/or directories that should be +# excluded from the INPUT source files. This way you can easily exclude a +# subdirectory from a directory tree whose root is specified with the INPUT tag. +# Note that relative paths are relative to the directory from which doxygen is +# run. + +EXCLUDE = + +# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or +# directories that are symbolic links (a Unix file system feature) are excluded +# from the input. + +EXCLUDE_SYMLINKS = NO + +# If the value of the INPUT tag contains directories, you can use the +# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude +# certain files from those directories. Note that the wildcards are matched +# against the file with absolute path, so to exclude all test directories +# for example use the pattern */test/* + +EXCLUDE_PATTERNS = + +# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names +# (namespaces, classes, functions, etc.) that should be excluded from the +# output. The symbol name can be a fully qualified name, a word, or if the +# wildcard * is used, a substring. Examples: ANamespace, AClass, +# AClass::ANamespace, ANamespace::*Test + +EXCLUDE_SYMBOLS = + +# The EXAMPLE_PATH tag can be used to specify one or more files or +# directories that contain example code fragments that are included (see +# the \include command). + +EXAMPLE_PATH = + +# If the value of the EXAMPLE_PATH tag contains directories, you can use the +# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp +# and *.h) to filter out the source-files in the directories. If left +# blank all files are included. + +EXAMPLE_PATTERNS = examples/* + +# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be +# searched for input files to be used with the \include or \dontinclude +# commands irrespective of the value of the RECURSIVE tag. +# Possible values are YES and NO. If left blank NO is used. + +EXAMPLE_RECURSIVE = YES + +# The IMAGE_PATH tag can be used to specify one or more files or +# directories that contain image that are included in the documentation (see +# the \image command). + +IMAGE_PATH = + +# The INPUT_FILTER tag can be used to specify a program that doxygen should +# invoke to filter for each input file. Doxygen will invoke the filter program +# by executing (via popen()) the command , where +# is the value of the INPUT_FILTER tag, and is the name of an +# input file. Doxygen will then use the output that the filter program writes +# to standard output. +# If FILTER_PATTERNS is specified, this tag will be ignored. +# Note that the filter must not add or remove lines; it is applied before the +# code is scanned, but not when the output code is generated. If lines are added +# or removed, the anchors will not be placed correctly. + +INPUT_FILTER = + +# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern +# basis. +# Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. +# The filters are a list of the form: +# pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further +# info on how filters are used. If FILTER_PATTERNS is empty or if +# non of the patterns match the file name, INPUT_FILTER is applied. + +FILTER_PATTERNS = + +# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using +# INPUT_FILTER) will be used to filter the input files when producing source +# files to browse (i.e. when SOURCE_BROWSER is set to YES). + +FILTER_SOURCE_FILES = NO + +# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file +# pattern. A pattern will override the setting for FILTER_PATTERN (if any) +# and it is also possible to disable source filtering for a specific pattern +# using *.ext= (so without naming a filter). This option only has effect when +# FILTER_SOURCE_FILES is enabled. + +FILTER_SOURCE_PATTERNS = + +# If the USE_MD_FILE_AS_MAINPAGE tag refers to the name of a markdown file that +# is part of the input, its contents will be placed on the main page +# (index.html). This can be useful if you have a project on for instance GitHub +# and want reuse the introduction page also for the doxygen output. + +USE_MDFILE_AS_MAINPAGE = + +#--------------------------------------------------------------------------- +# configuration options related to source browsing +#--------------------------------------------------------------------------- + +# If the SOURCE_BROWSER tag is set to YES then a list of source files will +# be generated. Documented entities will be cross-referenced with these sources. +# Note: To get rid of all source code in the generated output, make sure also +# VERBATIM_HEADERS is set to NO. + +SOURCE_BROWSER = NO + +# Setting the INLINE_SOURCES tag to YES will include the body +# of functions and classes directly in the documentation. + +INLINE_SOURCES = NO + +# Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct +# doxygen to hide any special comment blocks from generated source code +# fragments. Normal C, C++ and Fortran comments will always remain visible. + +STRIP_CODE_COMMENTS = NO + +# If the REFERENCED_BY_RELATION tag is set to YES +# then for each documented function all documented +# functions referencing it will be listed. + +REFERENCED_BY_RELATION = NO + +# If the REFERENCES_RELATION tag is set to YES +# then for each documented function all documented entities +# called/used by that function will be listed. + +REFERENCES_RELATION = NO + +# If the REFERENCES_LINK_SOURCE tag is set to YES (the default) +# and SOURCE_BROWSER tag is set to YES, then the hyperlinks from +# functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will +# link to the source code. +# Otherwise they will link to the documentation. + +REFERENCES_LINK_SOURCE = YES + +# If the USE_HTAGS tag is set to YES then the references to source code +# will point to the HTML generated by the htags(1) tool instead of doxygen +# built-in source browser. The htags tool is part of GNU's global source +# tagging system (see http://www.gnu.org/software/global/global.html). You +# will need version 4.8.6 or higher. + +USE_HTAGS = NO + +# If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen +# will generate a verbatim copy of the header file for each class for +# which an include is specified. Set to NO to disable this. + +VERBATIM_HEADERS = YES + +#--------------------------------------------------------------------------- +# configuration options related to the alphabetical class index +#--------------------------------------------------------------------------- + +# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index +# of all compounds will be generated. Enable this if the project +# contains a lot of classes, structs, unions or interfaces. + +ALPHABETICAL_INDEX = YES + +# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then +# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns +# in which this list will be split (can be a number in the range [1..20]) + +COLS_IN_ALPHA_INDEX = 5 + +# In case all classes in a project start with a common prefix, all +# classes will be put under the same header in the alphabetical index. +# The IGNORE_PREFIX tag can be used to specify one or more prefixes that +# should be ignored while generating the index headers. + +IGNORE_PREFIX = + +#--------------------------------------------------------------------------- +# configuration options related to the HTML output +#--------------------------------------------------------------------------- + +# If the GENERATE_HTML tag is set to YES (the default) Doxygen will +# generate HTML output. + +GENERATE_HTML = YES + +# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `html' will be used as the default path. + +HTML_OUTPUT = html + +# The HTML_FILE_EXTENSION tag can be used to specify the file extension for +# each generated HTML page (for example: .htm,.php,.asp). If it is left blank +# doxygen will generate files with .html extension. + +HTML_FILE_EXTENSION = .html + +# The HTML_HEADER tag can be used to specify a personal HTML header for +# each generated HTML page. If it is left blank doxygen will generate a +# standard header. Note that when using a custom header you are responsible +# for the proper inclusion of any scripts and style sheets that doxygen +# needs, which is dependent on the configuration options used. +# It is advised to generate a default header using "doxygen -w html +# header.html footer.html stylesheet.css YourConfigFile" and then modify +# that header. Note that the header is subject to change so you typically +# have to redo this when upgrading to a newer version of doxygen or when +# changing the value of configuration settings such as GENERATE_TREEVIEW! + +HTML_HEADER = + +# The HTML_FOOTER tag can be used to specify a personal HTML footer for +# each generated HTML page. If it is left blank doxygen will generate a +# standard footer. + +HTML_FOOTER = + +# The HTML_STYLESHEET tag can be used to specify a user-defined cascading +# style sheet that is used by each HTML page. It can be used to +# fine-tune the look of the HTML output. If left blank doxygen will +# generate a default style sheet. Note that it is recommended to use +# HTML_EXTRA_STYLESHEET instead of this one, as it is more robust and this +# tag will in the future become obsolete. + +HTML_STYLESHEET = + +# The HTML_EXTRA_STYLESHEET tag can be used to specify an additional +# user-defined cascading style sheet that is included after the standard +# style sheets created by doxygen. Using this option one can overrule +# certain style aspects. This is preferred over using HTML_STYLESHEET +# since it does not replace the standard style sheet and is therefor more +# robust against future updates. Doxygen will copy the style sheet file to +# the output directory. + +HTML_EXTRA_STYLESHEET = Doxymods.css + +# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or +# other source files which should be copied to the HTML output directory. Note +# that these files will be copied to the base HTML output directory. Use the +# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these +# files. In the HTML_STYLESHEET file, use the file name only. Also note that +# the files will be copied as-is; there are no commands or markers available. + +HTML_EXTRA_FILES = + +# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. +# Doxygen will adjust the colors in the style sheet and background images +# according to this color. Hue is specified as an angle on a colorwheel, +# see http://en.wikipedia.org/wiki/Hue for more information. +# For instance the value 0 represents red, 60 is yellow, 120 is green, +# 180 is cyan, 240 is blue, 300 purple, and 360 is red again. +# The allowed range is 0 to 359. + +HTML_COLORSTYLE_HUE = 220 + +# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of +# the colors in the HTML output. For a value of 0 the output will use +# grayscales only. A value of 255 will produce the most vivid colors. + +HTML_COLORSTYLE_SAT = 100 + +# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to +# the luminance component of the colors in the HTML output. Values below +# 100 gradually make the output lighter, whereas values above 100 make +# the output darker. The value divided by 100 is the actual gamma applied, +# so 80 represents a gamma of 0.8, The value 220 represents a gamma of 2.2, +# and 100 does not change the gamma. + +HTML_COLORSTYLE_GAMMA = 80 + +# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML +# page will contain the date and time when the page was generated. Setting +# this to NO can help when comparing the output of multiple runs. + +HTML_TIMESTAMP = YES + +# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML +# documentation will contain sections that can be hidden and shown after the +# page has loaded. + +HTML_DYNAMIC_SECTIONS = NO + +# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of +# entries shown in the various tree structured indices initially; the user +# can expand and collapse entries dynamically later on. Doxygen will expand +# the tree to such a level that at most the specified number of entries are +# visible (unless a fully collapsed tree already exceeds this amount). +# So setting the number of entries 1 will produce a full collapsed tree by +# default. 0 is a special value representing an infinite number of entries +# and will result in a full expanded tree by default. + +HTML_INDEX_NUM_ENTRIES = 100 + +# If the GENERATE_DOCSET tag is set to YES, additional index files +# will be generated that can be used as input for Apple's Xcode 3 +# integrated development environment, introduced with OSX 10.5 (Leopard). +# To create a documentation set, doxygen will generate a Makefile in the +# HTML output directory. Running make will produce the docset in that +# directory and running "make install" will install the docset in +# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find +# it at startup. +# See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html +# for more information. + +GENERATE_DOCSET = NO + +# When GENERATE_DOCSET tag is set to YES, this tag determines the name of the +# feed. A documentation feed provides an umbrella under which multiple +# documentation sets from a single provider (such as a company or product suite) +# can be grouped. + +DOCSET_FEEDNAME = "Doxygen generated docs" + +# When GENERATE_DOCSET tag is set to YES, this tag specifies a string that +# should uniquely identify the documentation set bundle. This should be a +# reverse domain-name style string, e.g. com.mycompany.MyDocSet. Doxygen +# will append .docset to the name. + +DOCSET_BUNDLE_ID = org.doxygen.Project + +# When GENERATE_PUBLISHER_ID tag specifies a string that should uniquely +# identify the documentation publisher. This should be a reverse domain-name +# style string, e.g. com.mycompany.MyDocSet.documentation. + +DOCSET_PUBLISHER_ID = org.doxygen.Publisher + +# The GENERATE_PUBLISHER_NAME tag identifies the documentation publisher. + +DOCSET_PUBLISHER_NAME = Publisher + +# If the GENERATE_HTMLHELP tag is set to YES, additional index files +# will be generated that can be used as input for tools like the +# Microsoft HTML help workshop to generate a compiled HTML help file (.chm) +# of the generated HTML documentation. + +GENERATE_HTMLHELP = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can +# be used to specify the file name of the resulting .chm file. You +# can add a path in front of the file if the result should not be +# written to the html output directory. + +CHM_FILE = + +# If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can +# be used to specify the location (absolute path including file name) of +# the HTML help compiler (hhc.exe). If non-empty doxygen will try to run +# the HTML help compiler on the generated index.hhp. + +HHC_LOCATION = + +# If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag +# controls if a separate .chi index file is generated (YES) or that +# it should be included in the master .chm file (NO). + +GENERATE_CHI = NO + +# If the GENERATE_HTMLHELP tag is set to YES, the CHM_INDEX_ENCODING +# is used to encode HtmlHelp index (hhk), content (hhc) and project file +# content. + +CHM_INDEX_ENCODING = + +# If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag +# controls whether a binary table of contents is generated (YES) or a +# normal table of contents (NO) in the .chm file. + +BINARY_TOC = NO + +# The TOC_EXPAND flag can be set to YES to add extra items for group members +# to the contents of the HTML help documentation and to the tree view. + +TOC_EXPAND = NO + +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and +# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated +# that can be used as input for Qt's qhelpgenerator to generate a +# Qt Compressed Help (.qch) of the generated HTML documentation. + +GENERATE_QHP = NO + +# If the QHG_LOCATION tag is specified, the QCH_FILE tag can +# be used to specify the file name of the resulting .qch file. +# The path specified is relative to the HTML output folder. + +QCH_FILE = + +# The QHP_NAMESPACE tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#namespace + +QHP_NAMESPACE = org.doxygen.Project + +# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating +# Qt Help Project output. For more information please see +# http://doc.trolltech.com/qthelpproject.html#virtual-folders + +QHP_VIRTUAL_FOLDER = doc + +# If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to +# add. For more information please see +# http://doc.trolltech.com/qthelpproject.html#custom-filters + +QHP_CUST_FILTER_NAME = + +# The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the +# custom filter to add. For more information please see +# +# Qt Help Project / Custom Filters. + +QHP_CUST_FILTER_ATTRS = + +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this +# project's +# filter section matches. +# +# Qt Help Project / Filter Attributes. + +QHP_SECT_FILTER_ATTRS = + +# If the GENERATE_QHP tag is set to YES, the QHG_LOCATION tag can +# be used to specify the location of Qt's qhelpgenerator. +# If non-empty doxygen will try to run qhelpgenerator on the generated +# .qhp file. + +QHG_LOCATION = + +# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files +# will be generated, which together with the HTML files, form an Eclipse help +# plugin. To install this plugin and make it available under the help contents +# menu in Eclipse, the contents of the directory containing the HTML and XML +# files needs to be copied into the plugins directory of eclipse. The name of +# the directory within the plugins directory should be the same as +# the ECLIPSE_DOC_ID value. After copying Eclipse needs to be restarted before +# the help appears. + +GENERATE_ECLIPSEHELP = NO + +# A unique identifier for the eclipse help plugin. When installing the plugin +# the directory name containing the HTML and XML files should also have +# this name. + +ECLIPSE_DOC_ID = org.doxygen.Project + +# The DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) +# at top of each HTML page. The value NO (the default) enables the index and +# the value YES disables it. Since the tabs have the same information as the +# navigation tree you can set this option to NO if you already set +# GENERATE_TREEVIEW to YES. + +DISABLE_INDEX = YES + +# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index +# structure should be generated to display hierarchical information. +# If the tag value is set to YES, a side panel will be generated +# containing a tree-like index structure (just like the one that +# is generated for HTML Help). For this to work a browser that supports +# JavaScript, DHTML, CSS and frames is required (i.e. any modern browser). +# Windows users are probably better off using the HTML help feature. +# Since the tree basically has the same information as the tab index you +# could consider to set DISABLE_INDEX to NO when enabling this option. + +GENERATE_TREEVIEW = YES + +# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values +# (range [0,1..20]) that doxygen will group on one line in the generated HTML +# documentation. Note that a value of 0 will completely suppress the enum +# values from appearing in the overview section. + +ENUM_VALUES_PER_LINE = 4 + +# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be +# used to set the initial width (in pixels) of the frame in which the tree +# is shown. + +TREEVIEW_WIDTH = 200 + +# When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open +# links to external symbols imported via tag files in a separate window. + +EXT_LINKS_IN_WINDOW = NO + +# Use this tag to change the font size of Latex formulas included +# as images in the HTML documentation. The default is 10. Note that +# when you change the font size after a successful doxygen run you need +# to manually remove any form_*.png images from the HTML output directory +# to force them to be regenerated. + +FORMULA_FONTSIZE = 10 + +# Use the FORMULA_TRANPARENT tag to determine whether or not the images +# generated for formulas are transparent PNGs. Transparent PNGs are +# not supported properly for IE 6.0, but are supported on all modern browsers. +# Note that when changing this option you need to delete any form_*.png files +# in the HTML output before the changes have effect. + +FORMULA_TRANSPARENT = YES + +# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax +# (see http://www.mathjax.org) which uses client side Javascript for the +# rendering instead of using prerendered bitmaps. Use this if you do not +# have LaTeX installed or if you want to formulas look prettier in the HTML +# output. When enabled you may also need to install MathJax separately and +# configure the path to it using the MATHJAX_RELPATH option. + +USE_MATHJAX = NO + +# When MathJax is enabled you can set the default output format to be used for +# the MathJax output. Supported types are HTML-CSS, NativeMML (i.e. MathML) and +# SVG. The default value is HTML-CSS, which is slower, but has the best +# compatibility. + +MATHJAX_FORMAT = HTML-CSS + +# When MathJax is enabled you need to specify the location relative to the +# HTML output directory using the MATHJAX_RELPATH option. The destination +# directory should contain the MathJax.js script. For instance, if the mathjax +# directory is located at the same level as the HTML output directory, then +# MATHJAX_RELPATH should be ../mathjax. The default value points to +# the MathJax Content Delivery Network so you can quickly see the result without +# installing MathJax. +# However, it is strongly recommended to install a local +# copy of MathJax from http://www.mathjax.org before deployment. + +MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest + +# The MATHJAX_EXTENSIONS tag can be used to specify one or MathJax extension +# names that should be enabled during MathJax rendering. + +MATHJAX_EXTENSIONS = + +# The MATHJAX_CODEFILE tag can be used to specify a file with javascript +# pieces of code that will be used on startup of the MathJax code. + +MATHJAX_CODEFILE = + +# When the SEARCHENGINE tag is enabled doxygen will generate a search box +# for the HTML output. The underlying search engine uses javascript +# and DHTML and should work on any modern browser. Note that when using +# HTML help (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets +# (GENERATE_DOCSET) there is already a search function so this one should +# typically be disabled. For large projects the javascript based search engine +# can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution. + +SEARCHENGINE = YES + +# When the SERVER_BASED_SEARCH tag is enabled the search engine will be +# implemented using a web server instead of a web client using Javascript. +# There are two flavours of web server based search depending on the +# EXTERNAL_SEARCH setting. When disabled, doxygen will generate a PHP script for +# searching and an index file used by the script. When EXTERNAL_SEARCH is +# enabled the indexing and searching needs to be provided by external tools. +# See the manual for details. + +SERVER_BASED_SEARCH = NO + +# When EXTERNAL_SEARCH is enabled doxygen will no longer generate the PHP +# script for searching. Instead the search results are written to an XML file +# which needs to be processed by an external indexer. Doxygen will invoke an +# external search engine pointed to by the SEARCHENGINE_URL option to obtain +# the search results. Doxygen ships with an example indexer (doxyindexer) and +# search engine (doxysearch.cgi) which are based on the open source search +# engine library Xapian. See the manual for configuration details. + +EXTERNAL_SEARCH = NO + +# The SEARCHENGINE_URL should point to a search engine hosted by a web server +# which will returned the search results when EXTERNAL_SEARCH is enabled. +# Doxygen ships with an example search engine (doxysearch) which is based on +# the open source search engine library Xapian. See the manual for configuration +# details. + +SEARCHENGINE_URL = + +# When SERVER_BASED_SEARCH and EXTERNAL_SEARCH are both enabled the unindexed +# search data is written to a file for indexing by an external tool. With the +# SEARCHDATA_FILE tag the name of this file can be specified. + +SEARCHDATA_FILE = searchdata.xml + +# When SERVER_BASED_SEARCH AND EXTERNAL_SEARCH are both enabled the +# EXTERNAL_SEARCH_ID tag can be used as an identifier for the project. This is +# useful in combination with EXTRA_SEARCH_MAPPINGS to search through multiple +# projects and redirect the results back to the right project. + +EXTERNAL_SEARCH_ID = + +# The EXTRA_SEARCH_MAPPINGS tag can be used to enable searching through doxygen +# projects other than the one defined by this configuration file, but that are +# all added to the same external search index. Each project needs to have a +# unique id set via EXTERNAL_SEARCH_ID. The search mapping then maps the id +# of to a relative location where the documentation can be found. +# The format is: EXTRA_SEARCH_MAPPINGS = id1=loc1 id2=loc2 ... + +EXTRA_SEARCH_MAPPINGS = + +#--------------------------------------------------------------------------- +# configuration options related to the LaTeX output +#--------------------------------------------------------------------------- + +# If the GENERATE_LATEX tag is set to YES (the default) Doxygen will +# generate Latex output. + +GENERATE_LATEX = NO + +# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `latex' will be used as the default path. + +LATEX_OUTPUT = latex + +# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be +# invoked. If left blank `latex' will be used as the default command name. +# Note that when enabling USE_PDFLATEX this option is only used for +# generating bitmaps for formulas in the HTML output, but not in the +# Makefile that is written to the output directory. + +LATEX_CMD_NAME = latex + +# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to +# generate index for LaTeX. If left blank `makeindex' will be used as the +# default command name. + +MAKEINDEX_CMD_NAME = makeindex + +# If the COMPACT_LATEX tag is set to YES Doxygen generates more compact +# LaTeX documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_LATEX = NO + +# The PAPER_TYPE tag can be used to set the paper type that is used +# by the printer. Possible values are: a4, letter, legal and +# executive. If left blank a4 will be used. + +PAPER_TYPE = a4 + +# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX +# packages that should be included in the LaTeX output. + +EXTRA_PACKAGES = + +# The LATEX_HEADER tag can be used to specify a personal LaTeX header for +# the generated latex document. The header should contain everything until +# the first chapter. If it is left blank doxygen will generate a +# standard header. Notice: only use this tag if you know what you are doing! + +LATEX_HEADER = + +# The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for +# the generated latex document. The footer should contain everything after +# the last chapter. If it is left blank doxygen will generate a +# standard footer. Notice: only use this tag if you know what you are doing! + +LATEX_FOOTER = + +# The LATEX_EXTRA_FILES tag can be used to specify one or more extra images +# or other source files which should be copied to the LaTeX output directory. +# Note that the files will be copied as-is; there are no commands or markers +# available. + +LATEX_EXTRA_FILES = + +# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated +# is prepared for conversion to pdf (using ps2pdf). The pdf file will +# contain links (just like the HTML output) instead of page references +# This makes the output suitable for online browsing using a pdf viewer. + +PDF_HYPERLINKS = YES + +# If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of +# plain latex in the generated Makefile. Set this option to YES to get a +# higher quality PDF documentation. + +USE_PDFLATEX = YES + +# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\batchmode. +# command to the generated LaTeX files. This will instruct LaTeX to keep +# running if errors occur, instead of asking the user for help. +# This option is also used when generating formulas in HTML. + +LATEX_BATCHMODE = NO + +# If LATEX_HIDE_INDICES is set to YES then doxygen will not +# include the index chapters (such as File Index, Compound Index, etc.) +# in the output. + +LATEX_HIDE_INDICES = NO + +# If LATEX_SOURCE_CODE is set to YES then doxygen will include +# source code with syntax highlighting in the LaTeX output. +# Note that which sources are shown also depends on other settings +# such as SOURCE_BROWSER. + +LATEX_SOURCE_CODE = YES + +# The LATEX_BIB_STYLE tag can be used to specify the style to use for the +# bibliography, e.g. plainnat, or ieeetr. The default style is "plain". See +# http://en.wikipedia.org/wiki/BibTeX for more info. + +LATEX_BIB_STYLE = plain + +#--------------------------------------------------------------------------- +# configuration options related to the RTF output +#--------------------------------------------------------------------------- + +# If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output +# The RTF output is optimized for Word 97 and may not look very pretty with +# other RTF readers or editors. + +GENERATE_RTF = NO + +# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `rtf' will be used as the default path. + +RTF_OUTPUT = rtf + +# If the COMPACT_RTF tag is set to YES Doxygen generates more compact +# RTF documents. This may be useful for small projects and may help to +# save some trees in general. + +COMPACT_RTF = NO + +# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated +# will contain hyperlink fields. The RTF file will +# contain links (just like the HTML output) instead of page references. +# This makes the output suitable for online browsing using WORD or other +# programs which support those fields. +# Note: wordpad (write) and others do not support links. + +RTF_HYPERLINKS = NO + +# Load style sheet definitions from file. Syntax is similar to doxygen's +# config file, i.e. a series of assignments. You only have to provide +# replacements, missing definitions are set to their default value. + +RTF_STYLESHEET_FILE = + +# Set optional variables used in the generation of an rtf document. +# Syntax is similar to doxygen's config file. + +RTF_EXTENSIONS_FILE = + +#--------------------------------------------------------------------------- +# configuration options related to the man page output +#--------------------------------------------------------------------------- + +# If the GENERATE_MAN tag is set to YES (the default) Doxygen will +# generate man pages + +GENERATE_MAN = NO + +# The MAN_OUTPUT tag is used to specify where the man pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `man' will be used as the default path. + +MAN_OUTPUT = man + +# The MAN_EXTENSION tag determines the extension that is added to +# the generated man pages (default is the subroutine's section .3) + +MAN_EXTENSION = .3 + +# If the MAN_LINKS tag is set to YES and Doxygen generates man output, +# then it will generate one additional man file for each entity +# documented in the real man page(s). These additional files +# only source the real man page, but without them the man command +# would be unable to find the correct page. The default is NO. + +MAN_LINKS = NO + +#--------------------------------------------------------------------------- +# configuration options related to the XML output +#--------------------------------------------------------------------------- + +# If the GENERATE_XML tag is set to YES Doxygen will +# generate an XML file that captures the structure of +# the code including all documentation. + +GENERATE_XML = NO + +# The XML_OUTPUT tag is used to specify where the XML pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be +# put in front of it. If left blank `xml' will be used as the default path. + +XML_OUTPUT = xml + +# The XML_SCHEMA tag can be used to specify an XML schema, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_SCHEMA = + +# The XML_DTD tag can be used to specify an XML DTD, +# which can be used by a validating XML parser to check the +# syntax of the XML files. + +XML_DTD = + +# If the XML_PROGRAMLISTING tag is set to YES Doxygen will +# dump the program listings (including syntax highlighting +# and cross-referencing information) to the XML output. Note that +# enabling this will significantly increase the size of the XML output. + +XML_PROGRAMLISTING = YES + +#--------------------------------------------------------------------------- +# configuration options related to the DOCBOOK output +#--------------------------------------------------------------------------- + +# If the GENERATE_DOCBOOK tag is set to YES Doxygen will generate DOCBOOK files +# that can be used to generate PDF. + +GENERATE_DOCBOOK = NO + +# The DOCBOOK_OUTPUT tag is used to specify where the DOCBOOK pages will be put. +# If a relative path is entered the value of OUTPUT_DIRECTORY will be put in +# front of it. If left blank docbook will be used as the default path. + +DOCBOOK_OUTPUT = docbook + +#--------------------------------------------------------------------------- +# configuration options for the AutoGen Definitions output +#--------------------------------------------------------------------------- + +# If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will +# generate an AutoGen Definitions (see autogen.sf.net) file +# that captures the structure of the code including all +# documentation. Note that this feature is still experimental +# and incomplete at the moment. + +GENERATE_AUTOGEN_DEF = NO + +#--------------------------------------------------------------------------- +# configuration options related to the Perl module output +#--------------------------------------------------------------------------- + +# If the GENERATE_PERLMOD tag is set to YES Doxygen will +# generate a Perl module file that captures the structure of +# the code including all documentation. Note that this +# feature is still experimental and incomplete at the +# moment. + +GENERATE_PERLMOD = NO + +# If the PERLMOD_LATEX tag is set to YES Doxygen will generate +# the necessary Makefile rules, Perl scripts and LaTeX code to be able +# to generate PDF and DVI output from the Perl module output. + +PERLMOD_LATEX = NO + +# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be +# nicely formatted so it can be parsed by a human reader. +# This is useful +# if you want to understand what is going on. +# On the other hand, if this +# tag is set to NO the size of the Perl module output will be much smaller +# and Perl will parse it just the same. + +PERLMOD_PRETTY = YES + +# The names of the make variables in the generated doxyrules.make file +# are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. +# This is useful so different doxyrules.make files included by the same +# Makefile don't overwrite each other's variables. + +PERLMOD_MAKEVAR_PREFIX = + +#--------------------------------------------------------------------------- +# Configuration options related to the preprocessor +#--------------------------------------------------------------------------- + +# If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will +# evaluate all C-preprocessor directives found in the sources and include +# files. + +ENABLE_PREPROCESSING = YES + +# If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro +# names in the source code. If set to NO (the default) only conditional +# compilation will be performed. Macro expansion can be done in a controlled +# way by setting EXPAND_ONLY_PREDEF to YES. + +MACRO_EXPANSION = NO + +# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES +# then the macro expansion is limited to the macros specified with the +# PREDEFINED and EXPAND_AS_DEFINED tags. + +EXPAND_ONLY_PREDEF = NO + +# If the SEARCH_INCLUDES tag is set to YES (the default) the includes files +# pointed to by INCLUDE_PATH will be searched when a #include is found. + +SEARCH_INCLUDES = YES + +# The INCLUDE_PATH tag can be used to specify one or more directories that +# contain include files that are not input files but should be processed by +# the preprocessor. + +INCLUDE_PATH = + +# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard +# patterns (like *.h and *.hpp) to filter out the header-files in the +# directories. If left blank, the patterns specified with FILE_PATTERNS will +# be used. + +INCLUDE_FILE_PATTERNS = + +# The PREDEFINED tag can be used to specify one or more macro names that +# are defined before the preprocessor is started (similar to the -D option of +# gcc). The argument of the tag is a list of macros of the form: name +# or name=definition (no spaces). If the definition and the = are +# omitted =1 is assumed. To prevent a macro definition from being +# undefined via #undef or recursively expanded use the := operator +# instead of the = operator. + +PREDEFINED = + +# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then +# this tag can be used to specify a list of macro names that should be expanded. +# The macro definition that is found in the sources will be used. +# Use the PREDEFINED tag if you want to use a different macro definition that +# overrules the definition found in the source code. + +EXPAND_AS_DEFINED = + +# If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then +# doxygen's preprocessor will remove all references to function-like macros +# that are alone on a line, have an all uppercase name, and do not end with a +# semicolon, because these will confuse the parser if not removed. + +SKIP_FUNCTION_MACROS = YES + +#--------------------------------------------------------------------------- +# Configuration::additions related to external references +#--------------------------------------------------------------------------- + +# The TAGFILES option can be used to specify one or more tagfiles. For each +# tag file the location of the external documentation should be added. The +# format of a tag file without this location is as follows: +# +# TAGFILES = file1 file2 ... +# Adding location for the tag files is done as follows: +# +# TAGFILES = file1=loc1 "file2 = loc2" ... +# where "loc1" and "loc2" can be relative or absolute paths +# or URLs. Note that each tag file must have a unique name (where the name does +# NOT include the path). If a tag file is not located in the directory in which +# doxygen is run, you must also specify the path to the tagfile here. + +TAGFILES = + +# When a file name is specified after GENERATE_TAGFILE, doxygen will create +# a tag file that is based on the input files it reads. + +GENERATE_TAGFILE = + +# If the ALLEXTERNALS tag is set to YES all external classes will be listed +# in the class index. If set to NO only the inherited external classes +# will be listed. + +ALLEXTERNALS = NO + +# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed +# in the modules index. If set to NO, only the current project's groups will +# be listed. + +EXTERNAL_GROUPS = YES + +# If the EXTERNAL_PAGES tag is set to YES all external pages will be listed +# in the related pages index. If set to NO, only the current project's +# pages will be listed. + +EXTERNAL_PAGES = YES + +# The PERL_PATH should be the absolute path and name of the perl script +# interpreter (i.e. the result of `which perl'). + +PERL_PATH = /usr/bin/perl + +#--------------------------------------------------------------------------- +# Configuration options related to the dot tool +#--------------------------------------------------------------------------- + +# If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will +# generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base +# or super classes. Setting the tag to NO turns the diagrams off. Note that +# this option also works with HAVE_DOT disabled, but it is recommended to +# install and use dot, since it yields more powerful graphs. + +CLASS_DIAGRAMS = YES + +# You can define message sequence charts within doxygen comments using the \msc +# command. Doxygen will then run the mscgen tool (see +# http://www.mcternan.me.uk/mscgen/) to produce the chart and insert it in the +# documentation. The MSCGEN_PATH tag allows you to specify the directory where +# the mscgen tool resides. If left empty the tool is assumed to be found in the +# default search path. + +MSCGEN_PATH = + +# If set to YES, the inheritance and collaboration graphs will hide +# inheritance and usage relations if the target is undocumented +# or is not a class. + +HIDE_UNDOC_RELATIONS = YES + +# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is +# available from the path. This tool is part of Graphviz, a graph visualization +# toolkit from AT&T and Lucent Bell Labs. The other options in this section +# have no effect if this option is set to NO (the default) + +HAVE_DOT = NO + +# The DOT_NUM_THREADS specifies the number of dot invocations doxygen is +# allowed to run in parallel. When set to 0 (the default) doxygen will +# base this on the number of processors available in the system. You can set it +# explicitly to a value larger than 0 to get control over the balance +# between CPU load and processing speed. + +DOT_NUM_THREADS = 0 + +# By default doxygen will use the Helvetica font for all dot files that +# doxygen generates. When you want a differently looking font you can specify +# the font name using DOT_FONTNAME. You need to make sure dot is able to find +# the font, which can be done by putting it in a standard location or by setting +# the DOTFONTPATH environment variable or by setting DOT_FONTPATH to the +# directory containing the font. + +DOT_FONTNAME = Helvetica + +# The DOT_FONTSIZE tag can be used to set the size of the font of dot graphs. +# The default size is 10pt. + +DOT_FONTSIZE = 10 + +# By default doxygen will tell dot to use the Helvetica font. +# If you specify a different font using DOT_FONTNAME you can use DOT_FONTPATH to +# set the path where dot can find it. + +DOT_FONTPATH = + +# If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect inheritance relations. Setting this tag to YES will force the +# CLASS_DIAGRAMS tag to NO. + +CLASS_GRAPH = YES + +# If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for each documented class showing the direct and +# indirect implementation dependencies (inheritance, containment, and +# class references variables) of the class with other documented classes. + +COLLABORATION_GRAPH = YES + +# If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen +# will generate a graph for groups, showing the direct groups dependencies + +GROUP_GRAPHS = YES + +# If the UML_LOOK tag is set to YES doxygen will generate inheritance and +# collaboration diagrams in a style similar to the OMG's Unified Modeling +# Language. + +UML_LOOK = NO + +# If the UML_LOOK tag is enabled, the fields and methods are shown inside +# the class node. If there are many fields or methods and many nodes the +# graph may become too big to be useful. The UML_LIMIT_NUM_FIELDS +# threshold limits the number of items for each type to make the size more +# manageable. Set this to 0 for no limit. Note that the threshold may be +# exceeded by 50% before the limit is enforced. + +UML_LIMIT_NUM_FIELDS = 10 + +# If set to YES, the inheritance and collaboration graphs will show the +# relations between templates and their instances. + +TEMPLATE_RELATIONS = NO + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT +# tags are set to YES then doxygen will generate a graph for each documented +# file showing the direct and indirect include dependencies of the file with +# other documented files. + +INCLUDE_GRAPH = YES + +# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and +# HAVE_DOT tags are set to YES then doxygen will generate a graph for each +# documented header file showing the documented files that directly or +# indirectly include this file. + +INCLUDED_BY_GRAPH = YES + +# If the CALL_GRAPH and HAVE_DOT options are set to YES then +# doxygen will generate a call dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable call graphs +# for selected functions only using the \callgraph command. + +CALL_GRAPH = NO + +# If the CALLER_GRAPH and HAVE_DOT tags are set to YES then +# doxygen will generate a caller dependency graph for every global function +# or class method. Note that enabling this option will significantly increase +# the time of a run. So in most cases it will be better to enable caller +# graphs for selected functions only using the \callergraph command. + +CALLER_GRAPH = NO + +# If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen +# will generate a graphical hierarchy of all classes instead of a textual one. + +GRAPHICAL_HIERARCHY = YES + +# If the DIRECTORY_GRAPH and HAVE_DOT tags are set to YES +# then doxygen will show the dependencies a directory has on other directories +# in a graphical way. The dependency relations are determined by the #include +# relations between the files in the directories. + +DIRECTORY_GRAPH = YES + +# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images +# generated by dot. Possible values are svg, png, jpg, or gif. +# If left blank png will be used. If you choose svg you need to set +# HTML_FILE_EXTENSION to xhtml in order to make the SVG files +# visible in IE 9+ (other browsers do not have this requirement). + +DOT_IMAGE_FORMAT = png + +# If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to +# enable generation of interactive SVG images that allow zooming and panning. +# Note that this requires a modern browser other than Internet Explorer. +# Tested and working are Firefox, Chrome, Safari, and Opera. For IE 9+ you +# need to set HTML_FILE_EXTENSION to xhtml in order to make the SVG files +# visible. Older versions of IE do not have SVG support. + +INTERACTIVE_SVG = NO + +# The tag DOT_PATH can be used to specify the path where the dot tool can be +# found. If left blank, it is assumed the dot tool can be found in the path. + +DOT_PATH = + +# The DOTFILE_DIRS tag can be used to specify one or more directories that +# contain dot files that are included in the documentation (see the +# \dotfile command). + +DOTFILE_DIRS = + +# The MSCFILE_DIRS tag can be used to specify one or more directories that +# contain msc files that are included in the documentation (see the +# \mscfile command). + +MSCFILE_DIRS = + +# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of +# nodes that will be shown in the graph. If the number of nodes in a graph +# becomes larger than this value, doxygen will truncate the graph, which is +# visualized by representing a node as a red box. Note that doxygen if the +# number of direct children of the root node in a graph is already larger than +# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note +# that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH. + +DOT_GRAPH_MAX_NODES = 50 + +# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the +# graphs generated by dot. A depth value of 3 means that only nodes reachable +# from the root by following a path via at most 3 edges will be shown. Nodes +# that lay further from the root node will be omitted. Note that setting this +# option to 1 or 2 may greatly reduce the computation time needed for large +# code bases. Also note that the size of a graph can be further restricted by +# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction. + +MAX_DOT_GRAPH_DEPTH = 0 + +# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent +# background. This is disabled by default, because dot on Windows does not +# seem to support this out of the box. Warning: Depending on the platform used, +# enabling this option may lead to badly anti-aliased labels on the edges of +# a graph (i.e. they become hard to read). + +DOT_TRANSPARENT = NO + +# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output +# files in one run (i.e. multiple -o and -T options on the command line). This +# makes dot run faster, but since only newer versions of dot (>1.8.10) +# support this, this feature is disabled by default. + +DOT_MULTI_TARGETS = NO + +# If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will +# generate a legend page explaining the meaning of the various boxes and +# arrows in the dot generated graphs. + +GENERATE_LEGEND = YES + +# If the DOT_CLEANUP tag is set to YES (the default) Doxygen will +# remove the intermediate dot files that are used to generate +# the various graphs. + +DOT_CLEANUP = YES diff --git a/libraries/ethercard-master/Doxylogo.png b/libraries/ethercard-master/Doxylogo.png new file mode 100644 index 0000000..695ed91 Binary files /dev/null and b/libraries/ethercard-master/Doxylogo.png differ diff --git a/libraries/ethercard-master/Doxymods.css b/libraries/ethercard-master/Doxymods.css new file mode 100644 index 0000000..ec01e9e --- /dev/null +++ b/libraries/ethercard-master/Doxymods.css @@ -0,0 +1,73 @@ +/* Get rid of all those overriden font families */ +body, table, div, p, dl, +#projectname, +#projectbrief, +#nav-tree .label { + font: 15px/21px Georgia,serif +} + +#projectname { + color: #990000; + font-weight: bold; + font-size: 24px; +} + +#titlearea table { + padding: 20px; +} + +dl.reflist dt, div.memproto { + border: 1px solid #A8B8D9; +} + +dl.reflist dd, div.memdoc { + border-width: 0; +} + +div.contents { + margin-left: 20px; margin-right: 16px; + width: 700 px; +} + +/* Get rid of the gradient backgrounds and background colors */ +div.header, +#nav-tree, +.navpath ul, +.memproto, dl.reflist dt { + background: none; +} +#nav-tree .selected { + background: none; + background-color: #990000; + text-shadow: none; +} + +a, a:link, a:visited { + color: #2A5685; + text-decoration: underline; +} +a:active, a:hover { + color: #CC0000; +} + +.directory tr.even, +pre.fragment, +.mdescLeft, .mdescRight, .memItemLeft, .memItemRight, .memTemplItemLeft, .memTemplItemRight, .memTemplParams, +.memproto, dl.reflist dt { + background-color: #EEE; + box-shadow: none; + border-radius: 0; +} +.memdoc, dl.reflist dd { + background: none; + box-shadow: none; + border-radius: 0; +} +pre.fragment { + background-color: #FAFAFA; + border: 1px solid #DADADA; + margin: 1em 1em 1em 1.6em; + overflow-x: auto; + overflow-y: hidden; + width: auto; +} diff --git a/libraries/ethercard-master/EtherCard.cpp b/libraries/ethercard-master/EtherCard.cpp new file mode 100644 index 0000000..d3142d6 --- /dev/null +++ b/libraries/ethercard-master/EtherCard.cpp @@ -0,0 +1,433 @@ +// This code slightly follows the conventions of, but is not derived from: +// EHTERSHIELD_H library for Arduino etherShield +// Copyright (c) 2008 Xing Yu. All right reserved. (this is LGPL v2.1) +// It is however derived from the enc28j60 and ip code (which is GPL v2) +// Author: Pascal Stang +// Modified by: Guido Socher +// DHCP code: Andrew Lindsay +// Hence: GPL V2 +// +// 2010-05-19 + +#include +#include +#include + +#define WRITEBUF 0 +#define READBUF 1 +#define BUFCOUNT 2 + +//#define FLOATEMIT // uncomment line to enable $T in emit_P for float emitting + +byte Stash::map[SCRATCH_MAP_SIZE]; +Stash::Block Stash::bufs[BUFCOUNT]; + +uint8_t Stash::allocBlock () { + for (uint8_t i = 0; i < sizeof map; ++i) + if (map[i] != 0) + for (uint8_t j = 0; j < 8; ++j) + if (bitRead(map[i], j)) { + bitClear(map[i], j); + return (i << 3) + j; + } + return 0; +} + +void Stash::freeBlock (uint8_t block) { + bitSet(map[block>>3], block & 7); +} + +uint8_t Stash::fetchByte (uint8_t blk, uint8_t off) { + return blk == bufs[WRITEBUF].bnum ? bufs[WRITEBUF].bytes[off] : + blk == bufs[READBUF].bnum ? bufs[READBUF].bytes[off] : + ether.peekin(blk, off); +} + + +// block 0 is special since always occupied +void Stash::initMap (uint8_t last /*=SCRATCH_PAGE_NUM*/) { + last = SCRATCH_PAGE_NUM; + while (--last > 0) + freeBlock(last); +} + +// load a page/block either into the write or into the readbuffer +void Stash::load (uint8_t idx, uint8_t blk) { + if (blk != bufs[idx].bnum) { + if (idx == WRITEBUF) { + ether.copyout(bufs[idx].bnum, bufs[idx].bytes); + if (blk == bufs[READBUF].bnum) + bufs[READBUF].bnum = 255; // forget read page if same + } else if (blk == bufs[WRITEBUF].bnum) { + // special case: read page is same as write buffer + memcpy(&bufs[READBUF], &bufs[WRITEBUF], sizeof bufs[0]); + return; + } + bufs[idx].bnum = blk; + ether.copyin(bufs[idx].bnum, bufs[idx].bytes); + } +} + +uint8_t Stash::freeCount () { + uint8_t count = 0; + for (uint8_t i = 0; i < sizeof map; ++i) + for (uint8_t m = 0x80; m != 0; m >>= 1) + if (map[i] & m) + ++count; + return count; +} + +// create a new stash; make it the active stash; return the first block as a handle +uint8_t Stash::create () { + uint8_t blk = allocBlock(); + load(WRITEBUF, blk); + bufs[WRITEBUF].head.count = 0; + bufs[WRITEBUF].head.first = bufs[0].head.last = blk; + bufs[WRITEBUF].tail = sizeof (StashHeader); + bufs[WRITEBUF].next = 0; + return open(blk); // you are now the active stash +} + +// the stashheader part only contains reasonable data if we are the first block +uint8_t Stash::open (uint8_t blk) { + curr = blk; + offs = sizeof (StashHeader); // goto first byte + load(READBUF, curr); + memcpy((StashHeader*) this, bufs[READBUF].bytes, sizeof (StashHeader)); + return curr; +} + +// save the metadata of current block into the first block +void Stash::save () { + load(WRITEBUF, first); + memcpy(bufs[WRITEBUF].bytes, (StashHeader*) this, sizeof (StashHeader)); + if (bufs[READBUF].bnum == first) + load(READBUF, 0); // invalidates original in case it was the same block +} + +// follow the linked list of blocks and free every block +void Stash::release () { + while (first > 0) { + freeBlock(first); + first = ether.peekin(first, 63); + } +} + +void Stash::put (char c) { + load(WRITEBUF, last); + uint8_t t = bufs[WRITEBUF].tail; + bufs[WRITEBUF].bytes[t++] = c; + if (t <= 62) + bufs[WRITEBUF].tail = t; + else { + bufs[WRITEBUF].next = allocBlock(); + last = bufs[WRITEBUF].next; + load(WRITEBUF, last); + bufs[WRITEBUF].tail = bufs[WRITEBUF].next = 0; + ++count; + } +} + +char Stash::get () { + load(READBUF, curr); + if (curr == last && offs >= bufs[READBUF].tail) + return 0; + uint8_t b = bufs[READBUF].bytes[offs]; + if (++offs >= 63 && curr != last) { + curr = bufs[READBUF].next; + offs = 0; + } + return b; +} + +// fetchbyte(last, 62) is tail, i.e., number of characters in last block +uint16_t Stash::size () { + return 63 * count + fetchByte(last, 62) - sizeof (StashHeader); +} + +static char* wtoa (uint16_t value, char* ptr) { + if (value > 9) + ptr = wtoa(value / 10, ptr); + *ptr = '0' + value % 10; + *++ptr = 0; + return ptr; +} + +// write information about the fmt string and the arguments into special page/block 0 +// block 0 is initially marked as allocated and never returned by allocateBlock +void Stash::prepare (const char* fmt PROGMEM, ...) { + Stash::load(WRITEBUF, 0); + uint16_t* segs = Stash::bufs[WRITEBUF].words; + *segs++ = strlen_P(fmt); +#ifdef __AVR__ + *segs++ = (uint16_t) fmt; +#else + *segs++ = (uint32_t) fmt; + *segs++ = (uint32_t) fmt >> 16; +#endif + va_list ap; + va_start(ap, fmt); + for (;;) { + char c = pgm_read_byte(fmt++); + if (c == 0) + break; + if (c == '$') { +#ifdef __AVR__ + uint16_t argval = va_arg(ap, uint16_t), arglen = 0; +#else + uint32_t argval = va_arg(ap, int), arglen = 0; +#endif + switch (pgm_read_byte(fmt++)) { + case 'D': { + char buf[7]; + wtoa(argval, buf); + arglen = strlen(buf); + break; + } + case 'S': + arglen = strlen((const char*) argval); + break; + case 'F': + arglen = strlen_P((const char*) argval); + break; + case 'E': { + byte* s = (byte*) argval; + char d; + while ((d = eeprom_read_byte(s++)) != 0) + ++arglen; + break; + } + case 'H': { + Stash stash (argval); + arglen = stash.size(); + break; + } + } +#ifdef __AVR__ + *segs++ = argval; +#else + *segs++ = argval; + *segs++ = argval >> 16; +#endif + Stash::bufs[WRITEBUF].words[0] += arglen - 2; + } + } + va_end(ap); +} + +uint16_t Stash::length () { + Stash::load(WRITEBUF, 0); + return Stash::bufs[WRITEBUF].words[0]; +} + +void Stash::extract (uint16_t offset, uint16_t count, void* buf) { + Stash::load(WRITEBUF, 0); + uint16_t* segs = Stash::bufs[WRITEBUF].words; +#ifdef __AVR__ + const char* fmt PROGMEM = (const char*) *++segs; +#else + const char* fmt PROGMEM = (const char*)((segs[2] << 16) | segs[1]); + segs += 2; +#endif + Stash stash; + char mode = '@', tmp[7], *ptr = NULL, *out = (char*) buf; + for (uint16_t i = 0; i < offset + count; ) { + char c = 0; + switch (mode) { + case '@': { + c = pgm_read_byte(fmt++); + if (c == 0) + return; + if (c != '$') + break; +#ifdef __AVR__ + uint16_t arg = *++segs; +#else + uint32_t arg = *++segs; + arg |= *++segs << 16; +#endif + mode = pgm_read_byte(fmt++); + switch (mode) { + case 'D': + wtoa(arg, tmp); + ptr = tmp; + break; + case 'S': + case 'F': + case 'E': + ptr = (char*) arg; + break; + case 'H': + stash.open(arg); + ptr = (char*) &stash; + break; + } + continue; + } + case 'D': + case 'S': + c = *ptr++; + break; + case 'F': + c = pgm_read_byte(ptr++); + break; + case 'E': + c = eeprom_read_byte((byte*) ptr++); + break; + case 'H': + c = ((Stash*) ptr)->get(); + break; + } + if (c == 0) { + mode = '@'; + continue; + } + if (i >= offset) + *out++ = c; + ++i; + } +} + +void Stash::cleanup () { + Stash::load(WRITEBUF, 0); + uint16_t* segs = Stash::bufs[WRITEBUF].words; +#ifdef __AVR__ + const char* fmt PROGMEM = (const char*) *++segs; +#else + const char* fmt PROGMEM = (const char*)((segs[2] << 16) | segs[1]); + segs += 2; +#endif + for (;;) { + char c = pgm_read_byte(fmt++); + if (c == 0) + break; + if (c == '$') { +#ifdef __AVR__ + uint16_t arg = *++segs; +#else + uint32_t arg = *++segs; + arg |= *++segs << 16; +#endif + if (pgm_read_byte(fmt++) == 'H') { + Stash stash (arg); + stash.release(); + } + } + } +} + +void BufferFiller::emit_p(const char* fmt PROGMEM, ...) { + va_list ap; + va_start(ap, fmt); + for (;;) { + char c = pgm_read_byte(fmt++); + if (c == 0) + break; + if (c != '$') { + *ptr++ = c; + continue; + } + c = pgm_read_byte(fmt++); + switch (c) { + case 'D': +#ifdef __AVR__ + wtoa(va_arg(ap, uint16_t), (char*) ptr); +#else + wtoa(va_arg(ap, int), (char*) ptr); +#endif + break; +#ifdef FLOATEMIT + case 'T': + dtostrf ( va_arg(ap, double), 10, 3, (char*)ptr ); + break; +#endif + case 'H': { +#ifdef __AVR__ + char p1 = va_arg(ap, uint16_t); +#else + char p1 = va_arg(ap, int); +#endif + char p2; + p2 = (p1 >> 4) & 0x0F; + p1 = p1 & 0x0F; + if (p1 > 9) p1 += 0x07; // adjust 0x0a-0x0f to come out 'a'-'f' + p1 += 0x30; // and complete + if (p2 > 9) p2 += 0x07; // adjust 0x0a-0x0f to come out 'a'-'f' + p2 += 0x30; // and complete + *ptr++ = p2; + *ptr++ = p1; + continue; + } + case 'L': + ltoa(va_arg(ap, long), (char*) ptr, 10); + break; + case 'S': + strcpy((char*) ptr, va_arg(ap, const char*)); + break; + case 'F': { + const char* s PROGMEM = va_arg(ap, const char*); + char d; + while ((d = pgm_read_byte(s++)) != 0) + *ptr++ = d; + continue; + } + case 'E': { + byte* s = va_arg(ap, byte*); + char d; + while ((d = eeprom_read_byte(s++)) != 0) + *ptr++ = d; + continue; + } + default: + *ptr++ = c; + continue; + } + ptr += strlen((char*) ptr); + } + va_end(ap); +} + +EtherCard ether; + +uint8_t EtherCard::mymac[ETH_LEN]; // my MAC address +uint8_t EtherCard::myip[IP_LEN]; // my ip address +uint8_t EtherCard::netmask[IP_LEN]; // subnet mask +uint8_t EtherCard::broadcastip[IP_LEN]; // broadcast address +uint8_t EtherCard::gwip[IP_LEN]; // gateway +uint8_t EtherCard::dhcpip[IP_LEN]; // dhcp server +uint8_t EtherCard::dnsip[IP_LEN]; // dns server +uint8_t EtherCard::hisip[IP_LEN]; // ip address of remote host +uint16_t EtherCard::hisport = HTTP_PORT; // tcp port to browse to +bool EtherCard::using_dhcp = false; +bool EtherCard::persist_tcp_connection = false; +uint16_t EtherCard::delaycnt = 0; //request gateway ARP lookup + +uint8_t EtherCard::begin (const uint16_t size, + const uint8_t* macaddr, + uint8_t csPin) { + using_dhcp = false; +#if ETHERCARD_STASH + Stash::initMap(); +#endif + copyMac(mymac, macaddr); + return initialize(size, mymac, csPin); +} + +bool EtherCard::staticSetup (const uint8_t* my_ip, + const uint8_t* gw_ip, + const uint8_t* dns_ip, + const uint8_t* mask) { + using_dhcp = false; + + if (my_ip != 0) + copyIp(myip, my_ip); + if (gw_ip != 0) + setGwIp(gw_ip); + if (dns_ip != 0) + copyIp(dnsip, dns_ip); + if(mask != 0) + copyIp(netmask, mask); + updateBroadcastAddress(); + delaycnt = 0; //request gateway ARP lookup + return true; +} diff --git a/libraries/ethercard-master/EtherCard.h b/libraries/ethercard-master/EtherCard.h new file mode 100644 index 0000000..f1656d6 --- /dev/null +++ b/libraries/ethercard-master/EtherCard.h @@ -0,0 +1,644 @@ +// This code slightly follows the conventions of, but is not derived from: +// EHTERSHIELD_H library for Arduino etherShield +// Copyright (c) 2008 Xing Yu. All right reserved. (this is LGPL v2.1) +// It is however derived from the enc28j60 and ip code (which is GPL v2) +// Author: Pascal Stang +// Modified by: Guido Socher +// DHCP code: Andrew Lindsay +// Hence: GPL V2 +// +// 2010-05-19 +// +// +// PIN Connections (Using Arduino UNO): +// VCC - 3.3V +// GND - GND +// SCK - Pin 13 +// SO - Pin 12 +// SI - Pin 11 +// CS - Pin 8 +// +/** @file */ + +#ifndef EtherCard_h +#define EtherCard_h +#ifndef __PROG_TYPES_COMPAT__ + #define __PROG_TYPES_COMPAT__ +#endif + +#if ARDUINO >= 100 +#include // Arduino 1.0 +#define WRITE_RESULT size_t +#define WRITE_RETURN return 1; +#else +#include // Arduino 0022 +#define WRITE_RESULT void +#define WRITE_RETURN +#endif + +#include +#include "enc28j60.h" +#include "net.h" + +/** Enable DHCP. +* Setting this to zero disables the use of DHCP; if a program uses DHCP it will +* still compile but the program will not work. Saves about 60 bytes SRAM and +* 1550 bytes flash. +*/ +#define ETHERCARD_DHCP 1 + +/** Enable client connections. +* Setting this to zero means that the program cannot issue TCP client requests +* anymore. Compilation will still work but the request will never be +* issued. Saves 4 bytes SRAM and 550 byte flash. +*/ +#define ETHERCARD_TCPCLIENT 1 + +/** Enable TCP server functionality. +* Setting this to zero means that the program will not accept TCP client +* requests. Saves 2 bytes SRAM and 250 bytes flash. +*/ +#define ETHERCARD_TCPSERVER 1 + +/** Enable UDP server functionality. +* If zero UDP server is disabled. It is +* still possible to register callbacks but these will never be called. Saves +* about 40 bytes SRAM and 200 bytes flash. If building with -flto this does not +* seem to save anything; maybe the linker is then smart enough to optimize the +* call away. +*/ +#define ETHERCARD_UDPSERVER 1 + +/** Enable automatic reply to pings. +* Setting to zero means that the program will not automatically answer to +* PINGs anymore. Also the callback that can be registered to answer incoming +* pings will not be called. Saves 2 bytes SRAM and 230 bytes flash. +*/ +#define ETHERCARD_ICMP 1 + +/** Enable use of stash. +* Setting this to zero means that the stash mechanism cannot be used. Again +* compilation will still work but the program may behave very unexpectedly. +* Saves 30 bytes SRAM and 80 bytes flash. +*/ +#define ETHERCARD_STASH 1 + + +/** This type definition defines the structure of a UDP server event handler callback funtion */ +typedef void (*UdpServerCallback)( + uint16_t dest_port, ///< Port the packet was sent to + uint8_t src_ip[IP_LEN], ///< IP address of the sender + uint16_t src_port, ///< Port the packet was sent from + const char *data, ///< UDP payload data + uint16_t len); ///< Length of the payload data + +/** This type definition defines the structure of a DHCP Option callback funtion */ +typedef void (*DhcpOptionCallback)( + uint8_t option, ///< The option number + const byte* data, ///< DHCP option data + uint8_t len); ///< Length of the DHCP option data + + +/** This structure describes the structure of memory used within the ENC28J60 network interface. */ +typedef struct { + uint8_t count; ///< Number of allocated pages + uint8_t first; ///< First allocated page + uint8_t last; ///< Last allocated page +} StashHeader; + +/** This class provides access to the memory within the ENC28J60 network interface. */ +class Stash : public /*Stream*/ Print, private StashHeader { + uint8_t curr; //!< Current page + uint8_t offs; //!< Current offset in page + + typedef struct { + union { + uint8_t bytes[64]; + uint16_t words[32]; + struct { + StashHeader head; // StashHeader is only stored in first block + uint8_t filler[59]; + uint8_t tail; // only meaningful if bnum==last; number of bytes in last block + uint8_t next; // pointer to next block + }; + }; + uint8_t bnum; + } Block; + + static uint8_t allocBlock (); + static void freeBlock (uint8_t block); + static uint8_t fetchByte (uint8_t blk, uint8_t off); + + static Block bufs[2]; + static uint8_t map[SCRATCH_MAP_SIZE]; + +public: + static void initMap (uint8_t last=SCRATCH_PAGE_NUM); + static void load (uint8_t idx, uint8_t blk); + static uint8_t freeCount (); + + Stash () : curr (0) { first = 0; } + Stash (uint8_t fd) { open(fd); } + + uint8_t create (); + uint8_t open (uint8_t blk); + void save (); + void release (); + + void put (char c); + char get (); + uint16_t size (); + + virtual WRITE_RESULT write(uint8_t b) { put(b); WRITE_RETURN } + + // virtual int available() { + // if (curr != last) + // return 1; + // load(1, last); + // return offs < bufs[1].tail; + // } + // virtual int read() { + // return available() ? get() : -1; + // } + // virtual int peek() { + // return available() ? bufs[1].bytes[offs] : -1; + // } + // virtual void flush() { + // curr = last; + // offs = 63; + // } + + static void prepare (const char* fmt PROGMEM, ...); + static uint16_t length (); + static void extract (uint16_t offset, uint16_t count, void* buf); + static void cleanup (); + + friend void dumpBlock (const char* msg, uint8_t idx); // optional + friend void dumpStash (const char* msg, void* ptr); // optional +}; + +/** This class populates network send and receive buffers. +* +* This class provides formatted printing into memory. Users can use it to write into send buffers. +* +* Nota: PGM_P: is a pointer to a string in program space (defined in the source code, updated to PROGMEM) +* +* # Format string +* +* | Format | Parameter | Output +* |--------|-------------|---------- +* | $D | uint16_t | Decimal representation +* | $T ¤ | double | Decimal representation with 3 digits after decimal sign ([-]d.ddd) +* | $H | uint16_t | Hexadecimal value of lsb (from 00 to ff) +* | $L | long | Decimal representation +* | $S | const char* | Copy null terminated string from main memory +* | $F | PGM_P | Copy null terminated string from program space +* | $E | byte* | Copy null terminated string from EEPROM space +* | $$ | _none_ | '$' +* +* ¤ _Available only if FLOATEMIT is defined_ +* +* # Examples +* ~~~~~~~~~~~~~{.c} +* uint16_t ddd = 123; +* double ttt = 1.23; +* uint16_t hhh = 0xa4; +* long lll = 123456789; +* char * sss; +* char fff[] PROGMEM = "MyMemory"; +* +* sss[0] = 'G'; +* sss[1] = 'P'; +* sss[2] = 'L'; +* sss[3] = 0; +* buf.emit_p( PSTR("ddd=$D\n"), ddd ); // "ddd=123\n" +* buf.emit_p( PSTR("ttt=$T\n"), ttt ); // "ttt=1.23\n" **TO CHECK** +* buf.emit_p( PSTR("hhh=$H\n"), hhh ); // "hhh=a4\n" +* buf.emit_p( PSTR("lll=$L\n"), lll ); // "lll=123456789\n" +* buf.emit_p( PSTR("sss=$S\n"), sss ); // "sss=GPL\n" +* buf.emit_p( PSTR("fff=$F\n"), fff ); // "fff=MyMemory\n" +* ~~~~~~~~~~~~~ +* +*/ +class BufferFiller : public Print { + uint8_t *start; //!< Pointer to start of buffer + uint8_t *ptr; //!< Pointer to cursor position +public: + /** @brief Empty constructor + */ + BufferFiller () {} + + /** @brief Constructor + * @param buf Pointer to the ethernet data buffer + */ + BufferFiller (uint8_t* buf) : start (buf), ptr (buf) {} + + /** @brief Add formatted text to buffer + * @param fmt Format string (see Class description) + * @param ... parameters for format string + */ + void emit_p (const char* fmt PROGMEM, ...); + + /** @brief Add data to buffer from main memory + * @param s Pointer to data + * @param n Number of characters to copy + */ + void emit_raw (const char* s, uint16_t n) { memcpy(ptr, s, n); ptr += n; } + + /** @brief Add data to buffer from program space string + * @param p Program space string pointer + * @param n Number of characters to copy + */ + void emit_raw_p (const char* p PROGMEM, uint16_t n) { memcpy_P(ptr, p, n); ptr += n; } + + /** @brief Get pointer to start of buffer + * @return uint8_t* Pointer to start of buffer + */ + uint8_t* buffer () const { return start; } + + /** @brief Get cursor position + * @return uint16_t Cursor postion + */ + uint16_t position () const { return ptr - start; } + + /** @brief Write one byte to buffer + * @param v Byte to add to buffer + */ + virtual WRITE_RESULT write (uint8_t v) { *ptr++ = v; WRITE_RETURN } +}; + +/** This class provides the main interface to a ENC28J60 based network interface card and is the class most users will use. +* @note All TCP/IP client (outgoing) connections are made from source port in range 2816-3071. Do not use these source ports for other purposes. +*/ +class EtherCard : public Ethernet { +public: + static uint8_t mymac[ETH_LEN]; ///< MAC address + static uint8_t myip[IP_LEN]; ///< IP address + static uint8_t netmask[IP_LEN]; ///< Netmask + static uint8_t broadcastip[IP_LEN]; ///< Subnet broadcast address + static uint8_t gwip[IP_LEN]; ///< Gateway + static uint8_t dhcpip[IP_LEN]; ///< DHCP server IP address + static uint8_t dnsip[IP_LEN]; ///< DNS server IP address + static uint8_t hisip[IP_LEN]; ///< DNS lookup result + static uint16_t hisport; ///< TCP port to connect to (default 80) + static bool using_dhcp; ///< True if using DHCP + static bool persist_tcp_connection; ///< False to break connections on first packet received + static uint16_t delaycnt; ///< Counts number of cycles of packetLoop when no packet received - used to trigger periodic gateway ARP request + + // EtherCard.cpp + /** @brief Initialise the network interface + * @param size Size of data buffer + * @param macaddr Hardware address to assign to the network interface (6 bytes) + * @param csPin Arduino pin number connected to chip select. Default = 8 + * @return uint8_t Firmware version or zero on failure. + */ + static uint8_t begin (const uint16_t size, const uint8_t* macaddr, + uint8_t csPin = SS); + + /** @brief Configure network interface with static IP + * @param my_ip IP address (4 bytes). 0 for no change. + * @param gw_ip Gateway address (4 bytes). 0 for no change. Default = 0 + * @param dns_ip DNS address (4 bytes). 0 for no change. Default = 0 + * @param mask Subnet mask (4 bytes). 0 for no change. Default = 0 + * @return bool Returns true on success - actually always true + */ + static bool staticSetup (const uint8_t* my_ip, + const uint8_t* gw_ip = 0, + const uint8_t* dns_ip = 0, + const uint8_t* mask = 0); + + // tcpip.cpp + /** @brief Sends a UDP packet to the IP address of last processed received packet + * @param data Pointer to data payload + * @param len Size of data payload (max 220) + * @param port Source IP port + */ + static void makeUdpReply (const char *data, uint8_t len, uint16_t port); + + /** @brief Parse received data + * @param plen Size of data to parse (e.g. return value of packetReceive()). + * @return uint16_t Offset of TCP payload data in data buffer or zero if packet processed + * @note Data buffer is shared by receive and transmit functions + * @note Only handles ARP and IP + */ + static uint16_t packetLoop (uint16_t plen); + + /** @brief Accept a TCP/IP connection + * @param port IP port to accept on - do nothing if wrong port + * @param plen Number of bytes in packet + * @return uint16_t Offset within packet of TCP payload. Zero for no data. + */ + static uint16_t accept (uint16_t port, uint16_t plen); + + /** @brief Send a response to a HTTP request + * @param dlen Size of the HTTP (TCP) payload + */ + static void httpServerReply (uint16_t dlen); + + /** @brief Send a response to a HTTP request + * @param dlen Size of the HTTP (TCP) payload + * @param flags TCP flags + */ + static void httpServerReply_with_flags (uint16_t dlen , uint8_t flags); + + /** @brief Acknowledge TCP message + * @todo Is this / should this be private? + */ + static void httpServerReplyAck (); + + /** @brief Set the gateway address + * @param gwipaddr Gateway address (4 bytes) + */ + static void setGwIp (const uint8_t *gwipaddr); + + /** @brief Updates the broadcast address based on current IP address and subnet mask + */ + static void updateBroadcastAddress(); + + /** @brief Check if got gateway hardware address (ARP lookup) + * @return unit8_t True if gateway found + */ + static uint8_t clientWaitingGw (); + + /** @brief Check if got gateway DNS address (ARP lookup) + * @return unit8_t True if DNS found + */ + static uint8_t clientWaitingDns (); + + /** @brief Prepare a TCP request + * @param result_cb Pointer to callback function that handles TCP result + * @param datafill_cb Pointer to callback function that handles TCP data payload + * @param port Remote TCP/IP port to connect to + * @return unit8_t ID of TCP/IP session (0-7) + * @note Return value provides id of the request to allow up to 7 concurrent requests + */ + static uint8_t clientTcpReq (uint8_t (*result_cb)(uint8_t,uint8_t,uint16_t,uint16_t), + uint16_t (*datafill_cb)(uint8_t),uint16_t port); + + /** @brief Prepare HTTP request + * @param urlbuf Pointer to c-string URL folder + * @param urlbuf_varpart Pointer to c-string URL file + * @param hoststr Pointer to c-string hostname + * @param additionalheaderline Pointer to c-string with additional HTTP header info + * @param callback Pointer to callback function to handle response + * @note Request sent in main packetloop + */ + static void browseUrl (const char *urlbuf, const char *urlbuf_varpart, + const char *hoststr, const char *additionalheaderline, + void (*callback)(uint8_t,uint16_t,uint16_t)); + + /** @brief Prepare HTTP request + * @param urlbuf Pointer to c-string URL folder + * @param urlbuf_varpart Pointer to c-string URL file + * @param hoststr Pointer to c-string hostname + * @param callback Pointer to callback function to handle response + * @note Request sent in main packetloop + */ + static void browseUrl (const char *urlbuf, const char *urlbuf_varpart, + const char *hoststr, + void (*callback)(uint8_t,uint16_t,uint16_t)); + + /** @brief Prepare HTTP post message + * @param urlbuf Pointer to c-string URL folder + * @param hoststr Pointer to c-string hostname + * @param additionalheaderline Pointer to c-string with additional HTTP header info + * @param postval Pointer to c-string HTML Post value + * @param callback Pointer to callback function to handle response + * @note Request sent in main packetloop + */ + static void httpPost (const char *urlbuf, const char *hoststr, + const char *additionalheaderline, const char *postval, + void (*callback)(uint8_t,uint16_t,uint16_t)); + + /** @brief Send NTP request + * @param ntpip IP address of NTP server + * @param srcport IP port to send from + */ + static void ntpRequest (uint8_t *ntpip,uint8_t srcport); + + /** @brief Process network time protocol response + * @param time Pointer to integer to hold result + * @param dstport_l Destination port to expect response. Set to zero to accept on any port + * @return uint8_t True (1) on success + */ + static uint8_t ntpProcessAnswer (uint32_t *time, uint8_t dstport_l); + + /** @brief Prepare a UDP message for transmission + * @param sport Source port + * @param dip Pointer to 4 byte destination IP address + * @param dport Destination port + */ + static void udpPrepare (uint16_t sport, const uint8_t *dip, uint16_t dport); + + /** @brief Transmit UDP packet + * @param len Size of payload + */ + static void udpTransmit (uint16_t len); + + /** @brief Sends a UDP packet + * @param data Pointer to data + * @param len Size of payload (maximum 220 octets / bytes) + * @param sport Source port + * @param dip Pointer to 4 byte destination IP address + * @param dport Destination port + */ + static void sendUdp (const char *data, uint8_t len, uint16_t sport, + const uint8_t *dip, uint16_t dport); + + /** @brief Resister the function to handle ping events + * @param cb Pointer to function + */ + static void registerPingCallback (void (*cb)(uint8_t*)); + + /** @brief Send ping + * @param destip Ponter to 4 byte destination IP address + */ + static void clientIcmpRequest (const uint8_t *destip); + + /** @brief Check for ping response + * @param ip_monitoredhost Pointer to 4 byte IP address of host to check + * @return uint8_t True (1) if ping response from specified host + */ + static uint8_t packetLoopIcmpCheckReply (const uint8_t *ip_monitoredhost); + + /** @brief Send a wake on lan message + * @param wolmac Pointer to 6 byte hardware (MAC) address of host to send message to + */ + static void sendWol (uint8_t *wolmac); + + // new stash-based API + /** @brief Send TCP request + */ + static uint8_t tcpSend (); + + /** @brief Get TCP reply + * @return char* Pointer to TCP reply payload. NULL if no data. + */ + static const char* tcpReply (uint8_t fd); + + /** @brief Configure TCP connections to be persistent or not + * @param persist True to maintain TCP connection. False to finish TCP connection after first packet. + */ + static void persistTcpConnection(bool persist); + + //udpserver.cpp + /** @brief Register function to handle incomint UDP events + * @param callback Function to handle event + * @param port Port to listen on + */ + static void udpServerListenOnPort(UdpServerCallback callback, uint16_t port); + + /** @brief Pause listing on UDP port + * @brief port Port to pause + */ + static void udpServerPauseListenOnPort(uint16_t port); + + /** @brief Resume listing on UDP port + * @brief port Port to pause + */ + static void udpServerResumeListenOnPort(uint16_t port); + + /** @brief Check if UDP server is listening on any ports + * @return bool True if listening on any ports + */ + static bool udpServerListening(); //called by tcpip, in packetLoop + + /** @brief Passes packet to UDP Server + * @param len Not used + * @return bool True if packet processed + */ + static bool udpServerHasProcessedPacket(uint16_t len); //called by tcpip, in packetLoop + + // dhcp.cpp + /** @brief Update DHCP state + * @param len Length of received data packet + */ + static void DhcpStateMachine(uint16_t len); + + /** @brief Not implemented + * @todo Implement dhcpStartTime or remove declaration + */ + static uint32_t dhcpStartTime (); + + /** @brief Not implemented + * @todo Implement dhcpLeaseTime or remove declaration + */ + static uint32_t dhcpLeaseTime (); + + /** @brief Not implemented + * @todo Implement dhcpLease or remove declaration + */ + static bool dhcpLease (); + + /** @brief Configure network interface with DHCP + * @param hname The hostname to pass to the DHCP server + * @param fromRam Set true to indicate whether hname is in RAM or in program space. Default = false + * @return bool True if DHCP successful + * @note Blocks until DHCP complete or timeout after 60 seconds + */ + static bool dhcpSetup (const char *hname = NULL, bool fromRam =false); + + /** @brief Register a callback for a specific DHCP option number + * @param option The option number to request from the DHCP server + * @param callback The function to be call when the option is received + */ + static void dhcpAddOptionCallback(uint8_t option, DhcpOptionCallback callback); + + // dns.cpp + /** @brief Perform DNS lookup + * @param name Host name to lookup + * @param fromRam Set true to indicate whether name is in RAM or in program space. Default = false + * @return bool True on success. + * @note Result is stored in hisip member + */ + static bool dnsLookup (const char* name, bool fromRam =false); + + // webutil.cpp + /** @brief Copies an IP address + * @param dst Pointer to the 4 byte destination + * @param src Pointer to the 4 byte source + * @note There is no check of source or destination size. Ensure both are 4 bytes + */ + static void copyIp (uint8_t *dst, const uint8_t *src); + + /** @brief Copies a hardware address + * @param dst Pointer to the 6 byte destination + * @param src Pointer to the 6 byte destination + * @note There is no check of source or destination size. Ensure both are 6 bytes + */ + static void copyMac (uint8_t *dst, const uint8_t *src); + + /** @brief Output to serial port in dotted decimal IP format + * @param buf Pointer to 4 byte IP address + * @note There is no check of source or destination size. Ensure both are 4 bytes + */ + static void printIp (const uint8_t *buf); + + /** @brief Output message and IP address to serial port in dotted decimal IP format + * @param msg Pointer to null terminated string + * @param buf Pointer to 4 byte IP address + * @note There is no check of source or destination size. Ensure both are 4 bytes + */ + static void printIp (const char* msg, const uint8_t *buf); + + /** @brief Output Flash String Helper and IP address to serial port in dotted decimal IP format + * @param ifsh Pointer to Flash String Helper + * @param buf Pointer to 4 byte IP address + * @note There is no check of source or destination size. Ensure both are 4 bytes + * @todo What is a FlashStringHelper? + */ + static void printIp (const __FlashStringHelper *ifsh, const uint8_t *buf); + + /** @brief Search for a string of the form key=value in a string that looks like q?xyz=abc&uvw=defgh HTTP/1.1\\r\\n + * @param str Pointer to the null terminated string to search + * @param strbuf Pointer to buffer to hold null terminated result string + * @param maxlen Maximum length of result + * @param key Pointer to null terminated string holding the key to search for + * @return unit_t Length of the value. 0 if not found + * @note Ensure strbuf has memory allocated of at least maxlen + 1 (to accomodate result plus terminating null) + */ + static uint8_t findKeyVal(const char *str,char *strbuf, + uint8_t maxlen, const char *key); + + /** @brief Decode a URL string e.g "hello%20joe" or "hello+joe" becomes "hello joe" + * @param urlbuf Pointer to the null terminated URL + * @note urlbuf is modified + */ + static void urlDecode(char *urlbuf); + + /** @brief Encode a URL, replacing illegal charaters like ' ' + * @param str Pointer to the null terminated string to encode + * @param urlbuf Pointer to a buffer to contain the null terminated encoded URL + * @note There must be enough space in urlbuf. In the worst case that is 3 times the length of str + */ + static void urlEncode(char *str,char *urlbuf); + + /** @brief Convert an IP address from dotted decimal formated string to 4 bytes + * @param bytestr Pointer to the 4 byte array to store IP address + * @param str Pointer to string to parse + * @return uint8_t 0 on success + */ + static uint8_t parseIp(uint8_t *bytestr,char *str); + + /** @brief Convert a byte array to a human readable display string + * @param resultstr Pointer to a buffer to hold the resulting null terminated string + * @param bytestr Pointer to the byte array containing the address to convert + * @param len Length of the array (4 for IP address, 6 for hardware (MAC) address) + * @param separator Delimiter character (typically '.' for IP address and ':' for hardware (MAC) address) + * @param base Base for numerical representation (typically 10 for IP address and 16 for hardware (MAC) address + */ + static void makeNetStr(char *resultstr,uint8_t *bytestr,uint8_t len, + char separator,uint8_t base); + + /** @brief Return the sequence number of the current TCP package + */ + static uint32_t getSequenceNumber(); + + /** @brief Return the payload length of the current Tcp package + */ + static uint16_t getTcpPayloadLength(); +}; + +extern EtherCard ether; //!< Global presentation of EtherCard class + +#endif diff --git a/libraries/ethercard-master/README.md b/libraries/ethercard-master/README.md new file mode 100644 index 0000000..a854c01 --- /dev/null +++ b/libraries/ethercard-master/README.md @@ -0,0 +1,79 @@ +# EtherCard + +[![Travis Status][S]][T] + +**EtherCard** is a driver for the ENC28J60 chip, compatible with Arduino IDE. +Adapted and extended from code written by Guido Socher and Pascal Stang. + +License: GPL2 + +The documentation for this library is at http://jeelabs.net/pub/docs/ethercard/. + +## Requirements + +* Hardware: This library **only** supports the ENC28J60 chip. +* Hardware: Only AVR-based microcontrollers are supported, such as: + * Arduino Uno + * Arduino Mega + * Arduino Leonardo + * Arduino Nano/Pro/Fio/Pro-mini/LiliPad/Duemilanove + * Any other Arduino clone using an AVR microcontroller should work +* Hardware: Non-AVR boards are **NOT** currently supported (101/Zero/Due) + [#211](https://github.com/jcw/ethercard/issues/211#issuecomment-255011491) +* Hardware: Depending on the size of the buffer for packets, this library + uses about 1k of Arduino RAM. Large strings and other global variables + can easily push the limits of smaller microcontrollers. +* Hardware: This library uses the SPI interface of the microcontroller, + and will require at least one dedicated pin for CS, plus the SO, SI, and + SCK pins of the SPI interface. +* Software: Any Arduino IDE >= 1.0.0 should be fine + +## Library Installation + +1. Download the ZIP file from https://github.com/jcw/ethercard/archive/master.zip +2. Rename the downloaded file to `ethercard.zip` +3. From the Arduino IDE: Sketch -> Include Library... -> Add .ZIP Library... +4. Restart the Arduino IDE to see the new "EtherCard" library with examples + +See the comments in the example sketches for details about how to try them out. + +## Physical Installation + +### PIN Connections (Using Arduino UNO): + + VCC - 3.3V + GND - GND + SCK - Pin 13 + SO - Pin 12 + SI - Pin 11 + CS - Pin 10 # Selectable with the ether.begin() function + +### PIN Connections using an Arduino Mega + + VCC - 3.3V + GND - GND + SCK - Pin 52 + SO - Pin 50 + SI - Pin 51 + CS - Pin 53 # Selectable with the ether.begin() function + +## Support + +For questions and help, see the [forums][F] (at JeeLabs.net). +The issue tracker has been moved back to [Github][I] again. + +[F]: http://jeelabs.net/projects/cafe/boards +[I]: https://github.com/jcw/ethercard/issues +[S]: https://travis-ci.org/jcw/ethercard.svg +[T]: https://travis-ci.org/jcw/ethercard + +## Related Work + +There are other Arduino libraries for the ENC28J60 that are worth mentioning: + +* [UIPEthernet](https://github.com/ntruchsess/arduino_uip) (Drop in replacement for stock Arduino Ethernet library) +* [EtherSia](https://github.com/njh/EtherSia) (IPv6 Arduino library for ENC28J60) +* [EtherShield](https://github.com/thiseldo/EtherShield) (no longer maintained, predecessor to Ethercard) +* [ETHER_28J60](https://github.com/muanis/arduino-projects/tree/master/libraries/ETHER_28J60) (no longer maintained, very low footprint and simple) + +Read more about the differences at [this blog post](http://www.tweaking4all.com/hardware/arduino/arduino-enc28j60-ethernet/). diff --git a/libraries/ethercard-master/dhcp.cpp b/libraries/ethercard-master/dhcp.cpp new file mode 100644 index 0000000..bdd40ea --- /dev/null +++ b/libraries/ethercard-master/dhcp.cpp @@ -0,0 +1,437 @@ +// DHCP look-up functions based on the udp client +// http://www.ietf.org/rfc/rfc2131.txt +// +// Author: Andrew Lindsay +// Rewritten and optimized by Jean-Claude Wippler, http://jeelabs.org/ +// +// Rewritten dhcpStateMachine by Chris van den Hooven +// as to implement dhcp-renew when lease expires (jun 2012) +// +// Various modifications and bug fixes contributed by Victor Aprea (oct 2012) +// +// Copyright: GPL V2 +// See http://www.gnu.org/licenses/gpl.html + +//#define DHCPDEBUG + +#include "EtherCard.h" +#include "net.h" + +#define gPB ether.buffer + +#define DHCP_BOOTREQUEST 1 +#define DHCP_BOOTRESPONSE 2 + +// DHCP Message Type (option 53) (ref RFC 2132) +#define DHCP_DISCOVER 1 +#define DHCP_OFFER 2 +#define DHCP_REQUEST 3 +#define DHCP_DECLINE 4 +#define DHCP_ACK 5 +#define DHCP_NAK 6 +#define DHCP_RELEASE 7 + +// DHCP States for access in applications (ref RFC 2131) +enum { + DHCP_STATE_INIT, + DHCP_STATE_SELECTING, + DHCP_STATE_REQUESTING, + DHCP_STATE_BOUND, + DHCP_STATE_RENEWING, +}; + +/* + op 1 Message op code / message type. + 1 = BOOTREQUEST, 2 = BOOTREPLY + htype 1 Hardware address type, see ARP section in "Assigned + Numbers" RFC; e.g., '1' = 10mb ethernet. + hlen 1 Hardware address length (e.g. '6' for 10mb + ethernet). + hops 1 Client sets to zero, optionally used by relay agents + when booting via a relay agent. + xid 4 Transaction ID, a random number chosen by the + client, used by the client and server to associate + messages and responses between a client and a + server. + secs 2 Filled in by client, seconds elapsed since client + began address acquisition or renewal process. + flags 2 Flags (see figure 2). + ciaddr 4 Client IP address; only filled in if client is in + BOUND, RENEW or REBINDING state and can respond + to ARP requests. + yiaddr 4 'your' (client) IP address. + siaddr 4 IP address of next server to use in bootstrap; + returned in DHCPOFFER, DHCPACK by server. + giaddr 4 Relay agent IP address, used in booting via a + relay agent. + chaddr 16 Client hardware address. + sname 64 Optional server host name, null terminated string. + file 128 Boot file name, null terminated string; "generic" + name or null in DHCPDISCOVER, fully qualified + directory-path name in DHCPOFFER. + options var Optional parameters field. See the options + documents for a list of defined options. + */ + + + + +// size 236 +typedef struct { + byte op, htype, hlen, hops; + uint32_t xid; + uint16_t secs, flags; + byte ciaddr[IP_LEN], yiaddr[IP_LEN], siaddr[IP_LEN], giaddr[IP_LEN]; + byte chaddr[16], sname[64], file[128]; + // options +} DHCPdata; + +#define DHCP_SERVER_PORT 67 +#define DHCP_CLIENT_PORT 68 + +// timeouts im ms +#define DHCP_REQUEST_TIMEOUT 10000 + +#define DHCP_HOSTNAME_MAX_LEN 32 + +// RFC 2132 Section 3.3: +// The time value of 0xffffffff is reserved to represent "infinity". +#define DHCP_INFINITE_LEASE 0xffffffff + +static byte dhcpState = DHCP_STATE_INIT; +static char hostname[DHCP_HOSTNAME_MAX_LEN] = "Arduino-ENC28j60-00"; // Last two characters will be filled by last 2 MAC digits ; +static uint32_t currentXid; +static uint32_t stateTimer; +static uint32_t leaseStart; +static uint32_t leaseTime; +static byte* bufPtr; + +static uint8_t dhcpCustomOptionNum = 0; +static DhcpOptionCallback dhcpCustomOptionCallback = NULL; + +extern uint8_t allOnes[];// = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF }; + +static void addToBuf (byte b) { + *bufPtr++ = b; +} + +static void addBytes (byte len, const byte* data) { + while (len-- > 0) + addToBuf(*data++); +} + +static void addOption (byte opt, byte len, const byte* data) { + addToBuf(opt); + addToBuf(len); + addBytes(len, data); +} + + +// Main DHCP sending function + +// implemented +// state / msgtype +// INIT / DHCPDISCOVER +// SELECTING / DHCPREQUEST +// BOUND (RENEWING) / DHCPREQUEST + +// ---------------------------------------------------------- +// | |SELECTING |RENEWING |INIT | +// ---------------------------------------------------------- +// |broad/unicast |broadcast |unicast |broadcast | +// |server-ip |MUST |MUST NOT |MUST NOT | option 54 +// |requested-ip |MUST |MUST NOT |MUST NOT | option 50 +// |ciaddr |zero |IP address |zero | +// ---------------------------------------------------------- + +// options used (both send/receive) +#define DHCP_OPT_SUBNET_MASK 1 +#define DHCP_OPT_ROUTERS 3 +#define DHCP_OPT_DOMAIN_NAME_SERVERS 6 +#define DHCP_OPT_HOSTNAME 12 +#define DHCP_OPT_REQUESTED_ADDRESS 50 +#define DHCP_OPT_LEASE_TIME 51 +#define DHCP_OPT_MESSAGE_TYPE 53 +#define DHCP_OPT_SERVER_IDENTIFIER 54 +#define DHCP_OPT_PARAMETER_REQUEST_LIST 55 +#define DHCP_OPT_RENEWAL_TIME 58 +#define DHCP_OPT_CLIENT_IDENTIFIER 61 +#define DHCP_OPT_END 255 + +#define DHCP_HTYPE_ETHER 1 + +static void send_dhcp_message(uint8_t *requestip) { + + memset(gPB, 0, UDP_DATA_P + sizeof( DHCPdata )); + + EtherCard::udpPrepare(DHCP_CLIENT_PORT, + (dhcpState == DHCP_STATE_BOUND ? EtherCard::dhcpip : allOnes), + DHCP_SERVER_PORT); + + // If we ever don't do this, the DHCP renewal gets sent to whatever random + // destmacaddr was used by other code. Rather than cache the MAC address of + // the DHCP server, just force a broadcast here in all cases. + EtherCard::copyMac(gPB + ETH_DST_MAC, allOnes); //force broadcast mac + + // Build DHCP Packet from buf[UDP_DATA_P] + DHCPdata *dhcpPtr = (DHCPdata*) (gPB + UDP_DATA_P); + dhcpPtr->op = DHCP_BOOTREQUEST; + dhcpPtr->htype = 1; + dhcpPtr->hlen = 6; + dhcpPtr->xid = currentXid; + if (dhcpState == DHCP_STATE_BOUND) { + EtherCard::copyIp(dhcpPtr->ciaddr, EtherCard::myip); + } + EtherCard::copyMac(dhcpPtr->chaddr, EtherCard::mymac); + + // options defined as option, length, value + bufPtr = gPB + UDP_DATA_P + sizeof( DHCPdata ); + // DHCP magic cookie + static const byte cookie[] PROGMEM = { 0x63,0x82,0x53,0x63 }; + for (byte i = 0; i < sizeof(cookie); i++) + addToBuf(pgm_read_byte(&cookie[i])); + addToBuf(DHCP_OPT_MESSAGE_TYPE); // DHCP_STATE_SELECTING, DHCP_STATE_REQUESTING + addToBuf(1); // Length + addToBuf(dhcpState == DHCP_STATE_INIT ? DHCP_DISCOVER : DHCP_REQUEST); + + // Client Identifier Option, this is the client mac address + addToBuf(DHCP_OPT_CLIENT_IDENTIFIER); + addToBuf(1 + ETH_LEN); // Length (hardware type + client MAC) + addToBuf(DHCP_HTYPE_ETHER); + addBytes(ETH_LEN, EtherCard::mymac); + + if (hostname[0]) { + addOption(DHCP_OPT_HOSTNAME, strlen(hostname), (byte*) hostname); + } + + if (requestip != NULL) { + addOption(DHCP_OPT_REQUESTED_ADDRESS, IP_LEN, requestip); + addOption(DHCP_OPT_SERVER_IDENTIFIER, IP_LEN, EtherCard::dhcpip); + } + + // Additional info in parameter list - minimal list for what we need + byte len = 3; + if (dhcpCustomOptionNum) + len++; + addToBuf(DHCP_OPT_PARAMETER_REQUEST_LIST); + addToBuf(len); // Length + addToBuf(DHCP_OPT_SUBNET_MASK); + addToBuf(DHCP_OPT_ROUTERS); + addToBuf(DHCP_OPT_DOMAIN_NAME_SERVERS); + if (dhcpCustomOptionNum) + addToBuf(dhcpCustomOptionNum); // Custom option + + addToBuf(DHCP_OPT_END); + + // packet size will be under 300 bytes + EtherCard::udpTransmit((bufPtr - gPB) - UDP_DATA_P); +} + +static void process_dhcp_offer(uint16_t len, uint8_t *offeredip) { + // Map struct onto payload + DHCPdata *dhcpPtr = (DHCPdata*) (gPB + UDP_DATA_P); + + // Offered IP address is in yiaddr + EtherCard::copyIp(offeredip, dhcpPtr->yiaddr); + + // Search for the server IP + byte *ptr = (byte*) (dhcpPtr + 1) + 4; + do { + byte option = *ptr++; + byte optionLen = *ptr++; + if (option == DHCP_OPT_SERVER_IDENTIFIER) { + EtherCard::copyIp(EtherCard::dhcpip, ptr); + break; + } + ptr += optionLen; + } while (ptr < gPB + len); +} + +static void process_dhcp_ack(uint16_t len) { + // Map struct onto payload + DHCPdata *dhcpPtr = (DHCPdata*) (gPB + UDP_DATA_P); + + // Allocated IP address is in yiaddr + EtherCard::copyIp(EtherCard::myip, dhcpPtr->yiaddr); + + // Scan through variable length option list identifying options we want + byte *ptr = (byte*) (dhcpPtr + 1) + 4; + bool done = false; + do { + byte option = *ptr++; + byte optionLen = *ptr++; + switch (option) { + case DHCP_OPT_SUBNET_MASK: + EtherCard::copyIp(EtherCard::netmask, ptr); + break; + case DHCP_OPT_ROUTERS: + EtherCard::copyIp(EtherCard::gwip, ptr); + break; + case DHCP_OPT_DOMAIN_NAME_SERVERS: + EtherCard::copyIp(EtherCard::dnsip, ptr); + break; + case DHCP_OPT_LEASE_TIME: + case DHCP_OPT_RENEWAL_TIME: + leaseTime = 0; + for (byte i = 0; i<4; i++) + leaseTime = (leaseTime << 8) + ptr[i]; + if (leaseTime != DHCP_INFINITE_LEASE) { + leaseTime *= 1000; // milliseconds + } + break; + case DHCP_OPT_END: + done = true; + break; + default: { + // Is is a custom configured option? + if (dhcpCustomOptionCallback && option == dhcpCustomOptionNum) { + dhcpCustomOptionCallback(option, ptr, optionLen); + } + } + } + ptr += optionLen; + } while (!done && ptr < gPB + len); +} + +static bool dhcp_received_message_type (uint16_t len, byte msgType) { + // Map struct onto payload + DHCPdata *dhcpPtr = (DHCPdata*) (gPB + UDP_DATA_P); + + if (len >= 70 && gPB[UDP_SRC_PORT_L_P] == DHCP_SERVER_PORT && + dhcpPtr->xid == currentXid ) { + + byte *ptr = (byte*) (dhcpPtr + 1) + 4; + do { + byte option = *ptr++; + byte optionLen = *ptr++; + if(option == DHCP_OPT_MESSAGE_TYPE && *ptr == msgType ) { + return true; + } + ptr += optionLen; + } while (ptr < gPB + len); + } + return false; +} + +static char toAsciiHex(byte b) { + char c = b & 0x0f; + c += (c <= 9) ? '0' : 'A'-10; + return c; +} + +bool EtherCard::dhcpSetup (const char *hname, bool fromRam) { + // Use during setup, as this discards all incoming requests until it returns. + // That shouldn't be a problem, because we don't have an IP-address yet. + // Will try 60 secs to obtain DHCP-lease. + + using_dhcp = true; + + if(hname != NULL) { + if(fromRam) { + strncpy(hostname, hname, DHCP_HOSTNAME_MAX_LEN); + } + else { + strncpy_P(hostname, hname, DHCP_HOSTNAME_MAX_LEN); + } + } + else { + // Set a unique hostname, use Arduino-?? with last octet of mac address + hostname[strlen(hostname) - 2] = toAsciiHex(mymac[5] >> 4); // Appends mac to last 2 digits of the hostname + hostname[strlen(hostname) - 1] = toAsciiHex(mymac[5]); // Even if it's smaller than the maximum + } + + dhcpState = DHCP_STATE_INIT; + uint16_t start = millis(); + + while (dhcpState != DHCP_STATE_BOUND && uint16_t(millis()) - start < 60000) { + if (isLinkUp()) DhcpStateMachine(packetReceive()); + } + updateBroadcastAddress(); + delaycnt = 0; + return dhcpState == DHCP_STATE_BOUND ; +} + +void EtherCard::dhcpAddOptionCallback(uint8_t option, DhcpOptionCallback callback) +{ + dhcpCustomOptionNum = option; + dhcpCustomOptionCallback = callback; +} + +void EtherCard::DhcpStateMachine (uint16_t len) +{ + +#ifdef DHCPDEBUG + if (dhcpState != DHCP_STATE_BOUND) { + Serial.print(millis()); + Serial.print(" State: "); + } + switch (dhcpState) { + case DHCP_STATE_INIT: + Serial.println("Init"); + break; + case DHCP_STATE_SELECTING: + Serial.println("Selecting"); + break; + case DHCP_STATE_REQUESTING: + Serial.println("Requesting"); + break; + case DHCP_STATE_RENEWING: + Serial.println("Renew"); + break; + } +#endif + + switch (dhcpState) { + + case DHCP_STATE_BOUND: + //!@todo Due to millis() wrap-around, DHCP renewal may not work if leaseTime is larger than 49days + if (leaseTime != DHCP_INFINITE_LEASE && millis() - leaseStart >= leaseTime) { + send_dhcp_message(myip); + dhcpState = DHCP_STATE_RENEWING; + stateTimer = millis(); + } + break; + + case DHCP_STATE_INIT: + currentXid = millis(); + memset(myip,0,IP_LEN); // force ip 0.0.0.0 + send_dhcp_message(NULL); + enableBroadcast(true); //Temporarily enable broadcasts + dhcpState = DHCP_STATE_SELECTING; + stateTimer = millis(); + break; + + case DHCP_STATE_SELECTING: + if (dhcp_received_message_type(len, DHCP_OFFER)) { + uint8_t offeredip[IP_LEN]; + process_dhcp_offer(len, offeredip); + send_dhcp_message(offeredip); + dhcpState = DHCP_STATE_REQUESTING; + stateTimer = millis(); + } else { + if (millis() - stateTimer > DHCP_REQUEST_TIMEOUT) { + dhcpState = DHCP_STATE_INIT; + } + } + break; + + case DHCP_STATE_REQUESTING: + case DHCP_STATE_RENEWING: + if (dhcp_received_message_type(len, DHCP_ACK)) { + disableBroadcast(true); //Disable broadcast after temporary enable + process_dhcp_ack(len); + leaseStart = millis(); + if (gwip[0] != 0) setGwIp(gwip); // why is this? because it initiates an arp request + dhcpState = DHCP_STATE_BOUND; + } else { + if (millis() - stateTimer > DHCP_REQUEST_TIMEOUT) { + dhcpState = DHCP_STATE_INIT; + } + } + break; + + } +} + + + diff --git a/libraries/ethercard-master/dns.cpp b/libraries/ethercard-master/dns.cpp new file mode 100644 index 0000000..45c1ed1 --- /dev/null +++ b/libraries/ethercard-master/dns.cpp @@ -0,0 +1,120 @@ +// DNS look-up functions based on the udp client +// Author: Guido Socher +// Copyright: GPL V2 +// +// 2010-05-20 + +#include "EtherCard.h" +#include "net.h" + +#define gPB ether.buffer + +static byte dnstid_l; // a counter for transaction ID +#define DNSCLIENT_SRC_PORT_H 0xE0 + +#define DNS_TYPE_A 1 +#define DNS_CLASS_IN 1 + +static void dnsRequest (const char *hostname, bool fromRam) { + ++dnstid_l; // increment for next request, finally wrap + if (ether.dnsip[0] == 0) + memset(ether.dnsip, 8, IP_LEN); // use 8.8.8.8 Google DNS as default + ether.udpPrepare((DNSCLIENT_SRC_PORT_H << 8) | dnstid_l, ether.dnsip, DNS_PORT); + memset(gPB + UDP_DATA_P, 0, 12); + + byte *p = gPB + UDP_DATA_P + 12; + char c; + do { + byte n = 0; + for(;;) { + c = fromRam ? *hostname : pgm_read_byte(hostname); + ++hostname; + if (c == '.' || c == 0) + break; + p[++n] = c; + } + *p++ = n; + p += n; + } while (c != 0); + + *p++ = 0; // terminate with zero, means root domain. + *p++ = 0; + *p++ = DNS_TYPE_A; + *p++ = 0; + *p++ = DNS_CLASS_IN; + byte i = p - gPB - UDP_DATA_P; + gPB[UDP_DATA_P] = i; + gPB[UDP_DATA_P+1] = dnstid_l; + gPB[UDP_DATA_P+2] = 1; // flags, standard recursive query + gPB[UDP_DATA_P+5] = 1; // 1 question + ether.udpTransmit(i); +} + +/** @brief Check if packet is DNS response. + @param plen Size of packet + @return bool True if DNS response has error. False if not DNS response or DNS response OK. + @note hisip contains IP address of requested host or 0.0.0.0 on failure +*/ +static bool checkForDnsAnswer (uint16_t plen) { + byte *p = gPB + UDP_DATA_P; //start of UDP payload + if (plen < 70 || gPB[UDP_SRC_PORT_L_P] != DNS_PORT || //from DNS source port + gPB[UDP_DST_PORT_H_P] != DNSCLIENT_SRC_PORT_H || //response to same port as we sent from (MSB) + gPB[UDP_DST_PORT_L_P] != dnstid_l || //response to same port as we sent from (LSB) + p[1] != dnstid_l) //message id same as we sent + return false; //not our DNS response + if((p[3] & 0x0F) != 0) + return true; //DNS response received with error + + p += *p; // we encoded the query len into tid + for (;;) { + if (*p & 0xC0) + p += 2; + else + while (++p < gPB + plen) { + if (*p == 0) { + ++p; + break; + } + } + if (p + 14 > gPB + plen) + break; + if (p[1] == DNS_TYPE_A && p[9] == 4) { // type "A" and IPv4 + ether.copyIp(ether.hisip, p + 10); + break; + } + p += p[9] + 10; + } + return false; //No error +} + +// use during setup, as this discards all incoming requests until it returns +bool EtherCard::dnsLookup (const char* name, bool fromRam) { + uint16_t start = millis(); + + while(!isLinkUp()) + { + if (uint16_t(millis()) - start >= 30000) + return false; //timeout waiting for link + } + while(clientWaitingDns()) + { + packetLoop(packetReceive()); + if (uint16_t(millis()) - start >= 30000) + return false; //timeout waiting for gateway ARP + } + + memset(hisip, 0, IP_LEN); + dnsRequest(name, fromRam); + + start = millis(); + while (hisip[0] == 0) { + if (uint16_t(millis()) - start >= 30000) + return false; //timout waiting for dns response + word len = packetReceive(); + if (len > 0 && packetLoop(len) == 0) //packet not handled by tcp/ip packet loop + if(checkForDnsAnswer(len)) + return false; //DNS response recieved with error + } + + return true; +} diff --git a/libraries/ethercard-master/docu.dox b/libraries/ethercard-master/docu.dox new file mode 100644 index 0000000..a2717e0 --- /dev/null +++ b/libraries/ethercard-master/docu.dox @@ -0,0 +1,96 @@ +/** +@mainpage EtherCard is a driver for the ENC28J60 chip, compatible with Arduino IDE.
+Adapted and extended from code written by Guido Socher and Pascal Stang.
+The home page for this library is at http://jeelabs.net/projects/ethercard/wiki.
+License: GPL2

+PIN Connections (Using Arduino UNO): + + + + + + + + +
EtherCardArduino UNO
VCC3.3V
GNDGND
SCKPin 13
SOPin 12
SIPin 11
CSPin 8
+ +@section intro_sec Introduction +EtherCard is a library that performs low-level interfacing with network interfaces based on the MicroChip (C) ENC28J60. +High-level routines are provided to allow a variety of purposes including simple data transfer through to HTTP handling. +EtherCard is a driver for the ENC28J60 chip, compatible with Arduino IDE. + +Adapted and extended from code written by Guido Socher and Pascal Stang. + +The documentation for this library is at http://jeelabs.net/pub/docs/ethercard/ + +The code is available on GitHub, at https://github.com/jcw/ethercard - to install: + +Download the ZIP file from https://github.com/jcw/ethercard/archive/master.zip +From the Arduino IDE: Sketch -> Import Library... -> Add Library... +Restart the Arduino IDE to see the new "EtherCard" library with examples +See the comments in the example sketches for details about how to try them out. + +For questions and help, see the forums. For bugs and feature requests, see the issue tracker. +@section eg_sec Examples +Several @link examples example scripts @endlink are provided with the library which demonstrate various features. Below are descriptions on how to use the library. + +

Note: ether is defined globally and may be used to access the library thus: ether.member. + +@subsection Initiate To initiate the library call EtherCard::begin +

+uint8_t Ethernet::buffer[700]; // configure buffer size to 700 octets
+static uint8_t mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; // define (unique on LAN) hardware (MAC) address
+
+uint8_type nFirmwareVersion ether.begin(sizeof Ethernet::buffer, mymac);
+if(0 == nFirmwareVersion)
+{
+    // handle failure to initiate network interface
+}
+
+ +@subsection DHCP To configure IP address via DHCP use EtherCard::dhcpSetup +
+if(!ether.dhcpSetup())
+{
+// handle failure to obtain IP address via DHCP
+}
+ether.printIp("IP:   ", ether.myip); // output IP address to Serial
+ether.printIp("GW:   ", ether.gwip); // output gateway address to Serial
+ether.printIp("Mask: ", ether.mymask); // output netmask to Serial
+ether.printIp("DHCP server: ", ether.dhcpip); // output IP address of the DHCP server
+
+ +@subsection StaticIP To configure a static IP address use EtherCard::staticSetup +
+const static uint8_t ip[] = {192,168,0,100};
+const static uint8_t gw[] = {192,168,0,254};
+const static uint8_t dns[] = {192,168,0,1};
+
+if(!ether.staticSetup(ip, gw, dns);
+{
+    // handle failure to configure static IP address (current implementation always returns true!)
+}
+
+ +@subsection SendUDP Send UDP packet +To send a UDP packet use EtherCard::sendUdp +
+char payload[] = "My UDP message";
+uint8_t nSourcePort = 1234;
+uint8_t nDestinationPort = 5678;
+uint8_t ipDestinationAddress[IP_LEN];
+ether.parseIp(ipDestinationAddress, "192.168.0.200");
+
+ether.sendUdp(payload, sizeof(payload), nSourcePort, ipDestinationAddress, nDestinationPort);
+
+ +@subsection DNSLookup DNS Lookup +To perform a DNS lookup use EtherCard::dnsLookup +
+if(!ether.dnsLookup("google.com"))
+{
+    // handle failure of DNS lookup
+}
+ether.printIp("Server: ", ether.hispip); // Result of DNS lookup is placed in the hisip member of EtherCard.
+
+*/ diff --git a/libraries/ethercard-master/enc28j60.cpp b/libraries/ethercard-master/enc28j60.cpp new file mode 100644 index 0000000..d9bef16 --- /dev/null +++ b/libraries/ethercard-master/enc28j60.cpp @@ -0,0 +1,778 @@ +// Microchip ENC28J60 Ethernet Interface Driver +// Author: Guido Socher +// Copyright: GPL V2 +// +// Based on the enc28j60.c file from the AVRlib library by Pascal Stang. +// For AVRlib See http://www.procyonengineering.com/ +// Used with explicit permission of Pascal Stang. +// +// 2010-05-20 + +#if ARDUINO >= 100 +#include // Arduino 1.0 +#else +#include // Arduino 0022 +#endif +#include "enc28j60.h" + +uint16_t ENC28J60::bufferSize; +bool ENC28J60::broadcast_enabled = false; +bool ENC28J60::promiscuous_enabled = false; + +// ENC28J60 Control Registers +// Control register definitions are a combination of address, +// bank number, and Ethernet/MAC/PHY indicator bits. +// - Register address (bits 0-4) +// - Bank number (bits 5-6) +// - MAC/PHY indicator (bit 7) +#define ADDR_MASK 0x1F +#define BANK_MASK 0x60 +#define SPRD_MASK 0x80 +// All-bank registers +#define EIE 0x1B +#define EIR 0x1C +#define ESTAT 0x1D +#define ECON2 0x1E +#define ECON1 0x1F +// Bank 0 registers +#define ERDPT (0x00|0x00) +#define EWRPT (0x02|0x00) +#define ETXST (0x04|0x00) +#define ETXND (0x06|0x00) +#define ERXST (0x08|0x00) +#define ERXND (0x0A|0x00) +#define ERXRDPT (0x0C|0x00) +// #define ERXWRPT (0x0E|0x00) +#define EDMAST (0x10|0x00) +#define EDMAND (0x12|0x00) +// #define EDMADST (0x14|0x00) +#define EDMACS (0x16|0x00) +// Bank 1 registers +#define EHT0 (0x00|0x20) +#define EHT1 (0x01|0x20) +#define EHT2 (0x02|0x20) +#define EHT3 (0x03|0x20) +#define EHT4 (0x04|0x20) +#define EHT5 (0x05|0x20) +#define EHT6 (0x06|0x20) +#define EHT7 (0x07|0x20) +#define EPMM0 (0x08|0x20) +#define EPMM1 (0x09|0x20) +#define EPMM2 (0x0A|0x20) +#define EPMM3 (0x0B|0x20) +#define EPMM4 (0x0C|0x20) +#define EPMM5 (0x0D|0x20) +#define EPMM6 (0x0E|0x20) +#define EPMM7 (0x0F|0x20) +#define EPMCS (0x10|0x20) +// #define EPMO (0x14|0x20) +#define EWOLIE (0x16|0x20) +#define EWOLIR (0x17|0x20) +#define ERXFCON (0x18|0x20) +#define EPKTCNT (0x19|0x20) +// Bank 2 registers +#define MACON1 (0x00|0x40|0x80) +#define MACON2 (0x01|0x40|0x80) +#define MACON3 (0x02|0x40|0x80) +#define MACON4 (0x03|0x40|0x80) +#define MABBIPG (0x04|0x40|0x80) +#define MAIPG (0x06|0x40|0x80) +#define MACLCON1 (0x08|0x40|0x80) +#define MACLCON2 (0x09|0x40|0x80) +#define MAMXFL (0x0A|0x40|0x80) +#define MAPHSUP (0x0D|0x40|0x80) +#define MICON (0x11|0x40|0x80) +#define MICMD (0x12|0x40|0x80) +#define MIREGADR (0x14|0x40|0x80) +#define MIWR (0x16|0x40|0x80) +#define MIRD (0x18|0x40|0x80) +// Bank 3 registers +#define MAADR1 (0x00|0x60|0x80) +#define MAADR0 (0x01|0x60|0x80) +#define MAADR3 (0x02|0x60|0x80) +#define MAADR2 (0x03|0x60|0x80) +#define MAADR5 (0x04|0x60|0x80) +#define MAADR4 (0x05|0x60|0x80) +#define EBSTSD (0x06|0x60) +#define EBSTCON (0x07|0x60) +#define EBSTCS (0x08|0x60) +#define MISTAT (0x0A|0x60|0x80) +#define EREVID (0x12|0x60) +#define ECOCON (0x15|0x60) +#define EFLOCON (0x17|0x60) +#define EPAUS (0x18|0x60) + +// ENC28J60 ERXFCON Register Bit Definitions +#define ERXFCON_UCEN 0x80 +#define ERXFCON_ANDOR 0x40 +#define ERXFCON_CRCEN 0x20 +#define ERXFCON_PMEN 0x10 +#define ERXFCON_MPEN 0x08 +#define ERXFCON_HTEN 0x04 +#define ERXFCON_MCEN 0x02 +#define ERXFCON_BCEN 0x01 +// ENC28J60 EIE Register Bit Definitions +#define EIE_INTIE 0x80 +#define EIE_PKTIE 0x40 +#define EIE_DMAIE 0x20 +#define EIE_LINKIE 0x10 +#define EIE_TXIE 0x08 +#define EIE_WOLIE 0x04 +#define EIE_TXERIE 0x02 +#define EIE_RXERIE 0x01 +// ENC28J60 EIR Register Bit Definitions +#define EIR_PKTIF 0x40 +#define EIR_DMAIF 0x20 +#define EIR_LINKIF 0x10 +#define EIR_TXIF 0x08 +#define EIR_WOLIF 0x04 +#define EIR_TXERIF 0x02 +#define EIR_RXERIF 0x01 +// ENC28J60 ESTAT Register Bit Definitions +#define ESTAT_INT 0x80 +#define ESTAT_LATECOL 0x10 +#define ESTAT_RXBUSY 0x04 +#define ESTAT_TXABRT 0x02 +#define ESTAT_CLKRDY 0x01 +// ENC28J60 ECON2 Register Bit Definitions +#define ECON2_AUTOINC 0x80 +#define ECON2_PKTDEC 0x40 +#define ECON2_PWRSV 0x20 +#define ECON2_VRPS 0x08 +// ENC28J60 ECON1 Register Bit Definitions +#define ECON1_TXRST 0x80 +#define ECON1_RXRST 0x40 +#define ECON1_DMAST 0x20 +#define ECON1_CSUMEN 0x10 +#define ECON1_TXRTS 0x08 +#define ECON1_RXEN 0x04 +#define ECON1_BSEL1 0x02 +#define ECON1_BSEL0 0x01 +// ENC28J60 MACON1 Register Bit Definitions +#define MACON1_LOOPBK 0x10 +#define MACON1_TXPAUS 0x08 +#define MACON1_RXPAUS 0x04 +#define MACON1_PASSALL 0x02 +#define MACON1_MARXEN 0x01 +// ENC28J60 MACON2 Register Bit Definitions +#define MACON2_MARST 0x80 +#define MACON2_RNDRST 0x40 +#define MACON2_MARXRST 0x08 +#define MACON2_RFUNRST 0x04 +#define MACON2_MATXRST 0x02 +#define MACON2_TFUNRST 0x01 +// ENC28J60 MACON3 Register Bit Definitions +#define MACON3_PADCFG2 0x80 +#define MACON3_PADCFG1 0x40 +#define MACON3_PADCFG0 0x20 +#define MACON3_TXCRCEN 0x10 +#define MACON3_PHDRLEN 0x08 +#define MACON3_HFRMLEN 0x04 +#define MACON3_FRMLNEN 0x02 +#define MACON3_FULDPX 0x01 +// ENC28J60 MICMD Register Bit Definitions +#define MICMD_MIISCAN 0x02 +#define MICMD_MIIRD 0x01 +// ENC28J60 MISTAT Register Bit Definitions +#define MISTAT_NVALID 0x04 +#define MISTAT_SCAN 0x02 +#define MISTAT_BUSY 0x01 + +// ENC28J60 EBSTCON Register Bit Definitions +#define EBSTCON_PSV2 0x80 +#define EBSTCON_PSV1 0x40 +#define EBSTCON_PSV0 0x20 +#define EBSTCON_PSEL 0x10 +#define EBSTCON_TMSEL1 0x08 +#define EBSTCON_TMSEL0 0x04 +#define EBSTCON_TME 0x02 +#define EBSTCON_BISTST 0x01 + +// PHY registers +#define PHCON1 0x00 +#define PHSTAT1 0x01 +#define PHHID1 0x02 +#define PHHID2 0x03 +#define PHCON2 0x10 +#define PHSTAT2 0x11 +#define PHIE 0x12 +#define PHIR 0x13 +#define PHLCON 0x14 + +// ENC28J60 PHY PHCON1 Register Bit Definitions +#define PHCON1_PRST 0x8000 +#define PHCON1_PLOOPBK 0x4000 +#define PHCON1_PPWRSV 0x0800 +#define PHCON1_PDPXMD 0x0100 +// ENC28J60 PHY PHSTAT1 Register Bit Definitions +#define PHSTAT1_PFDPX 0x1000 +#define PHSTAT1_PHDPX 0x0800 +#define PHSTAT1_LLSTAT 0x0004 +#define PHSTAT1_JBSTAT 0x0002 +// ENC28J60 PHY PHCON2 Register Bit Definitions +#define PHCON2_FRCLINK 0x4000 +#define PHCON2_TXDIS 0x2000 +#define PHCON2_JABBER 0x0400 +#define PHCON2_HDLDIS 0x0100 + +// ENC28J60 Packet Control Byte Bit Definitions +#define PKTCTRL_PHUGEEN 0x08 +#define PKTCTRL_PPADEN 0x04 +#define PKTCTRL_PCRCEN 0x02 +#define PKTCTRL_POVERRIDE 0x01 + +// SPI operation codes +#define ENC28J60_READ_CTRL_REG 0x00 +#define ENC28J60_READ_BUF_MEM 0x3A +#define ENC28J60_WRITE_CTRL_REG 0x40 +#define ENC28J60_WRITE_BUF_MEM 0x7A +#define ENC28J60_BIT_FIELD_SET 0x80 +#define ENC28J60_BIT_FIELD_CLR 0xA0 +#define ENC28J60_SOFT_RESET 0xFF + +// max frame length which the controller will accept: +// (note: maximum ethernet frame length would be 1518) +#define MAX_FRAMELEN 1500 + +#define FULL_SPEED 1 // switch to full-speed SPI for bulk transfers + +static byte Enc28j60Bank; +static byte selectPin; + +void ENC28J60::initSPI () { + pinMode(SS, OUTPUT); + digitalWrite(SS, HIGH); + pinMode(MOSI, OUTPUT); + pinMode(SCK, OUTPUT); + pinMode(MISO, INPUT); + + digitalWrite(MOSI, HIGH); + digitalWrite(MOSI, LOW); + digitalWrite(SCK, LOW); + + SPCR = bit(SPE) | bit(MSTR); // 8 MHz @ 16 + bitSet(SPSR, SPI2X); +} + +static void enableChip () { + cli(); + digitalWrite(selectPin, LOW); +} + +static void disableChip () { + digitalWrite(selectPin, HIGH); + sei(); +} + +static void xferSPI (byte data) { + SPDR = data; + while (!(SPSR&(1<>5); + } +} + +static byte readRegByte (byte address) { + SetBank(address); + return readOp(ENC28J60_READ_CTRL_REG, address); +} + +static uint16_t readReg(byte address) { + return readRegByte(address) + (readRegByte(address+1) << 8); +} + +static void writeRegByte (byte address, byte data) { + SetBank(address); + writeOp(ENC28J60_WRITE_CTRL_REG, address, data); +} + +static void writeReg(byte address, uint16_t data) { + writeRegByte(address, data); + writeRegByte(address + 1, data >> 8); +} + +static uint16_t readPhyByte (byte address) { + writeRegByte(MIREGADR, address); + writeRegByte(MICMD, MICMD_MIIRD); + while (readRegByte(MISTAT) & MISTAT_BUSY) + ; + writeRegByte(MICMD, 0x00); + return readRegByte(MIRD+1); +} + +static void writePhy (byte address, uint16_t data) { + writeRegByte(MIREGADR, address); + writeReg(MIWR, data); + while (readRegByte(MISTAT) & MISTAT_BUSY) + ; +} + +byte ENC28J60::initialize (uint16_t size, const byte* macaddr, byte csPin) { + bufferSize = size; + if (bitRead(SPCR, SPE) == 0) + initSPI(); + selectPin = csPin; + pinMode(selectPin, OUTPUT); + disableChip(); + + writeOp(ENC28J60_SOFT_RESET, 0, ENC28J60_SOFT_RESET); + delay(2); // errata B7/2 + while (!readOp(ENC28J60_READ_CTRL_REG, ESTAT) & ESTAT_CLKRDY) + ; + + writeReg(ERXST, RXSTART_INIT); + writeReg(ERXRDPT, RXSTART_INIT); + writeReg(ERXND, RXSTOP_INIT); + writeReg(ETXST, TXSTART_INIT); + writeReg(ETXND, TXSTOP_INIT); + + writeRegByte(ERXFCON, ERXFCON_UCEN|ERXFCON_CRCEN|ERXFCON_PMEN|ERXFCON_BCEN); + writeReg(EPMM0, 0x303f); + writeReg(EPMCS, 0xf7f9); + writeRegByte(MACON1, MACON1_MARXEN|MACON1_TXPAUS|MACON1_RXPAUS); + writeRegByte(MACON2, 0x00); + writeOp(ENC28J60_BIT_FIELD_SET, MACON3, + MACON3_PADCFG0|MACON3_TXCRCEN|MACON3_FRMLNEN); + writeReg(MAIPG, 0x0C12); + writeRegByte(MABBIPG, 0x12); + writeReg(MAMXFL, MAX_FRAMELEN); + writeRegByte(MAADR5, macaddr[0]); + writeRegByte(MAADR4, macaddr[1]); + writeRegByte(MAADR3, macaddr[2]); + writeRegByte(MAADR2, macaddr[3]); + writeRegByte(MAADR1, macaddr[4]); + writeRegByte(MAADR0, macaddr[5]); + writePhy(PHCON2, PHCON2_HDLDIS); + SetBank(ECON1); + writeOp(ENC28J60_BIT_FIELD_SET, EIE, EIE_INTIE|EIE_PKTIE); + writeOp(ENC28J60_BIT_FIELD_SET, ECON1, ECON1_RXEN); + + byte rev = readRegByte(EREVID); + // microchip forgot to step the number on the silcon when they + // released the revision B7. 6 is now rev B7. We still have + // to see what they do when they release B8. At the moment + // there is no B8 out yet + if (rev > 5) ++rev; + return rev; +} + +bool ENC28J60::isLinkUp() { + return (readPhyByte(PHSTAT2) >> 2) & 1; +} + +/* +struct __attribute__((__packed__)) transmit_status_vector { + uint16_t transmitByteCount; + byte transmitCollisionCount : 4; + byte transmitCrcError : 1; + byte transmitLengthCheckError : 1; + byte transmitLengthOutRangeError : 1; + byte transmitDone : 1; + byte transmitMulticast : 1; + byte transmitBroadcast : 1; + byte transmitPacketDefer : 1; + byte transmitExcessiveDefer : 1; + byte transmitExcessiveCollision : 1; + byte transmitLateCollision : 1; + byte transmitGiant : 1; + byte transmitUnderrun : 1; + uint16_t totalTransmitted; + byte transmitControlFrame : 1; + byte transmitPauseControlFrame : 1; + byte backpressureApplied : 1; + byte transmitVLAN : 1; + byte zero : 4; +}; +*/ + +struct transmit_status_vector { + uint8_t bytes[7]; +}; + +#if ETHERCARD_SEND_PIPELINING + #define BREAKORCONTINUE retry=0; continue; +#else + #define BREAKORCONTINUE break; +#endif + +void ENC28J60::packetSend(uint16_t len) { + byte retry = 0; + + #if ETHERCARD_SEND_PIPELINING + goto resume_last_transmission; + #endif + while (1) { + // latest errata sheet: DS80349C + // always reset transmit logic (Errata Issue 12) + // the Microchip TCP/IP stack implementation used to first check + // whether TXERIF is set and only then reset the transmit logic + // but this has been changed in later versions; possibly they + // have a reason for this; they don't mention this in the errata + // sheet + writeOp(ENC28J60_BIT_FIELD_SET, ECON1, ECON1_TXRST); + writeOp(ENC28J60_BIT_FIELD_CLR, ECON1, ECON1_TXRST); + writeOp(ENC28J60_BIT_FIELD_CLR, EIR, EIR_TXERIF|EIR_TXIF); + + // prepare new transmission + if (retry == 0) { + writeReg(EWRPT, TXSTART_INIT); + writeReg(ETXND, TXSTART_INIT+len); + writeOp(ENC28J60_WRITE_BUF_MEM, 0, 0x00); + writeBuf(len, buffer); + } + + // initiate transmission + writeOp(ENC28J60_BIT_FIELD_SET, ECON1, ECON1_TXRTS); + #if ETHERCARD_SEND_PIPELINING + if (retry == 0) return; + #endif + + resume_last_transmission: + + // wait until transmission has finished; referrring to the data sheet and + // to the errata (Errata Issue 13; Example 1) you only need to wait until either + // TXIF or TXERIF gets set; however this leads to hangs; apparently Microchip + // realized this and in later implementations of their tcp/ip stack they introduced + // a counter to avoid hangs; of course they didn't update the errata sheet + uint16_t count = 0; + while ((readRegByte(EIR) & (EIR_TXIF | EIR_TXERIF)) == 0 && ++count < 1000U) + ; + + if (!(readRegByte(EIR) & EIR_TXERIF) && count < 1000U) { + // no error; start new transmission + BREAKORCONTINUE + } + + // cancel previous transmission if stuck + writeOp(ENC28J60_BIT_FIELD_CLR, ECON1, ECON1_TXRTS); + + #if ETHERCARD_RETRY_LATECOLLISIONS == 0 + BREAKORCONTINUE + #endif + + // Check whether the chip thinks that a late collision ocurred; the chip + // may be wrong (Errata Issue 13); therefore we retry. We could check + // LATECOL in the ESTAT register in order to find out whether the chip + // thinks a late collision ocurred but (Errata Issue 15) tells us that + // this is not working. Therefore we check TSV + transmit_status_vector tsv; + uint16_t etxnd = readReg(ETXND); + writeReg(ERDPT, etxnd+1); + readBuf(sizeof(transmit_status_vector), (byte*) &tsv); + // LATECOL is bit number 29 in TSV (starting from 0) + + if (!((readRegByte(EIR) & EIR_TXERIF) && (tsv.bytes[3] & 1<<5) /*tsv.transmitLateCollision*/) || retry > 16U) { + // there was some error but no LATECOL so we do not repeat + BREAKORCONTINUE + } + + retry++; + } +} + + +uint16_t ENC28J60::packetReceive() { + static uint16_t gNextPacketPtr = RXSTART_INIT; + static bool unreleasedPacket = false; + uint16_t len = 0; + + if (unreleasedPacket) { + if (gNextPacketPtr == 0) + writeReg(ERXRDPT, RXSTOP_INIT); + else + writeReg(ERXRDPT, gNextPacketPtr - 1); + unreleasedPacket = false; + } + + if (readRegByte(EPKTCNT) > 0) { + writeReg(ERDPT, gNextPacketPtr); + + struct { + uint16_t nextPacket; + uint16_t byteCount; + uint16_t status; + } header; + + readBuf(sizeof header, (byte*) &header); + + gNextPacketPtr = header.nextPacket; + len = header.byteCount - 4; //remove the CRC count + if (len>bufferSize-1) + len=bufferSize-1; + if ((header.status & 0x80)==0) + len = 0; + else + readBuf(len, buffer); + buffer[len] = 0; + unreleasedPacket = true; + + writeOp(ENC28J60_BIT_FIELD_SET, ECON2, ECON2_PKTDEC); + } + return len; +} + +void ENC28J60::copyout (byte page, const byte* data) { + uint16_t destPos = SCRATCH_START + (page << SCRATCH_PAGE_SHIFT); + if (destPos < SCRATCH_START || destPos > SCRATCH_LIMIT - SCRATCH_PAGE_SIZE) + return; + writeReg(EWRPT, destPos); + writeBuf(SCRATCH_PAGE_SIZE, data); +} + +void ENC28J60::copyin (byte page, byte* data) { + uint16_t destPos = SCRATCH_START + (page << SCRATCH_PAGE_SHIFT); + if (destPos < SCRATCH_START || destPos > SCRATCH_LIMIT - SCRATCH_PAGE_SIZE) + return; + writeReg(ERDPT, destPos); + readBuf(SCRATCH_PAGE_SIZE, data); +} + +byte ENC28J60::peekin (byte page, byte off) { + byte result = 0; + uint16_t destPos = SCRATCH_START + (page << SCRATCH_PAGE_SHIFT) + off; + if (SCRATCH_START <= destPos && destPos < SCRATCH_LIMIT) { + writeReg(ERDPT, destPos); + readBuf(1, &result); + } + return result; +} + +// Contributed by Alex M. Based on code from: http://blog.derouineau.fr +// /2011/07/putting-enc28j60-ethernet-controler-in-sleep-mode/ +void ENC28J60::powerDown() { + writeOp(ENC28J60_BIT_FIELD_CLR, ECON1, ECON1_RXEN); + while(readRegByte(ESTAT) & ESTAT_RXBUSY); + while(readRegByte(ECON1) & ECON1_TXRTS); + writeOp(ENC28J60_BIT_FIELD_SET, ECON2, ECON2_VRPS); + writeOp(ENC28J60_BIT_FIELD_SET, ECON2, ECON2_PWRSV); +} + +void ENC28J60::powerUp() { + writeOp(ENC28J60_BIT_FIELD_CLR, ECON2, ECON2_PWRSV); + while(!readRegByte(ESTAT) & ESTAT_CLKRDY); + writeOp(ENC28J60_BIT_FIELD_SET, ECON1, ECON1_RXEN); +} + +void ENC28J60::enableBroadcast (bool temporary) { + writeRegByte(ERXFCON, readRegByte(ERXFCON) | ERXFCON_BCEN); + if(!temporary) + broadcast_enabled = true; +} + +void ENC28J60::disableBroadcast (bool temporary) { + if(!temporary) + broadcast_enabled = false; + if(!broadcast_enabled) + writeRegByte(ERXFCON, readRegByte(ERXFCON) & ~ERXFCON_BCEN); +} + +void ENC28J60::enableMulticast () { + writeRegByte(ERXFCON, readRegByte(ERXFCON) | ERXFCON_MCEN); +} + +void ENC28J60::disableMulticast () { + writeRegByte(ERXFCON, readRegByte(ERXFCON) & ~ERXFCON_MCEN); +} + +void ENC28J60::enablePromiscuous (bool temporary) { + writeRegByte(ERXFCON, readRegByte(ERXFCON) & ERXFCON_CRCEN); + if(!temporary) + promiscuous_enabled = true; +} + +void ENC28J60::disablePromiscuous (bool temporary) { + if(!temporary) + promiscuous_enabled = false; + if(!promiscuous_enabled) { + writeRegByte(ERXFCON, ERXFCON_UCEN|ERXFCON_CRCEN|ERXFCON_PMEN|ERXFCON_BCEN); + } +} + +uint8_t ENC28J60::doBIST ( byte csPin) { +#define RANDOM_FILL 0b0000 +#define ADDRESS_FILL 0b0100 +#define PATTERN_SHIFT 0b1000 +#define RANDOM_RACE 0b1100 + +// init + if (bitRead(SPCR, SPE) == 0) + initSPI(); + selectPin = csPin; + pinMode(selectPin, OUTPUT); + disableChip(); + + writeOp(ENC28J60_SOFT_RESET, 0, ENC28J60_SOFT_RESET); + delay(2); // errata B7/2 + while (!readOp(ENC28J60_READ_CTRL_REG, ESTAT) & ESTAT_CLKRDY) ; + + + // now we can start the memory test + + uint16_t macResult; + uint16_t bitsResult; + + // clear some of the registers registers + writeRegByte(ECON1, 0); + writeReg(EDMAST, 0); + + // Set up necessary pointers for the DMA to calculate over the entire memory + writeReg(EDMAND, 0x1FFFu); + writeReg(ERXND, 0x1FFFu); + + // Enable Test Mode and do an Address Fill + SetBank(EBSTCON); + writeRegByte(EBSTCON, EBSTCON_TME | EBSTCON_BISTST | ADDRESS_FILL); + + // wait for BISTST to be reset, only after that are we actually ready to + // start the test + // this was undocumented :( + while (readOp(ENC28J60_READ_CTRL_REG, EBSTCON) & EBSTCON_BISTST); + writeOp(ENC28J60_BIT_FIELD_CLR, EBSTCON, EBSTCON_TME); + + + // now start the actual reading an calculating the checksum until the end is + // reached + writeOp(ENC28J60_BIT_FIELD_SET, ECON1, ECON1_DMAST | ECON1_CSUMEN); + SetBank(EDMACS); + while(readOp(ENC28J60_READ_CTRL_REG, ECON1) & ECON1_DMAST); + macResult = readReg(EDMACS); + bitsResult = readReg(EBSTCS); + // Compare the results + // 0xF807 should always be generated in Address fill mode + if ((macResult != bitsResult) || (bitsResult != 0xF807)) { + return 0; + } + // reset test flag + writeOp(ENC28J60_BIT_FIELD_CLR, EBSTCON, EBSTCON_TME); + + + // Now start the BIST with random data test, and also keep on swapping the + // DMA/BIST memory ports. + writeRegByte(EBSTSD, 0b10101010 | millis()); + writeRegByte(EBSTCON, EBSTCON_TME | EBSTCON_PSEL | EBSTCON_BISTST | RANDOM_FILL); + + + // wait for BISTST to be reset, only after that are we actually ready to + // start the test + // this was undocumented :( + while (readOp(ENC28J60_READ_CTRL_REG, EBSTCON) & EBSTCON_BISTST); + writeOp(ENC28J60_BIT_FIELD_CLR, EBSTCON, EBSTCON_TME); + + + // now start the actual reading an calculating the checksum until the end is + // reached + writeOp(ENC28J60_BIT_FIELD_SET, ECON1, ECON1_DMAST | ECON1_CSUMEN); + SetBank(EDMACS); + while(readOp(ENC28J60_READ_CTRL_REG, ECON1) & ECON1_DMAST); + + macResult = readReg(EDMACS); + bitsResult = readReg(EBSTCS); + // The checksum should be equal + return macResult == bitsResult; +} + + +void ENC28J60::memcpy_to_enc(uint16_t dest, void* source, int16_t num) { + writeReg(EWRPT, dest); + writeBuf(num, (uint8_t*) source); +} + +void ENC28J60::memcpy_from_enc(void* dest, uint16_t source, int16_t num) { + writeReg(ERDPT, source); + readBuf(num, (uint8_t*) dest); +} + +static uint16_t endRam = ENC_HEAP_END; +uint16_t ENC28J60::enc_malloc(uint16_t size) { + if (endRam-size >= ENC_HEAP_START) { + endRam -= size; + return endRam; + } + return 0; +} + +uint16_t ENC28J60::enc_freemem() { + return endRam-ENC_HEAP_START; +} + +uint16_t ENC28J60::readPacketSlice(char* dest, int16_t maxlength, int16_t packetOffset) { + uint16_t erxrdpt = readReg(ERXRDPT); + int16_t packetLength; + + memcpy_from_enc((char*) &packetLength, (erxrdpt+3)%(RXSTOP_INIT+1), 2); + packetLength -= 4; // remove crc + + int16_t bytesToCopy = packetLength - packetOffset; + if (bytesToCopy > maxlength) bytesToCopy = maxlength; + if (bytesToCopy <= 0) bytesToCopy = 0; + + int16_t startofSlice = (erxrdpt+7+packetOffset)%(RXSTOP_INIT+1); + memcpy_from_enc(dest, startofSlice, bytesToCopy); + dest[bytesToCopy] = 0; + + return bytesToCopy; +} diff --git a/libraries/ethercard-master/enc28j60.h b/libraries/ethercard-master/enc28j60.h new file mode 100644 index 0000000..f14fc8e --- /dev/null +++ b/libraries/ethercard-master/enc28j60.h @@ -0,0 +1,207 @@ +// Microchip ENC28J60 Ethernet Interface Driver +// Author: Pascal Stang +// Modified by: Guido Socher +// Copyright: GPL V2 +// +// This driver provides initialization and transmit/receive +// functions for the Microchip ENC28J60 10Mb Ethernet Controller and PHY. +// This chip is novel in that it is a full MAC+PHY interface all in a 28-pin +// chip, using an SPI interface to the host processor. +// +// 2010-05-20 +/** @file */ + +#ifndef ENC28J60_H +#define ENC28J60_H + +// buffer boundaries applied to internal 8K ram +// the entire available packet buffer space is allocated + +#define RXSTART_INIT 0x0000 // start of RX buffer, (must be zero, Rev. B4 Errata point 5) +#define RXSTOP_INIT 0x0BFF // end of RX buffer, room for 2 packets + +#define TXSTART_INIT 0x0C00 // start of TX buffer, room for 1 packet +#define TXSTOP_INIT 0x11FF // end of TX buffer + +#define SCRATCH_START 0x1200 // start of scratch area +#define SCRATCH_LIMIT 0x2000 // past end of area, i.e. 3 Kb +#define SCRATCH_PAGE_SHIFT 6 // addressing is in pages of 64 bytes +#define SCRATCH_PAGE_SIZE (1 << SCRATCH_PAGE_SHIFT) +#define SCRATCH_PAGE_NUM ((SCRATCH_LIMIT-SCRATCH_START) >> SCRATCH_PAGE_SHIFT) +#define SCRATCH_MAP_SIZE (((SCRATCH_PAGE_NUM % 8) == 0) ? (SCRATCH_PAGE_NUM / 8) : (SCRATCH_PAGE_NUM/8+1)) + +// area in the enc memory that can be used via enc_malloc; by default 0 bytes; decrease SCRATCH_LIMIT in order +// to use this functionality +#define ENC_HEAP_START SCRATCH_LIMIT +#define ENC_HEAP_END 0x2000 + +/** This class provide low-level interfacing with the ENC28J60 network interface. This is used by the EtherCard class and not intended for use by (normal) end users. */ +class ENC28J60 { +public: + static uint8_t buffer[]; //!< Data buffer (shared by recieve and transmit) + static uint16_t bufferSize; //!< Size of data buffer + static bool broadcast_enabled; //!< True if broadcasts enabled (used to allow temporary disable of broadcast for DHCP or other internal functions) + static bool promiscuous_enabled; //!< True if promiscuous mode enabled (used to allow temporary disable of promiscuous mode) + + static uint8_t* tcpOffset () { return buffer + 0x36; } //!< Pointer to the start of TCP payload + + /** @brief Initialise SPI interface + * @note Configures Arduino pins as input / output, etc. + */ + static void initSPI (); + + /** @brief Initialise network interface + * @param size Size of data buffer + * @param macaddr Pointer to 6 byte hardware (MAC) address + * @param csPin Arduino pin used for chip select (enable network interface SPI bus). Default = 8 + * @return uint8_t ENC28J60 firmware version or zero on failure. + */ + static uint8_t initialize (const uint16_t size, const uint8_t* macaddr, + uint8_t csPin = 8); + + /** @brief Check if network link is connected + * @return bool True if link is up + */ + static bool isLinkUp (); + + /** @brief Sends data to network interface + * @param len Size of data to send + * @note Data buffer is shared by recieve and transmit functions + */ + static void packetSend (uint16_t len); + + /** @brief Copy recieved packets to data buffer + * @return uint16_t Size of recieved data + * @note Data buffer is shared by recieve and transmit functions + */ + static uint16_t packetReceive (); + + /** @brief Copy data from ENC28J60 memory + * @param page Data page of memory + * @param data Pointer to buffer to copy data to + */ + static void copyout (uint8_t page, const uint8_t* data); + + /** @brief Copy data to ENC28J60 memory + * @param page Data page of memory + * @param data Pointer to buffer to copy data from + */ + static void copyin (uint8_t page, uint8_t* data); + + /** @brief Get single byte of data from ENC28J60 memory + * @param page Data page of memory + * @param off Offset of data within page + * @return Data value + */ + static uint8_t peekin (uint8_t page, uint8_t off); + + /** @brief Put ENC28J60 in sleep mode + */ + static void powerDown(); // contrib by Alex M. + + /** @brief Wake ENC28J60 from sleep mode + */ + static void powerUp(); // contrib by Alex M. + + /** @brief Enable reception of broadcast messages + * @param temporary Set true to temporarily enable broadcast + * @note This will increase load on recieved data handling + */ + static void enableBroadcast(bool temporary = false); + + /** @brief Disable reception of broadcast messages + * @param temporary Set true to only disable if temporarily enabled + * @note This will reduce load on recieved data handling + */ + static void disableBroadcast(bool temporary = false); + + /** @brief Enables reception of mulitcast messages + * @note This will increase load on recieved data handling + */ + static void enableMulticast (); + + /** @brief Enables reception of all messages + * @param temporary Set true to temporarily enable promiscuous + * @note This will increase load significantly on recieved data handling + * @note All messages will be accepted, even messages with destination MAC other than own + * @note Messages with invalid CRC checksum will still be rejected + */ + static void enablePromiscuous (bool temporary = false); + + /** @brief Disable reception of all messages and go back to default mode + * @param temporary Set true to only disable if temporarily enabled + * @note This will reduce load on received data handling + * @note In this mode only unicast and broadcast messages will be received + */ + static void disablePromiscuous(bool temporary = false); + + /** @brief Disable reception of mulitcast messages + * @note This will reduce load on recieved data handling + */ + static void disableMulticast(); + + /** @brief Reset and fully initialise ENC28J60 + * @param csPin Arduino pin used for chip select (enable SPI bus) + * @return uint8_t 0 on failure + */ + static uint8_t doBIST(uint8_t csPin = 8); + + /** @brief Copies a slice from the current packet to RAM + * @param dest pointer in RAM where the data is copied to + * @param maxlength how many bytes to copy; + * @param packetOffset where within the packet to start; if less than maxlength bytes are available only the remaining bytes are copied. + * @return uint16_t the number of bytes that have been read + * @note At the destination at least maxlength+1 bytes should be reserved because the copied content will be 0-terminated. + */ + static uint16_t readPacketSlice(char* dest, int16_t maxlength, int16_t packetOffset); + + /** @brief reserves a block of RAM in the memory of the enc chip + * @param size number of bytes to reserve + * @return uint16_t start address of the block within the enc memory. 0 if the remaining memory for malloc operation is less than size. + * @note There is no enc_free(), i.e., reserved blocks stay reserved for the duration of the program. + * @note The total memory available for malloc-operations is determined by ENC_HEAP_END-ENC_HEAP_START, defined in enc28j60.h; by default this is 0, i.e., you have to change these values in order to use enc_malloc(). + */ + static uint16_t enc_malloc(uint16_t size); + + /** @brief returns the amount of memory within the enc28j60 chip that is still available for malloc. + * @return uint16_t the amount of memory in bytes. + */ + static uint16_t enc_freemem(); + + /** @brief copies a block of data from SRAM to the enc memory + @param dest destination address within enc memory + @param source source pointer to a block of SRAM in the arduino + @param num number of bytes to copy + @note There is no sanity check. Handle with care + */ + static void memcpy_to_enc(uint16_t dest, void* source, int16_t num); + + /** @brief copies a block of data from the enc memory to SRAM + @param dest destination address within SRAM + @param source source address within enc memory + @param num number of bytes to copy + */ + static void memcpy_from_enc(void* dest, uint16_t source, int16_t num); +}; + +typedef ENC28J60 Ethernet; //!< Define alias Ethernet for ENC28J60 + + +/** Workaround for Errata 13. +* The transmission hardware may drop some packets because it thinks a late collision +* occurred (which should never happen if all cable length etc. are ok). If setting +* this to 1 these packages will be retried a fixed number of times. Costs about 150bytes +* of flash. +*/ +#define ETHERCARD_RETRY_LATECOLLISIONS 0 + +/** Enable pipelining of packet transmissions. +* If enabled the packetSend function will not block/wait until the packet is actually +* transmitted; but instead this wait is shifted to the next time that packetSend is +* called. This gives higher performance; however in combination with +* ETHERCARD_RETRY_LATECOLLISIONS this may lead to problems because a packet whose +* transmission fails because the ENC-chip thinks that it is a late collision will +* not be retried until the next call to packetSend. +*/ +#define ETHERCARD_SEND_PIPELINING 0 +#endif diff --git a/libraries/ethercard-master/examples/JeeUdp/JeeUdp.ino b/libraries/ethercard-master/examples/JeeUdp/JeeUdp.ino new file mode 100644 index 0000000..4df8678 --- /dev/null +++ b/libraries/ethercard-master/examples/JeeUdp/JeeUdp.ino @@ -0,0 +1,321 @@ +// Collect RF12 packets and send them on as UDP collectd packets on Ethernet. +// 2010-05-20 http://opensource.org/licenses/mit-license.php + +// This sketch is derived from RF12eth.pde (and etherNode.ino): +// May 2010, Andras Tucsni, http://opensource.org/licenses/mit-license.php + +#include +#include +#include + +#define DEBUG 1 // set to 1 to display free RAM on web page +#define SERIAL 1 // set to 1 to show incoming requests on serial port + +#define CONFIG_EEPROM_ADDR ((byte*) 0x10) + +// configuration, as stored in EEPROM +struct Config { + byte band; + byte group; + byte collect; + word port; + byte valid; // keep this as last byte +} config; + +// ethernet interface mac address - must be unique on your network +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; + +// buffer for an outgoing data packet +static byte outBuf[RF12_MAXDATA], outDest; +static char outCount = -1; + +// this buffer will be used to construct a collectd UDP packet +static byte collBuf [200], collPos; + +#define NUM_MESSAGES 3 // Number of messages saved in history +#define MESSAGE_TRUNC 15 // Truncate message payload to reduce memory use + +static BufferFiller bfill; // used as cursor while filling the buffer + +static byte history_rcvd[NUM_MESSAGES][MESSAGE_TRUNC+1]; //history record +static byte history_len[NUM_MESSAGES]; // # of RF12 messages+header in history +static byte next_msg; // pointer to next rf12rcvd line +static word msgs_rcvd; // total number of lines received modulo 10,000 + +byte Ethernet::buffer[700]; // tcp/ip send and receive buffer + +static void loadConfig () { + for (byte i = 0; i < sizeof config; ++i) + ((byte*) &config)[i] = eeprom_read_byte(CONFIG_EEPROM_ADDR + i); + if (config.valid != 253) { + config.valid = 253; + config.band = 8; + config.group = 1; + config.collect = 1; + config.port = 25827; + } + byte freq = config.band == 4 ? RF12_433MHZ : + config.band == 8 ? RF12_868MHZ : + RF12_915MHZ; + rf12_initialize(31, freq, config.group); +} + +static void saveConfig () { + for (byte i = 0; i < sizeof config; ++i) + eeprom_write_byte(CONFIG_EEPROM_ADDR + i, ((byte*) &config)[i]); +} + +#if DEBUG +static int freeRam () { +extern int __heap_start, *__brkval; +int v; +return (int) &v - (__brkval == 0 ? (int) &__heap_start : (int) __brkval); +} +#endif + +void setup (){ + Serial.begin(57600); + Serial.println("\n[JeeUdp]"); + loadConfig(); + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println( "Failed to access Ethernet controller"); + if (!ether.dhcpSetup()) + Serial.println("DHCP failed"); + ether.printIp("IP: ", ether.myip); +} + +const char okHeader[] PROGMEM = + "HTTP/1.0 200 OK\r\n" + "Content-Type: text/html\r\n" + "Pragma: no-cache\r\n" +; + +static void homePage (BufferFiller& buf) { + word mhz = config.band == 4 ? 433 : config.band == 8 ? 868 : 915; + buf.emit_p(PSTR("$F\r\n" + "RF12 JeeUdp" + "

RF12 JeeUdp @ $D - RF12 @ $D.$D

" + "Configure - Send Packet" + "

Last $D messages:

" + "
"), okHeader, config.port, mhz, config.group, NUM_MESSAGES);
+  for (byte i = 0; i < NUM_MESSAGES; ++i) {
+    byte j = (next_msg + i) % NUM_MESSAGES;
+    if (history_len[j] > 0) {
+      word n = msgs_rcvd - NUM_MESSAGES + i;
+      buf.emit_p(PSTR("\n$D$D$D$D: OK"), // hack, to show leading zero's
+                          n/1000, (n/100) % 10, (n/10) % 10, n % 10);
+      for (byte k = 0; k < history_len[j]; ++k)
+        buf.emit_p(PSTR(" $D"), history_rcvd[j][k]);
+    }
+  }
+  long t = millis() / 1000;
+  word h = t / 3600;
+  byte m = (t / 60) % 60;
+  byte s = t % 60;
+  buf.emit_p(PSTR(
+    "
" + "Uptime is $D$D:$D$D:$D$D"), h/10, h%10, m/10, m%10, s/10, s%10); +#if DEBUG + buf.emit_p(PSTR(" ($D bytes free)"), freeRam()); +#endif +} + +static int getIntArg(const char* data, const char* key, int value =-1) { + char temp[10]; + if (ether.findKeyVal(data + 7, temp, sizeof temp, key) > 0) + value = atoi(temp); + return value; +} + +static void configPage (const char* data, BufferFiller& buf) { + // pick up submitted data, if present + if (data[6] == '?') { + byte b = getIntArg(data, "b", 8); + byte g = getIntArg(data, "g", 1); + byte c = getIntArg(data, "c", 0); + word p = getIntArg(data, "p", 25827); + if (1 <= g && g <= 250 && 1024 <= p && p <= 30000) { + // store values as new settings + config.band = b; + config.group = g; + config.collect = c; + config.port = p; + saveConfig(); + // re-init RF12 driver + loadConfig(); + // clear history + memset(history_len, 0, sizeof history_len); + // redirect to the home page + buf.emit_p(PSTR( + "HTTP/1.0 302 found\r\n" + "Location: /\r\n" + "\r\n")); + return; + } + } + // else show a configuration form + buf.emit_p(PSTR("$F\r\n" + "

Server node configuration

" + "
" + "

" + "Freq band (4, 8, or 9)
" + "Net group (1..250)
" + "Collect mode: " + "(don't send ACKs)

" + "UDP Port (1024..30000)" + "

" + "" + "
"), okHeader, config.band, config.group, + config.collect ? "CHECKED" : "", + config.port); +} + +static void sendPage (const char* data, BufferFiller& buf) { + // pick up submitted data, if present + const char* p = strstr(data, "b="); + byte d = getIntArg(data, "d"); + if (data[6] == '?' && p != 0 && 0 <= d && d <= 31) { + // prepare to send data as soon as possible in loop() + outDest = d & RF12_HDR_MASK ? RF12_HDR_DST | d : 0; + outCount = 0; + // convert the input string to a number of decimal data bytes in outBuf + ++p; + while (*p != 0 && *p != '&') { + outBuf[outCount] = 0; + while ('0' <= *++p && *p <= '9') + outBuf[outCount] = 10 * outBuf[outCount] + (*p - '0'); + ++outCount; + } +#if SERIAL + Serial.print("Send to "); + Serial.print(outDest, DEC); + Serial.print(':'); + for (byte i = 0; i < outCount; ++i) { + Serial.print(' '); + Serial.print(outBuf[i], DEC); + } + Serial.println(); +#endif + // redirect to home page + buf.emit_p(PSTR( + "HTTP/1.0 302 found\r\n" + "Location: /\r\n" + "\r\n")); + return; + } + // else show a send form + buf.emit_p(PSTR("$F\r\n" + "

Send a wireless data packet

" + "
" + "

" + "Data bytes (decimal)
" + "Destination node " + "(1..31, or 0 to broadcast)
" + "

" + "" + "
"), okHeader); +} + +static void collectTypeLen (word type, word len) { + len += 4; + collBuf[collPos++] = type >> 8; + collBuf[collPos++] = (byte) type; + collBuf[collPos++] = len >> 8; + collBuf[collPos++] = (byte) len; +} + +static void collectStr (word type, const char* data) { + word len = strlen(data) + 1; + collectTypeLen(type, len); + strcpy((char*) collBuf + collPos, data); + collPos += len; +} + +static void collectPayload (word type) { + // Copy the received RF12 data into a as many values as needed. + byte num = rf12_len / 8 + 1; // this many values will be needed + collectTypeLen(type, 2 + 9 * num); + collBuf[collPos++] = 0; + collBuf[collPos++] = num; + for (byte i = 0; i < num; ++i) + collBuf[collPos++] = 0; // counter + for (char i = 0; i < 8 * num; ++i) // include -1, i.e. the length byte + collBuf[collPos++] = i <= rf12_len ? rf12_data[i-1] : 0; +} + +static void forwardToUDP () { + static byte destIp[] = { 239,192,74,66 }; // UDP multicast address + char buf[10]; + + collPos = 0; + collectStr(0x0000, "JeeUdp"); + collectStr(0x0002, "RF12"); + word mhz = config.band == 4 ? 433 : config.band == 8 ? 868 : 915; + sprintf(buf, "%d.%d", mhz, config.group); + collectStr(0x0003, buf); + collectStr(0x0004, "OK"); + sprintf(buf, "%d", rf12_hdr); + collectStr(0x0005, buf); + collectPayload(0x0006); + + ether.sendUdp ((char*) collBuf, collPos, 23456, destIp, config.port); +#if SERIAL + Serial.println("UDP sent"); +#endif +} + +void loop (){ + word len = ether.packetReceive(); + word pos = ether.packetLoop(len); + // check if valid tcp data is received + if (pos) { + bfill = ether.tcpOffset(); + char* data = (char *) Ethernet::buffer + pos; +#if SERIAL + Serial.println(data); +#endif + // receive buf hasn't been clobbered by reply yet + if (strncmp("GET / ", data, 6) == 0) + homePage(bfill); + else if (strncmp("GET /c", data, 6) == 0) + configPage(data, bfill); + else if (strncmp("GET /s", data, 6) == 0) + sendPage(data, bfill); + else + bfill.emit_p(PSTR( + "HTTP/1.0 401 Unauthorized\r\n" + "Content-Type: text/html\r\n" + "\r\n" + "

401 Unauthorized

")); + ether.httpServerReply(bfill.position()); // send web page data + } + + // RFM12 loop runner, don't report acks + if (rf12_recvDone() && rf12_crc == 0 && (rf12_hdr & RF12_HDR_CTL) == 0) { + history_rcvd[next_msg][0] = rf12_hdr; + for (byte i = 0; i < rf12_len; ++i) + if (i < MESSAGE_TRUNC) + history_rcvd[next_msg][i+1] = rf12_data[i]; + history_len[next_msg] = rf12_len < MESSAGE_TRUNC ? rf12_len+1 + : MESSAGE_TRUNC+1; + next_msg = (next_msg + 1) % NUM_MESSAGES; + msgs_rcvd = (msgs_rcvd + 1) % 10000; + + if (RF12_WANTS_ACK && !config.collect) { +#if SERIAL + Serial.println(" -> ack"); +#endif + rf12_sendStart(RF12_ACK_REPLY); + } + + forwardToUDP(); + } + + // send a data packet out if requested + if (outCount >= 0 && rf12_canSend()) { + rf12_sendStart(outDest, outBuf, outCount); + rf12_sendWait(1); + outCount = -1; + } +} + diff --git a/libraries/ethercard-master/examples/SSDP/SSDP.ino b/libraries/ethercard-master/examples/SSDP/SSDP.ino new file mode 100644 index 0000000..2be0715 --- /dev/null +++ b/libraries/ethercard-master/examples/SSDP/SSDP.ino @@ -0,0 +1,144 @@ +#include // |Mac adress| +const char SSDP_RESPONSE[] PROGMEM = "HTTP/1.1 200 OK\r\nCACHE-CONTROL: max-age=1200\r\nEXT:\r\nSERVER:Arduino\r\nST: upnp:rootdevice\r\nUSN: uuid:abcdefgh-7dec-11d0-a765-7499692d3040\r\nLOCATION: http://"; //dont forget our mac adress USN: uuid:abcdefgh-7dec-11d0-a765-Mac addr +const char SSDP_RESPONSE_XML[] PROGMEM = "/??\r\n\r\n"; // here is the adress of xml file /?? in this exemple but you could use another /upnp.xml\r\n\r\n +const char XML_DESCRIP[] PROGMEM = "HTTP/1.1 200 OK\r\nContent-Type: text/xml\r\n\r\n\rurn:schemas-upnp-org:device:BinaryLight:1/ArduinoFredycpuhttp://fredycpu.pro1uuid:abcdefgh-7dec-11d0-a765-7499692d3040 "; +const char SSDP_NOTIFY[] PROGMEM = "NOTIFY * HTTP/1.1\r\nHOST: 239.255.255.250:1900\r\nCACHE-CONTROL: max-age=1200\r\nNT: upnp:rootdevice\r\nUSN: uuid:abcdefga-7dec-11d0-a765-7499692d3040::upnp:rootdevice\r\nNTS: ssdp:alive\r\nSERVER: Arduino UPnP/1.0\r\nLOCATION: http://"; //dont forget our mac adress USN: uuid:abcdefgh-7dec-11d0-a765-Mac addr +// in XML_DESCRIP // urn:schemas-upnp-org:device:BinaryLight:1 // declare as home automation +// in XML_DESCRIP // Arduino // declare the name of the service here Arduino +// in XML_DESCRIP // / // adress of the page who would opened on service double click ,you could use http://ip but if you use dhcp it's better so and dont wase memory +// this is the entire protocol, but you can try to use SSDP_NOTIFY as SSDP_RESPONSE with most systems will work and you can free a bit of flash mem. +static byte myip[] = { + 192,168,0,67 }; +static byte gwip[] = { + 192,168,0,250 }; +static byte ssdp[] = { + 239,255,255,250 }; +static byte mymac[] = { + 0x74,0x99,0x69,0x2D,0x30,0x40 }; // if you change it you must update SSDP_RESPONSE and XML_DESCRIP +byte Ethernet::buffer[750]; // tcp ip send and receive buffer +unsigned long timer=9999; +const char pageA[] PROGMEM = +"HTTP/1.0 200 OK\r\n" +"Content-Type: text/html\r\n" +"\r\n" +"" +"" +"multipackets Test" +"" +"" +"Start here
" +"Image test
" +"

packet 1

" +"

" +"the first packet send " +"

" +; +const char pageB[] PROGMEM = +"

packet 2

" +"

" +"if you read this it mean it works" +"

" +; +const char pageC[] PROGMEM = +"

packet 3

" +"

" +"if you read this it mean it works" +"

" +; +const char pageD[] PROGMEM = +"

packet 4

" +"

" +"if you read this it mean it works" +"

" +; + +void setup(){ + ether.begin(sizeof Ethernet::buffer, mymac , SS);// SS = 53 for the mega ethernet shield and 10 for normal ethernet shield + ether.staticSetup(myip, gwip); + ENC28J60::disableMulticast(); //disable multicast filter means enable multicast reception + Serial.begin(115200); +} + +void loop(){ +wait: + word pos = ether.packetLoop(ether.packetReceive()); + // check if valid tcp data is received + if (pos) { + char* data = (char *) Ethernet::buffer + pos; + if (strncmp("GET / ", data, 6) == 0) { + ether.httpServerReplyAck(); // send ack to the request + memcpy_P(ether.tcpOffset(), pageA, sizeof pageA); // send first packet and not send the terminate flag + ether.httpServerReply_with_flags(sizeof pageA - 1,TCP_FLAGS_ACK_V); + memcpy_P(ether.tcpOffset(), pageB, sizeof pageB); // send second packet and not send the terminate flag + ether.httpServerReply_with_flags(sizeof pageB - 1,TCP_FLAGS_ACK_V); + memcpy_P(ether.tcpOffset(), pageC, sizeof pageC); // send thirdt packet and not send the terminate flag + ether.httpServerReply_with_flags(sizeof pageC - 1,TCP_FLAGS_ACK_V); + memcpy_P(ether.tcpOffset(), pageD, sizeof pageD); // send fourth packet and send the terminate flag + ether.httpServerReply_with_flags(sizeof pageD - 1,TCP_FLAGS_ACK_V|TCP_FLAGS_FIN_V); + goto wait; + } + if (strncmp("GET /??", data, 7) == 0) { // description of services (normaly an xml file but here .....) + ether.httpServerReplyAck(); + memcpy_P(Ethernet::buffer + TCP_OPTIONS_P,XML_DESCRIP, sizeof XML_DESCRIP); + ether.httpServerReply_with_flags(sizeof XML_DESCRIP - 1 ,TCP_FLAGS_ACK_V|TCP_FLAGS_FIN_V); + goto wait; + } + if (strncmp("M-SEARCH", data, 8) == 0) { // service discovery request comes here (udp protocol) + ssdpresp(); + goto wait; + } + } + if (((millis()-timer)>50000)||(timer>millis())) { + timer=millis(); + ssdpnotify(); + } +} +void ssdpresp() { //response to m-search + byte ip_dst[IP_LEN]; + unsigned int port_dst=Ethernet::buffer[34]*256+Ethernet::buffer[35];//extract source port of request + for( int i=0; i http://opensource.org/licenses/mit-license.php + +#include + +#define STATIC 0 // set to 1 to disable DHCP (adjust myip/gwip values below) + +#if STATIC +// ethernet interface ip address +static byte myip[] = { 192,168,1,200 }; +// gateway ip address +static byte gwip[] = { 192,168,1,1 }; +#endif + +// ethernet mac address - must be unique on your network +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; + +byte Ethernet::buffer[500]; // tcp/ip send and receive buffer + +const char page[] PROGMEM = +"HTTP/1.0 503 Service Unavailable\r\n" +"Content-Type: text/html\r\n" +"Retry-After: 600\r\n" +"\r\n" +"" + "" + "Service Temporarily Unavailable" + "" + "" + "

This service is currently unavailable

" + "

" + "The main server is currently off-line.
" + "Please try again later." + "

" + "" +"" +; + +void setup(){ + Serial.begin(57600); + Serial.println("\n[backSoon]"); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println( "Failed to access Ethernet controller"); +#if STATIC + ether.staticSetup(myip, gwip); +#else + if (!ether.dhcpSetup()) + Serial.println("DHCP failed"); +#endif + + ether.printIp("IP: ", ether.myip); + ether.printIp("GW: ", ether.gwip); + ether.printIp("DNS: ", ether.dnsip); +} + +void loop(){ + // wait for an incoming TCP packet, but ignore its contents + if (ether.packetLoop(ether.packetReceive())) { + memcpy_P(ether.tcpOffset(), page, sizeof page); + ether.httpServerReply(sizeof page - 1); + } +} diff --git a/libraries/ethercard-master/examples/etherNode/etherNode.ino b/libraries/ethercard-master/examples/etherNode/etherNode.ino new file mode 100644 index 0000000..da8069a --- /dev/null +++ b/libraries/ethercard-master/examples/etherNode/etherNode.ino @@ -0,0 +1,277 @@ +// Arduino demo sketch for testing RFM12B + ethernet +// 2010-05-20 http://opensource.org/licenses/mit-license.php + +// Listens for RF12 messages and displays valid messages on a webpage +// Memory usage exceeds 1K, so use Atmega328 or decrease history/buffers +// +// This sketch is derived from RF12eth.pde: +// May 2010, Andras Tucsni, http://opensource.org/licenses/mit-license.php + +#include +#include +#include + +#define DEBUG 1 // set to 1 to display free RAM on web page +#define SERIAL 0 // set to 1 to show incoming requests on serial port + +#define CONFIG_EEPROM_ADDR ((byte*) 0x10) + +// configuration, as stored in EEPROM +struct Config { + byte band; + byte group; + byte collect; + word refresh; + byte valid; // keep this as last byte +} config; + +// ethernet interface mac address - must be unique on your network +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; + +// buffer for an outgoing data packet +static byte outBuf[RF12_MAXDATA], outDest; +static char outCount = -1; + +#define NUM_MESSAGES 10 // Number of messages saved in history +#define MESSAGE_TRUNC 15 // Truncate message payload to reduce memory use + +static BufferFiller bfill; // used as cursor while filling the buffer + +static byte history_rcvd[NUM_MESSAGES][MESSAGE_TRUNC+1]; //history record +static byte history_len[NUM_MESSAGES]; // # of RF12 messages+header in history +static byte next_msg; // pointer to next rf12rcvd line +static word msgs_rcvd; // total number of lines received modulo 10,000 + +byte Ethernet::buffer[1000]; // tcp/ip send and receive buffer + +static void loadConfig() { + for (byte i = 0; i < sizeof config; ++i) + ((byte*) &config)[i] = eeprom_read_byte(CONFIG_EEPROM_ADDR + i); + if (config.valid != 253) { + config.valid = 253; + config.band = 8; + config.group = 1; + config.collect = 1; + config.refresh = 5; + } + byte freq = config.band == 4 ? RF12_433MHZ : + config.band == 8 ? RF12_868MHZ : + RF12_915MHZ; + rf12_initialize(31, freq, config.group); +} + +static void saveConfig() { + for (byte i = 0; i < sizeof config; ++i) + eeprom_write_byte(CONFIG_EEPROM_ADDR + i, ((byte*) &config)[i]); +} + +#if DEBUG +static int freeRam () { + extern int __heap_start, *__brkval; + int v; + return (int) &v - (__brkval == 0 ? (int) &__heap_start : (int) __brkval); +} +#endif + +void setup(){ +#if SERIAL + Serial.begin(57600); + Serial.println("\n[etherNode]"); +#endif + loadConfig(); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println( "Failed to access Ethernet controller"); + if (!ether.dhcpSetup()) + Serial.println("DHCP failed"); +#if SERIAL + ether.printIp("IP: ", ether.myip); +#endif +} + +const char okHeader[] PROGMEM = + "HTTP/1.0 200 OK\r\n" + "Content-Type: text/html\r\n" + "Pragma: no-cache\r\n" +; + +static void homePage(BufferFiller& buf) { + word mhz = config.band == 4 ? 433 : config.band == 8 ? 868 : 915; + buf.emit_p(PSTR("$F\r\n" + "" + "RF12 etherNode - $D MHz, group $D" + "RF12 etherNode - $D MHz, group $D " + "- configure - send packet" + "

Last $D messages:

" + "
"), okHeader, config.refresh, mhz, config.group,
+                                            mhz, config.group, NUM_MESSAGES);
+    for (byte i = 0; i < NUM_MESSAGES; ++i) {
+        byte j = (next_msg + i) % NUM_MESSAGES;
+        if (history_len[j] > 0) {
+            word n = msgs_rcvd - NUM_MESSAGES + i;
+            buf.emit_p(PSTR("\n$D$D$D$D: OK"), // hack, to show leading zero's
+                                n/1000, (n/100) % 10, (n/10) % 10, n % 10);
+            for (byte k = 0; k < history_len[j]; ++k)
+                buf.emit_p(PSTR(" $D"), history_rcvd[j][k]);
+        }
+    }
+    long t = millis() / 1000;
+    word h = t / 3600;
+    byte m = (t / 60) % 60;
+    byte s = t % 60;
+    buf.emit_p(PSTR(
+        "
" + "Uptime is $D$D:$D$D:$D$D"), h/10, h%10, m/10, m%10, s/10, s%10); +#if DEBUG + buf.emit_p(PSTR(" ($D bytes free)"), freeRam()); +#endif +} + +static int getIntArg(const char* data, const char* key, int value =-1) { + char temp[10]; + if (ether.findKeyVal(data + 7, temp, sizeof temp, key) > 0) + value = atoi(temp); + return value; +} + +static void configPage(const char* data, BufferFiller& buf) { + // pick up submitted data, if present + if (data[6] == '?') { + byte b = getIntArg(data, "b"); + byte g = getIntArg(data, "g"); + byte c = getIntArg(data, "c", 0); + word r = getIntArg(data, "r"); + if (1 <= g && g <= 250 && 1 <= r && r <= 3600) { + // store values as new settings + config.band = b; + config.group = g; + config.collect = c; + config.refresh = r; + saveConfig(); + // re-init RF12 driver + loadConfig(); + // clear history + memset(history_len, 0, sizeof history_len); + // redirect to the home page + buf.emit_p(PSTR( + "HTTP/1.0 302 found\r\n" + "Location: /\r\n" + "\r\n")); + return; + } + } + // else show a configuration form + buf.emit_p(PSTR("$F\r\n" + "

Server node configuration

" + "
" + "

" + "Freq band (4, 8, or 9)
" + "Net group (1..250)
" + "Collect mode: " + "Don't send ACKs

" + "Refresh rate (1..3600 seconds)" + "

" + "" + "
"), okHeader, config.band, config.group, + config.collect ? "CHECKED" : "", + config.refresh); +} + +static void sendPage(const char* data, BufferFiller& buf) { + // pick up submitted data, if present + const char* p = strstr(data, "b="); + byte d = getIntArg(data, "d"); + if (data[6] == '?' && p != 0 && 0 <= d && d <= 31) { + // prepare to send data as soon as possible in loop() + outDest = d & RF12_HDR_MASK ? RF12_HDR_DST | d : 0; + outCount = 0; + // convert the input string to a number of decimal data bytes in outBuf + ++p; + while (*p != 0 && *p != '&') { + outBuf[outCount] = 0; + while ('0' <= *++p && *p <= '9') + outBuf[outCount] = 10 * outBuf[outCount] + (*p - '0'); + ++outCount; + } +#if SERIAL + Serial.print("Send to "); + Serial.print(outDest, DEC); + Serial.print(':'); + for (byte i = 0; i < outCount; ++i) { + Serial.print(' '); + Serial.print(outBuf[i], DEC); + } + Serial.println(); +#endif + // redirect to home page + buf.emit_p(PSTR( + "HTTP/1.0 302 found\r\n" + "Location: /\r\n" + "\r\n")); + return; + } + // else show a send form + buf.emit_p(PSTR("$F\r\n" + "

Send a wireless data packet

" + "
" + "

" + "Data bytes (decimal)
" + "Destination node " + "(1..31, or 0 to broadcast)
" + "

" + "" + "
"), okHeader); +} + +void loop(){ + word len = ether.packetReceive(); + word pos = ether.packetLoop(len); + // check if valid tcp data is received + if (pos) { + bfill = ether.tcpOffset(); + char* data = (char *) Ethernet::buffer + pos; +#if SERIAL + Serial.println(data); +#endif + // receive buf hasn't been clobbered by reply yet + if (strncmp("GET / ", data, 6) == 0) + homePage(bfill); + else if (strncmp("GET /c", data, 6) == 0) + configPage(data, bfill); + else if (strncmp("GET /s", data, 6) == 0) + sendPage(data, bfill); + else + bfill.emit_p(PSTR( + "HTTP/1.0 401 Unauthorized\r\n" + "Content-Type: text/html\r\n" + "\r\n" + "

401 Unauthorized

")); + ether.httpServerReply(bfill.position()); // send web page data + } + + // RFM12 loop runner, don't report acks + if (rf12_recvDone() && rf12_crc == 0 && (rf12_hdr & RF12_HDR_CTL) == 0) { + history_rcvd[next_msg][0] = rf12_hdr; + for (byte i = 0; i < rf12_len; ++i) + if (i < MESSAGE_TRUNC) + history_rcvd[next_msg][i+1] = rf12_data[i]; + history_len[next_msg] = rf12_len < MESSAGE_TRUNC ? rf12_len+1 + : MESSAGE_TRUNC+1; + next_msg = (next_msg + 1) % NUM_MESSAGES; + msgs_rcvd = (msgs_rcvd + 1) % 10000; + + if (RF12_WANTS_ACK && !config.collect) { +#if SERIAL + Serial.println(" -> ack"); +#endif + rf12_sendStart(RF12_ACK_REPLY); + } + } + + // send a data packet out if requested + if (outCount >= 0 && rf12_canSend()) { + rf12_sendStart(outDest, outBuf, outCount); + rf12_sendWait(1); + outCount = -1; + } +} diff --git a/libraries/ethercard-master/examples/getDHCPandDNS/getDHCPandDNS.ino b/libraries/ethercard-master/examples/getDHCPandDNS/getDHCPandDNS.ino new file mode 100644 index 0000000..ce03a89 --- /dev/null +++ b/libraries/ethercard-master/examples/getDHCPandDNS/getDHCPandDNS.ino @@ -0,0 +1,55 @@ +// This demo does web requests via DHCP and DNS lookup. +// 2011-07-05 http://opensource.org/licenses/mit-license.php + +#include + +#define REQUEST_RATE 5000 // milliseconds + +// ethernet interface mac address +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; +// remote website name +const char website[] PROGMEM = "google.com"; + +byte Ethernet::buffer[700]; +static long timer; + +// called when the client request is complete +static void my_result_cb (byte status, word off, word len) { + Serial.print("<<< reply "); + Serial.print(millis() - timer); + Serial.println(" ms"); + Serial.println((const char*) Ethernet::buffer + off); +} + +void setup () { + Serial.begin(57600); + Serial.println("\n[getDHCPandDNS]"); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println( "Failed to access Ethernet controller"); + + if (!ether.dhcpSetup()) + Serial.println("DHCP failed"); + + ether.printIp("My IP: ", ether.myip); + // ether.printIp("Netmask: ", ether.mymask); + ether.printIp("GW IP: ", ether.gwip); + ether.printIp("DNS IP: ", ether.dnsip); + + if (!ether.dnsLookup(website)) + Serial.println("DNS failed"); + ether.printIp("Server: ", ether.hisip); + + timer = - REQUEST_RATE; // start timing out right away +} + +void loop () { + + ether.packetLoop(ether.packetReceive()); + + if (millis() > timer + REQUEST_RATE) { + timer = millis(); + Serial.println("\n>>> REQ"); + ether.browseUrl(PSTR("/foo/"), "bar", website, my_result_cb); + } +} diff --git a/libraries/ethercard-master/examples/getStaticIP/getStaticIP.ino b/libraries/ethercard-master/examples/getStaticIP/getStaticIP.ino new file mode 100644 index 0000000..6f9a5d2 --- /dev/null +++ b/libraries/ethercard-master/examples/getStaticIP/getStaticIP.ino @@ -0,0 +1,57 @@ +// This demo does web requests to a fixed IP address, using a fixed gateway. +// 2010-11-27 http://opensource.org/licenses/mit-license.php + +#include + +#define REQUEST_RATE 5000 // milliseconds + +// ethernet interface mac address +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; +// ethernet interface ip address +static byte myip[] = { 192,168,1,203 }; +// gateway ip address +static byte gwip[] = { 192,168,1,1 }; +// remote website ip address and port +static byte hisip[] = { 74,125,79,99 }; +// remote website name +const char website[] PROGMEM = "google.com"; + +byte Ethernet::buffer[300]; // a very small tcp/ip buffer is enough here +static long timer; + +// called when the client request is complete +static void my_result_cb (byte status, word off, word len) { + Serial.print("<<< reply "); + Serial.print(millis() - timer); + Serial.println(" ms"); + Serial.println((const char*) Ethernet::buffer + off); +} + +void setup () { + Serial.begin(57600); + Serial.println("\n[getStaticIP]"); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println( "Failed to access Ethernet controller"); + + ether.staticSetup(myip, gwip); + + ether.copyIp(ether.hisip, hisip); + ether.printIp("Server: ", ether.hisip); + + while (ether.clientWaitingGw()) + ether.packetLoop(ether.packetReceive()); + Serial.println("Gateway found"); + + timer = - REQUEST_RATE; // start timing out right away +} + +void loop () { + ether.packetLoop(ether.packetReceive()); + + if (millis() > timer + REQUEST_RATE) { + timer = millis(); + Serial.println("\n>>> REQ"); + ether.browseUrl(PSTR("/foo/"), "bar", website, my_result_cb); + } +} diff --git a/libraries/ethercard-master/examples/getViaDNS/getViaDNS.ino b/libraries/ethercard-master/examples/getViaDNS/getViaDNS.ino new file mode 100644 index 0000000..586a35e --- /dev/null +++ b/libraries/ethercard-master/examples/getViaDNS/getViaDNS.ino @@ -0,0 +1,52 @@ +// This demo does web requests via DNS lookup, using a fixed gateway. +// 2010-11-27 http://opensource.org/licenses/mit-license.php + +#include + +#define REQUEST_RATE 5000 // milliseconds + +// ethernet interface mac address +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; +// ethernet interface ip address +static byte myip[] = { 192,168,1,203 }; +// gateway ip address +static byte gwip[] = { 192,168,1,1 }; +// remote website name +const char website[] PROGMEM = "google.com"; + +byte Ethernet::buffer[300]; // a very small tcp/ip buffer is enough here +static long timer; + +// called when the client request is complete +static void my_result_cb (byte status, word off, word len) { + Serial.print("<<< reply "); + Serial.print(millis() - timer); + Serial.println(" ms"); + Serial.println((const char*) Ethernet::buffer + off); +} + +void setup () { + Serial.begin(57600); + Serial.println("\n[getViaDNS]"); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println( "Failed to access Ethernet controller"); + + ether.staticSetup(myip, gwip); + + if (!ether.dnsLookup(website)) + Serial.println("DNS failed"); + ether.printIp("Server: ", ether.hisip); + + timer = - REQUEST_RATE; // start timing out right away +} + +void loop () { + ether.packetLoop(ether.packetReceive()); + + if (millis() > timer + REQUEST_RATE) { + timer = millis(); + Serial.println("\n>>> REQ"); + ether.browseUrl(PSTR("/foo/"), "bar", website, my_result_cb); + } +} diff --git a/libraries/ethercard-master/examples/multipacket/multipacket.ino b/libraries/ethercard-master/examples/multipacket/multipacket.ino new file mode 100644 index 0000000..a19f1b6 --- /dev/null +++ b/libraries/ethercard-master/examples/multipacket/multipacket.ino @@ -0,0 +1,77 @@ +#include +#define TCP_FLAGS_FIN_V 1 //as declared in net.h +#define TCP_FLAGS_ACK_V 0x10 //as declared in net.h +static byte myip[] = { 192,168,0,66 }; +static byte gwip[] = { 192,168,0,250 }; +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x39 }; +byte Ethernet::buffer[900]; // tcp ip send and receive buffer +const char pageA[] PROGMEM = +"HTTP/1.0 200 OK\r\n" +"Content-Type: text/html\r\n" +"\r\n" +"" + "" + "multipackets Test" + "" + "" + "Start here
" + "

packet 1

" + "

" + "the first packet send " + "

" +; +const char pageB[] PROGMEM = + "

packet 2

" + "

" + "if you read this it mean it works" + "

" +; +const char pageC[] PROGMEM = + "

packet 3

" + "

" + "if you read this it mean it works" + "

" +; +const char pageD[] PROGMEM = + "

packet 4

" + "

" + "if you read this it mean it works" + "

" +; +const char pageE[] PROGMEM = + "

packet 5

" + "

" + "this is the last packet" + "

" +; + + +void setup(){ + ether.begin(sizeof Ethernet::buffer, mymac , 10);// 53 for the mega ethernet shield and 10 for normal ethernet shield + ether.staticSetup(myip, gwip); +} +void loop(){ + word pos = ether.packetLoop(ether.packetReceive()); + // check if valid tcp data is received + if (pos) { + char* data = (char *) Ethernet::buffer + pos; + if (strncmp("GET / ", data, 6) == 0) { + ether.httpServerReplyAck(); // send ack to the request + memcpy_P(ether.tcpOffset(), pageA, sizeof pageA); // send first packet and not send the terminate flag + ether.httpServerReply_with_flags(sizeof pageA - 1,TCP_FLAGS_ACK_V); + memcpy_P(ether.tcpOffset(), pageB, sizeof pageB); // send second packet and not send the terminate flag + ether.httpServerReply_with_flags(sizeof pageB - 1,TCP_FLAGS_ACK_V); + memcpy_P(ether.tcpOffset(), pageC, sizeof pageC); // send thirdt packet and not send the terminate flag + ether.httpServerReply_with_flags(sizeof pageC - 1,TCP_FLAGS_ACK_V); + memcpy_P(ether.tcpOffset(), pageD, sizeof pageD); // send fourth packet and not send the terminate flag + ether.httpServerReply_with_flags(sizeof pageD - 1,TCP_FLAGS_ACK_V); + memcpy_P(ether.tcpOffset(), pageE, sizeof pageE); // send fiveth packet and send the terminate flag + ether.httpServerReply_with_flags(sizeof pageE - 1,TCP_FLAGS_ACK_V|TCP_FLAGS_FIN_V); } + else + { + ether.httpServerReplyAck(); // send ack to the request + memcpy_P(ether.tcpOffset(), pageA, sizeof pageA);//only the first part will sended + ether.httpServerReply_with_flags(sizeof pageA - 1,TCP_FLAGS_ACK_V|TCP_FLAGS_FIN_V); + } + } +} diff --git a/libraries/ethercard-master/examples/multipacketSD/multipacketSD.ino b/libraries/ethercard-master/examples/multipacketSD/multipacketSD.ino new file mode 100644 index 0000000..5bac8aa --- /dev/null +++ b/libraries/ethercard-master/examples/multipacketSD/multipacketSD.ino @@ -0,0 +1,129 @@ +// works only with tinyfat library +// with SD library packets lost will occurs +// don't know why ! +// tested with arduino mega 1280 and uno +// send 240 Megabyte file without packet loss +// at 100 kbyte/s +// tinyfat read a block of 512 bytes on SD card , +// so the buffer must be 512 + 60 bytes +// on the arduino mega with bigger buffer you can adjust +// if (cur>=512) { // 512 to 1024 with 1100 bytes buffer + +#include +#include +#include +#define TCP_FLAGS_FIN_V 1 //as declared in net.h +#define TCP_FLAGS_ACK_V 16 //as declared in net.h +static byte myip[] = { 192,168,0,66 }; +static byte gwip[] = { 192,168,0,250 }; +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x39 }; +byte Ethernet::buffer[700]; // tcp/ip send and receive buffer +unsigned long cur; +unsigned long pos; +byte res; + +void setup() { + // Initialize serial communication at 115200 baud + Serial.begin(115200); + // Initialize tinyFAT + // You might need to select a lower speed than the default SPISPEED_HIGH + file.setSSpin(4); + res=file.initFAT(0); + if (res==NO_ERROR) Serial.println("SD started"); + ether.begin(sizeof Ethernet::buffer, mymac , SS); //SS = 53 on mega ethernet shield 10 on others + ether.staticSetup(myip, gwip); + Serial.println("ETH started"); +} + +void loop() +{ + wait: + pos = ether.packetLoop(ether.packetReceive());// check if valid tcp data is received + if (pos) { + char* data = (char *) Ethernet::buffer + pos; + cur=0; + if (strncmp("GET / ", data, 6) == 0) {// nothing specified + sendfiles("index.htm"); + goto wait; + } + if (strncmp("GET /", data, 5) == 0) { // serve anything on sd card + int i =0; + char temp[15]=""; // here will be the name of requested file + while (data[i+5]!=32) {temp[i]=data[i+5];i++;}//search the end + sendfiles((char*) temp); + goto wait; + } + not_found(); + + } + +} + +void not_found() { //content not found + cur=0; + streamfile ("404.hea",TCP_FLAGS_FIN_V); + // Serial.println("not found"); +} + +byte streamfile (char* name , byte lastflag) { //send a file to the buffer + if (!file.exists(name)) {return 0;} + res=file.openFile(name, FILEMODE_BINARY); + int car=512; + while (car==512) { + car=file.readBinary(); + for(int i=0;i=512) { + ether.httpServerReply_with_flags(cur,TCP_FLAGS_ACK_V); + cur=0; + } else { + + if (lastflag==TCP_FLAGS_FIN_V) { + ether.httpServerReply_with_flags(cur,TCP_FLAGS_ACK_V+TCP_FLAGS_FIN_V); + } + } +} + file.closeFile(); + return 1; +} + +byte sendfiles(char* name) { // function to find the correct header and send a file + ether.httpServerReplyAck(); + int i =0; + char dtype[13]=""; + while (name[i]!=0) { + i++; + }//search the end + int b=i-1; + while ((name[b]!=46)&&(b>0)) { + b--; + }//search the point + int a=b+1; + while (a + +#define BUF_SIZE 512 + +byte mac[] = { 0x00, 0x04, 0xA3, 0x21, 0xCA, 0x38 }; // Nanode MAC address. + +uint8_t ip[] = { 192, 168, 1, 8 }; // The fallback board address. +uint8_t dns[] = { 192, 168, 1, 20 }; // The DNS server address. +uint8_t gateway[] = { 192, 168, 1, 20 }; // The gateway router address. +uint8_t subnet[] = { 255, 255, 255, 0 }; // The subnet mask. +byte Ethernet::buffer[BUF_SIZE]; +byte fixed; // Address fixed, no DHCP + +void setup(void) +{ + Serial.begin(57600); + delay(2000); + + /* Check that the Ethernet controller exists */ + Serial.println("Initialising the Ethernet controller"); + if (ether.begin(sizeof Ethernet::buffer, mac, 8) == 0) { + Serial.println( "Ethernet controller NOT initialised"); + while (true) + /* MT */ ; + } + + /* Get a DHCP connection */ + Serial.println("Attempting to get an IP address using DHCP"); + fixed = false; + if (ether.dhcpSetup()) { + ether.printIp("Got an IP address using DHCP: ", ether.myip); + } + /* If DHCP fails, start with a hard-coded address */ + else { + ether.staticSetup(ip, gateway, dns); + ether.printIp("DHCP FAILED, using fixed address: ", ether.myip); + fixed = true; + } + + return; +} + +void loop(void) +{ + word rc; + + /* These function calls are required if ICMP packets are to be accepted */ + rc = ether.packetLoop(ether.packetReceive()); + Serial.print("ether.packetLoop() returned "); + Serial.println(rc, DEC); + + // For debugging + delay(5000); + + return; +} diff --git a/libraries/ethercard-master/examples/noipClient/noipClient.ino b/libraries/ethercard-master/examples/noipClient/noipClient.ino new file mode 100644 index 0000000..2c7c495 --- /dev/null +++ b/libraries/ethercard-master/examples/noipClient/noipClient.ino @@ -0,0 +1,279 @@ +// NoIP client sketch for ENC28J60 based Ethernet Shield. +// You need a free account from www.no-ip.com +// +// 1. On NoIP website, create a host of type DNS Host (A) +// 2. Insert your host name in noIP_host[] variable +// 3. Encode "username:password" in base64 using an online tool like +// 4. Paste the encoded string in noIP_auth[] variable +// +// Contributed by Luca Dentella +// http://www.lucadentella.it/2012/04/28/enc28j60-e-arduino-6/ + + +#include + +// Finite-State Machine states +#define STATUS_IDLE 0 +#define STATUS_WAITING_FOR_PUBLIC_IP 1 +#define STATUS_NOIP_NEEDS_UPDATE 2 +#define STATUS_WAITING_FOR_NOIP 3 +#define STATUS_ERROR 99 + +// The sketch will check your public IP every CHECK_IP_INTERVAL ms, +// and wait for REQUEST_TIMEOUT ms for a response. +// It will retry for maximum of MAX_ATTEMPTS attemps. +#define CHECK_IP_INTERVAL 60000 +#define REQUEST_TIMEOUT 10000 +#define MAX_ATTEMPTS 3 + +// MAC Address of Ethernet Shield +static byte mymac[] = {0xDD,0xDD,0xDD,0x00,0x00,0x01}; + +// Insert your hostname and authentication string +const char noIP_host[] PROGMEM = "myhost.no-ip.info"; +const char noIP_auth[] PROGMEM = "XXXXXXXXXX"; + +// Don't change these ones... +const char getIP_web[] PROGMEM = "www.lucadentella.it"; +const char noIP_web[] PROGMEM = "dynupdate.no-ip.com"; + +// Some global variables +byte Ethernet::buffer[700]; +byte getIP_address[IP_LEN]; +byte noIP_address[IP_LEN]; +byte actual_status; +static byte session_id; +static uint32_t check_ip_timer; +static uint32_t request_timer; +int attempt; +Stash stash; + +void setup () { + + Serial.begin(57600); + Serial.println(F("NoIP Client Demo")); + Serial.println(); + + if (!ether.begin(sizeof Ethernet::buffer, mymac, SS)) + Serial.println(F( "Failed to access Ethernet controller")); + else + Serial.println(F("Ethernet controller initialized")); + Serial.println(); + + if (!ether.dhcpSetup()) + Serial.println(F("Failed to get configuration from DHCP")); + else + Serial.println(F("DHCP configuration done")); + + ether.printIp("IP Address:\t", ether.myip); + ether.printIp("Netmask:\t", ether.netmask); + ether.printIp("Gateway:\t", ether.gwip); + Serial.println(); + + actual_status = STATUS_IDLE; + attempt = 0; + + // Resolve IP for getIP_web and noIP_web + // and store them into global variables + if (!ether.dnsLookup(getIP_web)) { + Serial.print(F("Unable to resolve IP for ")); + SerialPrint_P(getIP_web); + actual_status = STATUS_ERROR; + } else { + ether.copyIp(getIP_address, ether.hisip); + SerialPrint_P(getIP_web); + ether.printIp(" resolved to:\t", ether.hisip); + } + if (!ether.dnsLookup(noIP_web)) { + Serial.print(F("Unable to resolve IP for ")); + SerialPrint_P(noIP_web); + actual_status = STATUS_ERROR; + } else { + ether.copyIp(noIP_address, ether.hisip); + SerialPrint_P(noIP_web); + ether.printIp(" resolved to:\t", ether.hisip); + } + + Serial.println(); +} + + +void loop() { + + ether.packetLoop(ether.packetReceive()); + + // FSM + switch(actual_status) { + + case STATUS_IDLE: + checkPublicIP(); + break; + case STATUS_WAITING_FOR_PUBLIC_IP: + checkPublicIPResponse(); + break; + case STATUS_NOIP_NEEDS_UPDATE: + updateNoIP(); + break; + case STATUS_WAITING_FOR_NOIP: + checkNoIPResponse(); + break; + } +} + +void checkPublicIP() { + + if(millis() > check_ip_timer) { + + Serial.print(F("Checking public IP... ")); + + // Create a request for GetIP service, + // set destination IP and send request saving session_id + Stash::prepare(PSTR("GET /demo/getip.php HTTP/1.1" "\r\n" "Host: $F" "\r\n" "\r\n"), getIP_web); + ether.copyIp(ether.hisip, getIP_address); + session_id = ether.tcpSend(); + + // Change FSM state, prepare for timeout and increment attempts counter + actual_status = STATUS_WAITING_FOR_PUBLIC_IP; + request_timer = millis() + REQUEST_TIMEOUT; + attempt++; + } +} + +void checkPublicIPResponse() { + + String actualIp, dnsIp; + + const char* reply = ether.tcpReply(session_id); + + // We got a valid response + if(reply != 0) { + + // Parse response for public IP + for(int i = 0; i < strlen(reply) - 189; i++) actualIp = actualIp + reply[187 + i]; + Serial.println(actualIp); + + // If we can't resolve actual IP for our hostname on NoIP, + // return to IDLE state and wait for the next interval + if(!ether.dnsLookup(noIP_host)) { + Serial.print(F("Unable to resolve actual IP for ")); + SerialPrint_P(noIP_host); + Serial.println(); + actual_status = STATUS_IDLE; + attempt = 0; + check_ip_timer = millis() + CHECK_IP_INTERVAL; + + // If we can resolve the IP for our hostname, save it in xxx.xxx.xxx.xxx form + // and compare it with our public IP + } else { + for(int i = 0; i < 4; i++) { + dnsIp = dnsIp + String(ether.hisip[i]); + if(i < 3) dnsIp = dnsIp + "."; + } + SerialPrint_P(noIP_host); + Serial.print(F(" resolved to ")); + Serial.println(dnsIp); + + // If they are the same, we can sit down and wait for the next interval + if(actualIp.compareTo(dnsIp) == 0) { + Serial.println(F("No update needed :)")); + actual_status = STATUS_IDLE; + attempt = 0; + check_ip_timer = millis() + CHECK_IP_INTERVAL; + + // Different? We'd better to update NoIP! + } else { + Serial.println(F("Update needed :(")); + actual_status = STATUS_NOIP_NEEDS_UPDATE; + attempt = 0; + } + } + + // No valid response? Check for timeout + // If we've already sent a max number of requests, return to IDLE state + // and wait for the next interval + } else { + if(millis() > request_timer) { + Serial.println(F(" no response :(")); + actual_status = STATUS_IDLE; + if(attempt == MAX_ATTEMPTS) { + Serial.println(F("Max number of attempts reached")); + attempt = 0; + check_ip_timer = millis() + CHECK_IP_INTERVAL; + } + } + } +} + +void updateNoIP() { + + Serial.print(F("Updating NoIP...")); + + // Create a request for updating NoIP using NoIP API, + // set destination IP and send request saving session_id + Stash::prepare(PSTR("GET /nic/update?hostname=$F HTTP/1.0" "\r\n" + "Host: $F" "\r\n" + "Authorization: Basic $F" "\r\n" + "User-Agent: NoIP_Client" "\r\n" "\r\n"), + noIP_host, noIP_web, noIP_auth); + ether.copyIp(ether.hisip, noIP_address); + session_id = ether.tcpSend(); + + // Wait for response or timeout... + actual_status = STATUS_WAITING_FOR_NOIP; + request_timer = millis() + REQUEST_TIMEOUT; + attempt++; +} + +void checkNoIPResponse() { + + const char* reply = ether.tcpReply(session_id); + boolean done; + + // We got a valid response... + if(reply != 0) { + + // Parse NoIP response looking for status/error codes... + if(strstr(reply, "good") != 0) { + Serial.println(F(" done!")); + done = true; + } + else if(strstr(reply, "nochg") != 0) { + Serial.println(F(" no change required!")); + done = true; + } + else if(strstr(reply, "nohost") != 0) Serial.println(F(" host not found :(")); + else if(strstr(reply, "badauth") != 0) Serial.println(F(" invalid username or password :(")); + else if(strstr(reply, "badagent") != 0) Serial.println(F(" agent banned :(")); + else if(strstr(reply, "!donator") != 0) Serial.println(F(" feature not available for specified username :(")); + else if(strstr(reply, "abuse") != 0) Serial.println(F(" username blocked due to abuse :(")); + else Serial.println(F(" generic error :(")); + + // Record has been updated? Ok wait for next interval... + if(done) { + actual_status = STATUS_IDLE; + attempt = 0; + check_ip_timer = millis() + CHECK_IP_INTERVAL; + } + + // No valid response? Check for timeout + // If we've already sent a max number of requests, return to IDLE state + // and wait for the next interval + } else { + + if(millis() > request_timer) { + Serial.println(F("No response from NoIP")); + if(attempt == MAX_ATTEMPTS) { + Serial.println(F("Max number of attempts reached")); + actual_status = STATUS_IDLE; + attempt = 0; + check_ip_timer = millis() + CHECK_IP_INTERVAL; + } + else + actual_status = STATUS_NOIP_NEEDS_UPDATE; + } + } +} + +void SerialPrint_P(const char* str PROGMEM) { + for (uint8_t c; (c = pgm_read_byte(str)); str++) Serial.write(c); +} diff --git a/libraries/ethercard-master/examples/notifyMyAndroid/notifyMyAndroid.ino b/libraries/ethercard-master/examples/notifyMyAndroid/notifyMyAndroid.ino new file mode 100644 index 0000000..6ab529d --- /dev/null +++ b/libraries/ethercard-master/examples/notifyMyAndroid/notifyMyAndroid.ino @@ -0,0 +1,83 @@ +// This demo shows how to send a notification to the Notify My Android service +// +// Warning: Due to the limitations of the Arduino, this demo uses insecure +// HTTP to interact with the nma api (not HTTPS). The API key WILL be sent +// accross the wire in plain text. +// +// 2015-04-10 http://opensource.org/licenses/mit-license.php + +#include + +const char apihost[] PROGMEM = "www.notifymyandroid.com"; + +static byte mymac[] = { 0x74, 0x69, 0x69, 0x2D, 0x30, 0x31 }; + +byte Ethernet::buffer[900]; +Stash stash; +static byte session; + +static void notifyMyAndroid () { + byte sd = stash.create(); + + stash.print("apikey="); + stash.print("ADD YOUR API KEY HERE"); + + stash.print("&application="); + stash.print("arduino"); + + stash.print("&event="); + stash.print("Ethercard Notify My Android Example"); + + stash.print("&description="); + stash.print("Test message from an Arduino!"); + + stash.print("&priority="); + stash.print("0"); + + stash.save(); + int stash_size = stash.size(); + + // Compose the http POST request, taking the headers below and appending + // previously created stash in the sd holder. + Stash::prepare(PSTR("POST /publicapi/notify HTTP/1.1" "\r\n" + "Host: $F" "\r\n" + "Content-Length: $D" "\r\n" + "Content-Type: application/x-www-form-urlencoded" "\r\n" + "\r\n" + "$H"), + apihost, stash_size, sd); + + // send the packet - this also releases all stash buffers once done + // Save the session ID so we can watch for it in the main loop. + session = ether.tcpSend(); +} + +void setup () { + Serial.begin(57600); + Serial.println("\nStarting Notify My Android Example"); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println(F("Failed to access Ethernet controller")); + if (!ether.dhcpSetup()) + Serial.println(F("DHCP failed")); + + ether.printIp("IP: ", ether.myip); + ether.printIp("GW: ", ether.gwip); + ether.printIp("DNS: ", ether.dnsip); + + if (!ether.dnsLookup(apihost)) + Serial.println(F("DNS lookup failed for the apihost")); + ether.printIp("SRV: ", ether.hisip); + + notifyMyAndroid(); +} + +void loop () { + ether.packetLoop(ether.packetReceive()); + + const char* reply = ether.tcpReply(session); + if (reply != 0) { + Serial.println("Got a response!"); + Serial.println(reply); + } +} diff --git a/libraries/ethercard-master/examples/persistence/persistence.ino b/libraries/ethercard-master/examples/persistence/persistence.ino new file mode 100644 index 0000000..89a73bd --- /dev/null +++ b/libraries/ethercard-master/examples/persistence/persistence.ino @@ -0,0 +1,74 @@ +// Demo for using persistence flag and readPacketSlice() +// http://opensource.org/licenses/mit-license.php + +#include + +// ethernet interface mac address, must be unique on the LAN +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; + +// the buffersize must be relatively large for DHCP to work; when +// using static setup a buffer size of 100 is sufficient; +#define BUFFERSIZE 350 +byte Ethernet::buffer[BUFFERSIZE]; + +const char website[] PROGMEM = "textfiles.com"; + +uint32_t nextSeq; +// called when the client request is complete +static void my_callback (byte status, word off, word len) { + + if (strncmp_P((char*) Ethernet::buffer+off,PSTR("HTTP"),4) == 0) { + Serial.println(">>>"); + // first reply packet + nextSeq = ether.getSequenceNumber(); + } + + if (nextSeq != ether.getSequenceNumber()) { Serial.print(F("")); return; } + + uint16_t payloadlength = ether.getTcpPayloadLength(); + int16_t chunk_size = BUFFERSIZE-off-1; + int16_t char_written = 0; + int16_t char_in_buf = chunk_size < payloadlength ? chunk_size : payloadlength; + + while (char_written < payloadlength) { + Serial.write((char*) Ethernet::buffer+off,char_in_buf); + char_written += char_in_buf; + + char_in_buf = ether.readPacketSlice((char*) Ethernet::buffer+off,chunk_size,off+char_written); + } + + nextSeq += ether.getTcpPayloadLength(); +} + +void setup () { + Serial.begin(57600); + Serial.println(F("\n[Persistence+readPacketSlice]")); + + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println(F("Failed to access Ethernet controller")); + if (!ether.dhcpSetup()) + Serial.println(F("DHCP failed")); + + ether.printIp("IP: ", ether.myip); + ether.printIp("GW: ", ether.gwip); + ether.printIp("DNS: ", ether.dnsip); + + if (!ether.dnsLookup(website)) + Serial.println("DNS failed"); + + ether.printIp("SRV: ", ether.hisip); + ether.persistTcpConnection(true); +} + +void loop () { + ether.packetLoop(ether.packetReceive()); + + static uint32_t timer = 0; + if (millis() > timer) { + timer = millis() + 7000; + Serial.println(); + Serial.print("<<< REQ "); + ether.browseUrl(PSTR("/stories/"), "cmoutmou.txt", website, my_callback); + } +} diff --git a/libraries/ethercard-master/examples/pings/pings.ino b/libraries/ethercard-master/examples/pings/pings.ino new file mode 100644 index 0000000..ffb7c60 --- /dev/null +++ b/libraries/ethercard-master/examples/pings/pings.ino @@ -0,0 +1,62 @@ +// Ping a remote server, also uses DHCP and DNS. +// 2011-06-12 http://opensource.org/licenses/mit-license.php + +#include + +// ethernet interface mac address, must be unique on the LAN +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; + +byte Ethernet::buffer[700]; +static uint32_t timer; + +// called when a ping comes in (replies to it are automatic) +static void gotPinged (byte* ptr) { + ether.printIp(">>> ping from: ", ptr); +} + +void setup () { + Serial.begin(57600); + Serial.println("\n[pings]"); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println(F("Failed to access Ethernet controller")); + if (!ether.dhcpSetup()) + Serial.println(F("DHCP failed")); + + ether.printIp("IP: ", ether.myip); + ether.printIp("GW: ", ether.gwip); + +#if 1 + // use DNS to locate the IP address we want to ping + if (!ether.dnsLookup(PSTR("www.google.com"))) + Serial.println("DNS failed"); +#else + ether.parseIp(ether.hisip, "74.125.77.99"); +#endif + ether.printIp("SRV: ", ether.hisip); + + // call this to report others pinging us + ether.registerPingCallback(gotPinged); + + timer = -9999999; // start timing out right away + Serial.println(); +} + +void loop () { + word len = ether.packetReceive(); // go receive new packets + word pos = ether.packetLoop(len); // respond to incoming pings + + // report whenever a reply to our outgoing ping comes back + if (len > 0 && ether.packetLoopIcmpCheckReply(ether.hisip)) { + Serial.print(" "); + Serial.print((micros() - timer) * 0.001, 3); + Serial.println(" ms"); + } + + // ping a remote server once every few seconds + if (micros() - timer >= 5000000) { + ether.printIp("Pinging: ", ether.hisip); + timer = micros(); + ether.clientIcmpRequest(ether.hisip); + } +} diff --git a/libraries/ethercard-master/examples/rbbb_server/rbbb_server.ino b/libraries/ethercard-master/examples/rbbb_server/rbbb_server.ino new file mode 100644 index 0000000..cacd69a --- /dev/null +++ b/libraries/ethercard-master/examples/rbbb_server/rbbb_server.ino @@ -0,0 +1,43 @@ +// This is a demo of the RBBB running as webserver with the Ether Card +// 2010-05-28 http://opensource.org/licenses/mit-license.php + +#include + +// ethernet interface mac address, must be unique on the LAN +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; +static byte myip[] = { 192,168,1,203 }; + +byte Ethernet::buffer[500]; +BufferFiller bfill; + +void setup () { + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println(F("Failed to access Ethernet controller")); + ether.staticSetup(myip); +} + +static word homePage() { + long t = millis() / 1000; + word h = t / 3600; + byte m = (t / 60) % 60; + byte s = t % 60; + bfill = ether.tcpOffset(); + bfill.emit_p(PSTR( + "HTTP/1.0 200 OK\r\n" + "Content-Type: text/html\r\n" + "Pragma: no-cache\r\n" + "\r\n" + "" + "RBBB server" + "

$D$D:$D$D:$D$D

"), + h/10, h%10, m/10, m%10, s/10, s%10); + return bfill.position(); +} + +void loop () { + word len = ether.packetReceive(); + word pos = ether.packetLoop(len); + + if (pos) // check if valid tcp data is received + ether.httpServerReply(homePage()); // send web page data +} diff --git a/libraries/ethercard-master/examples/stashTest/stashTest.ino b/libraries/ethercard-master/examples/stashTest/stashTest.ino new file mode 100644 index 0000000..5dd31da --- /dev/null +++ b/libraries/ethercard-master/examples/stashTest/stashTest.ino @@ -0,0 +1,118 @@ +// Test the offloaded RAM stash mechanism. +// 2011-07-10 http://opensource.org/licenses/mit-license.php + +#include +#include + +// ethernet interface mac address, must be unique on the LAN +byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; + +byte Ethernet::buffer[700]; + +void dumpBlock (const char* msg, byte idx) { + Serial.print(msg); + Serial.print(" ["); + Serial.print(idx, DEC); + Serial.print("] @ "); + Serial.print(Stash::bufs[idx].bnum, DEC); + Serial.print(" free "); + Serial.print(Stash::freeCount(), DEC); + for (byte i = 0; i < 64; ++i) { + if (i % 16 == 0) + Serial.println(); + Serial.print(' '); + Serial.print(Stash::bufs[idx].bytes[i], DEC); + } + Serial.println(); +} + +void dumpStash (const char* msg, void* ptr) { + Stash& buf = *(Stash*) ptr; + Serial.print(msg); + Serial.print(" c"); + Serial.print(buf.count, DEC); + Serial.print(" f"); + Serial.print(buf.first, DEC); + Serial.print(" l"); + Serial.print(buf.last, DEC); + Serial.print(" u"); + Serial.print(buf.curr, DEC); + Serial.print(" o"); + Serial.print(buf.offs, DEC); + Serial.print(" #"); + Serial.println(buf.size()); +} + +void setup () { + Serial.begin(57600); + Serial.println("\n[stashTest]"); + ether.begin(sizeof Ethernet::buffer, mymac); + +#if 1 + Stash buf; + dumpStash("> AAA", &buf); + byte fd = buf.create(); + Serial.print("fd "); + Serial.println(fd, DEC); + dumpStash("> BBB", &buf); + dumpBlock("EMPTY", 0); + for (char c = 'a'; c <= 'z'; ++c) + buf.put(c); + for (char c = 'A'; c <= 'Z'; ++c) + buf.put(c); + dumpBlock("LETTERS", 0); + dumpStash("> CCC", &buf); + for (char c = '0'; c <= '9'; ++c) + buf.put(c); + dumpBlock("DIGITS", 0); + dumpStash("> DDD", &buf); + buf.print(" x = "); + buf.println(123.45); + dumpBlock("PRINT", 0); + dumpStash("> EEE", &buf); + buf.load(1, 1); + dumpBlock("FIRST", 1); + buf.save(); + buf.load(1, 1); + dumpBlock("FLUSHED", 1); + dumpStash("> FFF", &buf); + for (;;) { + char c = buf.get(); + if (c == 0) + break; + Serial.print(c); + } + Serial.println(); + dumpStash("> GGG", &buf); +#endif + + Stash buf2; + byte fd2 = buf2.create(); + buf2.print(""); + buf2.save(); + buf2.load(1, fd2); + dumpBlock("SECOND", 1); + dumpStash("> HHH", &buf2); + + Stash::prepare(PSTR("a $S b $F c $D d $H e"), + "123", PSTR("4567"), -12345, fd2); + dumpBlock("BUFFER", 0); + Serial.println(Stash::length()); + for (word i = 0, n = Stash::length(); i < n; ++i) { + char c; + Stash::extract(i, 1, &c); + Serial.print(c); + } + Serial.println(); + Stash::cleanup(); +#if 1 + buf.release(); +#endif + Serial.print("free "); + Serial.println(Stash::freeCount(), DEC); + Serial.println("DONE"); +} + +void loop () { + // ether.packetLoop(ether.packetReceive()); +} diff --git a/libraries/ethercard-master/examples/testDHCP/testDHCP.ino b/libraries/ethercard-master/examples/testDHCP/testDHCP.ino new file mode 100644 index 0000000..e75c275 --- /dev/null +++ b/libraries/ethercard-master/examples/testDHCP/testDHCP.ino @@ -0,0 +1,40 @@ +// Arduino demo sketch for testing the DHCP client code +// +// Original author: Andrew Lindsay +// Major rewrite and API overhaul by jcw, 2011-06-07 +// +// Copyright: GPL V2 +// See http://www.gnu.org/licenses/gpl.html + +#include + +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; + +byte Ethernet::buffer[700]; + +void setup () { + Serial.begin(57600); + Serial.println(F("\n[testDHCP]")); + + Serial.print("MAC: "); + for (byte i = 0; i < 6; ++i) { + Serial.print(mymac[i], HEX); + if (i < 5) + Serial.print(':'); + } + Serial.println(); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println(F("Failed to access Ethernet controller")); + + Serial.println(F("Setting up DHCP")); + if (!ether.dhcpSetup()) + Serial.println(F("DHCP failed")); + + ether.printIp("My IP: ", ether.myip); + ether.printIp("Netmask: ", ether.netmask); + ether.printIp("GW IP: ", ether.gwip); + ether.printIp("DNS IP: ", ether.dnsip); +} + +void loop () {} diff --git a/libraries/ethercard-master/examples/thingspeak/thingspeak.ino b/libraries/ethercard-master/examples/thingspeak/thingspeak.ino new file mode 100644 index 0000000..3a1f37c --- /dev/null +++ b/libraries/ethercard-master/examples/thingspeak/thingspeak.ino @@ -0,0 +1,149 @@ +// Simple demo for feeding some random data to Pachube. +// 2011-07-08 http://opensource.org/licenses/mit-license.php + +// Handle returning code and reset ethernet module if needed +// 2013-10-22 hneiraf@gmail.com + +// Modifing so that it works on my setup for www.thingspeak.com. +// Arduino pro-mini 5V/16MHz, ETH modul on SPI with CS on pin 10. +// Also added a few changes found on various forums. Do not know what the +// res variable is for, tweaked it so it works faster for my application +// 2015-11-09 dani.lomajhenic@gmail.com + +#include + +// change these settings to match your own setup +//#define FEED "000" +#define APIKEY "beef1337beef1337" // put your key here +#define ethCSpin 10 // put your CS/SS pin here. + +// ethernet interface mac address, must be unique on the LAN +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; +const char website[] PROGMEM = "api.thingspeak.com"; +byte Ethernet::buffer[700]; +uint32_t timer; +Stash stash; +byte session; + +//timing variable +int res = 100; // was 0 + + + +void setup () { + Serial.begin(9600); + Serial.println("\n[ThingSpeak example]"); + + //Initialize Ethernet + initialize_ethernet(); +} + + +void loop () { + //if correct answer is not received then re-initialize ethernet module + if (res > 220){ + initialize_ethernet(); + } + + res = res + 1; + + ether.packetLoop(ether.packetReceive()); + + //200 res = 10 seconds (50ms each res) + if (res == 200) { + + + //Generate random info + float demo = random(0,500); + word one = random(0,500); + String msje; + + if (demo < 250){ + msje = "low"; + } + else{ + msje = "high"; + } + + // generate two fake values as payload - by using a separate stash, + // we can determine the size of the generated message ahead of time + // field1=(Field 1 Data)&field2=(Field 2 Data)&field3=(Field 3 Data)&field4=(Field 4 Data)&field5=(Field 5 Data)&field6=(Field 6 Data)&field7=(Field 7 Data)&field8=(Field 8 Data)&lat=(Latitude in Decimal Degrees)&long=(Longitude in Decimal Degrees)&elevation=(Elevation in meters)&status=(140 Character Message) + byte sd = stash.create(); + stash.print("field1="); + stash.print(demo); + //stash.print("&field2="); + //stash.print(one); + //stash.print("&field3="); + //stash.print(msje); + stash.save(); + + //Display data to be sent + Serial.println(demo); + + + // generate the header with payload - note that the stash size is used, + // and that a "stash descriptor" is passed in as argument using "$H" + Stash::prepare(PSTR("POST /update HTTP/1.0" "\r\n" + "Host: $F" "\r\n" + "Connection: close" "\r\n" + "X-THINGSPEAKAPIKEY: $F" "\r\n" + "Content-Type: application/x-www-form-urlencoded" "\r\n" + "Content-Length: $D" "\r\n" + "\r\n" + "$H"), + website, PSTR(APIKEY), stash.size(), sd); + + // send the packet - this also releases all stash buffers once done + session = ether.tcpSend(); + + // added from: http://jeelabs.net/boards/7/topics/2241 + int freeCount = stash.freeCount(); + if (freeCount <= 3) { Stash::initMap(56); } + } + + const char* reply = ether.tcpReply(session); + + if (reply != 0) { + res = 0; + Serial.println(F(" >>>REPLY recieved....")); + Serial.println(reply); + } + delay(300); +} + + + +void initialize_ethernet(void){ + for(;;){ // keep trying until you succeed + //Reinitialize ethernet module + //pinMode(5, OUTPUT); // do notknow what this is for, i ve got something elso on pin5 + //Serial.println("Reseting Ethernet..."); + //digitalWrite(5, LOW); + //delay(1000); + //digitalWrite(5, HIGH); + //delay(500); + + if (ether.begin(sizeof Ethernet::buffer, mymac, ethCSpin) == 0){ + Serial.println( "Failed to access Ethernet controller"); + continue; + } + + if (!ether.dhcpSetup()){ + Serial.println("DHCP failed"); + continue; + } + + ether.printIp("IP: ", ether.myip); + ether.printIp("GW: ", ether.gwip); + ether.printIp("DNS: ", ether.dnsip); + + if (!ether.dnsLookup(website)) + Serial.println("DNS failed"); + + ether.printIp("SRV: ", ether.hisip); + + //reset init value + res = 180; + break; + } +} diff --git a/libraries/ethercard-master/examples/twitter/twitter.ino b/libraries/ethercard-master/examples/twitter/twitter.ino new file mode 100644 index 0000000..fda0676 --- /dev/null +++ b/libraries/ethercard-master/examples/twitter/twitter.ino @@ -0,0 +1,86 @@ +// Twitter client sketch for ENC28J60 based Ethernet Shield. Uses +// arduino-tweet.appspot.com as a OAuth gateway. +// Step by step instructions: +// +// 1. Get a oauth token: +// http://arduino-tweet.appspot.com/oauth/twitter/login +// 2. Put the token value in the TOKEN define below +// 3. Run the sketch! +// +// WARNING: Don't send more than 1 tweet per minute! +// WARNING: This example uses insecure HTTP and not HTTPS. +// The API key will be sent over the wire in plain text. +// NOTE: Twitter rejects tweets with identical content as dupes (returns 403) + +#include + +// OAUTH key from http://arduino-tweet.appspot.com/ +#define TOKEN "Insert-your-token-here" + +// ethernet interface mac address, must be unique on the LAN +byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; + +const char website[] PROGMEM = "arduino-tweet.appspot.com"; + +static byte session; + +byte Ethernet::buffer[700]; +Stash stash; + +static void sendToTwitter () { + Serial.println("Sending tweet..."); + byte sd = stash.create(); + + const char tweet[] = "@solarkennedy the test Twitter sketch works!"; + stash.print("token="); + stash.print(TOKEN); + stash.print("&status="); + stash.println(tweet); + stash.save(); + int stash_size = stash.size(); + + // Compose the http POST request, taking the headers below and appending + // previously created stash in the sd holder. + Stash::prepare(PSTR("POST http://$F/update HTTP/1.0" "\r\n" + "Host: $F" "\r\n" + "Content-Length: $D" "\r\n" + "\r\n" + "$H"), + website, website, stash_size, sd); + + // send the packet - this also releases all stash buffers once done + // Save the session ID so we can watch for it in the main loop. + session = ether.tcpSend(); +} + +void setup () { + Serial.begin(57600); + Serial.println("\n[Twitter Client]"); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println(F("Failed to access Ethernet controller")); + if (!ether.dhcpSetup()) + Serial.println(F("DHCP failed")); + + ether.printIp("IP: ", ether.myip); + ether.printIp("GW: ", ether.gwip); + ether.printIp("DNS: ", ether.dnsip); + + if (!ether.dnsLookup(website)) + Serial.println(F("DNS failed")); + + ether.printIp("SRV: ", ether.hisip); + + sendToTwitter(); +} + +void loop () { + ether.packetLoop(ether.packetReceive()); + + const char* reply = ether.tcpReply(session); + if (reply != 0) { + Serial.println("Got a response!"); + Serial.println(reply); + } +} + diff --git a/libraries/ethercard-master/examples/udpClientSendOnly/Java_ClientAndServer/UDPClient.java b/libraries/ethercard-master/examples/udpClientSendOnly/Java_ClientAndServer/UDPClient.java new file mode 100644 index 0000000..0439c3e --- /dev/null +++ b/libraries/ethercard-master/examples/udpClientSendOnly/Java_ClientAndServer/UDPClient.java @@ -0,0 +1,29 @@ +import java.io.IOException; +import java.net.DatagramPacket; +import java.net.DatagramSocket; +import java.net.InetAddress; +import java.net.UnknownHostException; + +public class UDPClient { + + public static void main(String[] args) throws UnknownHostException { + DatagramSocket s; + byte[] sendBuffer = new byte[1024]; + DatagramPacket sendPacket; + final InetAddress ADDRESS = InetAddress.getByName("localhost"); + final int PORT = 1234; + try { + s = new DatagramSocket(); + System.out.println("Odesilam data na server..."); + + sendBuffer = "abc123".getBytes(); + sendPacket = new DatagramPacket(sendBuffer, sendBuffer.length, + ADDRESS, PORT); + s.send(sendPacket); + + } catch (IOException e) { + e.printStackTrace(); + } + } + +} \ No newline at end of file diff --git a/libraries/ethercard-master/examples/udpClientSendOnly/Java_ClientAndServer/UDPserver.java b/libraries/ethercard-master/examples/udpClientSendOnly/Java_ClientAndServer/UDPserver.java new file mode 100644 index 0000000..b7cda60 --- /dev/null +++ b/libraries/ethercard-master/examples/udpClientSendOnly/Java_ClientAndServer/UDPserver.java @@ -0,0 +1,39 @@ +import java.io.IOException; +import java.net.DatagramPacket; +import java.net.DatagramSocket; +import java.text.SimpleDateFormat; +import java.util.Date; + +public class UDPserver { + public static void main(String[] args) { + UDPserver server = new UDPserver(1234); + server.start(); + } + private int port; + private DatagramSocket s; + + SimpleDateFormat sdf = new SimpleDateFormat("yyyy-MM-dd HH:mm:ss"); + + public UDPserver(int port) { + this.port = port; + } + + public void start() { + System.out.println("SERVER: Waiting for incomming connections..."); + System.out.println("DATE TIME IP:PORT received_data"); + try { + s = new DatagramSocket(this.port); + while (true) { + byte[] data = new byte[1412]; + DatagramPacket p = new DatagramPacket(data, + data.length); + s.receive(p); + System.out.print(sdf.format(new Date()).toString() + " "); + System.out.print(p.getSocketAddress() + " "); + System.out.println(new String(p.getData())); + } + } catch (IOException e) { + e.printStackTrace(); + } + } +} \ No newline at end of file diff --git a/libraries/ethercard-master/examples/udpClientSendOnly/udpClientSendOnly.ino b/libraries/ethercard-master/examples/udpClientSendOnly/udpClientSendOnly.ino new file mode 100644 index 0000000..d3ec87b --- /dev/null +++ b/libraries/ethercard-master/examples/udpClientSendOnly/udpClientSendOnly.ino @@ -0,0 +1,38 @@ +#include + +static byte mymac[] = { 0x1A,0x2B,0x3C,0x4D,0x5E,0x6F }; +byte Ethernet::buffer[700]; +static uint32_t timer; + +const char website[] PROGMEM = "server.example.net"; +const int dstPort PROGMEM = 1234; + +const int srcPort PROGMEM = 4321; + +void setup () { + Serial.begin(9600); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println( "Failed to access Ethernet controller"); + if (!ether.dhcpSetup()) + Serial.println("DHCP failed"); + + ether.printIp("IP: ", ether.myip); + ether.printIp("GW: ", ether.gwip); + ether.printIp("DNS: ", ether.dnsip); + + if (!ether.dnsLookup(website)) + Serial.println("DNS failed"); + + ether.printIp("SRV: ", ether.hisip); +} + +char textToSend[] = "test 123"; + +void loop () { + if (millis() > timer) { + timer = millis() + 5000; + //static void sendUdp (char *data,uint8_t len,uint16_t sport, uint8_t *dip, uint16_t dport); + ether.sendUdp(textToSend, sizeof(textToSend), srcPort, ether.hisip, dstPort ); + } +} diff --git a/libraries/ethercard-master/examples/udpListener/udpListener.ino b/libraries/ethercard-master/examples/udpListener/udpListener.ino new file mode 100644 index 0000000..3809df0 --- /dev/null +++ b/libraries/ethercard-master/examples/udpListener/udpListener.ino @@ -0,0 +1,102 @@ +// Demonstrates usage of the new udpServer feature. +//You can register the same function to multiple ports, and multiple functions to the same port. +// +// 2013-4-7 Brian Lee + +#include +#include + +#define STATIC 0 // set to 1 to disable DHCP (adjust myip/gwip values below) + +#if STATIC +// ethernet interface ip address +static byte myip[] = { 192,168,0,200 }; +// gateway ip address +static byte gwip[] = { 192,168,0,1 }; +#endif + +// ethernet mac address - must be unique on your network +static byte mymac[] = { 0x70,0x69,0x69,0x2D,0x30,0x31 }; + +byte Ethernet::buffer[500]; // tcp/ip send and receive buffer + +//callback that prints received packets to the serial port +void udpSerialPrint(uint16_t dest_port, uint8_t src_ip[IP_LEN], uint16_t src_port, const char *data, uint16_t len){ + IPAddress src(src_ip[0],src_ip[1],src_ip[2],src_ip[3]); + + Serial.print("dest_port: "); + Serial.println(dest_port); + Serial.print("src_port: "); + Serial.println(src_port); + + + Serial.print("src_port: "); + ether.printIp(src_ip); + Serial.println("data: "); + Serial.println(data); +} + +void setup(){ + Serial.begin(57600); + Serial.println(F("\n[backSoon]")); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println(F("Failed to access Ethernet controller")); +#if STATIC + ether.staticSetup(myip, gwip); +#else + if (!ether.dhcpSetup()) + Serial.println(F("DHCP failed")); +#endif + + ether.printIp("IP: ", ether.myip); + ether.printIp("GW: ", ether.gwip); + ether.printIp("DNS: ", ether.dnsip); + + //register udpSerialPrint() to port 1337 + ether.udpServerListenOnPort(&udpSerialPrint, 1337); + + //register udpSerialPrint() to port 42. + ether.udpServerListenOnPort(&udpSerialPrint, 42); +} + +void loop(){ + //this must be called for ethercard functions to work. + ether.packetLoop(ether.packetReceive()); +} + + +/* +//Processing sketch to send test UDP packets. + +import hypermedia.net.*; + + UDP udp; // define the UDP object + + + void setup() { + udp = new UDP( this, 6000 ); // create a new datagram connection on port 6000 + //udp.log( true ); // <-- printout the connection activity + udp.listen( true ); // and wait for incoming message + } + + void draw() + { + } + + void keyPressed() { + String ip = "192.168.0.200"; // the remote IP address + int port = 1337; // the destination port + + udp.send("Greetings via UDP!", ip, port ); // the message to send + + } + + void receive( byte[] data ) { // <-- default handler + //void receive( byte[] data, String ip, int port ) { // <-- extended handler + + for(int i=0; i < data.length; i++) + print(char(data[i])); + println(); + } +*/ diff --git a/libraries/ethercard-master/examples/webClient/webClient.ino b/libraries/ethercard-master/examples/webClient/webClient.ino new file mode 100644 index 0000000..a5c6165 --- /dev/null +++ b/libraries/ethercard-master/examples/webClient/webClient.ino @@ -0,0 +1,62 @@ +// Demo using DHCP and DNS to perform a web client request. +// 2011-06-08 http://opensource.org/licenses/mit-license.php + +#include + +// ethernet interface mac address, must be unique on the LAN +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; + +byte Ethernet::buffer[700]; +static uint32_t timer; + +const char website[] PROGMEM = "www.google.com"; + +// called when the client request is complete +static void my_callback (byte status, word off, word len) { + Serial.println(">>>"); + Ethernet::buffer[off+300] = 0; + Serial.print((const char*) Ethernet::buffer + off); + Serial.println("..."); +} + +void setup () { + Serial.begin(57600); + Serial.println(F("\n[webClient]")); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0) + Serial.println(F("Failed to access Ethernet controller")); + if (!ether.dhcpSetup()) + Serial.println(F("DHCP failed")); + + ether.printIp("IP: ", ether.myip); + ether.printIp("GW: ", ether.gwip); + ether.printIp("DNS: ", ether.dnsip); + +#if 1 + // use DNS to resolve the website's IP address + if (!ether.dnsLookup(website)) + Serial.println("DNS failed"); +#elif 2 + // if website is a string containing an IP address instead of a domain name, + // then use it directly. Note: the string can not be in PROGMEM. + char websiteIP[] = "192.168.1.1"; + ether.parseIp(ether.hisip, websiteIP); +#else + // or provide a numeric IP address instead of a string + byte hisip[] = { 192,168,1,1 }; + ether.copyIp(ether.hisip, hisip); +#endif + + ether.printIp("SRV: ", ether.hisip); +} + +void loop () { + ether.packetLoop(ether.packetReceive()); + + if (millis() > timer) { + timer = millis() + 5000; + Serial.println(); + Serial.print("<<< REQ "); + ether.browseUrl(PSTR("/foo/"), "bar", website, my_callback); + } +} diff --git a/libraries/ethercard-master/examples/xively/xively.ino b/libraries/ethercard-master/examples/xively/xively.ino new file mode 100644 index 0000000..9e9a87b --- /dev/null +++ b/libraries/ethercard-master/examples/xively/xively.ino @@ -0,0 +1,139 @@ +// Simple demo for feeding some random data to Pachube. +// 2011-07-08 http://opensource.org/licenses/mit-license.php + +// Handle returning code and reset ethernet module if needed +// 2013-10-22 hneiraf@gmail.com + +#include + +// change these settings to match your own setup +#define FEED "000" +#define APIKEY "xxx" + +// ethernet interface mac address, must be unique on the LAN +static byte mymac[] = { 0x74,0x69,0x69,0x2D,0x30,0x31 }; + +const char website[] PROGMEM = "api.xively.com"; + +byte Ethernet::buffer[350]; +uint32_t timer; +Stash stash; +byte session; + +//timing variable +int res = 0; + + + +void setup () { + Serial.begin(57600); + Serial.println("\n[Xively example]"); + + //Initialize Ethernet + initialize_ethernet(); +} + + +void loop () { + + //if correct answer is not received then re-initialize ethernet module + if (res > 220){ + initialize_ethernet(); + } + + res = res + 1; + + ether.packetLoop(ether.packetReceive()); + + //200 res = 10 seconds (50ms each res) + if (res == 200) { + + + //Generate random info + float demo = random(0,500); + word one = random(0,500); + String msje; + + if (demo < 250){ + msje = "low"; + } + else{ + msje = "high"; + } + + + // generate two fake values as payload - by using a separate stash, + // we can determine the size of the generated message ahead of time + byte sd = stash.create(); + stash.print("demo,"); + stash.println(demo); + stash.print("one,"); + stash.println(one); + stash.print("mensaje,"); + stash.println(msje); + stash.save(); + + //Display data to be sent + Serial.println(demo); + Serial.println(one); + + + // generate the header with payload - note that the stash size is used, + // and that a "stash descriptor" is passed in as argument using "$H" + Stash::prepare(PSTR("PUT http://$F/v2/feeds/$F.csv HTTP/1.0" "\r\n" + "Host: $F" "\r\n" + "X-PachubeApiKey: $F" "\r\n" + "Content-Length: $D" "\r\n" + "\r\n" + "$H"), + website, PSTR(FEED), website, PSTR(APIKEY), stash.size(), sd); + + // send the packet - this also releases all stash buffers once done + session = ether.tcpSend(); + } + + const char* reply = ether.tcpReply(session); + + if (reply != 0) { + res = 0; + Serial.println(reply); + } + delay(50); +} + + + +void initialize_ethernet(void){ + for(;;){ // keep trying until you succeed + //Reinitialize ethernet module + pinMode(5, OUTPUT); + Serial.println("Reseting Ethernet..."); + digitalWrite(5, LOW); + delay(1000); + digitalWrite(5, HIGH); + delay(500); + + if (ether.begin(sizeof Ethernet::buffer, mymac) == 0){ + Serial.println( "Failed to access Ethernet controller"); + continue; + } + + if (!ether.dhcpSetup()){ + Serial.println("DHCP failed"); + continue; + } + + ether.printIp("IP: ", ether.myip); + ether.printIp("GW: ", ether.gwip); + ether.printIp("DNS: ", ether.dnsip); + + if (!ether.dnsLookup(website)) + Serial.println("DNS failed"); + + ether.printIp("SRV: ", ether.hisip); + + //reset init value + res = 0; + break; + } +} diff --git a/libraries/ethercard-master/library.json b/libraries/ethercard-master/library.json new file mode 100644 index 0000000..15b8222 --- /dev/null +++ b/libraries/ethercard-master/library.json @@ -0,0 +1,32 @@ +{ + "name": "EtherCard", + "keywords": "http, web, server, client, ethernet", + "description": "Driver for the ENC28J60 chip", + "authors": + [ + { + "name": "Jean-Claude Wippler", + "email": "jc@wippler.nl", + "url": "http://jeelabs.org/", + "maintainer": true + }, + { + "name": "Pascal Stang" + }, + { + "name": "Guido Socher" + } + ], + "include": [ + "examples", + "*.cpp", + "*.h" + ], + "repository": + { + "type": "git", + "url": "https://github.com/jcw/ethercard.git" + }, + "frameworks": "arduino", + "platforms": "atmelavr" +} diff --git a/libraries/ethercard-master/net.h b/libraries/ethercard-master/net.h new file mode 100644 index 0000000..0bbe89a --- /dev/null +++ b/libraries/ethercard-master/net.h @@ -0,0 +1,130 @@ +// Based on the net.h file from the AVRlib library by Pascal Stang. +// Author: Guido Socher +// Copyright: GPL V2 +// +// For AVRlib See http://www.procyonengineering.com/ +// Used with explicit permission of Pascal Stang. +// +// 2010-05-20 + +// notation: _P = position of a field +// _V = value of a field + +#ifndef NET_H +#define NET_H + +// ******* SERVICE PORTS ******* +#define HTTP_PORT 80 +#define DNS_PORT 53 +#define NTP_PORT 123 + +// ******* ETH ******* +#define ETH_HEADER_LEN 14 +#define ETH_LEN 6 +// values of certain bytes: +#define ETHTYPE_ARP_H_V 0x08 +#define ETHTYPE_ARP_L_V 0x06 +#define ETHTYPE_IP_H_V 0x08 +#define ETHTYPE_IP_L_V 0x00 +// byte positions in the ethernet frame: +// +// Ethernet type field (2bytes): +#define ETH_TYPE_H_P 12 +#define ETH_TYPE_L_P 13 +// +#define ETH_DST_MAC 0 +#define ETH_SRC_MAC 6 + + +// ******* ARP ******* +#define ETH_ARP_OPCODE_REPLY_H_V 0x0 +#define ETH_ARP_OPCODE_REPLY_L_V 0x02 +#define ETH_ARP_OPCODE_REQ_H_V 0x0 +#define ETH_ARP_OPCODE_REQ_L_V 0x01 +// start of arp header: +#define ETH_ARP_P 0xe +// +#define ETHTYPE_ARP_L_V 0x06 +// arp.dst.ip +#define ETH_ARP_DST_IP_P 0x26 +// arp.opcode +#define ETH_ARP_OPCODE_H_P 0x14 +#define ETH_ARP_OPCODE_L_P 0x15 +// arp.src.mac +#define ETH_ARP_SRC_MAC_P 0x16 +#define ETH_ARP_SRC_IP_P 0x1c +#define ETH_ARP_DST_MAC_P 0x20 +#define ETH_ARP_DST_IP_P 0x26 + +// ******* IP ******* +#define IP_HEADER_LEN 20 +#define IP_LEN 4 +// ip.src +#define IP_SRC_P 0x1a +#define IP_DST_P 0x1e +#define IP_HEADER_LEN_VER_P 0xe +#define IP_CHECKSUM_P 0x18 +#define IP_TTL_P 0x16 +#define IP_FLAGS_P 0x14 +#define IP_P 0xe +#define IP_TOTLEN_H_P 0x10 +#define IP_TOTLEN_L_P 0x11 + +#define IP_PROTO_P 0x17 + +#define IP_PROTO_ICMP_V 1 +#define IP_PROTO_TCP_V 6 +// 17=0x11 +#define IP_PROTO_UDP_V 17 +// ******* ICMP ******* +#define ICMP_TYPE_ECHOREPLY_V 0 +#define ICMP_TYPE_ECHOREQUEST_V 8 +// +#define ICMP_TYPE_P 0x22 +#define ICMP_CHECKSUM_P 0x24 +#define ICMP_CHECKSUM_H_P 0x24 +#define ICMP_CHECKSUM_L_P 0x25 +#define ICMP_IDENT_H_P 0x26 +#define ICMP_IDENT_L_P 0x27 +#define ICMP_DATA_P 0x2a + +// ******* UDP ******* +#define UDP_HEADER_LEN 8 +// +#define UDP_SRC_PORT_H_P 0x22 +#define UDP_SRC_PORT_L_P 0x23 +#define UDP_DST_PORT_H_P 0x24 +#define UDP_DST_PORT_L_P 0x25 +// +#define UDP_LEN_H_P 0x26 +#define UDP_LEN_L_P 0x27 +#define UDP_CHECKSUM_H_P 0x28 +#define UDP_CHECKSUM_L_P 0x29 +#define UDP_DATA_P 0x2a + +// ******* TCP ******* +#define TCP_SRC_PORT_H_P 0x22 +#define TCP_SRC_PORT_L_P 0x23 +#define TCP_DST_PORT_H_P 0x24 +#define TCP_DST_PORT_L_P 0x25 +// the tcp seq number is 4 bytes 0x26-0x29 +#define TCP_SEQ_H_P 0x26 +#define TCP_SEQACK_H_P 0x2a +// flags: SYN=2 +#define TCP_FLAGS_P 0x2f +#define TCP_FLAGS_SYN_V 2 +#define TCP_FLAGS_FIN_V 1 +#define TCP_FLAGS_RST_V 4 +#define TCP_FLAGS_PUSH_V 8 +#define TCP_FLAGS_SYNACK_V 0x12 +#define TCP_FLAGS_ACK_V 0x10 +#define TCP_FLAGS_PSHACK_V 0x18 +// plain len without the options: +#define TCP_HEADER_LEN_PLAIN 20 +#define TCP_HEADER_LEN_P 0x2e +#define TCP_WIN_SIZE 0x30 +#define TCP_CHECKSUM_H_P 0x32 +#define TCP_CHECKSUM_L_P 0x33 +#define TCP_OPTIONS_P 0x36 +// +#endif diff --git a/libraries/ethercard-master/tcpip.cpp b/libraries/ethercard-master/tcpip.cpp new file mode 100644 index 0000000..a7fd79f --- /dev/null +++ b/libraries/ethercard-master/tcpip.cpp @@ -0,0 +1,841 @@ +// IP, ARP, UDP and TCP functions. +// Author: Guido Socher +// Copyright: GPL V2 +// +// The TCP implementation uses some size optimisations which are valid +// only if all data can be sent in one single packet. This is however +// not a big limitation for a microcontroller as you will anyhow use +// small web-pages. The web server must send the entire web page in one +// packet. The client "web browser" as implemented here can also receive +// large pages. +// +// 2010-05-20 + +#include "EtherCard.h" +#include "net.h" +#undef word // arduino nonsense + +#define gPB ether.buffer + +#define PINGPATTERN 0x42 + +// Avoid spurious pgmspace warnings - http://forum.jeelabs.net/node/327 +// See also http://gcc.gnu.org/bugzilla/show_bug.cgi?id=34734 +//#undef PROGMEM +//#define PROGMEM __attribute__(( section(".progmem.data") )) +//#undef PSTR +//#define PSTR(s) (__extension__({static prog_char c[] PROGMEM = (s); &c[0];})) + +#define TCP_STATE_SENDSYN 1 +#define TCP_STATE_SYNSENT 2 +#define TCP_STATE_ESTABLISHED 3 +#define TCP_STATE_NOTUSED 4 +#define TCP_STATE_CLOSING 5 +#define TCP_STATE_CLOSED 6 + +#define TCPCLIENT_SRC_PORT_H 11 //Source port (MSB) for TCP/IP client connections - hardcode all TCP/IP client connection from ports in range 2816-3071 +static uint8_t tcpclient_src_port_l=1; // Source port (LSB) for tcp/ip client connections - increments on each TCP/IP request +static uint8_t tcp_fd; // a file descriptor, will be encoded into the port +static uint8_t tcp_client_state; //TCP connection state: 1=Send SYN, 2=SYN sent awaiting SYN+ACK, 3=Established, 4=Not used, 5=Closing, 6=Closed +static uint8_t tcp_client_port_h; // Destination port (MSB) of TCP/IP client connection +static uint8_t tcp_client_port_l; // Destination port (LSB) of TCP/IP client connection +static uint8_t (*client_tcp_result_cb)(uint8_t,uint8_t,uint16_t,uint16_t); // Pointer to callback function to handle response to current TCP/IP request +static uint16_t (*client_tcp_datafill_cb)(uint8_t); //Pointer to callback function to handle payload data in response to current TCP/IP request +static uint8_t www_fd; // ID of current http request (only one http request at a time - one of the 8 possible concurrent TCP/IP connections) +static void (*client_browser_cb)(uint8_t,uint16_t,uint16_t); // Pointer to callback function to handle result of current HTTP request +static const char *client_additionalheaderline; // Pointer to c-string additional http request header info +static const char *client_postval; +static const char *client_urlbuf; // Pointer to c-string path part of HTTP request URL +static const char *client_urlbuf_var; // Pointer to c-string filename part of HTTP request URL +static const char *client_hoststr; // Pointer to c-string hostname of current HTTP request +static void (*icmp_cb)(uint8_t *ip); // Pointer to callback function for ICMP ECHO response handler (triggers when localhost recieves ping respnse (pong)) +static uint8_t destmacaddr[ETH_LEN]; // storing both dns server and destination mac addresses, but at different times because both are never needed at same time. +static boolean waiting_for_dns_mac = false; //might be better to use bit flags and bitmask operations for these conditions +static boolean has_dns_mac = false; +static boolean waiting_for_dest_mac = false; +static boolean has_dest_mac = false; +static uint8_t gwmacaddr[ETH_LEN]; // Hardware (MAC) address of gateway router +static uint8_t waitgwmac; // Bitwise flags of gateway router status - see below for states +//Define gatweay router ARP statuses +#define WGW_INITIAL_ARP 1 // First request, no answer yet +#define WGW_HAVE_GW_MAC 2 // Have gateway router MAC +#define WGW_REFRESHING 4 // Refreshing but already have gateway MAC +#define WGW_ACCEPT_ARP_REPLY 8 // Accept an ARP reply + +static uint16_t info_data_len; // Length of TCP/IP payload +static uint8_t seqnum = 0xa; // My initial tcp sequence number +static uint8_t result_fd = 123; // Session id of last reply +static const char* result_ptr; // Pointer to TCP/IP data +static unsigned long SEQ; // TCP/IP sequence number + +#define CLIENTMSS 550 +#define TCP_DATA_START ((uint16_t)TCP_SRC_PORT_H_P+(gPB[TCP_HEADER_LEN_P]>>4)*4) // Get offset of TCP/IP payload data + +const unsigned char arpreqhdr[] PROGMEM = { 0,1,8,0,6,4,0,1 }; // ARP request header +const unsigned char iphdr[] PROGMEM = { 0x45,0,0,0x82,0,0,0x40,0,0x20 }; //IP header +const unsigned char ntpreqhdr[] PROGMEM = { 0xE3,0,4,0xFA,0,1,0,0,0,1 }; //NTP request header +extern const uint8_t allOnes[] = { 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF }; // Used for hardware (MAC) and IP broadcast addresses + +static void fill_checksum(uint8_t dest, uint8_t off, uint16_t len,uint8_t type) { + const uint8_t* ptr = gPB + off; + uint32_t sum = type==1 ? IP_PROTO_UDP_V+len-8 : + type==2 ? IP_PROTO_TCP_V+len-8 : 0; + while(len >1) { + sum += (uint16_t) (((uint32_t)*ptr<<8)|*(ptr+1)); + ptr+=2; + len-=2; + } + if (len) + sum += ((uint32_t)*ptr)<<8; + while (sum>>16) + sum = (uint16_t) sum + (sum >> 16); + uint16_t ck = ~ (uint16_t) sum; + gPB[dest] = ck>>8; + gPB[dest+1] = ck; +} + +static void setMACs (const uint8_t *mac) { + EtherCard::copyMac(gPB + ETH_DST_MAC, mac); + EtherCard::copyMac(gPB + ETH_SRC_MAC, EtherCard::mymac); +} + +static void setMACandIPs (const uint8_t *mac, const uint8_t *dst) { + setMACs(mac); + EtherCard::copyIp(gPB + IP_DST_P, dst); + EtherCard::copyIp(gPB + IP_SRC_P, EtherCard::myip); +} + +static uint8_t check_ip_message_is_from(const uint8_t *ip) { + return memcmp(gPB + IP_SRC_P, ip, IP_LEN) == 0; +} + +static boolean is_lan(const uint8_t source[IP_LEN], const uint8_t destination[IP_LEN]) { + if(source[0] == 0 || destination[0] == 0) { + return false; + } + for(int i = 0; i < IP_LEN; i++) + if((source[i] & EtherCard::netmask[i]) != (destination[i] & EtherCard::netmask[i])) { + return false; + } + return true; +} + +static uint8_t eth_type_is_arp_and_my_ip(uint16_t len) { + return len >= 41 && gPB[ETH_TYPE_H_P] == ETHTYPE_ARP_H_V && + gPB[ETH_TYPE_L_P] == ETHTYPE_ARP_L_V && + memcmp(gPB + ETH_ARP_DST_IP_P, EtherCard::myip, IP_LEN) == 0; +} + +static uint8_t eth_type_is_ip_and_my_ip(uint16_t len) { + return len >= 42 && gPB[ETH_TYPE_H_P] == ETHTYPE_IP_H_V && + gPB[ETH_TYPE_L_P] == ETHTYPE_IP_L_V && + gPB[IP_HEADER_LEN_VER_P] == 0x45 && + (memcmp(gPB + IP_DST_P, EtherCard::myip, IP_LEN) == 0 //not my IP + || (memcmp(gPB + IP_DST_P, EtherCard::broadcastip, IP_LEN) == 0) //not subnet broadcast + || (memcmp(gPB + IP_DST_P, allOnes, IP_LEN) == 0)); //not global broadcasts + //!@todo Handle multicast +} + +static void fill_ip_hdr_checksum() { + gPB[IP_CHECKSUM_P] = 0; + gPB[IP_CHECKSUM_P+1] = 0; + gPB[IP_FLAGS_P] = 0x40; // don't fragment + gPB[IP_FLAGS_P+1] = 0; // fragement offset + gPB[IP_TTL_P] = 64; // ttl + fill_checksum(IP_CHECKSUM_P, IP_P, IP_HEADER_LEN,0); +} + +static void make_eth_ip() { + setMACs(gPB + ETH_SRC_MAC); + EtherCard::copyIp(gPB + IP_DST_P, gPB + IP_SRC_P); + EtherCard::copyIp(gPB + IP_SRC_P, EtherCard::myip); + fill_ip_hdr_checksum(); +} + +static void step_seq(uint16_t rel_ack_num,uint8_t cp_seq) { + uint8_t i; + uint8_t tseq; + i = 4; + while(i>0) { + rel_ack_num = gPB[TCP_SEQ_H_P+i-1]+rel_ack_num; + tseq = gPB[TCP_SEQACK_H_P+i-1]; + gPB[TCP_SEQACK_H_P+i-1] = rel_ack_num; + if (cp_seq) + gPB[TCP_SEQ_H_P+i-1] = tseq; + else + gPB[TCP_SEQ_H_P+i-1] = 0; // some preset value + rel_ack_num = rel_ack_num>>8; + i--; + } +} + +static void make_tcphead(uint16_t rel_ack_num,uint8_t cp_seq) { + uint8_t i = gPB[TCP_DST_PORT_H_P]; + gPB[TCP_DST_PORT_H_P] = gPB[TCP_SRC_PORT_H_P]; + gPB[TCP_SRC_PORT_H_P] = i; + uint8_t j = gPB[TCP_DST_PORT_L_P]; + gPB[TCP_DST_PORT_L_P] = gPB[TCP_SRC_PORT_L_P]; + gPB[TCP_SRC_PORT_L_P] = j; + step_seq(rel_ack_num,cp_seq); + gPB[TCP_CHECKSUM_H_P] = 0; + gPB[TCP_CHECKSUM_L_P] = 0; + gPB[TCP_HEADER_LEN_P] = 0x50; +} + +static void make_arp_answer_from_request() { + setMACs(gPB + ETH_SRC_MAC); + gPB[ETH_ARP_OPCODE_H_P] = ETH_ARP_OPCODE_REPLY_H_V; + gPB[ETH_ARP_OPCODE_L_P] = ETH_ARP_OPCODE_REPLY_L_V; + EtherCard::copyMac(gPB + ETH_ARP_DST_MAC_P, gPB + ETH_ARP_SRC_MAC_P); + EtherCard::copyMac(gPB + ETH_ARP_SRC_MAC_P, EtherCard::mymac); + EtherCard::copyIp(gPB + ETH_ARP_DST_IP_P, gPB + ETH_ARP_SRC_IP_P); + EtherCard::copyIp(gPB + ETH_ARP_SRC_IP_P, EtherCard::myip); + EtherCard::packetSend(42); +} + +static void make_echo_reply_from_request(uint16_t len) { + make_eth_ip(); + gPB[ICMP_TYPE_P] = ICMP_TYPE_ECHOREPLY_V; + if (gPB[ICMP_CHECKSUM_P] > (0xFF-0x08)) + gPB[ICMP_CHECKSUM_P+1]++; + gPB[ICMP_CHECKSUM_P] += 0x08; + EtherCard::packetSend(len); +} + +void EtherCard::makeUdpReply (const char *data,uint8_t datalen,uint16_t port) { + if (datalen>220) + datalen = 220; + gPB[IP_TOTLEN_H_P] = (IP_HEADER_LEN+UDP_HEADER_LEN+datalen) >>8; + gPB[IP_TOTLEN_L_P] = IP_HEADER_LEN+UDP_HEADER_LEN+datalen; + make_eth_ip(); + gPB[UDP_DST_PORT_H_P] = gPB[UDP_SRC_PORT_H_P]; + gPB[UDP_DST_PORT_L_P] = gPB[UDP_SRC_PORT_L_P]; + gPB[UDP_SRC_PORT_H_P] = port>>8; + gPB[UDP_SRC_PORT_L_P] = port; + gPB[UDP_LEN_H_P] = (UDP_HEADER_LEN+datalen) >> 8; + gPB[UDP_LEN_L_P] = UDP_HEADER_LEN+datalen; + gPB[UDP_CHECKSUM_H_P] = 0; + gPB[UDP_CHECKSUM_L_P] = 0; + memcpy(gPB + UDP_DATA_P, data, datalen); + fill_checksum(UDP_CHECKSUM_H_P, IP_SRC_P, 16 + datalen,1); + packetSend(UDP_HEADER_LEN+IP_HEADER_LEN+ETH_HEADER_LEN+datalen); +} + +static void make_tcp_synack_from_syn() { + gPB[IP_TOTLEN_H_P] = 0; + gPB[IP_TOTLEN_L_P] = IP_HEADER_LEN+TCP_HEADER_LEN_PLAIN+4; + make_eth_ip(); + gPB[TCP_FLAGS_P] = TCP_FLAGS_SYNACK_V; + make_tcphead(1,0); + gPB[TCP_SEQ_H_P+0] = 0; + gPB[TCP_SEQ_H_P+1] = 0; + gPB[TCP_SEQ_H_P+2] = seqnum; + gPB[TCP_SEQ_H_P+3] = 0; + seqnum += 3; + gPB[TCP_OPTIONS_P] = 2; + gPB[TCP_OPTIONS_P+1] = 4; + gPB[TCP_OPTIONS_P+2] = 0x05; + gPB[TCP_OPTIONS_P+3] = 0x0; + gPB[TCP_HEADER_LEN_P] = 0x60; + gPB[TCP_WIN_SIZE] = 0x5; // 1400=0x578 + gPB[TCP_WIN_SIZE+1] = 0x78; + fill_checksum(TCP_CHECKSUM_H_P, IP_SRC_P, 8+TCP_HEADER_LEN_PLAIN+4,2); + EtherCard::packetSend(IP_HEADER_LEN+TCP_HEADER_LEN_PLAIN+4+ETH_HEADER_LEN); +} + +uint16_t EtherCard::getTcpPayloadLength() { + int16_t i = (((int16_t)gPB[IP_TOTLEN_H_P])<<8)|gPB[IP_TOTLEN_L_P]; + i -= IP_HEADER_LEN; + i -= (gPB[TCP_HEADER_LEN_P]>>4)*4; // generate len in bytes; + if (i<=0) + i = 0; + return (uint16_t)i; +} + +static void make_tcp_ack_from_any(int16_t datlentoack,uint8_t addflags) { + gPB[TCP_FLAGS_P] = TCP_FLAGS_ACK_V|addflags; + if (addflags!=TCP_FLAGS_RST_V && datlentoack==0) + datlentoack = 1; + make_tcphead(datlentoack,1); // no options + uint16_t j = IP_HEADER_LEN+TCP_HEADER_LEN_PLAIN; + gPB[IP_TOTLEN_H_P] = j>>8; + gPB[IP_TOTLEN_L_P] = j; + make_eth_ip(); + gPB[TCP_WIN_SIZE] = 0x4; // 1024=0x400, 1280=0x500 2048=0x800 768=0x300 + gPB[TCP_WIN_SIZE+1] = 0; + fill_checksum(TCP_CHECKSUM_H_P, IP_SRC_P, 8+TCP_HEADER_LEN_PLAIN,2); + EtherCard::packetSend(IP_HEADER_LEN+TCP_HEADER_LEN_PLAIN+ETH_HEADER_LEN); +} + +static void make_tcp_ack_with_data_noflags(uint16_t dlen) { + uint16_t j = IP_HEADER_LEN+TCP_HEADER_LEN_PLAIN+dlen; + gPB[IP_TOTLEN_H_P] = j>>8; + gPB[IP_TOTLEN_L_P] = j; + fill_ip_hdr_checksum(); + gPB[TCP_CHECKSUM_H_P] = 0; + gPB[TCP_CHECKSUM_L_P] = 0; + fill_checksum(TCP_CHECKSUM_H_P, IP_SRC_P, 8+TCP_HEADER_LEN_PLAIN+dlen,2); + EtherCard::packetSend(IP_HEADER_LEN+TCP_HEADER_LEN_PLAIN+dlen+ETH_HEADER_LEN); +} + +void EtherCard::httpServerReply (uint16_t dlen) { + make_tcp_ack_from_any(info_data_len,0); // send ack for http get + gPB[TCP_FLAGS_P] = TCP_FLAGS_ACK_V|TCP_FLAGS_PUSH_V|TCP_FLAGS_FIN_V; + make_tcp_ack_with_data_noflags(dlen); // send data +} + +static uint32_t getBigEndianLong(byte offs) { //get the sequence number of packets after an ack from GET + return (((unsigned long)gPB[offs]*256+gPB[offs+1])*256+gPB[offs+2])*256+gPB[offs+3]; +} //thanks to mstuetz for the missing (unsigned long) + +static void setSequenceNumber(uint32_t seq) { + gPB[TCP_SEQ_H_P] = (seq & 0xff000000 ) >> 24; + gPB[TCP_SEQ_H_P+1] = (seq & 0xff0000 ) >> 16; + gPB[TCP_SEQ_H_P+2] = (seq & 0xff00 ) >> 8; + gPB[TCP_SEQ_H_P+3] = (seq & 0xff ); +} + +uint32_t EtherCard::getSequenceNumber() { + return getBigEndianLong(TCP_SEQ_H_P); +} + +void EtherCard::httpServerReplyAck () { + make_tcp_ack_from_any(getTcpPayloadLength(),0); // send ack for http request + SEQ = getSequenceNumber(); //get the sequence number of packets after an ack from GET +} + +void EtherCard::httpServerReply_with_flags (uint16_t dlen , uint8_t flags) { + setSequenceNumber(SEQ); + gPB[TCP_FLAGS_P] = flags; // final packet + make_tcp_ack_with_data_noflags(dlen); // send data + SEQ=SEQ+dlen; +} + +void EtherCard::clientIcmpRequest(const uint8_t *destip) { + if(is_lan(EtherCard::myip, destip)) { + setMACandIPs(destmacaddr, destip); + } else { + setMACandIPs(gwmacaddr, destip); + } + gPB[ETH_TYPE_H_P] = ETHTYPE_IP_H_V; + gPB[ETH_TYPE_L_P] = ETHTYPE_IP_L_V; + memcpy_P(gPB + IP_P,iphdr,sizeof iphdr); + gPB[IP_TOTLEN_L_P] = 0x54; + gPB[IP_PROTO_P] = IP_PROTO_ICMP_V; + fill_ip_hdr_checksum(); + gPB[ICMP_TYPE_P] = ICMP_TYPE_ECHOREQUEST_V; + gPB[ICMP_TYPE_P+1] = 0; // code + gPB[ICMP_CHECKSUM_H_P] = 0; + gPB[ICMP_CHECKSUM_L_P] = 0; + gPB[ICMP_IDENT_H_P] = 5; // some number + gPB[ICMP_IDENT_L_P] = EtherCard::myip[3]; // last byte of my IP + gPB[ICMP_IDENT_L_P+1] = 0; // seq number, high byte + gPB[ICMP_IDENT_L_P+2] = 1; // seq number, low byte, we send only 1 ping at a time + memset(gPB + ICMP_DATA_P, PINGPATTERN, 56); + fill_checksum(ICMP_CHECKSUM_H_P, ICMP_TYPE_P, 56+8,0); + packetSend(98); +} + +void EtherCard::ntpRequest (uint8_t *ntpip,uint8_t srcport) { + if(is_lan(myip, ntpip)) { + setMACandIPs(destmacaddr, ntpip); + } else { + setMACandIPs(gwmacaddr, ntpip); + } + gPB[ETH_TYPE_H_P] = ETHTYPE_IP_H_V; + gPB[ETH_TYPE_L_P] = ETHTYPE_IP_L_V; + memcpy_P(gPB + IP_P,iphdr,sizeof iphdr); + gPB[IP_TOTLEN_L_P] = 0x4c; + gPB[IP_PROTO_P] = IP_PROTO_UDP_V; + fill_ip_hdr_checksum(); + gPB[UDP_DST_PORT_H_P] = 0; + gPB[UDP_DST_PORT_L_P] = NTP_PORT; // ntp = 123 + gPB[UDP_SRC_PORT_H_P] = 10; + gPB[UDP_SRC_PORT_L_P] = srcport; // lower 8 bit of src port + gPB[UDP_LEN_H_P] = 0; + gPB[UDP_LEN_L_P] = 56; // fixed len + gPB[UDP_CHECKSUM_H_P] = 0; + gPB[UDP_CHECKSUM_L_P] = 0; + memset(gPB + UDP_DATA_P, 0, 48); + memcpy_P(gPB + UDP_DATA_P,ntpreqhdr,10); + fill_checksum(UDP_CHECKSUM_H_P, IP_SRC_P, 16 + 48,1); + packetSend(90); +} + +uint8_t EtherCard::ntpProcessAnswer (uint32_t *time,uint8_t dstport_l) { + if ((dstport_l && gPB[UDP_DST_PORT_L_P]!=dstport_l) || gPB[UDP_LEN_H_P]!=0 || + gPB[UDP_LEN_L_P]!=56 || gPB[UDP_SRC_PORT_L_P]!=0x7b) + return 0; + ((uint8_t*) time)[3] = gPB[0x52]; + ((uint8_t*) time)[2] = gPB[0x53]; + ((uint8_t*) time)[1] = gPB[0x54]; + ((uint8_t*) time)[0] = gPB[0x55]; + return 1; +} + +void EtherCard::udpPrepare (uint16_t sport, const uint8_t *dip, uint16_t dport) { + if(is_lan(myip, dip)) { // this works because both dns mac and destinations mac are stored in same variable - destmacaddr + setMACandIPs(destmacaddr, dip); // at different times. The program could have separate variable for dns mac, then here should be + } else { // checked if dip is dns ip and separately if dip is hisip and then use correct mac. + setMACandIPs(gwmacaddr, dip); + } + // see http://tldp.org/HOWTO/Multicast-HOWTO-2.html + // multicast or broadcast address, https://github.com/jcw/ethercard/issues/59 + if ((dip[0] & 0xF0) == 0xE0 || *((unsigned long*) dip) == 0xFFFFFFFF || !memcmp(broadcastip,dip,IP_LEN)) + EtherCard::copyMac(gPB + ETH_DST_MAC, allOnes); + gPB[ETH_TYPE_H_P] = ETHTYPE_IP_H_V; + gPB[ETH_TYPE_L_P] = ETHTYPE_IP_L_V; + memcpy_P(gPB + IP_P,iphdr,sizeof iphdr); + gPB[IP_TOTLEN_H_P] = 0; + gPB[IP_PROTO_P] = IP_PROTO_UDP_V; + gPB[UDP_DST_PORT_H_P] = (dport>>8); + gPB[UDP_DST_PORT_L_P] = dport; + gPB[UDP_SRC_PORT_H_P] = (sport>>8); + gPB[UDP_SRC_PORT_L_P] = sport; + gPB[UDP_LEN_H_P] = 0; + gPB[UDP_CHECKSUM_H_P] = 0; + gPB[UDP_CHECKSUM_L_P] = 0; +} + +void EtherCard::udpTransmit (uint16_t datalen) { + gPB[IP_TOTLEN_H_P] = (IP_HEADER_LEN+UDP_HEADER_LEN+datalen) >> 8; + gPB[IP_TOTLEN_L_P] = IP_HEADER_LEN+UDP_HEADER_LEN+datalen; + fill_ip_hdr_checksum(); + gPB[UDP_LEN_H_P] = (UDP_HEADER_LEN+datalen) >>8; + gPB[UDP_LEN_L_P] = UDP_HEADER_LEN+datalen; + fill_checksum(UDP_CHECKSUM_H_P, IP_SRC_P, 16 + datalen,1); + packetSend(UDP_HEADER_LEN+IP_HEADER_LEN+ETH_HEADER_LEN+datalen); +} + +void EtherCard::sendUdp (const char *data, uint8_t datalen, uint16_t sport, + const uint8_t *dip, uint16_t dport) { + udpPrepare(sport, dip, dport); + if (datalen>220) + datalen = 220; + memcpy(gPB + UDP_DATA_P, data, datalen); + udpTransmit(datalen); +} + +void EtherCard::sendWol (uint8_t *wolmac) { + setMACandIPs(allOnes, allOnes); + gPB[ETH_TYPE_H_P] = ETHTYPE_IP_H_V; + gPB[ETH_TYPE_L_P] = ETHTYPE_IP_L_V; + memcpy_P(gPB + IP_P,iphdr,9); + gPB[IP_TOTLEN_L_P] = 0x82; + gPB[IP_PROTO_P] = IP_PROTO_UDP_V; + fill_ip_hdr_checksum(); + gPB[UDP_DST_PORT_H_P] = 0; + gPB[UDP_DST_PORT_L_P] = 0x9; // wol = normally 9 + gPB[UDP_SRC_PORT_H_P] = 10; + gPB[UDP_SRC_PORT_L_P] = 0x42; // source port does not matter + gPB[UDP_LEN_H_P] = 0; + gPB[UDP_LEN_L_P] = 110; // fixed len + gPB[UDP_CHECKSUM_H_P] = 0; + gPB[UDP_CHECKSUM_L_P] = 0; + copyMac(gPB + UDP_DATA_P, allOnes); + uint8_t pos = UDP_DATA_P; + for (uint8_t m = 0; m < 16; ++m) { + pos += 6; + copyMac(gPB + pos, wolmac); + } + fill_checksum(UDP_CHECKSUM_H_P, IP_SRC_P, 16 + 102,1); + packetSend(pos + 6); +} + +// make a arp request +static void client_arp_whohas(uint8_t *ip_we_search) { + setMACs(allOnes); + gPB[ETH_TYPE_H_P] = ETHTYPE_ARP_H_V; + gPB[ETH_TYPE_L_P] = ETHTYPE_ARP_L_V; + memcpy_P(gPB + ETH_ARP_P, arpreqhdr, sizeof arpreqhdr); + memset(gPB + ETH_ARP_DST_MAC_P, 0, ETH_LEN); + EtherCard::copyMac(gPB + ETH_ARP_SRC_MAC_P, EtherCard::mymac); + EtherCard::copyIp(gPB + ETH_ARP_DST_IP_P, ip_we_search); + EtherCard::copyIp(gPB + ETH_ARP_SRC_IP_P, EtherCard::myip); + EtherCard::packetSend(42); +} + +uint8_t EtherCard::clientWaitingGw () { + return !(waitgwmac & WGW_HAVE_GW_MAC); +} + +uint8_t EtherCard::clientWaitingDns () { + if(is_lan(myip, dnsip)) + return !has_dns_mac; + return !(waitgwmac & WGW_HAVE_GW_MAC); +} + +static uint8_t client_store_mac(uint8_t *source_ip, uint8_t *mac) { + if (memcmp(gPB + ETH_ARP_SRC_IP_P, source_ip, IP_LEN) != 0) + return 0; + EtherCard::copyMac(mac, gPB + ETH_ARP_SRC_MAC_P); + return 1; +} + +// static void client_gw_arp_refresh() { +// if (waitgwmac & WGW_HAVE_GW_MAC) +// waitgwmac |= WGW_REFRESHING; +// } + +void EtherCard::setGwIp (const uint8_t *gwipaddr) { + delaycnt = 0; //request gateway ARP lookup + waitgwmac = WGW_INITIAL_ARP; // causes an arp request in the packet loop + copyIp(gwip, gwipaddr); +} + +void EtherCard::updateBroadcastAddress() +{ + for(uint8_t i=0; i>4) * 4 + gPB[TCP_FLAGS_P] = TCP_FLAGS_SYN_V; + gPB[TCP_WIN_SIZE] = 0x3; // 1024 = 0x400 768 = 0x300, initial window + gPB[TCP_WIN_SIZE+1] = 0x0; + gPB[TCP_CHECKSUM_H_P] = 0; + gPB[TCP_CHECKSUM_L_P] = 0; + gPB[TCP_CHECKSUM_L_P+1] = 0; + gPB[TCP_CHECKSUM_L_P+2] = 0; + gPB[TCP_OPTIONS_P] = 2; + gPB[TCP_OPTIONS_P+1] = 4; + gPB[TCP_OPTIONS_P+2] = (CLIENTMSS>>8); + gPB[TCP_OPTIONS_P+3] = (uint8_t) CLIENTMSS; + fill_checksum(TCP_CHECKSUM_H_P, IP_SRC_P, 8 +TCP_HEADER_LEN_PLAIN+4,2); + // 4 is the tcp mss option: + EtherCard::packetSend(IP_HEADER_LEN+TCP_HEADER_LEN_PLAIN+ETH_HEADER_LEN+4); +} + +uint8_t EtherCard::clientTcpReq (uint8_t (*result_cb)(uint8_t,uint8_t,uint16_t,uint16_t), + uint16_t (*datafill_cb)(uint8_t),uint16_t port) { + client_tcp_result_cb = result_cb; + client_tcp_datafill_cb = datafill_cb; + tcp_client_port_h = port>>8; + tcp_client_port_l = port; + tcp_client_state = TCP_STATE_SENDSYN; // Flag to packetloop to initiate a TCP/IP session by send a syn + tcp_fd = (tcp_fd + 1) & 7; + return tcp_fd; +} + +static uint16_t www_client_internal_datafill_cb(uint8_t fd) { + BufferFiller bfill = EtherCard::tcpOffset(); + if (fd==www_fd) { + if (client_postval == 0) { + bfill.emit_p(PSTR("GET $F$S HTTP/1.0\r\n" + "Host: $F\r\n" + "$F\r\n" + "\r\n"), client_urlbuf, + client_urlbuf_var, + client_hoststr, client_additionalheaderline); + } else { + const char* ahl = client_additionalheaderline; + bfill.emit_p(PSTR("POST $F HTTP/1.0\r\n" + "Host: $F\r\n" + "$F$S" + "Accept: */*\r\n" + "Content-Length: $D\r\n" + "Content-Type: application/x-www-form-urlencoded\r\n" + "\r\n" + "$S"), client_urlbuf, + client_hoststr, + ahl != 0 ? ahl : PSTR(""), + ahl != 0 ? "\r\n" : "", + strlen(client_postval), + client_postval); + } + } + return bfill.position(); +} + +static uint8_t www_client_internal_result_cb(uint8_t fd, uint8_t statuscode, uint16_t datapos, uint16_t len_of_data) { + if (fd!=www_fd) + (*client_browser_cb)(4,0,0); + else if (statuscode==0 && len_of_data>12 && client_browser_cb) { + uint8_t f = strncmp("200",(char *)&(gPB[datapos+9]),3) != 0; + (*client_browser_cb)(f, ((uint16_t)TCP_SRC_PORT_H_P+(gPB[TCP_HEADER_LEN_P]>>4)*4),len_of_data); + } + return 0; +} + +void EtherCard::browseUrl (const char *urlbuf, const char *urlbuf_varpart, const char *hoststr, void (*callback)(uint8_t,uint16_t,uint16_t)) { + browseUrl(urlbuf, urlbuf_varpart, hoststr, PSTR("Accept: text/html"), callback); +} + +void EtherCard::browseUrl (const char *urlbuf, const char *urlbuf_varpart, const char *hoststr, const char *additionalheaderline, void (*callback)(uint8_t,uint16_t,uint16_t)) { + client_urlbuf = urlbuf; + client_urlbuf_var = urlbuf_varpart; + client_hoststr = hoststr; + client_additionalheaderline = additionalheaderline; + client_postval = 0; + client_browser_cb = callback; + www_fd = clientTcpReq(&www_client_internal_result_cb,&www_client_internal_datafill_cb,hisport); +} + +void EtherCard::httpPost (const char *urlbuf, const char *hoststr, const char *additionalheaderline, const char *postval, void (*callback)(uint8_t,uint16_t,uint16_t)) { + client_urlbuf = urlbuf; + client_hoststr = hoststr; + client_additionalheaderline = additionalheaderline; + client_postval = postval; + client_browser_cb = callback; + www_fd = clientTcpReq(&www_client_internal_result_cb,&www_client_internal_datafill_cb,hisport); +} + +static uint16_t tcp_datafill_cb(uint8_t fd) { + uint16_t len = Stash::length(); + Stash::extract(0, len, EtherCard::tcpOffset()); + Stash::cleanup(); + EtherCard::tcpOffset()[len] = 0; +#if SERIAL + Serial.print("REQUEST: "); + Serial.println(len); + Serial.println((char*) EtherCard::tcpOffset()); +#endif + result_fd = 123; // bogus value + return len; +} + +static uint8_t tcp_result_cb(uint8_t fd, uint8_t status, uint16_t datapos, uint16_t datalen) { + if (status == 0) { + result_fd = fd; // a valid result has been received, remember its session id + result_ptr = (char*) ether.buffer + datapos; + // result_ptr[datalen] = 0; + } + return 1; +} + +uint8_t EtherCard::tcpSend () { + www_fd = clientTcpReq(&tcp_result_cb, &tcp_datafill_cb, hisport); + return www_fd; +} + +const char* EtherCard::tcpReply (uint8_t fd) { + if (result_fd != fd) + return 0; + result_fd = 123; // set to a bogus value to prevent future match + return result_ptr; +} + +void EtherCard::registerPingCallback (void (*callback)(uint8_t *srcip)) { + icmp_cb = callback; +} + +uint8_t EtherCard::packetLoopIcmpCheckReply (const uint8_t *ip_monitoredhost) { + return gPB[IP_PROTO_P]==IP_PROTO_ICMP_V && + gPB[ICMP_TYPE_P]==ICMP_TYPE_ECHOREPLY_V && + gPB[ICMP_DATA_P]== PINGPATTERN && + check_ip_message_is_from(ip_monitoredhost); +} + +uint16_t EtherCard::accept(const uint16_t port, uint16_t plen) { + uint16_t pos; + + if (gPB[TCP_DST_PORT_H_P] == (port >> 8) && + gPB[TCP_DST_PORT_L_P] == ((uint8_t) port)) + { //Packet targetted at specified port + if (gPB[TCP_FLAGS_P] & TCP_FLAGS_SYN_V) + make_tcp_synack_from_syn(); //send SYN+ACK + else if (gPB[TCP_FLAGS_P] & TCP_FLAGS_ACK_V) + { //This is an acknowledgement to our SYN+ACK so let's start processing that payload + info_data_len = getTcpPayloadLength(); + if (info_data_len > 0) + { //Got some data + pos = TCP_DATA_START; // TCP_DATA_START is a formula + //!@todo no idea what this check pos<=plen-8 does; changed this to pos<=plen as otw. perfectly valid tcp packets are ignored; still if anybody has any idea please leave a comment + if (pos <= plen) + return pos; + } + else if (gPB[TCP_FLAGS_P] & TCP_FLAGS_FIN_V) + make_tcp_ack_from_any(0,0); //No data so close connection + } + } + return 0; +} + +uint16_t EtherCard::packetLoop (uint16_t plen) { + uint16_t len; + +#if ETHERCARD_DHCP + if(using_dhcp) { + ether.DhcpStateMachine(plen); + } +#endif + + if (plen==0) { + //Check every 65536 (no-packet) cycles whether we need to retry ARP request for gateway + if ((waitgwmac & WGW_INITIAL_ARP || waitgwmac & WGW_REFRESHING) && + delaycnt==0 && isLinkUp()) { + client_arp_whohas(gwip); + waitgwmac |= WGW_ACCEPT_ARP_REPLY; + } + delaycnt++; + +#if ETHERCARD_TCPCLIENT + //Initiate TCP/IP session if pending + if (tcp_client_state==TCP_STATE_SENDSYN && (waitgwmac & WGW_HAVE_GW_MAC)) { // send a syn + tcp_client_state = TCP_STATE_SYNSENT; + tcpclient_src_port_l++; // allocate a new port + client_syn(((tcp_fd<<5) | (0x1f & tcpclient_src_port_l)),tcp_client_port_h,tcp_client_port_l); + } +#endif + + //!@todo this is trying to find mac only once. Need some timeout to make another call if first one doesn't succeed. + if(is_lan(myip, dnsip) && !has_dns_mac && !waiting_for_dns_mac) { + client_arp_whohas(dnsip); + waiting_for_dns_mac = true; + } + + //!@todo this is trying to find mac only once. Need some timeout to make another call if first one doesn't succeed. + if(is_lan(myip, hisip) && !has_dest_mac && !waiting_for_dest_mac) { + client_arp_whohas(hisip); + waiting_for_dest_mac = true; + } + + return 0; + } + + if (eth_type_is_arp_and_my_ip(plen)) + { //Service ARP request + if (gPB[ETH_ARP_OPCODE_L_P]==ETH_ARP_OPCODE_REQ_L_V) + make_arp_answer_from_request(); + if (waitgwmac & WGW_ACCEPT_ARP_REPLY && (gPB[ETH_ARP_OPCODE_L_P]==ETH_ARP_OPCODE_REPLY_L_V) && client_store_mac(gwip, gwmacaddr)) + waitgwmac = WGW_HAVE_GW_MAC; + if (!has_dns_mac && waiting_for_dns_mac && client_store_mac(dnsip, destmacaddr)) { + has_dns_mac = true; + waiting_for_dns_mac = false; + } + if (!has_dest_mac && waiting_for_dest_mac && client_store_mac(hisip, destmacaddr)) { + has_dest_mac = true; + waiting_for_dest_mac = false; + } + return 0; + } + + if (eth_type_is_ip_and_my_ip(plen)==0) + { //Not IP so ignoring + //!@todo Add other protocols (and make each optional at compile time) + return 0; + } + +#if ETHERCARD_ICMP + if (gPB[IP_PROTO_P]==IP_PROTO_ICMP_V && gPB[ICMP_TYPE_P]==ICMP_TYPE_ECHOREQUEST_V) + { //Service ICMP echo request (ping) + if (icmp_cb) + (*icmp_cb)(&(gPB[IP_SRC_P])); + make_echo_reply_from_request(plen); + return 0; + } +#endif +#if ETHERCARD_UDPSERVER + if (ether.udpServerListening() && gPB[IP_PROTO_P]==IP_PROTO_UDP_V) + { //Call UDP server handler (callback) if one is defined for this packet + if(ether.udpServerHasProcessedPacket(plen)) + return 0; //An UDP server handler (callback) has processed this packet + } +#endif + + if (plen<54 || gPB[IP_PROTO_P]!=IP_PROTO_TCP_V ) + return 0; //from here on we are only interested in TCP-packets; these are longer than 54 bytes + +#if ETHERCARD_TCPCLIENT + if (gPB[TCP_DST_PORT_H_P]==TCPCLIENT_SRC_PORT_H) + { //Source port is in range reserved (by EtherCard) for client TCP/IP connections + if (check_ip_message_is_from(hisip)==0) + return 0; //Not current TCP/IP connection (only handle one at a time) + if (gPB[TCP_FLAGS_P] & TCP_FLAGS_RST_V) + { //TCP reset flagged + if (client_tcp_result_cb) + (*client_tcp_result_cb)((gPB[TCP_DST_PORT_L_P]>>5)&0x7,3,0,0); + tcp_client_state = TCP_STATE_CLOSING; + return 0; + } + len = getTcpPayloadLength(); + if (tcp_client_state==TCP_STATE_SYNSENT) + { //Waiting for SYN-ACK + if ((gPB[TCP_FLAGS_P] & TCP_FLAGS_SYN_V) && (gPB[TCP_FLAGS_P] &TCP_FLAGS_ACK_V)) + { //SYN and ACK flags set so this is an acknowledgement to our SYN + make_tcp_ack_from_any(0,0); + gPB[TCP_FLAGS_P] = TCP_FLAGS_ACK_V|TCP_FLAGS_PUSH_V; + if (client_tcp_datafill_cb) + len = (*client_tcp_datafill_cb)((gPB[TCP_SRC_PORT_L_P]>>5)&0x7); + else + len = 0; + tcp_client_state = TCP_STATE_ESTABLISHED; + make_tcp_ack_with_data_noflags(len); + } + else + { //Expecting SYN+ACK so reset and resend SYN + tcp_client_state = TCP_STATE_SENDSYN; // retry + len++; + if (gPB[TCP_FLAGS_P] & TCP_FLAGS_ACK_V) + len = 0; + make_tcp_ack_from_any(len,TCP_FLAGS_RST_V); + } + return 0; + } + if (tcp_client_state==TCP_STATE_ESTABLISHED && len>0) + { //TCP connection established so read data + if (client_tcp_result_cb) { + uint16_t tcpstart = TCP_DATA_START; // TCP_DATA_START is a formula + if (tcpstart>plen-8) + tcpstart = plen-8; // dummy but save + uint16_t save_len = len; + if (tcpstart+len>plen) + save_len = plen-tcpstart; + (*client_tcp_result_cb)((gPB[TCP_DST_PORT_L_P]>>5)&0x7,0,tcpstart,save_len); //Call TCP handler (callback) function + + if(persist_tcp_connection) + { //Keep connection alive by sending ACK + make_tcp_ack_from_any(len,TCP_FLAGS_PUSH_V); + } + else + { //Close connection + make_tcp_ack_from_any(len,TCP_FLAGS_PUSH_V|TCP_FLAGS_FIN_V); + tcp_client_state = TCP_STATE_CLOSED; + } + return 0; + } + } + if (tcp_client_state != TCP_STATE_CLOSING) + { // + if (gPB[TCP_FLAGS_P] & TCP_FLAGS_FIN_V) { + if(tcp_client_state == TCP_STATE_ESTABLISHED) { + return 0; // In some instances FIN is received *before* DATA. If that is the case, we just return here and keep looking for the data packet + } + make_tcp_ack_from_any(len+1,TCP_FLAGS_PUSH_V|TCP_FLAGS_FIN_V); + tcp_client_state = TCP_STATE_CLOSED; // connection terminated + } else if (len>0) { + make_tcp_ack_from_any(len,0); + } + } + return 0; + } +#endif + +#if ETHERCARD_TCPSERVER + //If we are here then this is a TCP/IP packet targetted at us and not related to our client connection so accept + return accept(hisport, plen); +#endif +} + +void EtherCard::persistTcpConnection(bool persist) { + persist_tcp_connection = persist; +} diff --git a/libraries/ethercard-master/udpserver.cpp b/libraries/ethercard-master/udpserver.cpp new file mode 100644 index 0000000..aa3b74f --- /dev/null +++ b/libraries/ethercard-master/udpserver.cpp @@ -0,0 +1,73 @@ +// Simple UDP listening server +// +// Author: Brian Lee +// +// Copyright: GPL V2 +// See http://www.gnu.org/licenses/gpl.html + +#include "EtherCard.h" +#include "net.h" + +#define gPB ether.buffer + +#define UDPSERVER_MAXLISTENERS 8 //the maximum number of port listeners. + +typedef struct { + UdpServerCallback callback; + uint16_t port; + bool listening; +} UdpServerListener; + +UdpServerListener listeners[UDPSERVER_MAXLISTENERS]; +byte numListeners = 0; + +void EtherCard::udpServerListenOnPort(UdpServerCallback callback, uint16_t port) { + if(numListeners < UDPSERVER_MAXLISTENERS) + { + listeners[numListeners] = (UdpServerListener) { + callback, port, true + }; + numListeners++; + } +} + +void EtherCard::udpServerPauseListenOnPort(uint16_t port) { + for(int i = 0; i < numListeners; i++) + { + if(gPB[UDP_DST_PORT_H_P] == (listeners[i].port >> 8) && gPB[UDP_DST_PORT_L_P] == ((byte) listeners[i].port)) { + listeners[i].listening = false; + } + } +} + +void EtherCard::udpServerResumeListenOnPort(uint16_t port) { + for(int i = 0; i < numListeners; i++) + { + if(gPB[UDP_DST_PORT_H_P] == (listeners[i].port >> 8) && gPB[UDP_DST_PORT_L_P] == ((byte) listeners[i].port)) { + listeners[i].listening = true; + } + } +} + +bool EtherCard::udpServerListening() { + return numListeners > 0; +} + +bool EtherCard::udpServerHasProcessedPacket(uint16_t plen) { + bool packetProcessed = false; + for(int i = 0; i < numListeners; i++) + { + if(gPB[UDP_DST_PORT_H_P] == (listeners[i].port >> 8) && gPB[UDP_DST_PORT_L_P] == ((byte) listeners[i].port) && listeners[i].listening) + { + uint16_t datalen = (uint16_t) (gPB[UDP_LEN_H_P] << 8) + gPB[UDP_LEN_L_P] - UDP_HEADER_LEN; + listeners[i].callback( + listeners[i].port, + gPB + IP_SRC_P, + (gPB[UDP_SRC_PORT_H_P] << 8) | gPB[UDP_SRC_PORT_L_P], + (const char *) (gPB + UDP_DATA_P), + datalen); + packetProcessed = true; + } + } + return packetProcessed; +} diff --git a/libraries/ethercard-master/webutil.cpp b/libraries/ethercard-master/webutil.cpp new file mode 100644 index 0000000..0e5ae12 --- /dev/null +++ b/libraries/ethercard-master/webutil.cpp @@ -0,0 +1,202 @@ +// Some common utilities needed for IP and web applications +// Author: Guido Socher +// Copyright: GPL V2 +// +// 2010-05-20 + +#include "EtherCard.h" + +void EtherCard::copyIp (uint8_t *dst, const uint8_t *src) { + memcpy(dst, src, IP_LEN); +} + +void EtherCard::copyMac (uint8_t *dst, const uint8_t *src) { + memcpy(dst, src, ETH_LEN); +} + +void EtherCard::printIp (const char* msg, const uint8_t *buf) { + Serial.print(msg); + EtherCard::printIp(buf); + Serial.println(); +} + +void EtherCard::printIp (const __FlashStringHelper *ifsh, const uint8_t *buf) { + Serial.print(ifsh); + EtherCard::printIp(buf); + Serial.println(); +} + +void EtherCard::printIp (const uint8_t *buf) { + for (uint8_t i = 0; i < IP_LEN; ++i) { + Serial.print( buf[i], DEC ); + if (i < 3) + Serial.print('.'); + } +} + +// search for a string of the form key=value in +// a string that looks like q?xyz=abc&uvw=defgh HTTP/1.1\r\n +// +// The returned value is stored in strbuf. You must allocate +// enough storage for strbuf, maxlen is the size of strbuf. +// I.e the value it is declated with: strbuf[5]-> maxlen=5 +uint8_t EtherCard::findKeyVal (const char *str,char *strbuf, uint8_t maxlen,const char *key) +{ + byte found = false; + uint8_t i=0; + const char *kp; + kp=key; + while(*str && *str!=' ' && *str!='\n' && !found) { + if (*str == *kp) { + kp++; + if (*kp == '\0') { + str++; + kp=key; + if (*str == '=') { + found = true; + } + } + } else { + kp=key; + } + str++; + } + if (found) { + // copy the value to a buffer and terminate it with '\0' + while(*str && *str!=' ' && *str!='\n' && *str!='&' && i9) { + hstr[1]=(c & 0xf) - 10 + 'a'; + } + c=(c>>4)&0xf; + hstr[0]=c+'0'; + if (c > 9) { + hstr[0]=c - 10 + 'a'; + } + hstr[2]='\0'; +} + +// there must be enough space in urlbuf. In the worst case that is +// 3 times the length of str +void EtherCard::urlEncode (char *str,char *urlbuf) +{ + char c; + while ((c = *str) != 0) { + if (c == ' '||isalnum(c)) { + if (c == ' ') { + c = '+'; + } + *urlbuf=c; + str++; + urlbuf++; + continue; + } + *urlbuf='%'; + urlbuf++; + int2h(c,urlbuf); + urlbuf++; + urlbuf++; + str++; + } + *urlbuf='\0'; +} + +// parse a string and extract the IP to bytestr +uint8_t EtherCard::parseIp (uint8_t *bytestr,char *str) +{ + char *sptr; + uint8_t i=0; + sptr=NULL; + while(ima[i]) + {ma[i]=in[i];} + else + if(in[i]150)?1:0; +} +void setValues(){ + if(in[3]==1)k=(-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 =k*in[3] + +(1-in[3])*(((in[1]+in[2])>(in[4]+in[5]))?(k-(+(255-in[1])*3+(255-in[2]))):((255-in[4])+(255-in[5])*3+k)); + else cv=1800*(pcv/abs(pcv)); + pcv=cv; + Serial.println(cv); +} +void loop (){ + /*for(int i=0;i<7;i++) + { + Serial.print(in[i]);Serial.print(" "); + }*/ + + takeInput(); + setValues(); +int err = 0 - cv; +cerr+=err; +float pwm = err*kp + cerr*ki + (err-perr)*kd; +perr=err; +//Serial.println(pwm); +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; +speedControl(pwma,pwmb); +} +void speedControl(int a, int b){ + + analogWrite(md[2], map(a,0,255,0,255));//246 + analogWrite(md[3], map(b,0,255,0,250));} diff --git a/motion_sense_robot/Readme.txt b/motion_sense_robot/Readme.txt new file mode 100644 index 0000000..bb718e7 --- /dev/null +++ b/motion_sense_robot/Readme.txt @@ -0,0 +1,3 @@ +This is a hand gesture based four wheeled robot. +This code uses Sensoduino-(Android app) Orientation sensor. +youtube.com/watch?v=Y7LjgHsPQ5U diff --git a/motion_sense_robot/motion_sense_robot.ino b/motion_sense_robot/motion_sense_robot.ino new file mode 100644 index 0000000..6b131cc --- /dev/null +++ b/motion_sense_robot/motion_sense_robot.ino @@ -0,0 +1,113 @@ +#define MA1 4 +#define MA2 5 +#define MB1 7 +#define MB2 8 +#define EA 6 +#define EB 9 + +//commented out part was for encoders. And it's incomplete. Looking forward to complete it when I get encoder motors. + +/*#define ACHA 3 +#define ACHB 11 +#define BCHA 2 +#define BCHB 12 +volatile int32_t a = 0; +volatile int32_t b = 0; +*/ +void setup() +{ + Serial.begin(57600); + //attachInterrupt(digitalPinToInterrupt(BCHA), BMI,RISING); + //attachInterrupt(digitalPinToInterrupt(ACHA), AMI,RISING); + /* add setup code here */ + pinMode(MA1,OUTPUT); + pinMode(MA2, OUTPUT); + pinMode(MB1, OUTPUT); + pinMode(MB2, OUTPUT); + pinMode(EA, OUTPUT); + pinMode(EB, OUTPUT); + +} +/* +void BMI() +{ + a += ((digitalRead(ACHB)) ? 1 : -1); +} + +void AMI() +{ + b += ((digitalRead(BCHB)) ? 1 : -1); +} +*/ +int r=0, p=0,lp=0,rp=0; +void loop() +{ + if (Serial.available()) + { + Serial.readStringUntil(','); + Serial.readStringUntil(','); + Serial.parseFloat(); + Serial.read(); + p = -5 - Serial.parseFloat(); + p = constrain(p, -40, 40); + Serial.read(); + r = Serial.parseFloat(); + r = constrain(r, -40, 40); + Serial.read(); + Serial.read(); + + rp = - r * 6.375 - abs(p) * p * 0.16; + lp = - r * 6.375 + abs(p) * p * 0.16; + if (r < 0) + { + if (lp > 0) + { + digitalWrite(MA1, 0); + digitalWrite(MA2, 1); + } + else + { + digitalWrite(MA1, 1); + digitalWrite(MA2, 0); + } + if (rp > 0) + { + digitalWrite(MB1, 0); + digitalWrite(MB2, 1); + } + else + { + digitalWrite(MB1, 1); + digitalWrite(MB2, 0); + } + + } + else + { + if (lp < 0) + { + digitalWrite(MA1, 1); + digitalWrite(MA2, 0); + } + else + { + digitalWrite(MA1, 0); + digitalWrite(MA2, 1); + } + if (rp < 0) + { + digitalWrite(MB1, 1); + digitalWrite(MB2, 0); + } + else + { + digitalWrite(MB1, 0); + digitalWrite(MB2, 1); + } + } + + + analogWrite(EA, constrain(abs(lp), 80, 255)); + analogWrite(EB, constrain(abs(rp), 35, 255)); + } +} diff --git a/neurosky-mindwave/README.md b/neurosky-mindwave/README.md new file mode 100644 index 0000000..49ad249 --- /dev/null +++ b/neurosky-mindwave/README.md @@ -0,0 +1 @@ +Simple experiment with NeuroSky Mindwave Mobile sensor. \ No newline at end of file diff --git a/neurosky-mindwave/neurosky-mindwave.ino b/neurosky-mindwave/neurosky-mindwave.ino new file mode 100644 index 0000000..cf0c139 --- /dev/null +++ b/neurosky-mindwave/neurosky-mindwave.ino @@ -0,0 +1,319 @@ +#include +#define LED 13 +#define BAUDRATE 57600 +#define DEBUGOUTPUT 0 + +/*#define GREENLED1 3 +#define GREENLED2 4 +#define GREENLED3 5 +#define YELLOWLED1 6 +#define YELLOWLED2 7 +#define YELLOWLED3 8 +#define YELLOWLED4 9 +#define REDLED1 10 +#define REDLED2 11 +#define REDLED3 12 + */ +#define powercontrol 10 +uint32_t eegPower[8]; +// checksum variables +byte generatedChecksum = 0; +byte checksum = 0; +int payloadLength = 0; +byte payloadData[64] = {0}; +byte poorQuality = 0; +byte blinkStrength = 0; +byte attention = 0; +byte meditation = 0; +byte batteryLevel = 0; +uint32_t delta; +uint32_t theta; +uint32_t lowAlpha; +uint32_t highAlpha; +uint32_t lowBeta; +uint32_t highBeta; +uint32_t lowGamma; +uint32_t midGamma; +// system variables +long lastReceivedPacket = 0; +boolean bigPacket = false; +SoftwareSerial BTSerial(2,3); +////////////////////////// +// Microprocessor Setup // +////////////////////////// +void setup() + +{ +/* pinMode(GREENLED1, OUTPUT); + pinMode(GREENLED2, OUTPUT); + pinMode(GREENLED3, OUTPUT); + pinMode(YELLOWLED1, OUTPUT); + pinMode(YELLOWLED2, OUTPUT); + pinMode(YELLOWLED3, OUTPUT); + pinMode(YELLOWLED4, OUTPUT); + pinMode(REDLED1, OUTPUT); + pinMode(REDLED2, OUTPUT); + pinMode(REDLED3, OUTPUT); + + pinMode(LED, OUTPUT); + */ + Serial.begin(BAUDRATE); + // USB + BTSerial.begin(57600); + Serial.begin(57600); +} + +//////////////////////////////// +// Read data from Serial UART // +//////////////////////////////// +byte ReadOneByte() + +{ + int ByteRead; + while(!BTSerial.available()); + ByteRead = BTSerial.read(); + + //Serial.write((char)ByteRead); // echo the same byte out the USB serial (for debug purposes) + return ByteRead; +} + +///////////// +//MAIN LOOP// +///////////// +void loop() + +{ + // Look for sync bytes + if(ReadOneByte() == 170) + { + if(ReadOneByte() == 170) + { + payloadLength = ReadOneByte(); + + if(payloadLength > 169) //Payload length can not be greater than 169 + return; + generatedChecksum = 0; + for(int i = 0; i < payloadLength; i++) + { + payloadData[i] = ReadOneByte(); //Read payload into memory + generatedChecksum += payloadData[i]; + } + + checksum = ReadOneByte(); //Read checksum byte from stream + generatedChecksum = 255 - generatedChecksum; //Take one's compliment of generated checksum + + if(checksum == generatedChecksum) + { + poorQuality = 200; + attention = 0; + meditation = 0; + + for(int i = 0; i < payloadLength; i++) + { // Parse the payload + switch (payloadData[i]) + { + case 2: + i++; + poorQuality = payloadData[i]; + bigPacket = true; + break; + case 4: + i++; + attention = payloadData[i]; + break; + case 5: + i++; + meditation = payloadData[i]; + break; + case 6: + i++; + batteryLevel = payloadData[i]; + case 16: + i++; + blinkStrength = payloadData[i]; + case 0x80: + i = i + 3; + break; + case 0x83: + i++; + for (int j = 0; j < 8; j++) { + eegPower[j] = ((uint32_t)payloadData[++i] << 16) | ((uint32_t)payloadData[++i] << 8) | (uint32_t)payloadData[++i]; + } + break; + default: + break; + } // switch + } // for loop + + + // *** Add your code here *** + delta = eegPower[0]; + theta = eegPower[1]; + lowAlpha = eegPower[2]; + highAlpha = eegPower[3]; + lowBeta = eegPower[4]; + highBeta = eegPower[5]; + lowGamma = eegPower[6]; + midGamma = eegPower[7]; + if(bigPacket) + { + /*Serial.print("PoorQuality: "); + Serial.print(poorQuality, DEC); + Serial.print(" Attention: "); + Serial.print(attention, DEC); + Serial.print(" Meditation: "); + Serial.print(meditation, DEC); + Serial.print(" Time since last packet: "); + Serial.print(millis() - lastReceivedPacket, DEC); + lastReceivedPacket = millis(); + Serial.print("\n"); + */ + Serial.print(attention,DEC); + Serial.print('\t'); + Serial.print(meditation,DEC); + Serial.print('\t'); + Serial.println(blinkStrength,DEC); + /*switch(attention / 10) + { + case 0: + digitalWrite(GREENLED1, HIGH); + digitalWrite(GREENLED2, LOW); + digitalWrite(GREENLED3, LOW); + digitalWrite(YELLOWLED1, LOW); + digitalWrite(YELLOWLED2, LOW); + digitalWrite(YELLOWLED3, LOW); + digitalWrite(YELLOWLED4, LOW); + digitalWrite(REDLED1, LOW); + digitalWrite(REDLED2, LOW); + digitalWrite(REDLED3, LOW); + break; + case 1: + digitalWrite(GREENLED1, HIGH); + digitalWrite(GREENLED2, HIGH); + digitalWrite(GREENLED3, LOW); + digitalWrite(YELLOWLED1, LOW); + digitalWrite(YELLOWLED2, LOW); + digitalWrite(YELLOWLED3, LOW); + digitalWrite(YELLOWLED4, LOW); + digitalWrite(REDLED1, LOW); + digitalWrite(REDLED2, LOW); + digitalWrite(REDLED3, LOW); + break; + case 2: + digitalWrite(GREENLED1, HIGH); + digitalWrite(GREENLED2, HIGH); + digitalWrite(GREENLED3, HIGH); + digitalWrite(YELLOWLED1, LOW); + digitalWrite(YELLOWLED2, LOW); + digitalWrite(YELLOWLED3, LOW); + digitalWrite(YELLOWLED4, LOW); + digitalWrite(REDLED1, LOW); + digitalWrite(REDLED2, LOW); + digitalWrite(REDLED3, LOW); + break; + case 3: + digitalWrite(GREENLED1, HIGH); + digitalWrite(GREENLED2, HIGH); + digitalWrite(GREENLED3, HIGH); + digitalWrite(YELLOWLED1, HIGH); + digitalWrite(YELLOWLED2, LOW); + digitalWrite(YELLOWLED3, LOW); + digitalWrite(YELLOWLED4, LOW); + digitalWrite(REDLED1, LOW); + digitalWrite(REDLED2, LOW); + digitalWrite(REDLED3, LOW); + break; + case 4: + digitalWrite(GREENLED1, HIGH); + digitalWrite(GREENLED2, HIGH); + digitalWrite(GREENLED3, HIGH); + digitalWrite(YELLOWLED1, HIGH); + digitalWrite(YELLOWLED2, HIGH); + digitalWrite(YELLOWLED3, LOW); + digitalWrite(YELLOWLED4, LOW); + digitalWrite(REDLED1, LOW); + digitalWrite(REDLED2, LOW); + digitalWrite(REDLED3, LOW); + break; + case 5: + digitalWrite(GREENLED1, HIGH); + digitalWrite(GREENLED2, HIGH); + digitalWrite(GREENLED3, HIGH); + digitalWrite(YELLOWLED1, HIGH); + digitalWrite(YELLOWLED2, HIGH); + digitalWrite(YELLOWLED3, HIGH); + digitalWrite(YELLOWLED4, LOW); + digitalWrite(REDLED1, LOW); + digitalWrite(REDLED2, LOW); + digitalWrite(REDLED3, LOW); + break; + case 6: + digitalWrite(GREENLED1, HIGH); + digitalWrite(GREENLED2, HIGH); + digitalWrite(GREENLED3, HIGH); + digitalWrite(YELLOWLED1, HIGH); + digitalWrite(YELLOWLED2, HIGH); + digitalWrite(YELLOWLED3, HIGH); + digitalWrite(YELLOWLED4, HIGH); + digitalWrite(REDLED1, LOW); + digitalWrite(REDLED2, LOW); + digitalWrite(REDLED3, LOW); + break; + case 7: + digitalWrite(GREENLED1, HIGH); + digitalWrite(GREENLED2, HIGH); + digitalWrite(GREENLED3, HIGH); + digitalWrite(YELLOWLED1, HIGH); + digitalWrite(YELLOWLED2, HIGH); + digitalWrite(YELLOWLED3, HIGH); + digitalWrite(YELLOWLED4, HIGH); + digitalWrite(REDLED1, HIGH); + digitalWrite(REDLED2, LOW); + digitalWrite(REDLED3, LOW); + break; + case 8: + digitalWrite(GREENLED1, HIGH); + digitalWrite(GREENLED2, HIGH); + digitalWrite(GREENLED3, HIGH); + digitalWrite(YELLOWLED1, HIGH); + digitalWrite(YELLOWLED2, HIGH); + digitalWrite(YELLOWLED3, HIGH); + digitalWrite(YELLOWLED4, HIGH); + digitalWrite(REDLED1, HIGH); + digitalWrite(REDLED2, HIGH); + digitalWrite(REDLED3, LOW); + break; + case 9: + digitalWrite(GREENLED1, HIGH); + digitalWrite(GREENLED2, HIGH); + digitalWrite(GREENLED3, HIGH); + digitalWrite(YELLOWLED1, HIGH); + digitalWrite(YELLOWLED2, HIGH); + digitalWrite(YELLOWLED3, HIGH); + digitalWrite(YELLOWLED4, HIGH); + digitalWrite(REDLED1, HIGH); + digitalWrite(REDLED2, HIGH); + digitalWrite(REDLED3, HIGH); + break; + case 10: + digitalWrite(GREENLED1, HIGH); + digitalWrite(GREENLED2, HIGH); + digitalWrite(GREENLED3, HIGH); + digitalWrite(YELLOWLED1, HIGH); + digitalWrite(YELLOWLED2, HIGH); + digitalWrite(YELLOWLED3, HIGH); + digitalWrite(YELLOWLED4, HIGH); + digitalWrite(REDLED1, HIGH); + digitalWrite(REDLED2, HIGH); + digitalWrite(REDLED3, HIGH); + break; + } */ + } + bigPacket = false; + } + else { + // Checksum Error + } // end if else for checksum + } // end if read 0xAA byte + } // end if read 0xAA byte +} diff --git a/pwm_vs_speed_plotter/README.md b/pwm_vs_speed_plotter/README.md new file mode 100644 index 0000000..d17dbf9 --- /dev/null +++ b/pwm_vs_speed_plotter/README.md @@ -0,0 +1 @@ +PWM vs Speed plotter for motor with encoder. \ No newline at end of file diff --git a/pwm_vs_speed_plotter/pwm_vs_speed_plotter.ino b/pwm_vs_speed_plotter/pwm_vs_speed_plotter.ino new file mode 100644 index 0000000..2ba39b4 --- /dev/null +++ b/pwm_vs_speed_plotter/pwm_vs_speed_plotter.ino @@ -0,0 +1,78 @@ + + + + +int encoderPin1 = 2; +int encoderPin2 = 3; + +volatile int A_lastEncoded = 0; +volatile long A_encoderValue = 0; +volatile int B_lastEncoded = 0; +volatile long B_encoderValue = 0; + +long A_lastencoderValue = 0; +long B_lastencoderValue = 0; + +int lastMSB = 0; +int lastLSB = 0; +ISR (PCINT1_vect){ + int MSB = digitalRead(encoderPin1); //MSB = most significant bit + int LSB = digitalRead(encoderPin2); //LSB = least significant bit + + int encoded = (MSB << 1) |LSB; //converting the 2 pin value to single number + int sum = (A_lastEncoded << 2) | encoded; //adding it to the previous encoded value + + if(sum == 0b1101 || sum == 0b0100 || sum == 0b0010 || sum == 0b1011) A_encoderValue ++; + if(sum == 0b1110 || sum == 0b0111 || sum == 0b0001 || sum == 0b1000) A_encoderValue --; + + A_lastEncoded = encoded; + } +void setup() { + Serial.begin (9600); + *digitalPinToPCMSK(A5) |= bit (digitalPinToPCMSKbit(A5)); // enable pin + PCIFR |= bit (digitalPinToPCICRbit(A5)); // clear any outstanding interrupt + PCICR |= bit (digitalPinToPCICRbit(A5)); + *digitalPinToPCMSK(A4) |= bit (digitalPinToPCMSKbit(A4)); // enable pin + PCIFR |= bit (digitalPinToPCICRbit(A4)); // clear any outstanding interrupt + PCICR |= bit (digitalPinToPCICRbit(A4)); + pinMode(encoderPin1, INPUT); + pinMode(encoderPin2, INPUT); + + digitalWrite(encoderPin1, HIGH); //turn pullup resistor on + digitalWrite(encoderPin2, HIGH); //turn pullup resistor on + int i; + for(i = 6; i<13; i++) + pinMode(i,OUTPUT); + digitalWrite(10,1); + digitalWrite(11,0); + + //call updateEncoder() when any high/low changed seen + //on interrupt 0 (pin 2), or interrupt 1 (pin 3) + attachInterrupt(0, updateEncoder, CHANGE); + attachInterrupt(1, updateEncoder, CHANGE); + +} + int j=100; +void loop(){ + //Do stuff here + analogWrite(9,j); + + Serial.print(j);Serial.print("\t");Serial.println(B_encoderValue); + j++;B_encoderValue=0; + delay(500); //just here to slow down the output, and show it will work even during a delay +if(j==256)return; +} + + +void updateEncoder(){ + int MSB = digitalRead(encoderPin1); //MSB = most significant bit + int LSB = digitalRead(encoderPin2); //LSB = least significant bit + + int encoded = (MSB << 1) |LSB; //converting the 2 pin value to single number + int sum = (B_lastEncoded << 2) | encoded; //adding it to the previous encoded value + + if(sum == 0b1101 || sum == 0b0100 || sum == 0b0010 || sum == 0b1011) B_encoderValue ++; + if(sum == 0b1110 || sum == 0b0111 || sum == 0b0001 || sum == 0b1000) B_encoderValue --; + + B_lastEncoded = encoded; + }