2017年11月8日水曜日

DRV8835を使った2輪倒立ロボの小改良 DRV8835IP6TKIRSp2.ino

//Inverted Pendulum Robot
//DRV8835 driver
//wheele dia = 55mm
//Battery: NiHM x 4
//MPU: ProMini 3.3V
//Gyro: MPU6050 (I2C pullup 4.7kohm)
//Motor driver: DRV8835 connected to Arduino pin 8,9,10,11
//Distance sensor: Sharp GP2Y0A21 connected to Arduino pin A1
//Trace sensor: Reflectance (distance from axis ~= 30mm) connected to Arduino pin A0
//IR sensor PL-IRM2161-XD1 connected to Arduino pin 2
#include <Wire.h>
#include <IRremote.h>
IRrecv receiveIR(2);
decode_results results;
void motor();
void drvMotorR(int pwm);
void drvMotorL(int pwm);
void drive();
void drvMotor(int pinPhase, int pinEnable, int pwm);
void pulseMotor(int n);
void calibrate();
void getBaselineAcc();
void getBaselineGyro();
bool standing();
bool laid();
bool upright();
void calcTarget();
void getDistance();
void getGyro();
void readGyro();
void getIR();
void monitorVoltage();
void selectMode();
void getBaselineGyro();
void resetMotor();
void resetVar();
void blinkLED(int n);
void checkVoltage();
void sendSerial();
int accX, accY, accZ, temp, gyroX, gyroY, gyroZ;
int counter=0;
unsigned long time1=0;
unsigned long time0=0;
float power, powerR, powerL;
float gyroZdps, accXg;
float varAng, varOmg, varSpd, varDst, varIang, varIdst;
float gyroZoffset, gyroYoffset, accXoffset;
float gyroZdata, gyroYdata, accXdata, accZdata;
float gyroLSB=1.0/131.0; // deg/sec
float accLSB=1.0/16384.0; // g
float clk = 0.01; // in sec,
unsigned long interval = (unsigned long) (clk*1000.0); // in msec
float cutoff = 0.1; // 2 * PI * f (f=Hz)
float yawPower;
float moveTarget, moveRate=0.0; //moveRate 0:stop, +:forward, -:backward
float moveStep = 0.0013;
float spinDestination, spinTarget, spinRate;
float spinStep = 30.0*clk;
float orientation;
float dirStep = 30.0 * clk; //30deg/sec
int state=-1;
int traceSensor;
bool serialMonitor=;
bool spinContinuous=false;
bool follow=false;
bool trace=false;
int ipowerR = 0;
int ipowerL = 0;
int motorRdir=0; //stop 1:+ -1:-
int motorLdir=0; //stop
float battFactor=1.0;
float bVolt;
float distance;
int traceThLevel=500;
int counterOverSpd;
float aveAccX=0.0;
float aveAccZ=0.0;
float Kang=120.0;
float Komg=2.8;
float KIang=2300.0;
float Kyaw=15.0;
float Kdst=100.0;
float Kspd=7.0;
float KIdst=0.0;
float mechFactorR=0.4;
float mechFactorL=0.4;
int backlashSpd=15;
int motorDeadPWM=0;
float maxSpd=250.0;
void setup() {
TCCR1B = TCCR1B & B11111000 | B00000001;
pinMode(2,INPUT); //IR
pinMode(8,OUTPUT); //APhase
pinMode(9,OUTPUT); //AEnable
pinMode(11,OUTPUT); //BPhase
pinMode(10,OUTPUT); //BEnable
pinMode(13, OUTPUT); //LED
Wire.begin();
Wire.setClock(50000L);
Wire.beginTransmission(0x68); //Gyro sensor
Wire.write(0x6B); // Power management register
Wire.write(0); // wake up MPU-6050
Wire.endTransmission(true);
receiveIR.enableIRIn(); // Start the receiver
Serial.begin(115200);
checkVoltage();
resetVar();
delay(50); //stabilize gyro
getBaselineGyro();
selectMode();
}
void loop() {
monitorVoltage();
getIR();
traceSensor = analogRead(A0);
getGyro();
getDistance();
switch (state) {
case -1:
calcTarget();
if (upright()) state =0;
break;
case 0: //baseline
calibrate();
state=1;
break;
case 1: //run
if (standing() && counterOverSpd <= 30) {
calcTarget();
drive();
}
else {
sendSerial();
resetMotor();
resetVar();
if (upright()) state=0;
else state=9;
}
break;
case 2: //wait until upright
if (upright()) state=0;
break;
case 9: //fell
if (laid()) state=2;
break;
}
counter += 1;
if (counter >= 100) {
counter = 0;
if (serialMonitor) sendSerial();
}
do time1 = millis();
while (time1 - time0 < interval);
time0 = time1;
}
void getIR() {
if (receiveIR.decode(&results)) {
// Serial.println(results.value, HEX);
switch (results.value & 0x0000FFFF) {
case 0x728D: //LAPIO up
case 0x7C83: //TOSHIBA up
moveRate=4.0; //forward
break;
case 0xF20D: //LAPIO down
case 0xFC03: //TOSHIBA down
moveRate=-4.0; //backward
break;
case 0xFA05: //LAPIO&TOSHIBA left = spin left
spinDestination -= 30.0;
break;
case 0xDA25: //LAPIO&TOSHIBA right = spin right
spinDestination += 30.0;
break;
case 0xBC43: //LAPIO&TOSHIBA OK = stop
trace=false;
follow=false;
spinContinuous=false;
moveRate=0.0;
spinDestination = spinTarget;
break;
case 0x807F: //LAPIO&TOSHIBA button 1
spinContinuous=true;
follow=false;
trace=false;
moveRate=3.0;
spinStep=0.30;
break;
}
receiveIR.resume(); // Receive the next value
}
}
void calcTarget() {
if (trace) {
float tmp = (float) (traceSensor - traceThLevel);
spinTarget += 0.001 * tmp;
moveRate = 2.0;
}
else {
if (spinContinuous) {
spinTarget += spinStep;
}
else {
if (spinTarget < spinDestination) spinTarget += spinStep;
if (spinTarget > spinDestination) spinTarget -= spinStep;
}
}
if (follow) {
if (distance > 180.0) moveRate=2.8;
else if (distance > 130.0) moveRate=2.4;
else if (distance > 90.0) moveRate=0.0;
else moveRate=-1.0;
}
moveTarget += moveStep * moveRate;
}
void drive() {
varSpd += power * clk;
varDst += Kdst * (varSpd * clk - moveTarget);
varIang += KIang * varAng * clk;
varIdst += KIdst * varDst * clk;
power = varIang + varIdst + varDst + (Kspd * varSpd) + (Kang * varAng) + (Komg * varOmg);
if (abs(power) > 3000.0) counterOverSpd += 1;
else counterOverSpd =0;
if (counterOverSpd > 30) return;
yawPower = (orientation - spinTarget) * Kyaw;
powerR = power + yawPower;
powerL = power - yawPower;
motor();
}
void motor() {
ipowerR = (int) (constrain(powerR * mechFactorR * battFactor, -maxSpd, maxSpd));
if (ipowerR > 0) {
if (motorRdir == 1) drvMotorR(ipowerR + motorDeadPWM);
else drvMotorR(ipowerR + motorDeadPWM + backlashSpd); //compensate backlash
motorRdir = 1;
}
else if (ipowerR < 0) {
if (motorRdir == -1) drvMotorR(ipowerR - motorDeadPWM);
else drvMotorR(ipowerR - motorDeadPWM - backlashSpd);
motorRdir = -1;
}
else {
drvMotorR(0);
motorRdir = 0;
}
ipowerL = (int) (constrain(powerL * mechFactorL * battFactor, -maxSpd, maxSpd));
if (ipowerL > 0) {
if (motorLdir == 1) drvMotorL(ipowerL + motorDeadPWM);
else drvMotorL(ipowerL + motorDeadPWM + backlashSpd); //compensate backlash
motorLdir = 1;
}
else if (ipowerL < 0) {
if (motorLdir == -1) drvMotorL(ipowerL - motorDeadPWM);
else drvMotorL(ipowerL - motorDeadPWM - backlashSpd);
motorLdir = -1;
}
else {
drvMotorL(0);
motorLdir = 0;
}
}
void getDistance() { //distance in mm
int dist=analogRead(A1);
if (dist>0) distance = constrain(95000.0 / ((float) dist) -30.0, 60.0, 400.0);
else distance = -1.0;
}
void getGyro() {
readGyro();
gyroZdps = (gyroZdata - gyroZoffset) * gyroLSB;
varOmg = (gyroYdata - gyroYoffset) * gyroLSB; // unit:deg/sec
accXg = (accXdata - accXoffset) * accLSB; //unit:g
orientation += gyroZdps * clk;
varAng += (varOmg + (accXg * 57.3 - varAng) * cutoff ) * clk;
}
void readGyro() {
Wire.beginTransmission(0x68);
Wire.write(0x3B);
Wire.endTransmission(false); //enable incremental read
Wire.requestFrom(0x68, 14, (int)true); //used to be requestFrom(0x68, 14, true) but got warning.
accX=Wire.read()<<8|Wire.read(); //0x3B
accY=Wire.read()<<8|Wire.read(); //0x3D
accZ=Wire.read()<<8|Wire.read(); //0x3F
temp=Wire.read()<<8|Wire.read(); //0x41
gyroX=Wire.read()<<8|Wire.read(); //0x43
gyroY=Wire.read()<<8|Wire.read(); //0x45
gyroZ=Wire.read()<<8|Wire.read(); //0x47
gyroZdata = (float) gyroY;
gyroYdata = (float) gyroZ;
accXdata = -(float) accX;
aveAccX = aveAccX * 0.9 + accXdata * 0.1;
accZdata = (float) accY;
aveAccZ = aveAccZ * 0.9 + accZdata * 0.1;
}
bool laid() {
if (abs(aveAccX) >13000.0) return true;
else return false;
}
bool upright() {
if (abs(aveAccZ) >13000.0) return true;
else return false;
}
bool standing() {
if (abs(aveAccZ) > 10000.0 && abs(varAng) < 40.0) return true;
else return false;
}
void calibrate() {
resetVar();
resetMotor();
delay(2000);
if (serialMonitor) sendSerial();
pulseMotor(1);
delay(100);
if (serialMonitor) sendSerial();
getBaselineAcc();
}
void getBaselineAcc() {
accXoffset=0.0;
for (int i=1; i <= 30; i++) {
readGyro();
accXoffset += accXdata;
delay(20);
}
accXoffset /= 30;
}
void getBaselineGyro() {
gyroYoffset=gyroZoffset=0.0;
for (int i=1; i <= 30; i++) {
readGyro();
gyroYoffset += gyroYdata;
gyroZoffset += gyroZdata;
delay(20);
}
gyroZoffset /= 30;
gyroYoffset /= 30;
}
void resetVar() {
power=0.0;
moveTarget=0.0;
spinDestination=0.0;
spinTarget=0.0;
spinRate=0.0;
orientation=0.0;
varAng=0.0;
varOmg=0.0;
varDst=0.0;
varSpd=0.0;
varIang=0.0;
varIdst=0.0;
}
void resetMotor() {
drvMotorR(0);
drvMotorL(0);
counterOverSpd=0;
sendSerial();
}
void checkVoltage() {
bVolt = ((float) analogRead(A2)) / 1023.0 * 6.6;
if (bVolt > 5.0) blinkLED(3);
else if (bVolt > 4.8) blinkLED(2);
else if (bVolt > 4.6) blinkLED(1);
else blinkLED(100);
}
void blinkLED(int n) {
for (int i=0; i<n; i++) {
digitalWrite(13,HIGH);
delay(10);
digitalWrite(13,LOW);
delay(200);
}
}
void monitorVoltage() {
digitalWrite(13, LOW);
bVolt = ((float) analogRead(A2)) / 1023.0 * 6.6;
battFactor = 5.0 / bVolt;
if (bVolt<=4.4) {
digitalWrite(13, HIGH);
if (serialMonitor) {
Serial.print("Batt=");
Serial.println(bVolt);
}
}
}
void selectMode() {
getDistance();
traceSensor = analogRead(A0);
if (distance > 100.0) {
if (traceSensor > traceThLevel) { //follow & trace
trace=true;
follow=true;
blinkLED(3);
}
else { //stand still
trace=false;
follow=false;
blinkLED(1);
}
}
else if (distance > 0.0) { //circle
follow=false;
trace=false;
moveRate=3.0;
spinStep=0.30;
spinContinuous=true;
blinkLED(5);
}
}
void pulseMotor(int n) {
for (int i=0; i<n; i++) {
drvMotorR(motorDeadPWM+50);
delay(15);
drvMotorR(0);
delay(50);
drvMotorR(-motorDeadPWM-50);
delay(15);
drvMotorR(0);
delay(200);
}
}
void drvMotorR(int pwm) {
drvMotor(8,9, constrain(pwm, -255, 255));
}
void drvMotorL(int pwm) {
drvMotor(11,10, constrain(pwm, -255, 255));
}
void drvMotor(int pinPhase, int pinEnable, int pwm) {
if (pwm>=0) {
// digitalWrite(pinEnable,LOW);
// delayMicroseconds(10);
digitalWrite(pinPhase,HIGH);
analogWrite(pinEnable,pwm);
}
else {
// digitalWrite(pinEnable,LOW);
// delayMicroseconds(10);
digitalWrite(pinPhase,LOW);
analogWrite(pinEnable,-pwm);
}
}
void sendSerial () {
Serial.print(millis()-time0);
Serial.print(" state=");Serial.print(state);
// Serial.print(" dist=");Serial.print(distance);
// Serial.print(" accX="); Serial.print(accXdata);
// Serial.print(" accOfs=");Serial.print(accXoffset);
// Serial.print(" gyYoffset="); Serial.print(gyroYoffset);
// Serial.print(" ang=");Serial.print(varAng);
// Serial.print(" temp = "); Serial.print(temp/340.0+36.53);
// Serial.print(" Omg="); Serial.print(varOmg);
// Serial.print(" power="); Serial.print(power);
// Serial.print(" Dst="); Serial.print(varDst);
Serial.print(" bVolt="); Serial.print(bVolt);
// Serial.print(" Iang="); Serial.print(varIang);
// Serial.print(" mTarg="); Serial.print(moveTarget);
// Serial.print(" follow="); Serial.print(follow);
// Serial.print(" interval="); Serial.print(interval);
Serial.print(" ");
Serial.println(millis()-time0);
}

2017年11月5日日曜日

DRV8835で2輪倒立ロボ DRV8835IP6TKIRSp.ino

//Inverted Pendulum Robot
//DRV8835 driver
//wheele dia = 55mm
//Battery: NiHM x 4
//MPU: ProMini 3.3V
//Gyro: MPU6050 (I2C pullup 4.7kohm)
//Motor driver: DRV8835 connected to Arduino pin 4,5,6,7
//Distance sensor: Sharp GP2Y0A21 connected to Arduino pin A1
//Trace sensor: Reflectance (distance from axis ~= 30mm) connected to Arduino pin A0
//IR sensor PL-IRM2161-XD1 connected to Arduino pin 2
#include <Wire.h>
#include <IRremote.h>
IRrecv receiveIR(2);
decode_results results;
void motor();
void drvMotorR(int pwm);
void drvMotorL(int pwm);
void drive();
void drvMotor(int pinPhase, int pinEnable, int pwm);
void pulseMotor(int n);
void calibrate();
void getBaselineAcc();
void getBaselineGyro();
bool standing();
bool laid();
bool upright();
void calcTarget();
void getDistance();
void getGyro();
void readGyro();
void getIR();
void monitorVoltage();
void selectMode();
void getBaselineGyro();
void resetMotor();
void resetVar();
void blinkLED(int n);
void checkVoltage();
void sendSerial();
int accX, accY, accZ, temp, gyroX, gyroY, gyroZ;
int counter=0;
unsigned long time1=0;
unsigned long time0=0;
float power, powerR, powerL;
float gyroZdps, accXg;
float varAng, varOmg, varSpd, varDst, varIang, varIdst;
float gyroZoffset, gyroYoffset, accXoffset;
float gyroZdata, gyroYdata, accXdata, accZdata;
float gyroLSB=1.0/131.0; // deg/sec
float accLSB=1.0/16384.0; // g
float clk = 0.01; // in sec,
unsigned long interval = (unsigned long) (clk*1000.0); // in msec
float cutoff = 0.1; // 2 * PI * f (f=Hz)
float yawPower;
float moveTarget, moveRate=0.0; //moveRate 0:stop, +:forward, -:backward
float moveStep = 0.0013;
float spinDestination, spinTarget, spinRate;
float spinStep = 30.0*clk;
float orientation;
float dirStep = 30.0 * clk; //30deg/sec
int state=-1;
int traceSensor;
bool serialMonitor=false;
bool spinContinuous=false;
bool follow=false;
bool trace=false;
int ipowerR = 0;
int ipowerL = 0;
int motorRdir=0; //stop 1:+ -1:-
int motorLdir=0; //stop
float battFactor=1.0;
float bVolt;
float distance;
int traceThLevel=500;
int counterOverSpd;
float aveAccX=0.0;
float aveAccZ=0.0;
float Kang=120.0;
float Komg=2.4;
float KIang=1800.0;
float Kyaw=15.0;
float Kdst=100.0;
float Kspd=7.0;
float KIdst=0.0;
float mechFactorR=0.6;
float mechFactorL=0.6;
int backlashSpd=15;
int motorDeadPWM=0;
float maxSpd=250.0;
void setup() {
pinMode(2,INPUT); //IR
pinMode(4,OUTPUT); //APhase
pinMode(5,OUTPUT); //AEnable
pinMode(6,OUTPUT); //BEnable
pinMode(7,OUTPUT); //BPhase
pinMode (13, OUTPUT); //LED
Wire.begin();
Wire.setClock(50000L);
Wire.beginTransmission(0x68); //Gyro sensor
Wire.write(0x6B); // Power management register
Wire.write(0); // wake up MPU-6050
Wire.endTransmission(true);
receiveIR.enableIRIn(); // Start the receiver
Serial.begin(115200);
checkVoltage();
resetVar();
delay(50); //stabilize gyro
getBaselineGyro();
selectMode();
}
void loop() {
monitorVoltage();
getIR();
traceSensor = analogRead(A0);
getGyro();
getDistance();
switch (state) {
case -1:
calcTarget();
if (upright()) state =0;
break;
case 0: //baseline
calibrate();
state=1;
break;
case 1: //run
if (standing() && counterOverSpd <= 30) {
calcTarget();
drive();
}
else {
sendSerial();
resetMotor();
resetVar();
if (upright()) state=0;
else state=9;
}
break;
case 2: //wait until upright
if (upright()) state=0;
break;
case 9: //fell
if (laid()) state=2;
break;
}
counter += 1;
if (counter >= 100) {
counter = 0;
if (serialMonitor) sendSerial();
}
do time1 = millis();
while (time1 - time0 < interval);
time0 = time1;
}
void getIR() {
if (receiveIR.decode(&results)) {
// Serial.println(results.value, HEX);
switch (results.value & 0x0000FFFF) {
case 0x728D: //LAPIO up
case 0x7C83: //TOSHIBA up
moveRate=4.0; //forward
break;
case 0xF20D: //LAPIO down
case 0xFC03: //TOSHIBA down
moveRate=-4.0; //backward
break;
case 0xFA05: //LAPIO&TOSHIBA left = spin left
spinDestination -= 30.0;
break;
case 0xDA25: //LAPIO&TOSHIBA right = spin right
spinDestination += 30.0;
break;
case 0xBC43: //LAPIO&TOSHIBA OK = stop
trace=false;
follow=false;
spinContinuous=false;
moveRate=0.0;
spinDestination = spinTarget;
break;
case 0x807F: //LAPIO&TOSHIBA button 1
spinContinuous=true;
follow=false;
trace=false;
moveRate=3.0;
spinStep=0.30;
break;
}
receiveIR.resume(); // Receive the next value
}
}
void calcTarget() {
if (trace) {
float tmp = (float) (traceSensor - traceThLevel);
spinTarget += 0.001 * tmp;
moveRate = 2.0;
}
else {
if (spinContinuous) {
spinTarget += spinStep;
}
else {
if (spinTarget < spinDestination) spinTarget += spinStep;
if (spinTarget > spinDestination) spinTarget -= spinStep;
}
}
if (follow) {
if (distance > 180.0) moveRate=2.8;
else if (distance > 130.0) moveRate=2.4;
else if (distance > 90.0) moveRate=0.0;
else moveRate=-1.0;
}
moveTarget += moveStep * moveRate;
}
void drive() {
varSpd += power * clk;
varDst += Kdst * (varSpd * clk - moveTarget);
varIang += KIang * varAng * clk;
varIdst += KIdst * varDst * clk;
power = varIang + varIdst + varDst + (Kspd * varSpd) + (Kang * varAng) + (Komg * varOmg);
if (abs(power) > 3000.0) counterOverSpd += 1;
else counterOverSpd =0;
if (counterOverSpd > 30) return;
yawPower = (orientation - spinTarget) * Kyaw;
powerR = power + yawPower;
powerL = power - yawPower;
motor();
}
void motor() {
ipowerR = (int) (constrain(powerR * mechFactorR * battFactor, -maxSpd, maxSpd));
if (ipowerR > 0) {
if (motorRdir == 1) drvMotorR(ipowerR + motorDeadPWM);
else drvMotorR(ipowerR + motorDeadPWM + backlashSpd); //compensate backlash
motorRdir = 1;
}
else if (ipowerR < 0) {
if (motorRdir == -1) drvMotorR(ipowerR - motorDeadPWM);
else drvMotorR(ipowerR - motorDeadPWM - backlashSpd);
motorRdir = -1;
}
else {
drvMotorR(0);
motorRdir = 0;
}
ipowerL = (int) (constrain(powerL * mechFactorL * battFactor, -maxSpd, maxSpd));
if (ipowerL > 0) {
if (motorLdir == 1) drvMotorL(ipowerL + motorDeadPWM);
else drvMotorL(ipowerL + motorDeadPWM + backlashSpd); //compensate backlash
motorLdir = 1;
}
else if (ipowerL < 0) {
if (motorLdir == -1) drvMotorL(ipowerL - motorDeadPWM);
else drvMotorL(ipowerL - motorDeadPWM - backlashSpd);
motorLdir = -1;
}
else {
drvMotorL(0);
motorLdir = 0;
}
}
void getDistance() { //distance in mm
int dist=analogRead(A1);
if (dist>0) distance = constrain(95000.0 / ((float) dist) -30.0, 60.0, 400.0);
else distance = 0.0;
}
void getGyro() {
readGyro();
gyroZdps = (gyroZdata - gyroZoffset) * gyroLSB;
varOmg = (gyroYdata - gyroYoffset) * gyroLSB; // unit:deg/sec
accXg = (accXdata - accXoffset) * accLSB; //unit:g
orientation += gyroZdps * clk;
varAng += (varOmg + (accXg * 57.3 - varAng) * cutoff ) * clk;
}
void readGyro() {
Wire.beginTransmission(0x68);
Wire.write(0x3B);
Wire.endTransmission(false); //enable incremental read
Wire.requestFrom(0x68, 14, (int)true); //used to be requestFrom(0x68, 14, true) but got warning.
accX=Wire.read()<<8|Wire.read(); //0x3B
accY=Wire.read()<<8|Wire.read(); //0x3D
accZ=Wire.read()<<8|Wire.read(); //0x3F
temp=Wire.read()<<8|Wire.read(); //0x41
gyroX=Wire.read()<<8|Wire.read(); //0x43
gyroY=Wire.read()<<8|Wire.read(); //0x45
gyroZ=Wire.read()<<8|Wire.read(); //0x47
gyroZdata = (float) gyroY;
gyroYdata = (float) gyroZ;
accXdata = -(float) accX;
aveAccX = aveAccX * 0.9 + accXdata * 0.1;
accZdata = (float) accY;
aveAccZ = aveAccZ * 0.9 + accZdata * 0.1;
}
bool laid() {
if (abs(aveAccX) >13000.0) return true;
else return false;
}
bool upright() {
if (abs(aveAccZ) >13000.0) return true;
else return false;
}
bool standing() {
if (abs(aveAccZ) > 10000.0 && abs(varAng) < 40.0) return true;
else return false;
}
void calibrate() {
resetVar();
resetMotor();
delay(2000);
if (serialMonitor) sendSerial();
pulseMotor(1);
delay(1000);
if (serialMonitor) sendSerial();
getBaselineAcc();
}
void getBaselineAcc() {
accXoffset=0.0;
// traceThLevel=0;
for (int i=1; i <= 30; i++){
readGyro();
accXoffset += accXdata;
// traceThLevel += analogRead(A0);
delay(20);
}
accXoffset /= 30;
// traceThLevel /= 30;
}
void getBaselineGyro() {
gyroYoffset=gyroZoffset=0.0;
for (int i=1; i <= 30; i++){
readGyro();
gyroYoffset += gyroYdata;
gyroZoffset += gyroZdata;
delay(20);
}
gyroZoffset /= 30;
gyroYoffset /= 30;
}
void resetVar() {
power=0.0;
moveTarget=0.0;
moveRate=0.0;
spinDestination=0.0;
spinTarget=0.0;
spinRate=0.0;
orientation=0.0;
varAng=0.0;
varOmg=0.0;
varDst=0.0;
varSpd=0.0;
varIang=0.0;
varIdst=0.0;
}
void resetMotor() {
drvMotorR(0);
drvMotorL(0);
counterOverSpd=0;
sendSerial();
}
void checkVoltage() {
bVolt = ((float) analogRead(A2)) / 1023.0 * 6.6;
if (bVolt > 5.0) blinkLED(3);
else if (bVolt > 4.8) blinkLED(2);
else if (bVolt > 4.6) blinkLED(1);
else blinkLED(100);
}
void blinkLED(int n) {
for (int i=0; i<n; i++) {
digitalWrite(13,HIGH);
delay(10);
digitalWrite(13,LOW);
delay(200);
}
}
void monitorVoltage() {
digitalWrite(13, LOW);
bVolt = ((float) analogRead(A2)) / 1023.0 * 6.6;
battFactor = 5.0 / bVolt;
if (bVolt<=4.4) {
digitalWrite(13, HIGH);
if (serialMonitor) {
Serial.print("Batt=");Serial.println(bVolt);
}
}
}
void selectMode() {
getDistance();
traceSensor = analogRead(A0);
if (distance > 100.0) {
if (traceSensor > traceThLevel) { //follow & trace
trace=true;
follow=true;
blinkLED(3);
}
else { //stand still
trace=false;
follow=false;
blinkLED(1);
}
}
else if (distance >=0.0) { //circle
follow=false;
trace=false;
moveRate=3.0;
spinStep=0.30;
spinContinuous=true;
blinkLED(5);
}
else { //no distance sensor
follow=false;
if (traceSensor > 500) { //trace only
trace=true;
blinkLED(2);
}
else { //stand still
trace=false;
blinkLED(1);
}
}
}
void pulseMotor(int n) {
for (int i=0; i<n; i++) {
drvMotorR(motorDeadPWM+50);
delay(15);
drvMotorR(0);
delay(50);
drvMotorR(-motorDeadPWM-50);
delay(15);
drvMotorR(0);
delay(200);
}
}
void drvMotorR(int pwm) {
drvMotor(4,5, constrain(pwm, -255, 255));
}
void drvMotorL(int pwm) {
drvMotor(7,6, constrain(pwm, -255, 255));
}
void drvMotor(int pinPhase, int pinEnable, int pwm) {
if (pwm>=0) {
// digitalWrite(pinEnable,LOW);
digitalWrite(pinPhase,HIGH);
analogWrite(pinEnable,pwm);
}
else {
// digitalWrite(pinEnable,LOW);
digitalWrite(pinPhase,LOW);
analogWrite(pinEnable,-pwm);
}
}
void sendSerial () {
Serial.print(millis()-time0);
Serial.print(" state=");Serial.print(state);
// Serial.print(" dist=");Serial.print(distance);
// Serial.print(" sens="); Serial.print(traceSensor);
Serial.print(" accX="); Serial.print(accXdata);
Serial.print(" accOfs=");Serial.print(accXoffset);
// Serial.print(" gyYoffset="); Serial.print(gyroYoffset);
Serial.print(" ang=");Serial.print(varAng);
// Serial.print(" temp = "); Serial.print(temp/340.0+36.53);
Serial.print(" Omg="); Serial.print(varOmg);
// Serial.print(" power="); Serial.print(power);
Serial.print(" Dst="); Serial.print(varDst);
Serial.print(" bVolt="); Serial.print(bVolt);
Serial.print(" Iang="); Serial.print(varIang);
// Serial.print(" mTarg="); Serial.print(moveTarget);
// Serial.print(" follow="); Serial.print(follow);
// Serial.print(" interval="); Serial.print(interval);
Serial.print(", ");
Serial.print(millis()-time0);
Serial.println();
}

2017年8月7日月曜日

棒テンプ時計の精度アップ Folio Clock v61

//(C) Kirakulabo 2017
//DRV8835 connected to D2,3,4,5,6 (MODE pin to GND)
//MPU6050 (I2C) gyro and acc sensor
//MB1422 (I2C) mag sensor with 3.3V power
//AQM0802 (I2C) LCD driver
//Touch sens antenna connected to A0
//LED connected to D9
//1H = 64 escapment wheel turn
//1 escapment turn = 15 tic
//tact time 100ms
//folio calc every 1 turn of ecapement
//V60 switch between Gyro and Mag,
//V61 removed nRF24
//#define NOMOTOR //define this to simulate motor
//#define GYRO //if defined, gyro(MPU6050). if not, mag(BM1422)
#include <ST7032.h>
#include <RTC.h>
#include <Wire.h>
#define TOUCHPIN A0
#define LED 9
#define DRVPWR 2
#define DRVAIN1 3
#define DRVAIN2 4
#define DRVBIN1 5
#define DRVBIN2 6
#define NHISTORY 64
#define BM14 0x0E
ST7032 lcd;
boolean serialMon=false;
volatile long rtcTic=1;
long rtcLastLoop=1;
int dataX, dataY, dataZ;
int angle, angLast; //1deg=10
int angMax, angMin, angThresh;
int angHyst=50; //5deg
int omegaHysteresis=2000;
int folioDir, folioDirLast;
unsigned long loopTime;
long rtcLastFolioMove;
long tFolio;
long tFolioCumulativeError=0;
long cFolio=-1;
int stepNumber=0;
int stepNumberTarget=0;
long rtcEscWheelHistory[NHISTORY];
long nEscapeTurn;
long tFolioRateError=0;
long nCumulativeStep=0;
long tFolioErrorMax=0;
long tFolioErrorMin=0;
boolean lcdEnabled=true;
int lcdOnTime=900; //90 sec
int lcdTimer;
int steps;
int accY, gyroY;
int gyroData, omega;
void setup() {
pinMode(DRVPWR, OUTPUT);
pinMode(DRVAIN1, OUTPUT);
pinMode(DRVAIN2, OUTPUT);
pinMode(DRVBIN1, OUTPUT);
pinMode(DRVBIN2, OUTPUT);
pinMode(LED, OUTPUT);
digitalWrite(LED, HIGH);
digitalWrite(DRVPWR, LOW);
#ifdef GYRO
initGyro();
#endif
setPowerManagementMode(PM_STOP_MODE);
rtc_init();
rtc_attach_constant_period_interrupt_handler(rtcIntHandler);
rtc_set_constant_period_interrupt_time(RTC_CONSTANT_PERIOD_TIME_1SECOND);
rtc_constant_period_interrupt_on();
delay(100);
initMag();
lcd.begin(8,2); //(c,r)
delay(1000);
startup();
if (serialMon) {
Serial.begin(115200);
Serial.println("Ready");
Serial.flush(); //this allows serial comm while CPU is in PM_STOP_MODE
}
}
void loop() {
loopTime=millis();
#ifdef GYRO
getOmega();
if (omega>omegaHysteresis) folioDir=1;
if (omega<-omegaHysteresis) folioDir=-1;
#else
getAngle();
if (angle>angThresh+angHyst) folioDir=1;
if (angle<angThresh-angHyst) folioDir=-1;
#endif
if (folioDir==1 && folioDirLast==-1) folioCycle();
folioDirLast=folioDir;
if (rtcTic != rtcLastLoop) { //executed very 1 sec
rtcLastLoop=rtcTic;
if (lcdEnabled) {
tFolioCumulativeError=tFolio-rtcTic;
lcdDispStatus();
}
}
delay(50);
touchSense();
while(millis()-loopTime<100) delay(2);
}
void rtcIntHandler() {
rtcTic++;
}
void startup() {
lcd.setContrast(25);
lcdOn();
lcdDispText(0,0, "STEPPER ");
lcdDispText(0,1, "TRAINING");
delay(1000);
for (int i=0; i<25; i++) {
stepNumberTarget+=10;
motorStep();
delay(200);
}
stepNumber=200;
stepNumberTarget=0;
motorStep();
nCumulativeStep=0;
lcdDispText(0,0, "WAIT FOR");
lcdDispText(0,1, "FOLIO MV");
#ifdef GYRO
do {
getOmega();
} while (omega<=omegaHysteresis);
delay(10000);
#else
waitFolioMotion();
lcdDispText(0,0, "CALC ANG");
lcdDispText(0,1, "THRESHLD");
getThresh();
#endif
lcdDispText(0,0, "OK 000");
lcdDispText(0,1, "0000 000");
}
void folioCycle() {
digitalWrite(LED, LOW);
delay(1);
digitalWrite(LED, HIGH);
cFolio++;
if (cFolio<0) return;
if (cFolio==0) rtcTic=0;
long rtcTicAtCycle=rtcTic;
rtcLastFolioMove=rtcTicAtCycle;
tFolio=cFolio*15/4; //escapement 1tic=3.75sec
tFolioCumulativeError=tFolio-rtcTicAtCycle;
if (tFolioCumulativeError>tFolioErrorMax) tFolioErrorMax=tFolioCumulativeError;
if (tFolioCumulativeError<tFolioErrorMin) tFolioErrorMin=tFolioCumulativeError;
lcdDispFolioTic(4,1);
lcdDispNum34(4,0, tFolioCumulativeError);
if (abs(tFolioCumulativeError)>300) return; //if error > 5min, do not move motor nor send RF
if (cFolio%15==0) { //every 15 turn =~1min
nEscapeTurn=cFolio/15;
rtcEscWheelHistory[nEscapeTurn%NHISTORY]=rtcTicAtCycle;
if (nEscapeTurn>=4) tFolioRateError=225-(rtcTicAtCycle-rtcEscWheelHistory[(nEscapeTurn+NHISTORY-4)%NHISTORY]); //gain against 4 escape turns ago (=~4min)
else tFolioRateError=tFolioCumulativeError;
lcdDispNum3(5,1, tFolioRateError);
if (abs(tFolioCumulativeError)<=300) { //if error > 5min, do not move motor
if (tFolioRateError*tFolioCumulativeError >=0) steps=(int) ((tFolioRateError*2)/3 + tFolioCumulativeError/5);
else steps=0;
stepNumberTarget = constrain(stepNumber+steps, -200, 200);
steps = stepNumberTarget-stepNumber;
if (stepNumberTarget != stepNumber) {
motorStep();
lcdDispNum4(0,0, nCumulativeStep);
}
}
}
}
void touchSense() {
int adata1=analogRead(TOUCHPIN); //touch sensor
delay(1);
int adata2=analogRead(TOUCHPIN);
if (abs(adata1-adata2) > 18 || adata1+adata2 < 800) { //touch detect threshold
if (!lcdEnabled) lcdOn();
lcdTimer=lcdOnTime;
}
else {
if (lcdEnabled) lcdTimer--;
if (lcdTimer<=0) lcdOff();
}
}
void lcdOn() {
lcdTimer=lcdOnTime;
lcd.display();
lcdEnabled=true;
lcdDispNum4(0,0, nCumulativeStep);
lcdDispNum4(0,1, tFolioErrorMax);
lcdDispNum34(4,0, tFolioCumulativeError);
lcdDispNum3(5,1, tFolioRateError);
}
void lcdOff() {
lcd.noDisplay();
lcdEnabled=false;
}
void lcdDispText(int col, int row, String s) {
if (!lcdEnabled) return;
lcd.setCursor(col,row);
lcd.print(s);
}
void lcdDispStatus() {
if (rtcTic-rtcLastFolioMove > 6) lcdDispNum34(4,0, tFolioCumulativeError); //disp LCD even if folio not moving
if (rtcTic%8==0) {
lcdDispNum4(0,0, nCumulativeStep);
lcdDispNum4(0,1, tFolioErrorMax);
}
else if (rtcTic%8==4) {
if (rtcTic<43200) {
lcdDispNum3(0,0, rtcTic/60);
lcdDispText(3,0, "M");
}
else if (rtcTic<3600000) {
lcdDispNum3(0,0, rtcTic/3600);
lcdDispText(3,0, "H");
}
else {
lcdDispNum3(0,0, rtcTic/86400);
lcdDispText(3,0, "D");
}
lcdDispNum4(0,1, tFolioErrorMin);
}
}
void lcdDispNum4(int col, int row, long n) {
if (!lcdEnabled) return;
char pNum[6];
if (n>999999) sprintf(pNum, "%s", ">1+6");
else if (n>99999) sprintf(pNum, "%02dE4", n/10000);
else if (n>9999) sprintf(pNum, "%02dE3", n/1000);
else if (n>=0) sprintf(pNum, "%04d", n);
else if (n>=-999) sprintf(pNum, "%04d", n);
else if (n>=-9999) sprintf(pNum, "%02d-2", -n/100);
else if (n>=-99999) sprintf(pNum, "%02d-3", -n/1000);
else if (n>=-999999) sprintf(pNum, "%02d-4", -n/10000);
else sprintf(pNum, "%s", "<1-6");
lcd.setCursor(col,row);
lcd.print(pNum);
}
void lcdDispNum3(int col, int row, long n) {
if (!lcdEnabled) return;
char pNum[6];
if (n>999) sprintf(pNum, "%s", ">k+");
else if (n>=-99) sprintf(pNum, "%03d", n);
else if (n>=-999) sprintf(pNum, "%02d-", -n/10);
else sprintf(pNum, "%s", "<k-");
lcd.setCursor(col,row);
lcd.print(pNum);
}
void lcdDispNum34(int col, int row, long n) {
if (!lcdEnabled) return;
char pNum[6];
if (n>999) sprintf(pNum, "%s", " >k+");
else if (n>=-99) sprintf(pNum, " %03d", n);
else if (n>=-999) sprintf(pNum, "%04d", n);
else sprintf(pNum, "%s", " <k-");
lcd.setCursor(col,row);
lcd.print(pNum);
}
void lcdDispFolioTic(int col, int row) {
if (!lcdEnabled) return;
lcd.setCursor(col, row);
char n=cFolio%60+0xA1; //"縲�"=0,... "繝ッ"=59
lcd.print(n);
}
void motorStep() {
digitalWrite(DRVPWR, HIGH);
delay(5);
while (stepNumberTarget-stepNumber != 0) {
if (stepNumberTarget>stepNumber) stepNumber++;
else stepNumber--;
nCumulativeStep++;
#if defined(NOMOTOR)
Serial.print("Motor setp=");
Serial.flush(); //this allows serial comm while CPU is in PM_STOP_MODE
Serial.println(stepNumber);
Serial.flush(); //this allows serial comm while CPU is in PM_STOP_MODE
#else
motorDrive();
#endif
delay(10); //motor freq=100Hz
}
motorOut(LOW, LOW, LOW, LOW);
digitalWrite(DRVPWR, LOW);
}
void motorDrive() {
int phase=stepNumber%4;
if (phase<0) phase=4+phase;
if (phase==0) motorOut(HIGH, LOW, HIGH, LOW);
if (phase==1) motorOut(LOW, HIGH, HIGH, LOW);
if (phase==2) motorOut(LOW, HIGH, LOW, HIGH);
if (phase==3) motorOut(HIGH, LOW, LOW, HIGH);
}
void motorOut(byte out1, byte out2, byte out3, byte out4) {
digitalWrite(DRVAIN1, out1);
digitalWrite(DRVAIN2, out2);
digitalWrite(DRVBIN1, out3);
digitalWrite(DRVBIN2, out4);
}
void getMag() {
magWrite(0x1D, 0x40); //Start ADC
delay(1);
dataX=magRead(0x10);
dataY=magRead(0x12);
dataY+=160;
dataZ=magRead(0x14);
dataZ+=50;
}
void initMag() {
magWrite(0x1B, 0x82); //CNTL1
delay(2);
magWrite(0x5C, 0); //CNTL4 LSB
magWrite(0x5D, 0); //CNTL4 MSB
magWrite(0x1C, 0x08); //CNTL2 DRDY enable with low active
getMag();
}
void waitFolioMotion() {
angMax=-3600;
angMin=3600;
do {
getAngle();
if (angle > angMax) angMax=angle;
if (angle < angMin) angMin=angle;
delay(100);
} while (angMax-angMin<300); //30deg
if (serialMon) {
Serial.println("MOTION OK");
Serial.flush();
}
}
void getThresh() {
unsigned long msec=millis();
angMax=-3600;
angMin=3600;
do {
getAngle();
if (angle > angMax) angMax=angle;
if (angle < angMin) angMin=angle;
delay(100);
} while (millis()-msec<15000); //15second
angThresh=(angMax+angMin)/2;
}
void getAngle() {
getMag();
angle= (int) (atan2((double)dataZ, (double)dataY)*572.9579); //1800.0/3.141592=572.9579, 180deg=1800
int diff=angle - angLast;
if (diff > 1800) angle-=3600;
if (diff < -1800) angle+=3600;
angLast=angle;
if (serialMon) {
Serial.print(dataZ);
Serial.print(" ");
Serial.print(dataY);
Serial.print(" ");
Serial.print(angle);
Serial.print(" ");
Serial.print(angMax);
Serial.print(" ");
Serial.print(angMin);
Serial.print(" ");
Serial.println(angThresh);
Serial.flush();
}
}
void magWrite (unsigned char adr, unsigned char data) {
Wire.beginTransmission(BM14);
Wire.write(adr);
Wire.write(data);
Wire.endTransmission(true);
}
int magRead(unsigned char adr) {
Wire.beginTransmission(BM14);
Wire.write(adr);
Wire.endTransmission(false);
Wire.requestFrom(BM14, 2, (int)true);
return Wire.read()|Wire.read()<<8;
}
void initGyro() {
delay(100);
Wire.beginTransmission(0x68); //Gyro sensor
Wire.write(0x6B); // Power management register1
Wire.write(0x0A); // wake up MPU-6050, disable Temperature sensor, use gyroY PLL for clock
Wire.endTransmission(true);
Wire.beginTransmission(0x68); //Gyro sensor
Wire.write(0x6C); // Power management register2
Wire.write(0xED); // disable accX, accZ, gyroX, gyroZ
Wire.endTransmission(true);
}
void getOmega() {
long tmp =0;
for (int i=0; i<5; i++) {
readGyro();
tmp += (long) gyroData;
delay(2);
}
omega=(int) (tmp / 5);
}
void readGyro() {
Wire.beginTransmission(0x68);
Wire.write(0x3D);
Wire.endTransmission(false); //enable incremental read
Wire.requestFrom(0x68, 2, (int)true); //used to be requestFrom(0x68, 14, true) but got warning.
accY=Wire.read()<<8|Wire.read(); //0x3D
Wire.beginTransmission(0x68);
Wire.write(0x45);
Wire.endTransmission(false); //enable incremental read
Wire.requestFrom(0x68, 2, (int)true); //used to be requestFrom(0x68, 14, true) but got warning.
gyroY=Wire.read()<<8|Wire.read(); //0x45
gyroData = gyroY;
}

2017年7月28日金曜日

GR-ADZUKIで倒立振子ロボADZUMIN v47

//ADZUMIN Inverted Pendulum Robot
//Copyright MAENOH! & KIRAKULABO 2017
//wheele dia ~= 58mm
//Gear ratio ~= 114 (TAMIYA Double Gear Box)
//Battery: Alkaline x 3
//MPU/Driver: GR-ADZUKI
//Gyro/Acc: MPU6050 (I2C)
//Adhoc IR remote control registration during laying just after power up.
//SW1: Stand still with debug and serialMonito on (1 blink)
//SW2: demo (2 blinks)
//Default: Stand still (no blink)
#include "Arduino.h"
#include <Wire.h>
#include <EEPROM.h>
#include <SD.h>
#define LED_R 22
#define LED_G 23
#define LED_B 24
#define HCODE 0x4D //M
#define PWMMAX 255
#define LED1_M1F 6
#define LED2_M0F 9
#define LED3_M0B 10
#define LED4_M1B 11
#define LED5 12
#define LED6 13
#define LED_ON 1
#define LED_OFF 0
#define SW1_SINT_PIN 3 //SW1 and Sound Interrupt
#define SW2_IRINT_PIN 2 // SW2 and IR Receive
#define GP2Y A0
#define BATT A1
#define TONE_PIN 5
#define SERVO_PIN 4
#define AKI_REMO_CUSTOMER (0x10EF)
#define AKI_REMO_POWER (0xD827)
#define AKI_REMO_A (0xF807)
#define AKI_REMO_B (0x7887)
#define AKI_REMO_C (0x58A7)
#define AKI_REMO_UP (0xA05F)
#define AKI_REMO_DOWN (0x00FF)
#define AKI_REMO_RIGHT (0x807F)
#define AKI_REMO_LEFT (0x10EF)
#define AKI_REMO_CENTER (0x20DF)
#define AKI_REMO_UR (0x21DE)
#define AKI_REMO_UL (0xB14E)
#define AKI_REMO_DR (0x817E)
#define AKI_REMO_DL (0x11EE)
#define INTSOUND 1 //Sound interrupt number
#define INTIR 0 // IR RECEIVE interrupt number
#define IRON LOW
#define IROFF HIGH
#define IRBUFFLEN 200
#define MINIRINTERVAL 220
// Ad hoc IR code
#define IR_UP 1
#define IR_DOWN 7
#define IR_RIGHT 5
#define IR_LEFT 3
#define IR_CENTER 4
#define IR_CIRL 0
#define IR_CIRR 2
#define IR_BALF 6
#define IR_BALB 8
#define ADHOC_IR_MAX 9
#define MAXSINTERVAL 15
#define MINSINTERVAL 5
unsigned int ADHOC_CUSTOMER[ADHOC_IR_MAX] = {0xFFFF,0xFFFF,0XFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF}; //1,2,3,4,5,6,7,8,9
unsigned int ADHOC_IR[ADHOC_IR_MAX] = {0xFFFF,0xFFFF,0XFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF}; // 1,2,3,4,5,6,7,8,9
int adhoc_ir_num=-1;
void selectMode();
void sendSerial();
void resetPara();
void resetVar();
void getGyro();
void readGyro();
void calibGyro();
void calibAcc();
void calcTarget();
boolean pendDrive();
void motor();
void resetMotor();
void freeMotor();
boolean laid();
boolean upright();
boolean standing();
void drvMotorL(int pwm);
void drvMotorR(int pwm);
void drvMotor0(int pwm);
void drvMotor1(int pwm);
void checkVoltage();
void monitorVoltage();
double getBattVolt();
void blinkLED(int n);
void setColor(int r, int g, int b);
void readEEPROMbal();
void writeEEPROMbal();
void readEEPROMadhoc();
void writeEEPROMadhoc();
void demo8();
void getIR();
void regIR();
void printIrData();
void decodeNECAEHA();
void decodeSONY();
void irInt();
void irCommand();
void printIrData(String s);
void soundIntSD();
void soundInt();
void soundStartSD(File s, unsigned long sz, int gain);
void soundStart(const byte* ptr, unsigned long sz, int gain);
void servoStart(double ang, double stp);
void servoContinue(double ang, double stp);
void servoDrive();
void pendulum();
void servoHead();
void randomPlay();
void openFiles();
boolean lightHead=false;
boolean usbPower=false;
int button=IR_CENTER;
volatile unsigned long irMicroOn;
volatile unsigned long irMicroOff;
volatile unsigned int irDataOn[200];
volatile unsigned int irDataOff[200];
volatile int irOnIndex=0;
volatile int irOffIndex=0;
volatile boolean irStarted=false;
volatile boolean irDecoding=false;
volatile unsigned long lastIrTime=0;
boolean irReady=false;
byte irData[30];
unsigned int ircode;
unsigned int customer_code;
int MotorConfig = 0; // 0 to 3
int accX, accY, accZ, temp, gyroX, gyroY, gyroZ;
int counter=0;
volatile int counterSec=0;
volatile int counterSec0=0;
unsigned long time1=0;
unsigned long time0=0;
double power, powerR, powerL;
double snsGyroY, snsAccX;
double varAng, varOmg, varSpd, varDst, varIang, varIdst;
double gyroOffsetY, gyroOffsetZ, accOffsetX;
double gyroDataY, gyroDataZ, accDataX, accDataY;
double gyroLSB=1.0/131.0; // deg/sec
double accLSB=1.0/16384.0; // g
double pendClk = 0.01; // in sec,
unsigned long pendInterval = 10000; // in usec
double cutoff = 0.1; // 2 * PI * f (f=Hz) //0.1
double Kang, Komg, Kdst, Kspd, Kspin, KIang, KIdst;
double spinPower;
double moveTarget, moveRate=0.0; //moveRate 0:stop, +:forward, -:backward
double moveStep = 0.0013;
double spinDestination, spinTarget;
double spinStep = 0.0;
double spinAngle;
boolean spinContinuous=false;
int pendPhase=-1;
int ipowerR = 0;
int ipowerL = 0;
int motorRdir=0; //stop 1:+ -1:-
int motorLdir=0; //stop
int backlashSpd;
double mechFactorR, mechFactorL;
double battFactor=1.3; // 2016.07.14
double bVolt;
double maxSpd=250.0;
int counterOverSpd;
int maxOverSpd=15;
double aveAccX=0.0;
double aveAccY=0.0;
boolean debug=false;
boolean serialMonitor=false;
double aveVolt=4.5;
int8_t drvHLbalance=0;
int demoPhase=0;
int demoDelayCounter=0;
int demoMode=0;
double minVolt=4.5;
int servoPhase=1;
boolean servoComplete=false;
int servoPulseWidth=1500;
double servoAngDestination=90.0;
double servoAngTarget=90.0;
double servoAngStep=1.0;
int servoWidth=1500; //in usec
File voiceFile[11];
unsigned long fsizeVoice[11];
File musicFile[10];
unsigned long fsizeMusic[10];
File sdfile, volFile;
File fGreet, fStop, fRight, fLeft, fForward, fBack, fSpin, fAccel, fTipover, fDemo, fDebug, fBattery, fReplace;
int vGreet, vStop, vRight, vLeft, vForward, vBack, vSpin, vAccel, vTipover, vDemo, vDebug, vBattery, vReplace;
unsigned long fsizeGreet, fsizeStop, fsizeRight, fsizeLeft, fsizeForward, fsizeBack, fsizeSpin, fsizeAccel, fsizeTipover, fsizeDemo, fsizeDebug, fsizeBattery, fsizeReplace;
volatile unsigned long filePointer;
volatile unsigned long fileSize;
volatile boolean soundBusy=false;
volatile unsigned long soundIndex=0;
volatile const byte *soundPtr;
volatile unsigned long soundSize;
volatile int soundGain=10; //10=100%
boolean soundFlg=false;
int soundInterval=MAXSINTERVAL;
volatile boolean soundStop=false;
int soundId;
boolean musicPlaying=false;
boolean randomSoundOn=true;
int soundPhase=1;
int maxVoiceFile=0;
int minVoiceFile=-1;
int maxMusicFile=0;
int minMusicFile=-1;
const char *soundVoice[] = {"vmu_168m.wav", "v1_168m.wav", "v2_168m.wav", "v3_168m.wav", "v4_168m.wav", "v5_168m.wav", "v6_168m.wav", "v7_168m.wav", "v8_168m.wav", "v9_168m.wav", "v10_168m.wav"};
const char *soundVoiceIni[] = {"vmu_168m.ini", "v1_168m.ini", "v2_168m.ini", "v3_168m.ini", "v4_168m.ini", "v5_168m.ini", "v6_168m.ini", "v7_168m.ini", "v8_168m.ini", "v9_168m.ini", "v10_168m.ini"};
const char *soundMusic[] = {"mu1_168m.wav", "mu2_168m.wav", "mu3_168m.wav", "mu4_168m.wav", "mu5_168m.wav", "mu6_168m.wav", "mu7_168m.wav", "mu8_168m.wav", "mu9_168m.wav", "mu10_168m.wav"};
const char *soundMusicIni[] = {"mu1_168m.ini", "mu2_168m.ini", "mu3_168m.ini", "mu4_168m.ini", "mu5_168m.ini", "mu6_168m.ini", "mu7_168m.ini", "mu8_168m.ini", "mu9_168m.ini", "mu10_168m.ini"};
const double headLeft=150.0;
const double headRight=30.0;
int vVoice[sizeof(soundVoice)/2];
int vMusic[sizeof(soundMusic)/2];
const byte soundGreet[] = {
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x75,0x74,0x71,0x6e,
0x6f,0x73,0x7b,0x81,0x8b,0x8e,0x8e,0x8c,0x8a,0x86,0x80,0x7e,0x80,0x7f,0x81,0x80,
0x80,0x7f,0x7e,0x80,0x78,0x77,0x76,0x7c,0x7f,0x84,0x8d,0x8f,0x95,0x92,0x8e,0x86,
0x80,0x7d,0x79,0x79,0x7c,0x7f,0x80,0x80,0x7d,0x79,0x7a,0x7a,0x7d,0x7f,0x84,0x87,
0x88,0x88,0x87,0x85,0x85,0x81,0x72,0x67,0x60,0x61,0x68,0x76,0x85,0x90,0x98,0x96,
0x8c,0x81,0x7d,0x7e,0x80,0x86,0x89,0x8b,0x8a,0x88,0x81,0x76,0x78,0x77,0x7c,0x82,
0x8a,0x91,0x92,0x8d,0x80,0x73,0x6a,0x69,0x6a,0x71,0x7b,0x84,0x85,0x84,0x80,0x7a,
0x75,0x73,0x74,0x73,0x77,0x7b,0x7f,0x81,0x87,0x8d,0x90,0x91,0x8f,0x8a,0x82,0x7c,
0x77,0x71,0x70,0x74,0x79,0x81,0x8d,0x9a,0xa1,0xa2,0x9c,0x93,0x85,0x78,0x70,0x6a,
0x69,0x6a,0x6d,0x6d,0x6f,0x72,0x72,0x71,0x75,0x7d,0x85,0x8e,0x96,0x97,0x93,0x8c,
0x84,0x78,0x72,0x73,0x76,0x7b,0x7f,0x80,0x80,0x80,0x7f,0x7e,0x76,0x71,0x6d,0x70,
0x78,0x81,0x8d,0x94,0x98,0x94,0x8e,0x84,0x7f,0x7e,0x7f,0x81,0x84,0x88,0x89,0x87,
0x83,0x7b,0x72,0x6c,0x6a,0x6b,0x6e,0x78,0x7f,0x86,0x8b,0x8e,0x8f,0x8e,0x8b,0x87,
0x83,0x7d,0x77,0x70,0x68,0x62,0x60,0x63,0x6a,0x78,0x89,0x96,0xa1,0xa3,0xa1,0x98,
0x91,0x8a,0x86,0x82,0x86,0x7e,0x7d,0x76,0x57,0x52,0x50,0x60,0x78,0xa2,0xbe,0xc9,
0xc8,0xac,0x83,0x60,0x57,0x57,0x66,0x7c,0x90,0x92,0x8b,0x7d,0x67,0x56,0x57,0x5f,
0x6d,0x81,0x95,0x9b,0x94,0x89,0x7b,0x70,0x6f,0x78,0x80,0x88,0x88,0x82,0x72,0x68,
0x64,0x69,0x73,0x83,0x90,0x95,0x98,0x91,0x8e,0x8b,0x93,0x9d,0x9f,0xa1,0x95,0x82,
0x6a,0x5c,0x5c,0x67,0x87,0x92,0x97,0x94,0x7d,0x65,0x53,0x5e,0x75,0x9b,0xbc,0xbc,
0xa9,0x92,0x75,0x5a,0x4d,0x50,0x5d,0x6d,0x7c,0x81,0x7d,0x7a,0x74,0x6b,0x66,0x6c,
0x78,0x83,0x8a,0x8c,0x89,0x80,0x7b,0x76,0x76,0x7a,0x83,0x8a,0x8c,0x8d,0x8d,0x8c,
0x88,0x8d,0x91,0x9a,0xa3,0xad,0xad,0xa6,0xa3,0xa2,0xa4,0xa4,0x8b,0x66,0x50,0x3c,
0x33,0x33,0x3f,0x53,0x6d,0x8c,0x9a,0x9e,0xa4,0xa8,0x9f,0x91,0x87,0x7a,0x72,0x6d,
0x64,0x58,0x52,0x54,0x58,0x5c,0x66,0x74,0x82,0x8a,0x90,0x90,0x8c,0x89,0x87,0x84,
0x83,0x86,0x8a,0x88,0x87,0x89,0x8b,0x8b,0x8e,0x90,0x94,0x9b,0xa2,0xaa,0xa8,0xb0,
0xa8,0xac,0x8f,0x66,0x57,0x3d,0x39,0x45,0x5b,0x69,0x84,0x94,0x8e,0x86,0x81,0x82,
0x7d,0x84,0x8e,0x91,0x92,0x91,0x81,0x6b,0x5b,0x54,0x50,0x54,0x62,0x74,0x7d,0x83,
0x81,0x7c,0x75,0x77,0x7a,0x7d,0x87,0x91,0x93,0x8b,0x84,0x7c,0x77,0x78,0x7c,0x86,
0x8e,0x97,0x9b,0x96,0x99,0x97,0x9e,0xa3,0xb0,0xb6,0xb5,0xb0,0x7e,0x5f,0x55,0x40,
0x38,0x4b,0x5d,0x6a,0x80,0x89,0x80,0x81,0x8c,0x8a,0x87,0x94,0x9f,0x96,0x8d,0x81,
0x6a,0x5c,0x5b,0x5b,0x5d,0x67,0x73,0x75,0x72,0x73,0x77,0x7a,0x82,0x8a,0x8e,0x90,
0x8f,0x87,0x7c,0x76,0x77,0x7a,0x7c,0x7e,0x80,0x7d,0x79,0x74,0x76,0x7c,0x8a,0x97,
0xa2,0xab,0xb5,0xbb,0xbd,0xc1,0xc2,0xc1,0xa0,0x72,0x45,0x2d,0x26,0x2a,0x3d,0x50,
0x70,0x88,0x8f,0x80,0x7f,0x8e,0x9a,0xa7,0xa9,0xa8,0xa2,0x97,0x7f,0x5b,0x46,0x45,
0x4d,0x54,0x5f,0x6b,0x72,0x78,0x79,0x77,0x7b,0x89,0x95,0x97,0x96,0x90,0x88,0x7d,
0x75,0x71,0x74,0x7b,0x82,0x83,0x82,0x80,0x83,0x85,0x8e,0x9b,0xab,0xbb,0xc6,0xd0,
0xd0,0xcb,0x9c,0x78,0x5a,0x32,0x25,0x30,0x40,0x59,0x6c,0x6e,0x70,0x70,0x80,0x89,
0x96,0xb0,0xbf,0xbb,0xa5,0x8a,0x6f,0x5b,0x56,0x57,0x5f,0x68,0x71,0x69,0x58,0x56,
0x5b,0x6b,0x7d,0x93,0x9f,0xa2,0x9c,0x8d,0x7c,0x75,0x7a,0x80,0x84,0x85,0x82,0x77,
0x6c,0x65,0x67,0x72,0x87,0x99,0xa6,0xaf,0xb5,0xb7,0xbd,0xc6,0xd1,0xde,0xb9,0x84,
0x5c,0x35,0x18,0x17,0x2a,0x45,0x6c,0x76,0x74,0x6e,0x7b,0x8f,0x97,0xab,0xbc,0xc5,
0xb9,0x9b,0x76,0x5b,0x53,0x53,0x55,0x58,0x63,0x69,0x63,0x54,0x56,0x67,0x7e,0x93,
0x9f,0xa3,0xa0,0x9b,0x88,0x77,0x74,0x7d,0x7f,0x7e,0x7a,0x74,0x70,0x6e,0x6f,0x78,
0x88,0x9d,0xac,0xb2,0xb9,0xbc,0xc4,0xcf,0xe5,0xb4,0x7f,0x77,0x3b,0x19,0x27,0x37,
0x4c,0x61,0x78,0x63,0x62,0x7b,0x7a,0x85,0xad,0xc8,0xb7,0xb4,0xa5,0x89,0x6d,0x57,
0x54,0x57,0x69,0x65,0x59,0x4f,0x4d,0x5f,0x68,0x75,0x8e,0xa8,0xa8,0x9a,0x8d,0x7d,
0x7d,0x81,0x80,0x7c,0x85,0x88,0x7d,0x6a,0x6b,0x72,0x7b,0x89,0x9b,0xab,0xb1,0xb0,
0xa5,0xb1,0xb4,0xc8,0xc6,0xb2,0x83,0x4e,0x35,0x1b,0x31,0x4f,0x63,0x68,0x6f,0x69,
0x5d,0x71,0x85,0x96,0xb0,0xbe,0xb9,0xa6,0x97,0x7f,0x6a,0x5b,0x53,0x54,0x5f,0x67,
0x5e,0x5a,0x55,0x5a,0x6b,0x7f,0x92,0xa3,0xab,0x9e,0x8e,0x82,0x7b,0x7b,0x7f,0x84,
0x80,0x81,0x7b,0x72,0x6f,0x78,0x85,0x94,0xa3,0xad,0xb4,0xbc,0xc2,0xc6,0xd0,0xae,
0x96,0x74,0x49,0x3b,0x38,0x3d,0x44,0x56,0x4e,0x4a,0x52,0x60,0x77,0x92,0xaf,0xb6,
0xba,0xb2,0xa0,0x90,0x85,0x7f,0x76,0x6f,0x62,0x58,0x4d,0x48,0x49,0x53,0x65,0x78,
0x88,0x91,0x95,0x95,0x94,0x8f,0x90,0x90,0x8f,0x8a,0x83,0x78,0x70,0x6c,0x6c,0x70,
0x7b,0x87,0x91,0x9b,0xa1,0xa8,0xaf,0xbd,0xc7,0xda,0xc4,0xa9,0x8d,0x5d,0x4c,0x42,
0x43,0x49,0x57,0x58,0x4c,0x4f,0x54,0x64,0x7c,0x96,0xa7,0xaf,0xb2,0xa4,0x97,0x8b,
0x85,0x7f,0x7a,0x70,0x63,0x58,0x4d,0x4a,0x4e,0x5b,0x6b,0x79,0x82,0x87,0x8b,0x8e,
0x8f,0x91,0x93,0x94,0x90,0x8c,0x85,0x7f,0x7f,0x7e,0x80,0x84,0x8a,0x8f,0x97,0x9f,
0xaa,0xb4,0xc5,0xc7,0xac,0x9a,0x79,0x60,0x58,0x55,0x57,0x5c,0x61,0x54,0x4b,0x4e,
0x57,0x6b,0x83,0x95,0x9e,0xa2,0x9e,0x94,0x8c,0x8a,0x8b,0x8b,0x83,0x77,0x68,0x5a,
0x51,0x51,0x59,0x65,0x74,0x7a,0x79,0x79,0x7c,0x80,0x88,0x92,0x97,0x96,0x92,0x88,
0x7f,0x7d,0x80,0x84,0x89,0x8d,0x8e,0x8e,0x91,0x95,0xa3,0xb2,0xc3,0xca,0xb0,0x9d,
0x7e,0x63,0x5c,0x5b,0x60,0x62,0x67,0x55,0x47,0x47,0x4d,0x62,0x7c,0x91,0x99,0x9e,
0x98,0x8d,0x8a,0x8c,0x90,0x92,0x8e,0x7e,0x6f,0x60,0x56,0x54,0x5c,0x68,0x71,0x77,
0x73,0x72,0x73,0x78,0x80,0x8b,0x93,0x96,0x94,0x8d,0x86,0x85,0x87,0x8a,0x8e,0x90,
0x90,0x91,0x93,0x95,0xa2,0xa9,0xb9,0xb9,0xa1,0x95,0x78,0x68,0x65,0x66,0x67,0x6a,
0x6b,0x57,0x4c,0x4c,0x52,0x65,0x7c,0x8a,0x8e,0x93,0x8d,0x86,0x88,0x8c,0x90,0x94,
0x8e,0x80,0x73,0x67,0x5f,0x5f,0x65,0x6b,0x72,0x70,0x6c,0x6c,0x6e,0x74,0x7f,0x8a,
0x90,0x93,0x90,0x8a,0x88,0x8a,0x8e,0x93,0x96,0x97,0x95,0x95,0x94,0x9b,0xa3,0xaf,
0xb1,0xa3,0x97,0x80,0x70,0x6a,0x66,0x69,0x6c,0x6c,0x60,0x55,0x52,0x54,0x61,0x72,
0x7e,0x86,0x8b,0x88,0x83,0x85,0x89,0x8e,0x93,0x91,0x87,0x7d,0x72,0x69,0x67,0x6c,
0x70,0x74,0x73,0x6f,0x6c,0x6c,0x70,0x77,0x82,0x88,0x8c,0x8b,0x88,0x85,0x87,0x8b,
0x8f,0x93,0x96,0x96,0x93,0x93,0x96,0x9c,0xa4,0xaf,0xa9,0x9d,0x93,0x7e,0x74,0x70,
0x6e,0x6f,0x71,0x6c,0x5d,0x58,0x56,0x59,0x65,0x72,0x79,0x7e,0x82,0x7e,0x7e,0x83,
0x88,0x8e,0x91,0x8f,0x87,0x80,0x77,0x73,0x73,0x75,0x77,0x77,0x72,0x6e,0x6c,0x6c,
0x70,0x77,0x7e,0x82,0x86,0x86,0x84,0x86,0x89,0x8b,0x90,0x93,0x95,0x94,0x95,0x94,
0x97,0x99,0xa1,0xa1,0x98,0x95,0x86,0x7e,0x7a,0x78,0x74,0x75,0x73,0x67,0x62,0x5f,
0x5f,0x64,0x6c,0x71,0x73,0x79,0x77,0x79,0x7b,0x80,0x84,0x88,0x89,0x86,0x86,0x80,
0x7f,0x7d,0x7e,0x7e,0x7f,0x7c,0x78,0x76,0x74,0x75,0x77,0x7a,0x7c,0x7e,0x7f,0x7e,
0x7f,0x83,0x85,0x8a,0x8d,0x8f,0x8f,0x91,0x8f,0x92,0x95,0x9a,0x9c,0x97,0x94,0x8b,
0x85,0x82,0x7f,0x7d,0x7c,0x7a,0x72,0x6c,0x68,0x66,0x69,0x6d,0x71,0x72,0x75,0x74,
0x74,0x76,0x79,0x7e,0x82,0x85,0x84,0x84,0x81,0x81,0x80,0x81,0x83,0x83,0x82,0x7f,
0x7e,0x7b,0x7b,0x7d,0x7d,0x7d,0x7e,0x7d,0x7d,0x7e,0x80,0x82,0x85,0x86,0x88,0x89,
0x8b,0x8b,0x8d,0x8e,0x90,0x91,0x90,0x8d,0x89,0x87,0x84,0x83,0x81,0x7f,0x7d,0x79,
0x75,0x72,0x71,0x71,0x72,0x73,0x73,0x74,0x73,0x74,0x75,0x77,0x7a,0x7d,0x7f,0x80,
0x80,0x80,0x81,0x81,0x83,0x83,0x83,0x82,0x7f,0x7d,0x7c,0x7c,0x7e,0x7e,0x80,0x7f,
0x7f,0x7d,0x7e,0x80,0x80,0x84,0x86,0x85,0x87,0x87,0x87,0x8a,0x8a,0x8d,0x8c,0x8b,
0x8a,0x85,0x85,0x83,0x83,0x83,0x82,0x80,0x7d,0x7a,0x77,0x76,0x76,0x76,0x76,0x76,
0x76,0x75,0x76,0x75,0x76,0x79,0x7b,0x7d,0x7f,0x80,0x80,0x81,0x81,0x81,0x82,0x82,
0x81,0x80,0x80,0x7f,0x7d,0x7f,0x7d,0x7e,0x7e,0x7d,0x7e,0x7f,0x80,0x81,0x81,0x82,
0x82,0x83,0x83,0x85,0x86,0x87,0x89,0x87,0x88,0x87,0x85,0x84,0x84,0x83,0x83,0x83,
0x82,0x80,0x7f,0x7d,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,0x78,0x78,0x77,0x78,0x79,0x7b,
0x7c,0x7e,0x7e,0x7f,0x7e,0x7f,0x7e,0x80,0x7f,0x82,0x81,0x80,0x80,0x7e,0x7d,0x7d,
0x7e,0x7e,0x80,0x7e,0x7f,0x7d,0x80,0x80,0x81,0x84,0x83,0x83,0x85,0x84,0x85,0x88,
0x87,0x88,0x86,0x85,0x83,0x81,0x82,0x81,0x81,0x81,0x80,0x7f,0x7e,0x7d,0x7d,0x7c,
0x7c,0x7c,0x7b,0x79,0x78,0x78,0x78,0x79,0x7a,0x7c,0x7c,0x7c,0x7b,0x7c,0x7c,0x7e,
0x82,0x82,0x83,0x82,0x80,0x7f,0x7f,0x7e,0x80,0x7f,0x7f,0x7f,0x7d,0x7e,0x7f,0x80,
0x82,0x84,0x83,0x84,0x84,0x83,0x85,0x85,0x88,0x88,0x87,0x87,0x84,0x83,0x81,0x81,
0x80,0x80,0x80,0x7f,0x7e,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7d,0x7c,0x7b,0x7a,0x7b,
0x7b,0x7c,0x7c,0x7c,0x7b,0x7a,0x7b,0x7c,0x7e,0x80,0x81,0x81,0x81,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x7f,0x81,0x7f,0x7e,0x80,0x7e,0x81,0x81,0x82,0x83,0x83,0x84,0x82,
0x85,0x84,0x84,0x86,0x85,0x84,0x83,0x82,0x81,0x80,0x81,0x80,0x7f,0x7f,0x7d,0x7d,
0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7d,0x7c,0x7d,0x7b,0x7c,
0x7c,0x7c,0x7e,0x7c,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x80,0x7e,0x82,0x80,
0x81,0x80,0x80,0x81,0x80,0x83,0x81,0x84,0x83,0x83,0x82,0x84,0x82,0x83,0x83,0x82,
0x83,0x81,0x82,0x80,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7e,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7d,0x7d,0x7c,0x7e,0x7d,0x7f,0x80,
0x80,0x80,0x7f,0x81,0x7f,0x80,0x80,0x81,0x7e,0x81,0x81,0x80,0x80,0x81,0x81,0x81,
0x83,0x83,0x81,0x83,0x84,0x81,0x83,0x82,0x82,0x81,0x82,0x80,0x80,0x80,0x7f,0x80,
0x7f,0x7f,0x7f,0x7f,0x7e,0x7f,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7e,0x80,0x7c,0x7f,
0x7e,0x7e,0x7f,0x7e,0x7f,0x7d,0x80,0x7d,0x7f,0x7e,0x80,0x7e,0x81,0x7f,0x80,0x80,
0x7e,0x81,0x7d,0x82,0x7e,0x82,0x81,0x81,0x81,0x80,0x81,0x7f,0x82,0x81,0x81,0x81,
0x81,0x81,0x80,0x80,0x81,0x80,0x7f,0x80,0x81,0x7f,0x7f,0x7f,0x7e,0x7d,0x7f,0x7d,
0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7e,0x81,0x7d,0x81,0x7e,0x7e,0x81,0x7e,
0x80,0x7f,0x7e,0x7f,0x7d,0x80,0x80,0x7e,0x81,0x81,0x7e,0x80,0x81,0x7f,0x80,0x81,
0x80,0x81,0x80,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,0x81,0x80,0x81,0x80,0x81,0x7f,
0x80,0x80,0x7f,0x7f,0x80,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x80,0x7c,0x81,
0x7e,0x7f,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x7e,0x81,0x7d,0x7f,0x7e,
0x80,0x7f,0x80,0x83,0x7e,0x81,0x82,0x7d,0x80,0x82,0x7f,0x81,0x83,0x80,0x7f,0x82,
0x7e,0x7f,0x80,0x80,0x7f,0x7f,0x81,0x80,0x7f,0x81,0x80,0x80,0x7f,0x81,0x7e,0x7f,
0x7f,0x7e,0x7f,0x7e,0x80,0x7f,0x80,0x7d,0x80,0x7e,0x7f,0x81,0x80,0x7f,0x82,0x7f,
0x80,0x81,0x7e,0x81,0x7f,0x81,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x82,0x7e,0x81,
0x7e,0x82,0x7e,0x81,0x82,0x7f,0x80,0x81,0x81,0x7c,0x84,0x7d,0x7f,0x80,0x7d,0x81,
0x7f,0x7f,0x81,0x7e,0x80,0x81,0x80,0x80,0x7f,0x81,0x7f,0x7e,0x82,0x7e,0x7e,0x81,
0x7c,0x80,0x7e,0x7e,0x82,0x7e,0x82,0x7f,0x7f,0x82,0x7c,0x83,0x7f,0x7f,0x84,0x7b,
0x83,0x7f,0x7d,0x84,0x79,0x82,0x7d,0x7e,0x84,0x7d,0x81,0x82,0x7f,0x7d,0x84,0x7d,
0x81,0x80,0x81,0x7e,0x7f,0x7f,0x7d,0x80,0x7d,0x80,0x7e,0x7f,0x7e,0x81,0x7f,0x80,
0x7e,0x82,0x7d,0x80,0x7f,0x7f,0x80,0x7e,0x81,0x7d,0x81,0x7c,0x81,0x7e,0x7f,0x80,
0x7e,0x81,0x7f,0x80,0x80,0x81,0x81,0x80,0x7f,0x83,0x7c,0x81,0x7f,0x7f,0x80,0x7c,
0x85,0x79,0x83,0x7f,0x7f,0x83,0x7b,0x83,0x7f,0x81,0x7f,0x81,0x80,0x7e,0x81,0x7d,
0x7d,0x80,0x7b,0x82,0x7c,0x7f,0x82,0x7a,0x85,0x7d,0x7e,0x86,0x79,0x80,0x83,0x7b,
0x83,0x7f,0x82,0x7d,0x7c,0x84,0x7a,0x7f,0x82,0x7d,0x82,0x7c,0x84,0x7c,0x7f,0x86,
0x7c,0x82,0x81,0x81,0x7d,0x83,0x7e,0x7f,0x80,0x7e,0x82,0x7d,0x82,0x7d,0x7f,0x80,
0x7d,0x83,0x7e,0x80,0x82,0x7d,0x7e,0x82,0x7c,0x81,0x7d,0x80,0x80,0x78,0x83,0x7d,
0x7c,0x7f,0x83,0x7b,0x82,0x82,0x7d,0x82,0x7d,0x83,0x7e,0x81,0x81,0x80,0x7d,0x80,
0x7f,0x7e,0x7f,0x82,0x7e,0x7f,0x83,0x7a,0x85,0x7b,0x85,0x81,0x80,0x82,0x7f,0x81,
0x7c,0x83,0x7e,0x80,0x7e,0x82,0x7c,0x7f,0x81,0x7f,0x80,0x81,0x7f,0x80,0x7f,0x80,
0x7e,0x80,0x80,0x7f,0x83,0x7a,0x82,0x7e,0x7a,0x81,0x7c,0x80,0x80,0x7e,0x83,0x7d,
0x80,0x81,0x7d,0x83,0x80,0x80,0x82,0x7d,0x83,0x7c,0x83,0x7e,0x7f,0x82,0x78,0x86,
0x79,0x84,0x80,0x7f,0x83,0x7f,0x81,0x7e,0x80,0x82,0x7c,0x82,0x82,0x7d,0x7f,0x7e,
0x83,0x79,0x84,0x80,0x7d,0x7f,0x83,0x7d,0x7f,0x83,0x7e,0x81,0x7d,0x83,0x7c,0x80,
0x81,0x7b,0x83,0x7b,0x7f,0x80,0x7c,0x83,0x7d,0x85,0x7b,0x84,0x7f,0x7d,0x84,0x7e,
0x83,0x80,0x82,0x7c,0x80,0x80,0x7e,0x82,0x83,0x7a,0x85,0x7d,0x7b,0x88,0x7a,0x84,
0x81,0x7b,0x86,0x7b,0x80,0x82,0x7d,0x83,0x7d,0x7f,0x82,0x7c,0x82,0x7e,0x80,0x7e,
0x7f,0x82,0x7c,0x83,0x7f,0x7e,0x80,0x81,0x7a,0x85,0x7a,0x7f,0x82,0x78,0x83,0x7c,
0x81,0x83,0x7c,0x80,0x84,0x7a,0x82,0x85,0x7d,0x82,0x84,0x7e,0x7f,0x81,0x83,0x7b,
0x83,0x80,0x7e,0x7d,0x80,0x82,0x7d,0x82,0x7d,0x7e,0x81,0x7e,0x82,0x82,0x7d,0x81,
0x7e,0x81,0x7a,0x83,0x7e,0x80,0x80,0x7d,0x83,0x7a,0x80,0x85,0x77,0x83,0x81,0x79,
0x82,0x7e,0x7f,0x7f,0x82,0x7b,0x83,0x7a,0x85,0x7a,0x82,0x81,0x79,0x88,0x78,0x84,
0x81,0x7d,0x81,0x7f,0x7e,0x83,0x7d,0x83,0x80,0x7d,0x83,0x7c,0x7f,0x83,0x79,0x83,
0x7d,0x7f,0x82,0x7a,0x85,0x7a,0x81,0x81,0x7b,0x87,0x7c,0x7e,0x85,0x79,0x84,0x7b,
0x81,0x7e,0x7c,0x85,0x7b,0x81,0x80,0x7e,0x7e,0x82,0x7f,0x7e,0x80,0x81,0x7e,0x7f,
0x83,0x7d,0x7e,0x80,0x7d,0x7e,0x80,0x7e,0x82,0x7e,0x7f,0x82,0x7e,0x80,0x81,0x80,
0x80,0x82,0x7d,0x82,0x7f,0x81,0x7f,0x81,0x7e,0x7e,0x82,0x7d,0x80,0x80,0x7c,0x81,
0x7f,0x7e,0x83,0x7c,0x83,0x7e,0x7e,0x81,0x7e,0x7d,0x81,0x7c,0x81,0x7f,0x7d,0x83,
0x7b,0x7e,0x83,0x7b,0x7f,0x83,0x7c,0x86,0x7d,0x7f,0x83,0x7c,0x83,0x7f,0x80,0x82,
0x7d,0x81,0x7f,0x7d,0x82,0x7f,0x7d,0x82,0x7c,0x81,0x81,0x80,0x81,0x7f,0x82,0x80,
0x7f,0x80,0x81,0x7c,0x83,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x82,0x7d,0x83,0x80,0x7e,
0x82,0x81,0x7b,0x84,0x7e,0x7d,0x82,0x7d,0x7e,0x82,0x7d,0x7e,0x81,0x7d,0x80,0x7f,
0x80,0x7f,0x82,0x7f,0x81,0x7f,0x80,0x82,0x7c,0x81,0x80,0x7e,0x81,0x81,0x7e,0x81,
0x81,0x7d,0x82,0x80,0x7e,0x81,0x80,0x81,0x7f,0x80,0x80,0x81,0x7d,0x80,0x7f,0x7e,
0x81,0x7d,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,0x80,0x80,0x80,0x80,0x82,0x7d,0x82,
0x7f,0x7f,0x81,0x7f,0x81,0x7d,0x81,0x7f,0x7e,0x81,0x80,0x7f,0x82,0x7f,0x80,0x80,
0x81,0x81,0x80,0x81,0x7f,0x7f,0x80,0x7e,0x7f,0x80,0x7d,0x80,0x7c,0x80,0x7f,0x80,
0x81,0x7f,0x80,0x7f,0x7e,0x80,0x81,0x7e,0x81,0x7f,0x7d,0x7f,0x7e,0x80,0x7f,0x7f,
0x80,0x7d,0x82,0x7f,0x80,0x83,0x80,0x80,0x81,0x81,0x80,0x80,0x81,0x81,0x80,0x80,
0x81,0x81,0x7f,0x82,0x80,0x7f,0x81,0x7f,0x7f,0x7f,0x80,0x7f,0x7e,0x80,0x7d,0x7f,
0x7c,0x7f,0x7e,0x7d,0x80,0x7d,0x7e,0x7f,0x7f,0x7f,0x7e,0x7f,0x80,0x7c,0x81,0x7f,
0x7d,0x7e,0x7f,0x7d,0x80,0x80,0x7f,0x81,0x80,0x82,0x81,0x82,0x83,0x82,0x81,0x84,
0x81,0x81,0x83,0x82,0x80,0x81,0x81,0x80,0x81,0x81,0x81,0x7e,0x7f,0x7f,0x7e,0x7f,
0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7d,0x7c,0x7c,0x7c,0x7a,0x7c,0x7a,0x7b,0x7c,
0x7b,0x7d,0x7c,0x7e,0x7e,0x7d,0x7f,0x7e,0x7f,0x80,0x80,0x81,0x80,0x81,0x82,0x80,
0x82,0x83,0x83,0x84,0x84,0x85,0x85,0x85,0x85,0x86,0x86,0x85,0x86,0x84,0x84,0x83,
0x83,0x83,0x82,0x81,0x80,0x7f,0x7d,0x7d,0x7d,0x7b,0x7b,0x79,0x77,0x77,0x76,0x75,
0x75,0x76,0x74,0x75,0x76,0x76,0x78,0x79,0x7a,0x7c,0x7d,0x7f,0x80,0x81,0x83,0x83,
0x84,0x85,0x86,0x86,0x87,0x86,0x88,0x86,0x88,0x87,0x85,0x87,0x86,0x86,0x88,0x88,
0x88,0x89,0x88,0x89,0x87,0x87,0x85,0x82,0x82,0x7e,0x7c,0x7b,0x78,0x76,0x74,0x72,
0x71,0x70,0x70,0x70,0x70,0x71,0x72,0x73,0x74,0x76,0x78,0x7a,0x7c,0x7e,0x7f,0x80,
0x81,0x82,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x89,0x89,0x89,0x87,0x89,0x88,0x89,
0x8a,0x89,0x8b,0x89,0x8b,0x8d,0x8c,0x8e,0x8a,0x86,0x84,0x7f,0x7e,0x7d,0x7c,0x7a,
0x79,0x73,0x70,0x6d,0x6c,0x6c,0x6f,0x6f,0x70,0x71,0x70,0x6f,0x71,0x74,0x78,0x7c,
0x7f,0x81,0x82,0x82,0x82,0x83,0x85,0x87,0x89,0x89,0x88,0x86,0x84,0x83,0x84,0x85,
0x86,0x88,0x87,0x87,0x88,0x86,0x89,0x8a,0x8d,0x90,0x92,0x94,0x8e,0x8b,0x86,0x82,
0x82,0x81,0x80,0x7e,0x7d,0x76,0x70,0x6e,0x6b,0x6c,0x6f,0x70,0x70,0x71,0x70,0x6e,
0x6f,0x72,0x75,0x79,0x7d,0x7f,0x7f,0x80,0x81,0x80,0x83,0x86,0x88,0x88,0x88,0x86,
0x83,0x83,0x81,0x82,0x83,0x84,0x84,0x84,0x83,0x84,0x84,0x88,0x8a,0x8c,0x90,0x91,
0x93,0x95,0x92,0x8d,0x8d,0x86,0x84,0x84,0x7f,0x7e,0x7c,0x77,0x6f,0x6e,0x6b,0x6a,
0x6c,0x6e,0x6d,0x6f,0x70,0x6f,0x70,0x74,0x76,0x79,0x7d,0x7d,0x7e,0x7f,0x80,0x80,
0x83,0x84,0x84,0x85,0x84,0x83,0x82,0x82,0x81,0x81,0x82,0x82,0x82,0x82,0x81,0x83,
0x84,0x87,0x89,0x8b,0x8d,0x90,0x91,0x94,0x99,0x95,0x92,0x91,0x89,0x85,0x84,0x7f,
0x7c,0x7d,0x77,0x70,0x6e,0x69,0x66,0x68,0x6a,0x69,0x6d,0x70,0x6f,0x70,0x73,0x73,
0x77,0x7c,0x7e,0x81,0x83,0x84,0x82,0x83,0x84,0x84,0x86,0x86,0x86,0x84,0x83,0x80,
0x7f,0x7e,0x7f,0x80,0x80,0x81,0x81,0x83,0x84,0x86,0x89,0x8c,0x8e,0x94,0x95,0x99,
0x9b,0x94,0x93,0x8c,0x88,0x85,0x83,0x7e,0x7e,0x7b,0x72,0x6d,0x69,0x66,0x66,0x68,
0x68,0x6a,0x6d,0x6d,0x6d,0x70,0x73,0x76,0x7b,0x7f,0x80,0x83,0x84,0x84,0x84,0x85,
0x85,0x86,0x87,0x85,0x84,0x82,0x80,0x7e,0x7e,0x7d,0x7e,0x7e,0x7f,0x7f,0x81,0x82,
0x84,0x88,0x8a,0x8e,0x91,0x94,0x96,0x9d,0x9a,0x96,0x94,0x8d,0x88,0x87,0x83,0x7e,
0x7f,0x79,0x70,0x6c,0x68,0x63,0x65,0x68,0x66,0x69,0x6d,0x6b,0x6c,0x71,0x73,0x77,
0x7d,0x7f,0x81,0x84,0x86,0x84,0x86,0x87,0x87,0x88,0x87,0x85,0x84,0x82,0x80,0x7e,
0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x80,0x81,0x85,0x86,0x8a,0x8f,0x91,0x95,0x98,0x9e,
0x9c,0x98,0x96,0x8e,0x8a,0x88,0x84,0x7e,0x7f,0x79,0x70,0x6d,0x67,0x63,0x64,0x67,
0x64,0x68,0x6c,0x6b,0x6d,0x71,0x73,0x78,0x7d,0x80,0x82,0x85,0x86,0x86,0x87,0x87,
0x88,0x88,0x86,0x85,0x83,0x81,0x7f,0x7e,0x7c,0x7c,0x7c,0x7b,0x7c,0x7d,0x7f,0x81,
0x84,0x87,0x8a,0x8f,0x91,0x95,0x97,0x9e,0xa0,0x99,0x9a,0x91,0x8b,0x89,0x86,0x7e,
0x80,0x7d,0x71,0x6e,0x69,0x63,0x62,0x67,0x64,0x66,0x6c,0x6b,0x6b,0x6f,0x72,0x75,
0x7c,0x80,0x82,0x85,0x87,0x86,0x86,0x88,0x88,0x89,0x88,0x87,0x84,0x81,0x7f,0x7c,
0x7a,0x7a,0x7b,0x7a,0x7a,0x7b,0x7c,0x7d,0x81,0x83,0x88,0x8c,0x91,0x93,0x96,0x99,
0x9f,0xa2,0x9a,0x9c,0x93,0x8d,0x8a,0x85,0x7f,0x7f,0x7d,0x70,0x6c,0x67,0x61,0x60,
0x64,0x62,0x64,0x6b,0x6a,0x6a,0x6e,0x72,0x75,0x7c,0x81,0x82,0x87,0x87,0x87,0x86,
0x88,0x88,0x89,0x89,0x87,0x85,0x81,0x7f,0x7b,0x7a,0x79,0x7a,0x79,0x78,0x79,0x7a,
0x7b,0x7e,0x81,0x85,0x8b,0x8f,0x91,0x95,0x9a,0x9d,0xa3,0x9e,0x9c,0x98,0x8f,0x8c,
0x87,0x82,0x7e,0x7e,0x73,0x6c,0x67,0x61,0x5f,0x61,0x63,0x62,0x68,0x6a,0x68,0x6c,
0x70,0x74,0x79,0x81,0x83,0x85,0x89,0x88,0x87,0x88,0x8a,0x8a,0x8a,0x89,0x86,0x83,
0x80,0x7d,0x7a,0x7a,0x7a,0x7a,0x78,0x79,0x78,0x7a,0x7b,0x7f,0x83,0x87,0x8c,0x90,
0x91,0x95,0x9a,0x9e,0xa3,0x9e,0x9d,0x97,0x8f,0x8c,0x85,0x80,0x7f,0x7c,0x72,0x6c,
0x66,0x60,0x60,0x61,0x60,0x63,0x68,0x69,0x69,0x6d,0x70,0x75,0x7b,0x81,0x83,0x87,
0x8a,0x89,0x88,0x8a,0x8a,0x8a,0x8a,0x89,0x86,0x82,0x7f,0x7b,0x79,0x78,0x79,0x78,
0x78,0x78,0x79,0x7a,0x7c,0x80,0x84,0x89,0x8f,0x91,0x93,0x9a,0x9b,0xa2,0xa5,0x9d,
0x9e,0x96,0x8e,0x89,0x85,0x7e,0x7d,0x7a,0x6d,0x69,0x63,0x5e,0x5d,0x60,0x60,0x63,
0x69,0x69,0x6a,0x6e,0x73,0x77,0x7e,0x84,0x87,0x8b,0x8c,0x8b,0x8a,0x8b,0x8b,0x8b,
0x8a,0x88,0x85,0x81,0x7d,0x79,0x77,0x77,0x77,0x76,0x76,0x77,0x77,0x79,0x7b,0x7f,
0x84,0x89,0x8e,0x91,0x95,0x98,0x9c,0xa0,0xa6,0x9f,0x9f,0x99,0x8e,0x8b,0x85,0x7f,
0x7c,0x7b,0x6f,0x69,0x64,0x5d,0x5c,0x5e,0x60,0x62,0x69,0x6a,0x6b,0x6f,0x73,0x77,
0x7d,0x85,0x87,0x8b,0x8d,0x8b,0x8a,0x8b,0x8b,0x8a,0x8b,0x89,0x85,0x81,0x7d,0x79,
0x76,0x76,0x76,0x76,0x76,0x76,0x77,0x78,0x7b,0x7e,0x84,0x89,0x8e,0x92,0x95,0x98,
0x9c,0xa1,0xa6,0xa0,0x9f,0x99,0x8e,0x8b,0x85,0x7d,0x7c,0x7b,0x6f,0x69,0x64,0x5c,
0x5c,0x60,0x60,0x62,0x6a,0x6b,0x6b,0x70,0x73,0x77,0x7f,0x86,0x88,0x8b,0x8e,0x8c,
0x89,0x8b,0x8b,0x8a,0x8b,0x89,0x84,0x81,0x7d,0x78,0x75,0x76,0x75,0x75,0x75,0x75,
0x75,0x76,0x78,0x7b,0x81,0x87,0x8c,0x90,0x93,0x95,0x98,0x9b,0xa1,0xa6,0xa0,0x9f,
0x98,0x8d,0x87,0x83,0x7c,0x79,0x7b,0x6f,0x68,0x65,0x5e,0x5b,0x60,0x61,0x63,0x6b,
0x6e,0x6d,0x71,0x76,0x79,0x7e,0x86,0x88,0x8b,0x8d,0x8c,0x89,0x8a,0x8a,0x88,0x88,
0x87,0x83,0x7f,0x7c,0x77,0x74,0x74,0x75,0x74,0x75,0x76,0x76,0x77,0x7a,0x7e,0x83,
0x89,0x8d,0x90,0x94,0x97,0x9a,0x9d,0xa4,0xa3,0x9c,0x9b,0x92,0x89,0x86,0x81,0x7a,
0x7b,0x77,0x6a,0x66,0x63,0x5d,0x5e,0x63,0x63,0x67,0x6e,0x6e,0x6e,0x73,0x79,0x7c,
0x83,0x89,0x8a,0x8c,0x8e,0x8a,0x87,0x89,0x8a,0x87,0x87,0x85,0x80,0x7c,0x79,0x74,
0x73,0x74,0x74,0x74,0x75,0x75,0x75,0x77,0x7b,0x7e,0x84,0x8a,0x8e,0x90,0x93,0x95,
0x98,0x9b,0xa2,0xa3,0x9e,0x9b,0x93,0x8a,0x84,0x82,0x7d,0x7b,0x7a,0x70,0x68,0x64,
0x60,0x5f,0x63,0x67,0x69,0x6e,0x70,0x70,0x71,0x77,0x7c,0x81,0x88,0x8b,0x8c,0x8b,
0x8a,0x87,0x86,0x88,0x88,0x87,0x86,0x82,0x7d,0x79,0x76,0x74,0x75,0x76,0x76,0x76,
0x75,0x75,0x75,0x78,0x7c,0x82,0x87,0x8b,0x8e,0x90,0x91,0x94,0x98,0x9b,0xa2,0xa1,
0x9b,0x97,0x90,0x88,0x83,0x83,0x7e,0x7d,0x7a,0x70,0x69,0x66,0x64,0x63,0x68,0x6a,
0x6d,0x70,0x70,0x70,0x72,0x78,0x7d,0x82,0x87,0x89,0x89,0x88,0x87,0x85,0x86,0x88,
0x88,0x87,0x85,0x81,0x7d,0x7a,0x77,0x77,0x77,0x78,0x77,0x76,0x75,0x75,0x76,0x78,
0x7b,0x80,0x84,0x87,0x89,0x8b,0x8d,0x90,0x93,0x97,0x9b,0x9d,0x99,0x94,0x8f,0x8a,
0x86,0x84,0x83,0x81,0x7e,0x78,0x71,0x6d,0x6b,0x6a,0x6c,0x6e,0x70,0x72,0x73,0x72,
0x72,0x75,0x79,0x7d,0x80,0x83,0x84,0x84,0x84,0x83,0x84,0x85,0x86,0x87,0x86,0x85,
0x83,0x80,0x7d,0x7b,0x7b,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x79,0x7a,0x7c,0x7f,0x82,
0x84,0x86,0x87,0x88,0x8a,0x8c,0x8f,0x92,0x91,0x8f,0x8c,0x89,0x87,0x85,0x83,0x83,
0x83,0x80,0x7c,0x78,0x77,0x76,0x75,0x75,0x76,0x77,0x78,0x78,0x77,0x78,0x79,0x7a,
0x7c,0x7e,0x7f,0x80,0x81,0x80,0x80,0x80,0x81,0x82,0x82,0x81,0x81,0x80,0x7f,0x7e,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7d,0x7e,0x7f,0x80,0x80,
0x81,0x82,0x83,0x85,0x87,0x88,0x89,0x88,0x87,0x87,0x87,0x87,0x87,0x87,0x87,0x85,
0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7c,0x7b,0x7a,0x7a,0x7a,0x7a,0x7a,
0x7a,0x7b,0x7b,0x7b,0x7b,0x7b,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,
0x7d,0x7d,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7d,0x7e,0x7e,0x7f,0x80,0x81,0x83,
0x84,0x86,0x88,0x88,0x88,0x87,0x88,0x88,0x88,0x88,0x88,0x87,0x85,0x84,0x82,0x81,
0x80,0x7f,0x7f,0x7e,0x7e,0x7c,0x7b,0x7a,0x7a,0x7a,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7c,0x7d,0x7e,0x7e,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,
0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7c,0x7d,0x7d,0x7e,0x7f,0x80,0x82,0x83,0x85,0x87,
0x88,0x89,0x89,0x89,0x89,0x89,0x89,0x89,0x88,0x87,0x86,0x84,0x83,0x82,0x81,0x80,
0x7f,0x7e,0x7d,0x7c,0x7b,0x7a,0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,
0x7d,0x7e,0x7e,0x7e,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,
0x7b,0x7b,0x7b,0x7c,0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x83,0x85,0x87,0x88,0x89,0x89,
0x89,0x89,0x89,0x89,0x89,0x88,0x87,0x85,0x84,0x83,0x82,0x80,0x7f,0x7e,0x7e,0x7d,
0x7c,0x7c,0x7b,0x7b,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,
0x7b,0x7c,0x7d,0x7e,0x7e,0x7f,0x80,0x81,0x82,0x84,0x86,0x88,0x89,0x89,0x89,0x89,
0x89,0x89,0x89,0x88,0x88,0x86,0x85,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7f,0x7e,0x7c,
0x7c,0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7b,
0x7c,0x7d,0x7e,0x7e,0x7f,0x80,0x81,0x82,0x84,0x86,0x88,0x89,0x88,0x88,0x88,0x88,
0x88,0x88,0x87,0x86,0x85,0x84,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7c,0x7b,
0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7c,0x7b,0x7b,0x7b,0x7a,0x7a,0x7b,0x7b,0x7c,
0x7c,0x7d,0x7e,0x7f,0x80,0x81,0x82,0x84,0x86,0x88,0x88,0x88,0x88,0x88,0x88,0x89,
0x88,0x88,0x87,0x85,0x84,0x83,0x82,0x80,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x7b,
0x7b,0x7c,0x7c,0x7c,0x7d,0x7d,0x7c,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7f,0x7e,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x7a,0x7a,0x7a,0x7b,0x7c,
0x7c,0x7d,0x7e,0x7f,0x80,0x82,0x84,0x86,0x88,0x89,0x89,0x89,0x89,0x89,0x89,0x89,
0x89,0x88,0x86,0x85,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x7b,0x7b,
0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7f,0x7f,0x80,0x7f,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7b,0x7a,0x7a,0x79,0x79,0x79,0x7a,0x7b,0x7b,0x7c,
0x7d,0x7e,0x7f,0x80,0x82,0x84,0x86,0x88,0x89,0x89,0x89,0x89,0x89,0x89,0x8a,0x89,
0x89,0x87,0x86,0x84,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,
0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x79,0x79,0x79,0x7a,0x7a,0x7b,0x7c,
0x7d,0x7e,0x7f,0x81,0x82,0x84,0x86,0x88,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,
0x89,0x87,0x86,0x85,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,
0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x78,0x79,0x79,0x7a,0x7b,0x7b,
0x7c,0x7d,0x7f,0x80,0x82,0x84,0x86,0x88,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,0x89,
0x89,0x87,0x86,0x84,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7b,0x7b,
0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x7e,0x7e,0x7e,
0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x79,0x78,0x78,0x79,0x79,0x7a,0x7b,
0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x84,0x86,0x88,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,
0x89,0x89,0x87,0x86,0x84,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x7b,
0x7b,0x7b,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x7f,0x7e,0x7e,
0x7e,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x79,0x78,0x78,0x78,0x79,0x7a,0x7a,
0x7b,0x7d,0x7e,0x7f,0x80,0x81,0x83,0x85,0x87,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,
0x8a,0x8a,0x89,0x87,0x86,0x84,0x83,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7b,
0x7b,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7e,
0x7e,0x7e,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x7a,
0x7b,0x7c,0x7d,0x7e,0x7f,0x80,0x82,0x84,0x85,0x87,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,
0x8a,0x8a,0x89,0x88,0x87,0x85,0x84,0x83,0x82,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7c,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,0x79,0x79,0x79,0x79,0x7a,
0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x80,0x82,0x83,0x85,0x87,0x89,0x8a,0x8a,0x8a,0x8a,
0x8a,0x8a,0x8a,0x8a,0x89,0x88,0x86,0x85,0x84,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7a,0x7a,0x7a,0x79,0x79,0x79,0x79,0x79,
0x79,0x7a,0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x81,0x83,0x84,0x86,0x88,0x8a,0x8b,0x8b,
0x8b,0x8b,0x8a,0x8a,0x8a,0x89,0x88,0x87,0x85,0x84,0x82,0x81,0x7f,0x7e,0x7e,0x7d,
0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,0x78,
0x78,0x78,0x78,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x80,0x81,0x83,0x85,0x87,0x89,0x8a,
0x8b,0x8b,0x8b,0x8b,0x8b,0x8b,0x8a,0x89,0x88,0x86,0x85,0x84,0x82,0x81,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7c,0x7c,0x7b,0x7a,0x7a,0x79,0x78,0x78,
0x78,0x78,0x78,0x78,0x79,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x84,0x86,
0x88,0x89,0x8b,0x8b,0x8b,0x8b,0x8b,0x8b,0x8a,0x89,0x89,0x87,0x86,0x85,0x84,0x82,
0x81,0x80,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7a,0x7a,
0x79,0x79,0x78,0x78,0x78,0x78,0x78,0x79,0x79,0x7a,0x7b,0x7b,0x7d,0x7e,0x7f,0x81,
0x82,0x84,0x86,0x88,0x8a,0x8b,0x8c,0x8b,0x8c,0x8b,0x8b,0x8b,0x8a,0x89,0x88,0x87,
0x85,0x84,0x82,0x81,0x7f,0x7f,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,
0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,
0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,0x78,0x78,0x78,0x78,0x79,0x7a,0x7a,0x7b,0x7d,
0x7e,0x7f,0x81,0x83,0x84,0x86,0x88,0x8a,0x8b,0x8c,0x8c,0x8c,0x8c,0x8b,0x8b,0x8a,
0x89,0x87,0x86,0x85,0x84,0x82,0x81,0x80,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,
0x7d,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,0x77,0x77,0x78,0x78,0x78,0x79,
0x7a,0x7b,0x7c,0x7e,0x7f,0x80,0x82,0x84,0x85,0x87,0x89,0x8b,0x8c,0x8c,0x8c,0x8c,
0x8b,0x8b,0x8a,0x89,0x88,0x87,0x86,0x84,0x83,0x82,0x80,0x7f,0x7e,0x7e,0x7d,0x7c,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x78,0x77,0x77,0x77,
0x78,0x78,0x79,0x79,0x7a,0x7b,0x7c,0x7e,0x7f,0x81,0x82,0x84,0x86,0x87,0x89,0x8b,
0x8c,0x8c,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x86,0x85,0x84,0x83,0x81,0x80,0x7f,
0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x79,0x79,0x78,0x77,
0x77,0x77,0x77,0x77,0x77,0x78,0x78,0x79,0x7a,0x7b,0x7d,0x7e,0x7f,0x81,0x83,0x84,
0x86,0x88,0x89,0x8b,0x8c,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x87,0x86,0x84,
0x84,0x82,0x81,0x80,0x7f,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7d,0x7c,0x7d,0x7d,0x7d,
0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,
0x79,0x79,0x78,0x78,0x77,0x77,0x77,0x78,0x78,0x78,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,
0x80,0x81,0x83,0x85,0x86,0x88,0x8a,0x8c,0x8c,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,
0x88,0x86,0x85,0x84,0x83,0x82,0x81,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,
0x7d,0x7c,0x7b,0x7a,0x7a,0x79,0x78,0x77,0x77,0x77,0x77,0x77,0x77,0x78,0x79,0x79,
0x7a,0x7b,0x7d,0x7e,0x7f,0x81,0x83,0x84,0x86,0x88,0x8a,0x8b,0x8d,0x8d,0x8d,0x8d,
0x8c,0x8c,0x8b,0x8a,0x89,0x87,0x86,0x85,0x84,0x82,0x81,0x80,0x7f,0x7e,0x7d,0x7c,
0x7c,0x7c,0x7b,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x77,0x77,0x76,0x76,0x76,
0x77,0x77,0x78,0x79,0x79,0x7b,0x7c,0x7d,0x7f,0x80,0x82,0x83,0x85,0x87,0x89,0x8b,
0x8c,0x8d,0x8e,0x8d,0x8d,0x8c,0x8b,0x8a,0x89,0x88,0x86,0x85,0x84,0x83,0x81,0x80,
0x7f,0x7e,0x7d,0x7d,0x7c,0x7a,0x78,0x78,0x7a,0x7d,0x80,0x81,0x7f,0x7d,0x7a,0x7a,
0x7b,0x7f,0x83,0x85,0x84,0x80,0x7c,0x79,0x79,0x7a,0x7c,0x7d,0x7d,0x7a,0x76,0x72,
0x71,0x72,0x75,0x78,0x79,0x78,0x77,0x76,0x76,0x78,0x7d,0x81,0x84,0x84,0x83,0x83,
0x86,0x8a,0x8f,0x92,0x90,0x8b,0x8b,0x8f,0x92,0x90,0x8b,0x85,0x84,0x85,0x86,0x83,
0x7f,0x7a,0x7b,0x7d,0x7c,0x78,0x77,0x78,0x7b,0x7c,0x7a,0x79,0x7b,0x7e,0x80,0x80,
0x7e,0x7f,0x82,0x84,0x82,0x80,0x81,0x83,0x82,0x80,0x7e,0x7d,0x7f,0x7e,0x7b,0x78,
0x78,0x78,0x78,0x75,0x72,0x74,0x77,0x76,0x74,0x74,0x76,0x79,0x7a,0x79,0x7a,0x7d,
0x80,0x81,0x81,0x83,0x86,0x89,0x89,0x8a,0x8c,0x92,0x91,0x8a,0x8c,0x93,0x94,0x8a,
0x86,0x88,0x8b,0x88,0x81,0x7d,0x7f,0x80,0x7e,0x7c,0x76,0x77,0x7b,0x7c,0x77,0x77,
0x7b,0x7c,0x7c,0x7d,0x7e,0x7f,0x80,0x80,0x82,0x83,0x81,0x81,0x82,0x82,0x82,0x81,
0x7e,0x7e,0x7f,0x7e,0x7a,0x78,0x79,0x79,0x77,0x75,0x74,0x75,0x75,0x74,0x75,0x75,
0x76,0x78,0x79,0x7a,0x7b,0x7d,0x7f,0x81,0x82,0x85,0x86,0x87,0x88,0x8c,0x8d,0x8f,
0x91,0x8c,0x8f,0x94,0x93,0x89,0x8a,0x8c,0x8b,0x86,0x82,0x81,0x81,0x80,0x7c,0x7e,
0x7a,0x78,0x7a,0x7b,0x78,0x79,0x7b,0x79,0x7d,0x7f,0x7e,0x7d,0x81,0x82,0x82,0x82,
0x82,0x82,0x83,0x82,0x81,0x82,0x7f,0x7f,0x7e,0x7d,0x7b,0x79,0x79,0x78,0x77,0x76,
0x74,0x73,0x74,0x75,0x74,0x74,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7e,0x7f,0x81,0x83,
0x84,0x84,0x88,0x89,0x8c,0x8c,0x91,0x8f,0x8a,0x92,0x94,0x8e,0x88,0x8e,0x8a,0x88,
0x86,0x83,0x82,0x80,0x7f,0x7d,0x7e,0x78,0x7a,0x7a,0x7a,0x79,0x7a,0x79,0x7a,0x7e,
0x7d,0x7c,0x7f,0x81,0x80,0x81,0x82,0x82,0x81,0x82,0x82,0x81,0x80,0x7f,0x7e,0x7e,
0x7c,0x7a,0x79,0x78,0x77,0x75,0x75,0x73,0x73,0x74,0x73,0x73,0x74,0x75,0x76,0x77,
0x78,0x79,0x7b,0x7d,0x7e,0x81,0x82,0x84,0x85,0x88,0x88,0x8c,0x8c,0x91,0x8e,0x8a,
0x93,0x93,0x8e,0x89,0x8f,0x89,0x89,0x86,0x83,0x82,0x81,0x7f,0x7d,0x7f,0x78,0x7a,
0x7a,0x7a,0x79,0x7b,0x79,0x7b,0x7e,0x7d,0x7d,0x80,0x81,0x80,0x82,0x82,0x82,0x82,
0x83,0x82,0x81,0x81,0x7f,0x7e,0x7d,0x7c,0x79,0x79,0x78,0x76,0x75,0x74,0x74,0x73,
0x74,0x73,0x73,0x74,0x75,0x75,0x77,0x78,0x79,0x7a,0x7d,0x7e,0x80,0x82,0x82,0x85,
0x86,0x89,0x88,0x8c,0x8c,0x91,0x8d,0x8c,0x93,0x92,0x8c,0x8a,0x8f,0x88,0x88,0x86,
0x84,0x82,0x81,0x7e,0x7e,0x7e,0x79,0x7a,0x7b,0x7b,0x79,0x7b,0x7b,0x7d,0x7e,0x7e,
0x7e,0x81,0x81,0x80,0x83,0x83,0x81,0x82,0x83,0x82,0x80,0x80,0x7e,0x7e,0x7d,0x7b,
0x79,0x79,0x77,0x75,0x75,0x74,0x73,0x72,0x73,0x73,0x73,0x73,0x74,0x76,0x77,0x77,
0x7a,0x7b,0x7d,0x7e,0x81,0x82,0x84,0x85,0x87,0x89,0x89,0x8d,0x8d,0x92,0x8a,0x8f,
0x93,0x90,0x8b,0x8d,0x8d,0x87,0x89,0x84,0x84,0x81,0x81,0x7d,0x80,0x7c,0x7a,0x7c,
0x7c,0x7b,0x7a,0x7c,0x7c,0x7f,0x7e,0x7f,0x7f,0x82,0x81,0x82,0x83,0x82,0x82,0x82,
0x83,0x81,0x80,0x7f,0x7e,0x7d,0x7c,0x7a,0x79,0x78,0x77,0x76,0x75,0x74,0x73,0x73,
0x73,0x73,0x74,0x74,0x75,0x76,0x77,0x78,0x7a,0x7c,0x7d,0x7f,0x80,0x82,0x83,0x86,
0x85,0x88,0x89,0x8d,0x8b,0x8f,0x8f,0x8a,0x90,0x91,0x8e,0x88,0x8f,0x89,0x88,0x87,
0x84,0x83,0x82,0x81,0x7f,0x80,0x7b,0x7d,0x7d,0x7d,0x7b,0x7d,0x7d,0x7d,0x7f,0x7f,
0x7f,0x80,0x81,0x81,0x82,0x82,0x81,0x81,0x82,0x81,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,
0x79,0x78,0x78,0x76,0x75,0x75,0x74,0x73,0x73,0x73,0x73,0x74,0x74,0x75,0x76,0x77,
0x78,0x7a,0x7c,0x7d,0x7e,0x80,0x82,0x84,0x85,0x86,0x87,0x8a,0x8c,0x8b,0x90,0x8a,
0x8e,0x92,0x8f,0x8a,0x8d,0x8c,0x87,0x89,0x85,0x84,0x81,0x82,0x7f,0x80,0x7d,0x7c,
0x7d,0x7d,0x7c,0x7b,0x7d,0x7c,0x7e,0x7f,0x7f,0x7e,0x80,0x80,0x81,0x81,0x81,0x80,
0x81,0x81,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x79,0x78,0x78,0x77,0x75,0x74,0x74,0x73,
0x73,0x73,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7e,0x7f,0x81,0x82,
0x85,0x84,0x87,0x88,0x8a,0x8a,0x8d,0x8f,0x88,0x90,0x92,0x8d,0x89,0x8e,0x8a,0x88,
0x88,0x84,0x84,0x82,0x82,0x80,0x82,0x7c,0x7d,0x7f,0x7d,0x7b,0x7d,0x7e,0x7d,0x7f,
0x7f,0x7f,0x80,0x81,0x80,0x81,0x81,0x80,0x80,0x82,0x81,0x7f,0x7f,0x7e,0x7d,0x7c,
0x7b,0x79,0x79,0x77,0x76,0x76,0x75,0x73,0x73,0x74,0x73,0x73,0x74,0x75,0x75,0x77,
0x77,0x78,0x7a,0x7c,0x7d,0x7f,0x80,0x82,0x83,0x85,0x85,0x87,0x89,0x8b,0x8a,0x8e,
0x8e,0x8a,0x92,0x90,0x8c,0x8b,0x8f,0x88,0x8a,0x88,0x85,0x84,0x83,0x82,0x81,0x81,
0x7b,0x7f,0x7e,0x7d,0x7b,0x7e,0x7d,0x7d,0x7f,0x7f,0x7f,0x80,0x81,0x80,0x82,0x81,
0x80,0x81,0x82,0x7f,0x7f,0x7f,0x7e,0x7c,0x7c,0x7a,0x79,0x79,0x77,0x76,0x75,0x74,
0x73,0x74,0x73,0x72,0x73,0x74,0x75,0x75,0x77,0x77,0x79,0x7a,0x7c,0x7d,0x7f,0x80,
0x82,0x83,0x84,0x85,0x88,0x88,0x8a,0x8b,0x8c,0x8f,0x8a,0x90,0x90,0x8d,0x8a,0x8e,
0x89,0x88,0x8a,0x86,0x85,0x83,0x83,0x81,0x82,0x7d,0x7e,0x7f,0x7e,0x7c,0x7e,0x7e,
0x7d,0x7f,0x7f,0x7f,0x7f,0x81,0x80,0x81,0x81,0x80,0x80,0x81,0x80,0x7f,0x7e,0x7e,
0x7c,0x7c,0x7a,0x79,0x78,0x77,0x76,0x75,0x74,0x73,0x73,0x73,0x73,0x73,0x74,0x74,
0x75,0x76,0x77,0x78,0x7a,0x7b,0x7d,0x7e,0x80,0x81,0x83,0x84,0x85,0x86,0x89,0x88,
0x8b,0x8b,0x8e,0x8c,0x8c,0x91,0x8e,0x8c,0x8b,0x8e,0x88,0x8a,0x86,0x86,0x83,0x83,
0x82,0x81,0x80,0x7d,0x80,0x7e,0x7e,0x7c,0x7f,0x7d,0x7e,0x7f,0x7f,0x7f,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x7e,0x7e,0x7d,0x7d,0x7b,0x7a,0x79,0x78,0x77,0x76,
0x75,0x74,0x73,0x73,0x73,0x73,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,
0x7d,0x7f,0x80,0x82,0x83,0x84,0x86,0x87,0x89,0x89,0x8b,0x8b,0x8f,0x8a,0x8e,0x91,
0x8d,0x8b,0x8d,0x8b,0x88,0x8b,0x86,0x86,0x83,0x84,0x81,0x82,0x7e,0x7e,0x80,0x7e,
0x7d,0x7d,0x7f,0x7d,0x7f,0x7f,0x7f,0x7e,0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x7f,
0x7e,0x7e,0x7d,0x7c,0x7b,0x7a,0x78,0x78,0x77,0x76,0x75,0x74,0x73,0x73,0x73,0x72,
0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x7a,0x7b,0x7d,0x7e,0x7f,0x80,0x82,0x83,0x85,
0x86,0x88,0x88,0x8a,0x8b,0x8c,0x8e,0x8a,0x8f,0x90,0x8d,0x8b,0x8d,0x8a,0x89,0x89,
0x86,0x86,0x84,0x83,0x83,0x82,0x7e,0x7f,0x80,0x7e,0x7d,0x7f,0x7f,0x7e,0x7f,0x80,
0x7e,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7e,0x7e,0x7e,0x7d,0x7b,0x7b,0x7a,
0x78,0x78,0x77,0x76,0x75,0x74,0x74,0x73,0x73,0x73,0x73,0x74,0x74,0x75,0x76,0x77,
0x78,0x79,0x7b,0x7c,0x7d,0x7e,0x80,0x81,0x83,0x83,0x85,0x86,0x87,0x88,0x8a,0x8a,
0x8d,0x8e,0x8a,0x90,0x90,0x8d,0x8c,0x8e,0x8b,0x89,0x8a,0x87,0x86,0x84,0x84,0x82,
0x83,0x7e,0x7f,0x80,0x7f,0x7d,0x7e,0x7e,0x7d,0x7f,0x7f,0x7e,0x7e,0x80,0x7f,0x80,
0x7f,0x7f,0x7f,0x80,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x78,0x78,0x77,0x76,0x75,
0x75,0x74,0x74,0x73,0x73,0x73,0x74,0x75,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7e,
0x7f,0x80,0x81,0x83,0x84,0x85,0x87,0x88,0x89,0x8a,0x8b,0x8d,0x8c,0x8c,0x90,0x8e,
0x8c,0x8c,0x8d,0x89,0x8a,0x89,0x87,0x85,0x85,0x83,0x82,0x81,0x7f,0x80,0x7f,0x7f,
0x7d,0x7f,0x7e,0x7e,0x7f,0x7f,0x7e,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,
0x7d,0x7d,0x7c,0x7b,0x7b,0x79,0x78,0x78,0x77,0x75,0x75,0x74,0x74,0x73,0x74,0x73,
0x73,0x74,0x75,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x83,
0x84,0x86,0x87,0x88,0x88,0x8a,0x8b,0x8e,0x89,0x8e,0x90,0x8d,0x8c,0x8d,0x8c,0x89,
0x8b,0x87,0x87,0x85,0x85,0x82,0x83,0x80,0x7f,0x81,0x7f,0x7d,0x7e,0x7f,0x7c,0x7f,
0x7f,0x7e,0x7d,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7f,0x7e,0x7d,0x7d,0x7c,0x7b,0x7b,
0x7a,0x78,0x78,0x77,0x76,0x75,0x75,0x74,0x74,0x74,0x73,0x73,0x73,0x74,0x75,0x75,
0x76,0x77,0x79,0x7a,0x7b,0x7c,0x7d,0x7f,0x81,0x82,0x83,0x84,0x85,0x86,0x88,0x88,
0x8a,0x8a,0x8d,0x8b,0x8b,0x8f,0x8e,0x8c,0x8b,0x8d,0x89,0x8a,0x89,0x87,0x85,0x85,
0x84,0x83,0x82,0x7f,0x80,0x80,0x7f,0x7e,0x7f,0x7e,0x7e,0x7f,0x7f,0x7e,0x7f,0x80,
0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7d,0x7d,0x7d,0x7b,0x7b,0x7a,0x79,0x78,0x78,
0x76,0x75,0x75,0x74,0x74,0x73,0x73,0x73,0x74,0x74,0x74,0x75,0x76,0x77,0x79,0x79,
0x7b,0x7c,0x7e,0x7f,0x80,0x81,0x83,0x84,0x86,0x86,0x88,0x89,0x89,0x8b,0x8c,0x8e,
0x8b,0x90,0x8f,0x8e,0x8c,0x8e,0x8c,0x8a,0x8b,0x88,0x87,0x86,0x85,0x83,0x84,0x80,
0x80,0x81,0x7f,0x7e,0x7f,0x7f,0x7d,0x7f,0x7f,0x7e,0x7e,0x80,0x7f,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7c,0x7c,0x7b,0x79,0x79,0x78,0x77,0x76,0x75,0x74,
0x73,0x73,0x73,0x73,0x73,0x73,0x74,0x75,0x75,0x76,0x78,0x79,0x7a,0x7c,0x7d,0x7e,
0x80,0x81,0x82,0x84,0x85,0x86,0x87,0x88,0x89,0x8b,0x8b,0x8c,0x8e,0x8b,0x8f,0x8f,
0x8e,0x8c,0x8d,0x8c,0x8a,0x8a,0x88,0x86,0x85,0x85,0x83,0x83,0x80,0x80,0x80,0x80,
0x7e,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x7e,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x79,0x78,0x78,0x76,0x75,0x74,0x74,0x73,0x73,0x72,
0x72,0x72,0x73,0x73,0x74,0x74,0x76,0x77,0x79,0x7a,0x7b,0x7c,0x7e,0x80,0x81,0x82,
0x83,0x85,0x86,0x87,0x87,0x89,0x8a,0x8b,0x8b,0x8c,0x8b,0x8c,0x8f,0x8d,0x8c,0x8b,
0x8c,0x89,0x8a,0x88,0x87,0x85,0x85,0x84,0x83,0x81,0x80,0x81,0x80,0x7f,0x7e,0x80,
0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7d,0x7d,
0x7c,0x7b,0x7a,0x79,0x78,0x77,0x76,0x75,0x74,0x74,0x73,0x73,0x72,0x72,0x72,0x73,
0x73,0x74,0x74,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7e,0x7f,0x80,0x82,0x83,0x85,0x85,
0x86,0x87,0x89,0x89,0x8a,0x8b,0x8b,0x8c,0x8b,0x8d,0x8e,0x8d,0x8c,0x8c,0x8b,0x8a,
0x8a,0x88,0x86,0x86,0x85,0x84,0x83,0x82,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x80,
0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7d,0x7d,0x7d,0x7b,0x7b,
0x7a,0x78,0x77,0x77,0x76,0x75,0x74,0x73,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,
0x75,0x75,0x77,0x78,0x79,0x7b,0x7c,0x7e,0x7f,0x80,0x81,0x83,0x84,0x85,0x86,0x87,
0x88,0x89,0x8a,0x8a,0x8b,0x8c,0x8c,0x8c,0x8d,0x8d,0x8d,0x8b,0x8c,0x8a,0x8a,0x88,
0x88,0x87,0x86,0x85,0x84,0x84,0x82,0x82,0x81,0x81,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x7b,0x7a,0x79,
0x77,0x77,0x76,0x75,0x74,0x73,0x72,0x72,0x72,0x71,0x72,0x72,0x73,0x73,0x74,0x75,
0x76,0x78,0x79,0x7a,0x7c,0x7d,0x7f,0x80,0x81,0x83,0x84,0x85,0x86,0x87,0x87,0x88,
0x89,0x89,0x8a,0x8b,0x8c,0x8b,0x8c,0x8d,0x8d,0x8c,0x8c,0x8c,0x8a,0x8a,0x89,0x89,
0x87,0x86,0x85,0x85,0x84,0x83,0x83,0x82,0x82,0x81,0x81,0x81,0x81,0x81,0x80,0x80,
0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x79,0x78,0x77,0x76,
0x75,0x75,0x74,0x73,0x72,0x72,0x71,0x72,0x71,0x72,0x72,0x73,0x74,0x75,0x76,0x77,
0x78,0x7a,0x7b,0x7d,0x7e,0x7f,0x80,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,
0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8d,0x8d,0x8c,0x8b,0x8b,0x8b,0x8a,0x8a,0x87,0x88,
0x86,0x86,0x85,0x84,0x83,0x83,0x83,0x82,0x82,0x81,0x81,0x81,0x81,0x80,0x80,0x80,
0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x7a,0x79,0x78,0x77,0x76,0x75,0x75,
0x74,0x73,0x72,0x72,0x71,0x71,0x71,0x72,0x72,0x72,0x73,0x74,0x75,0x76,0x77,0x79,
0x7a,0x7b,0x7d,0x7e,0x7f,0x81,0x82,0x83,0x84,0x85,0x86,0x86,0x87,0x88,0x88,0x89,
0x8a,0x8b,0x8b,0x8b,0x8c,0x8c,0x8d,0x8d,0x8c,0x8b,0x8b,0x8b,0x8a,0x89,0x88,0x87,
0x87,0x86,0x85,0x84,0x83,0x83,0x82,0x82,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x78,0x78,0x77,0x76,0x75,0x75,0x74,
0x73,0x73,0x72,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x7a,
0x7b,0x7d,0x7e,0x7f,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x87,0x88,0x89,0x89,0x8a,
0x8a,0x8b,0x8c,0x8c,0x8d,0x8d,0x8d,0x8c,0x8c,0x8c,0x8b,0x8a,0x8a,0x89,0x88,0x87,
0x86,0x86,0x85,0x84,0x83,0x83,0x82,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7e,0x7e,
0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x78,0x78,0x77,0x76,0x76,0x75,0x74,0x74,
0x73,0x73,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7b,
0x7c,0x7d,0x7f,0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8b,
0x8b,0x8c,0x8c,0x8d,0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8a,0x8a,0x89,0x88,0x87,
0x86,0x85,0x84,0x84,0x83,0x82,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,
0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x78,0x77,0x76,0x75,0x75,0x74,0x73,
0x73,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,0x74,0x75,0x76,0x77,0x79,0x7a,0x7c,
0x7d,0x7e,0x7f,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x89,0x8a,0x8b,
0x8b,0x8c,0x8c,0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x88,0x87,
0x86,0x85,0x84,0x83,0x83,0x82,0x81,0x80,0x80,0x80,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,
0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x78,0x78,0x77,0x76,0x75,0x75,0x74,0x73,0x73,
0x72,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,
0x7d,0x7f,0x80,0x81,0x82,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8e,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x87,0x86,
0x85,0x85,0x84,0x83,0x82,0x82,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,
0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x77,0x76,0x76,0x75,0x74,0x74,0x73,0x73,
0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x73,0x74,0x75,0x76,0x78,0x79,0x7a,0x7c,0x7d,
0x7e,0x80,0x81,0x82,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8a,0x8a,0x89,0x88,0x87,0x86,
0x85,0x84,0x83,0x83,0x82,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,
0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x73,0x73,0x73,
0x72,0x72,0x72,0x72,0x72,0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x7a,0x7b,0x7c,0x7e,
0x7f,0x80,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8d,0x8d,0x8d,0x8d,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x88,0x87,0x86,
0x85,0x84,0x83,0x82,0x81,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,
0x7b,0x7b,0x7a,0x7a,0x79,0x78,0x78,0x77,0x76,0x76,0x75,0x75,0x74,0x73,0x73,0x72,
0x72,0x72,0x72,0x72,0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7d,0x7e,
0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x86,0x85,
0x84,0x83,0x82,0x82,0x81,0x80,0x80,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,
0x7a,0x7a,0x79,0x79,0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x73,0x73,0x72,
0x72,0x72,0x72,0x72,0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7d,0x7e,
0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8b,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x8a,0x89,0x88,0x87,0x86,0x85,0x84,
0x83,0x82,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7b,
0x7a,0x7a,0x79,0x79,0x78,0x78,0x77,0x76,0x76,0x75,0x75,0x74,0x73,0x73,0x73,0x72,
0x72,0x72,0x73,0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7d,0x7e,0x7f,
0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8b,0x8b,0x8c,0x8c,0x8d,
0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x87,0x87,0x86,0x85,0x84,
0x83,0x82,0x81,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,
0x7b,0x7a,0x7a,0x79,0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x73,0x73,0x73,
0x73,0x73,0x74,0x74,0x75,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7d,0x7f,0x80,0x81,
0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x89,0x8a,0x8b,0x8b,0x8c,0x8c,0x8d,0x8d,
0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8a,0x8a,0x89,0x88,0x87,0x86,0x85,0x84,0x83,
0x82,0x81,0x81,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,
0x7a,0x7a,0x79,0x79,0x78,0x77,0x77,0x76,0x76,0x75,0x74,0x74,0x74,0x73,0x73,0x73,
0x73,0x73,0x74,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7b,0x7d,0x7e,0x7f,0x81,0x82,
0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8d,0x8d,
0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x88,0x87,0x86,0x85,0x84,0x83,0x82,0x81,
0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,
0x79,0x79,0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x74,0x73,0x73,0x73,0x73,
0x73,0x74,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x83,
0x84,0x85,0x86,0x87,0x88,0x89,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8c,0x8c,
0x8c,0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x86,0x85,0x84,0x84,0x83,0x82,0x81,0x81,
0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,
0x79,0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x74,0x73,0x73,0x73,0x73,0x74,
0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7b,0x7c,0x7e,0x7f,0x80,0x82,0x83,0x84,0x85,
0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8c,0x8c,0x8c,0x8b,
0x8b,0x8a,0x8a,0x89,0x88,0x87,0x86,0x86,0x85,0x84,0x83,0x82,0x82,0x81,0x80,0x80,
0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,
0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x74,0x74,0x74,0x74,0x74,0x74,0x75,
0x76,0x76,0x77,0x78,0x7a,0x7b,0x7c,0x7d,0x7f,0x80,0x81,0x82,0x83,0x84,0x85,0x86,
0x87,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8c,0x8c,0x8b,0x8b,0x8a,0x8a,
0x89,0x88,0x88,0x87,0x86,0x85,0x84,0x83,0x82,0x82,0x81,0x81,0x80,0x7f,0x7f,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,
0x77,0x77,0x76,0x76,0x75,0x75,0x74,0x74,0x74,0x74,0x74,0x75,0x75,0x76,0x76,0x77,
0x78,0x79,0x7a,0x7b,0x7d,0x7e,0x7f,0x80,0x81,0x83,0x84,0x85,0x86,0x87,0x87,0x88,
0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8c,0x8c,0x8b,0x8b,0x8a,0x8a,0x89,0x88,
0x87,0x86,0x86,0x85,0x84,0x83,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,
0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,0x77,0x77,
0x76,0x76,0x75,0x75,0x74,0x74,0x74,0x74,0x74,0x75,0x75,0x76,0x77,0x77,0x78,0x79,
0x7b,0x7c,0x7d,0x7e,0x7f,0x80,0x81,0x83,0x84,0x85,0x86,0x87,0x87,0x88,0x89,0x8a,
0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8b,0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x86,0x86,
0x85,0x84,0x83,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,
0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x79,0x78,0x78,0x77,0x77,0x76,
0x76,0x75,0x75,0x75,0x75,0x75,0x75,0x76,0x76,0x77,0x78,0x78,0x79,0x7a,0x7c,0x7d,
0x7e,0x7f,0x80,0x81,0x82,0x84,0x85,0x86,0x87,0x87,0x88,0x89,0x8a,0x8a,0x8b,0x8c,
0x8c,0x8c,0x8c,0x8b,0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x86,0x85,0x84,0x84,0x83,
0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,
0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x79,0x78,0x78,0x77,0x77,0x76,0x76,0x76,0x75,
0x75,0x75,0x75,0x76,0x76,0x76,0x77,0x78,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x80,
0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x89,0x8a,0x8b,0x8b,0x8b,0x8b,0x8b,
0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x87,0x86,0x85,0x84,0x83,0x82,0x82,0x81,0x81,
0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,
0x7a,0x7a,0x79,0x79,0x79,0x78,0x78,0x77,0x77,0x76,0x76,0x76,0x76,0x76,0x76,0x76,
0x76,0x76,0x77,0x78,0x78,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x80,0x81,0x82,0x83,0x84,
0x85,0x86,0x87,0x87,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8b,0x8b,0x8b,0x8a,0x8a,0x89,
0x89,0x88,0x87,0x87,0x86,0x85,0x84,0x83,0x83,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,
0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,
0x79,0x78,0x78,0x77,0x77,0x77,0x76,0x76,0x76,0x76,0x76,0x76,0x76,0x77,0x77,0x78,
0x79,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,
0x88,0x88,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,0x89,0x89,0x88,0x88,0x87,0x86,
0x86,0x85,0x84,0x83,0x82,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,
0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,0x79,0x78,0x78,0x78,
0x77,0x77,0x77,0x77,0x76,0x76,0x76,0x77,0x77,0x77,0x78,0x79,0x79,0x7a,0x7b,0x7c,
0x7d,0x7e,0x7f,0x80,0x81,0x82,0x83,0x84,0x84,0x85,0x86,0x87,0x87,0x88,0x89,0x89,
0x89,0x89,0x89,0x89,0x89,0x89,0x88,0x88,0x88,0x87,0x86,0x86,0x85,0x84,0x84,0x83,
0x82,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,
0x7c,0x7b,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,0x79,0x79,0x78,0x78,0x78,0x77,0x77,0x77,
0x77,0x77,0x78,0x78,0x78,0x79,0x79,0x7a,0x7b,0x7c,0x7c,0x7d,0x7e,0x7f,0x80,0x81,
0x82,0x83,0x83,0x84,0x85,0x86,0x86,0x87,0x87,0x88,0x88,0x89,0x89,0x89,0x89,0x89,
0x88,0x88,0x88,0x87,0x87,0x86,0x85,0x85,0x84,0x83,0x83,0x82,0x82,0x81,0x81,0x80,
0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7a,
0x7a,0x7a,0x79,0x79,0x79,0x79,0x78,0x78,0x78,0x78,0x78,0x78,0x78,0x78,0x78,0x79,
0x79,0x7a,0x7a,0x7b,0x7c,0x7d,0x7d,0x7e,0x7f,0x80,0x81,0x82,0x82,0x83,0x84,0x84,
0x85,0x86,0x86,0x87,0x87,0x88,0x88,0x88,0x88,0x88,0x88,0x88,0x88,0x87,0x87,0x86,
0x86,0x85,0x85,0x84,0x84,0x83,0x82,0x82,0x81,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,
0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x7a,0x7a,0x7b,0x7b,0x7c,0x7d,
0x7d,0x7e,0x7f,0x7f,0x80,0x81,0x82,0x82,0x83,0x84,0x84,0x85,0x86,0x86,0x86,0x87,
0x87,0x87,0x87,0x87,0x87,0x87,0x87,0x86,0x86,0x85,0x85,0x85,0x84,0x83,0x83,0x82,
0x82,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,
0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,
0x7a,0x7a,0x7a,0x7b,0x7b,0x7b,0x7c,0x7c,0x7d,0x7d,0x7e,0x7f,0x7f,0x80,0x80,0x81,
0x82,0x82,0x83,0x84,0x84,0x85,0x85,0x86,0x86,0x86,0x86,0x86,0x86,0x86,0x86,0x86,
0x85,0x85,0x85,0x84,0x84,0x83,0x83,0x83,0x82,0x82,0x81,0x81,0x81,0x80,0x80,0x7f,
0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,
0x7b,0x7b,0x7b,0x7b,0x7b,0x7a,0x7a,0x7b,0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,0x7d,
0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x80,0x80,0x81,0x81,0x82,0x82,0x83,0x83,0x84,0x84,
0x85,0x85,0x85,0x85,0x85,0x85,0x85,0x85,0x85,0x85,0x84,0x84,0x84,0x83,0x83,0x83,
0x82,0x82,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,
0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7b,0x7b,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x7f,0x80,0x80,
0x81,0x81,0x82,0x82,0x82,0x83,0x83,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,
0x84,0x84,0x83,0x83,0x83,0x82,0x82,0x82,0x81,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,
0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7f,
0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x81,0x81,0x81,0x82,0x82,0x82,0x83,0x83,0x83,
0x83,0x83,0x83,0x83,0x83,0x83,0x83,0x83,0x83,0x83,0x82,0x82,0x82,0x81,0x81,0x81,
0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,
0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x81,0x81,0x81,0x81,
0x81,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x81,
0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,
0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x81,
0x81,0x81,0x81,0x81,0x81,0x81,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x81,
0x81,0x81,0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,
0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,
0x80,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,
0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x7f,
0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,
0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,
0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x81,0x81,0x81,0x81,0x81,0x82,0x82,0x82,
0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x81,0x81,0x81,0x81,0x81,0x81,
0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,
0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x81,
0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,
0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x81,0x81,0x81,0x81,0x81,
0x81,0x81,0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7e,0x7f,0x7f,0x7f,0x7e,0x7e,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x80,0x81,0x7a,0x7b,0x7a,0x7c,0x7c,0x7d,0x7e,0x7d,0x81,0x7f,0x81,
0x81,0x82,0x83,0x82,0x86,0x84,0x84,0x83,0x81,0x82,0x82,0x82,0x80,0x80,0x80,0x7e,
0x80,0x80,0x7e,0x7e,0x7d,0x7e,0x7c,0x7f,0x7f,0x7e,0x7f,0x7f,0x80,0x80,0x81,0x80,
0x7f,0x82,0x81,0x81,0x81,0x81,0x80,0x80,0x81,0x80,0x80,0x81,0x80,0x7b,0x7c,0x7c,
0x7c,0x7b,0x7b,0x7b,0x7a,0x7f,0x7d,0x7e,0x7f,0x7f,0x80,0x80,0x83,0x81,0x82,0x82,
0x80,0x82,0x82,0x82,0x7f,0x80,0x81,0x7f,0x81,0x80,0x7e,0x7e,0x7f,0x7e,0x7d,0x7f,
0x7e,0x7d,0x7e,0x7e,0x7f,0x7f,0x80,0x7f,0x80,0x82,0x82,0x82,0x84,0x84,0x85,0x86,
0x86,0x86,0x86,0x87,0x86,0x86,0x87,0x87,0x87,0x87,0x86,0x86,0x87,0x87,0x86,0x85,
0x84,0x83,0x82,0x82,0x80,0x7e,0x7d,0x7b,0x79,0x78,0x77,0x75,0x74,0x73,0x74,0x73,
0x73,0x72,0x73,0x74,0x75,0x76,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7c,0x7d,0x7e,0x7f,
0x81,0x81,0x82,0x83,0x84,0x84,0x85,0x86,0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8a,
0x8a,0x8c,0x8d,0x8e,0x8e,0x8f,0x8f,0x8c,0x8b,0x8b,0x8b,0x89,0x85,0x81,0x7f,0x7e,
0x7b,0x77,0x74,0x72,0x71,0x6f,0x6e,0x6e,0x6d,0x6e,0x6e,0x6f,0x71,0x74,0x75,0x76,
0x79,0x7c,0x7f,0x80,0x81,0x83,0x85,0x86,0x86,0x86,0x86,0x85,0x83,0x81,0x81,0x80,
0x7e,0x7b,0x79,0x78,0x78,0x77,0x76,0x76,0x77,0x78,0x7a,0x7c,0x7f,0x82,0x83,0x86,
0x89,0x8e,0x91,0x94,0x94,0x9a,0x9d,0x94,0x98,0x94,0x96,0x92,0x8c,0x87,0x81,0x82,
0x79,0x75,0x71,0x6d,0x6c,0x67,0x65,0x66,0x67,0x67,0x67,0x6a,0x6e,0x71,0x75,0x76,
0x7c,0x81,0x83,0x86,0x87,0x8b,0x8d,0x8d,0x8d,0x8c,0x8c,0x89,0x85,0x83,0x81,0x7f,
0x7a,0x76,0x74,0x73,0x72,0x70,0x70,0x72,0x73,0x77,0x79,0x7d,0x80,0x85,0x8a,0x8e,
0x92,0x98,0x9b,0x9d,0xa1,0x9b,0x9b,0x9b,0x9a,0x96,0x8e,0x89,0x81,0x80,0x78,0x71,
0x6d,0x68,0x65,0x62,0x60,0x60,0x61,0x62,0x63,0x68,0x6d,0x71,0x76,0x79,0x7f,0x85,
0x89,0x8c,0x8f,0x91,0x93,0x94,0x93,0x92,0x90,0x8d,0x89,0x86,0x82,0x7f,0x7b,0x75,
0x72,0x70,0x6e,0x6b,0x69,0x69,0x6a,0x6c,0x6d,0x71,0x75,0x79,0x7d,0x82,0x86,0x8c,
0x90,0x94,0x97,0x9c,0x9d,0xa0,0xa1,0xa5,0xa6,0x97,0x98,0x92,0x93,0x8d,0x82,0x79,
0x72,0x73,0x69,0x65,0x61,0x5e,0x60,0x5e,0x5e,0x63,0x67,0x69,0x6d,0x73,0x7a,0x81,
0x85,0x86,0x8c,0x92,0x93,0x93,0x92,0x93,0x93,0x91,0x8c,0x88,0x85,0x80,0x7a,0x75,
0x72,0x6f,0x6b,0x67,0x67,0x68,0x6b,0x6c,0x6f,0x74,0x7a,0x80,0x85,0x8a,0x90,0x96,
0x9a,0x9e,0xa2,0xa6,0xa7,0xaa,0xa5,0x9b,0x9d,0x99,0x93,0x8a,0x80,0x78,0x73,0x6d,
0x64,0x5f,0x5c,0x59,0x59,0x59,0x5a,0x5f,0x63,0x67,0x6e,0x77,0x7d,0x83,0x87,0x8d,
0x94,0x97,0x97,0x98,0x98,0x98,0x96,0x92,0x8d,0x88,0x83,0x7e,0x7a,0x75,0x70,0x6b,
0x68,0x67,0x67,0x67,0x67,0x69,0x6d,0x71,0x75,0x7a,0x80,0x86,0x8b,0x8f,0x95,0x99,
0x9d,0x9e,0xa0,0xa2,0xa4,0xa4,0xa5,0xa3,0x93,0x94,0x8d,0x89,0x84,0x78,0x70,0x69,
0x67,0x60,0x5d,0x5b,0x58,0x5c,0x5e,0x61,0x67,0x6c,0x71,0x78,0x80,0x86,0x8c,0x8f,
0x91,0x96,0x98,0x98,0x96,0x93,0x90,0x8d,0x89,0x83,0x7f,0x7a,0x72,0x6e,0x6a,0x68,
0x67,0x64,0x63,0x65,0x69,0x6d,0x71,0x76,0x7c,0x83,0x8b,0x8f,0x96,0x9a,0x9f,0xa1,
0xa3,0xa5,0xa7,0xa8,0xa6,0xa6,0x99,0x92,0x90,0x89,0x83,0x77,0x6d,0x66,0x63,0x5e,
0x58,0x57,0x56,0x58,0x5d,0x5f,0x65,0x6c,0x72,0x78,0x81,0x88,0x8e,0x92,0x94,0x97,
0x9b,0x9a,0x97,0x94,0x90,0x8c,0x87,0x81,0x7b,0x76,0x71,0x6c,0x69,0x65,0x63,0x63,
0x63,0x66,0x69,0x6c,0x70,0x76,0x7d,0x84,0x8a,0x8f,0x94,0x99,0x9e,0xa0,0xa2,0xa2,
0xa4,0xa3,0xa3,0xa2,0xa5,0x98,0x8b,0x8a,0x85,0x83,0x77,0x6b,0x63,0x63,0x60,0x5a,
0x59,0x59,0x5b,0x60,0x63,0x68,0x72,0x76,0x7b,0x82,0x8a,0x90,0x94,0x94,0x95,0x98,
0x98,0x94,0x8f,0x8b,0x88,0x83,0x7c,0x77,0x73,0x6e,0x68,0x66,0x65,0x66,0x65,0x64,
0x68,0x6e,0x73,0x76,0x7b,0x81,0x8a,0x8f,0x93,0x97,0x9c,0x9e,0xa1,0xa1,0xa1,0xa1,
0xa1,0xa1,0xa0,0xa0,0x90,0x88,0x87,0x81,0x7d,0x73,0x68,0x63,0x61,0x5e,0x5a,0x5c,
0x5c,0x5f,0x64,0x67,0x70,0x77,0x7b,0x80,0x88,0x8e,0x93,0x94,0x93,0x95,0x97,0x93,
0x8f,0x8a,0x86,0x82,0x7c,0x77,0x72,0x6f,0x6a,0x68,0x67,0x66,0x67,0x68,0x6b,0x6f,
0x73,0x78,0x7c,0x81,0x87,0x8c,0x91,0x94,0x98,0x9a,0x9d,0x9e,0x9e,0x9e,0x9d,0x9d,
0x9e,0x9f,0x9b,0x8a,0x88,0x85,0x81,0x7c,0x6f,0x68,0x64,0x64,0x5e,0x5d,0x5e,0x5f,
0x63,0x66,0x6b,0x74,0x7a,0x7c,0x83,0x8a,0x90,0x93,0x92,0x91,0x94,0x94,0x90,0x8b,
0x87,0x83,0x80,0x7a,0x75,0x72,0x6f,0x6a,0x68,0x68,0x69,0x6a,0x6a,0x6c,0x71,0x77,
0x7b,0x7f,0x83,0x8a,0x8f,0x93,0x96,0x99,0x9b,0x9e,0x9e,0x9e,0x9e,0x9e,0x9e,0xa0,
0xa0,0x90,0x86,0x82,0x84,0x7e,0x75,0x66,0x62,0x63,0x60,0x5c,0x5b,0x5e,0x61,0x67,
0x69,0x73,0x7a,0x7e,0x81,0x89,0x90,0x95,0x95,0x91,0x92,0x95,0x92,0x8c,0x86,0x81,
0x7f,0x79,0x74,0x6f,0x6d,0x6a,0x66,0x65,0x68,0x6a,0x6b,0x6b,0x71,0x78,0x7c,0x7f,
0x83,0x89,0x8f,0x93,0x95,0x98,0x9b,0x9c,0x9d,0x9c,0x9d,0x9b,0x9c,0x9d,0xa0,0x99,
0x87,0x84,0x82,0x80,0x7b,0x6d,0x63,0x62,0x61,0x5f,0x5d,0x5f,0x5f,0x65,0x69,0x6f,
0x79,0x7d,0x80,0x86,0x8d,0x92,0x96,0x93,0x91,0x93,0x91,0x8c,0x87,0x81,0x7d,0x79,
0x73,0x6f,0x6d,0x6a,0x66,0x66,0x67,0x69,0x6c,0x6e,0x71,0x76,0x7c,0x81,0x85,0x88,
0x8e,0x92,0x96,0x98,0x9a,0x9b,0x9b,0x9a,0x9b,0x9d,0x9e,0x9c,0x9f,0x99,0x86,0x86,
0x81,0x81,0x7a,0x6c,0x63,0x61,0x61,0x5c,0x5d,0x5d,0x5f,0x65,0x6a,0x6f,0x7a,0x7f,
0x82,0x88,0x8e,0x94,0x96,0x94,0x91,0x93,0x91,0x8c,0x86,0x80,0x7b,0x77,0x72,0x6e,
0x6c,0x69,0x66,0x64,0x66,0x6b,0x6e,0x6e,0x70,0x77,0x7e,0x83,0x85,0x89,0x8e,0x93,
0x97,0x98,0x9a,0x9b,0x9b,0x9b,0x9c,0x9e,0x9e,0x9c,0xa0,0x95,0x88,0x86,0x80,0x7f,
0x77,0x6c,0x62,0x61,0x5f,0x5c,0x5e,0x5e,0x61,0x67,0x6b,0x72,0x7d,0x81,0x85,0x8b,
0x90,0x94,0x97,0x94,0x92,0x92,0x8e,0x8a,0x84,0x7e,0x79,0x75,0x70,0x6c,0x6b,0x69,
0x67,0x66,0x67,0x6c,0x70,0x72,0x75,0x79,0x7f,0x85,0x89,0x89,0x8d,0x90,0x94,0x96,
0x97,0x96,0x97,0x97,0x97,0x99,0x99,0x9a,0x9a,0x9f,0x8b,0x89,0x84,0x7f,0x80,0x73,
0x6c,0x62,0x66,0x5e,0x61,0x60,0x60,0x65,0x6a,0x6d,0x77,0x7f,0x80,0x87,0x8b,0x91,
0x93,0x96,0x90,0x91,0x8f,0x8b,0x87,0x81,0x7c,0x78,0x74,0x70,0x6d,0x6b,0x69,0x67,
0x69,0x6a,0x6e,0x70,0x72,0x77,0x7d,0x81,0x85,0x88,0x8d,0x91,0x95,0x96,0x98,0x9a,
0x9c,0x9c,0x9b,0x9a,0x9d,0x9e,0xa2,0x9c,0x85,0x86,0x82,0x81,0x7a,0x6b,0x61,0x60,
0x61,0x5b,0x5e,0x5d,0x5f,0x66,0x6c,0x71,0x7e,0x82,0x85,0x8b,0x92,0x97,0x99,0x95,
0x91,0x92,0x90,0x8a,0x83,0x7c,0x77,0x73,0x6f,0x6c,0x69,0x67,0x62,0x64,0x68,0x6d,
0x6f,0x70,0x74,0x7c,0x83,0x87,0x8a,0x8e,0x91,0x96,0x98,0x99,0x9a,0x99,0x99,0x9a,
0x9b,0x9b,0x9d,0x9c,0x9f,0x8b,0x83,0x81,0x7f,0x7f,0x70,0x65,0x5c,0x62,0x5f,0x5e,
0x5e,0x5f,0x65,0x6d,0x70,0x79,0x83,0x85,0x8a,0x8e,0x95,0x98,0x97,0x91,0x90,0x8f,
0x8b,0x84,0x7d,0x76,0x73,0x6f,0x6b,0x69,0x68,0x67,0x66,0x68,0x6a,0x70,0x72,0x76,
0x7a,0x80,0x84,0x89,0x8a,0x8f,0x91,0x94,0x94,0x96,0x97,0x97,0x97,0x98,0x98,0x9a,
0x9c,0x9c,0xa0,0x87,0x88,0x82,0x80,0x7d,0x71,0x67,0x5f,0x64,0x5a,0x60,0x5f,0x61,
0x64,0x6c,0x6f,0x7c,0x82,0x83,0x8a,0x8f,0x95,0x95,0x96,0x8f,0x91,0x8e,0x88,0x83,
0x7f,0x78,0x73,0x6e,0x6c,0x6a,0x69,0x65,0x63,0x67,0x6c,0x72,0x73,0x74,0x79,0x81,
0x87,0x8b,0x8c,0x8f,0x91,0x95,0x96,0x98,0x97,0x96,0x95,0x97,0x97,0x9b,0x9a,0x9c,
0x9b,0x85,0x87,0x81,0x81,0x7c,0x70,0x64,0x61,0x64,0x5d,0x60,0x60,0x61,0x67,0x6e,
0x71,0x7e,0x82,0x85,0x8a,0x90,0x94,0x96,0x94,0x8f,0x8f,0x8d,0x87,0x81,0x7b,0x76,
0x73,0x6f,0x6c,0x69,0x68,0x66,0x67,0x69,0x6d,0x71,0x73,0x75,0x7c,0x81,0x86,0x89,
0x8c,0x90,0x93,0x95,0x96,0x97,0x96,0x98,0x99,0x9b,0x99,0x9c,0x9a,0xa2,0x93,0x85,
0x85,0x7f,0x80,0x75,0x6a,0x60,0x63,0x5f,0x5d,0x5f,0x60,0x64,0x6c,0x6e,0x77,0x82,
0x85,0x89,0x8d,0x93,0x96,0x98,0x92,0x8f,0x8f,0x8b,0x84,0x7e,0x78,0x74,0x70,0x6b,
0x69,0x69,0x68,0x67,0x68,0x6a,0x6f,0x74,0x77,0x7a,0x80,0x83,0x88,0x8b,0x8e,0x91,
0x93,0x93,0x95,0x96,0x96,0x96,0x95,0x97,0x98,0x9b,0x9b,0xa3,0x8c,0x85,0x84,0x82,
0x82,0x75,0x69,0x60,0x65,0x5e,0x60,0x61,0x60,0x65,0x6b,0x6f,0x7a,0x83,0x83,0x88,
0x8d,0x93,0x96,0x96,0x90,0x8f,0x8e,0x89,0x84,0x7e,0x78,0x74,0x70,0x6c,0x6b,0x6a,
0x68,0x66,0x68,0x6c,0x71,0x74,0x76,0x7a,0x7f,0x84,0x89,0x8b,0x8e,0x91,0x94,0x96,
0x98,0x97,0x98,0x98,0x99,0x99,0x9c,0x9a,0x9f,0x9b,0x84,0x85,0x80,0x81,0x79,0x6d,
0x61,0x60,0x62,0x5b,0x60,0x60,0x63,0x69,0x6e,0x74,0x81,0x84,0x87,0x8c,0x92,0x96,
0x97,0x94,0x8e,0x8f,0x8c,0x85,0x7f,0x79,0x75,0x71,0x6c,0x69,0x68,0x68,0x66,0x67,
0x69,0x6f,0x74,0x76,0x79,0x7f,0x84,0x88,0x8b,0x8d,0x90,0x92,0x94,0x94,0x96,0x95,
0x97,0x94,0x96,0x96,0x9a,0x99,0xa2,0x90,0x83,0x87,0x80,0x82,0x73,0x6b,0x61,0x67,
0x5f,0x5c,0x60,0x60,0x66,0x6b,0x6f,0x77,0x84,0x83,0x88,0x8c,0x94,0x95,0x96,0x90,
0x8e,0x8f,0x89,0x83,0x7d,0x78,0x73,0x70,0x6b,0x6a,0x69,0x67,0x67,0x6b,0x6e,0x71,
0x73,0x77,0x7c,0x82,0x84,0x88,0x8a,0x8d,0x8f,0x91,0x92,0x93,0x94,0x92,0x94,0x95,
0x97,0x97,0x99,0x9a,0xa2,0x8e,0x86,0x86,0x80,0x83,0x75,0x6a,0x61,0x65,0x5f,0x5f,
0x61,0x60,0x66,0x6b,0x6e,0x79,0x82,0x83,0x88,0x8d,0x93,0x96,0x96,0x90,0x8e,0x8d,
0x89,0x83,0x7d,0x77,0x74,0x70,0x6c,0x6a,0x69,0x67,0x68,0x6a,0x6d,0x72,0x75,0x77,
0x7b,0x81,0x85,0x8a,0x8b,0x8d,0x90,0x94,0x93,0x95,0x94,0x96,0x96,0x97,0x97,0x9a,
0x9b,0x9f,0x9b,0x84,0x87,0x83,0x82,0x7c,0x6e,0x64,0x61,0x63,0x5c,0x60,0x60,0x62,
0x68,0x6e,0x74,0x81,0x84,0x86,0x8b,0x92,0x96,0x97,0x94,0x8e,0x8e,0x8b,0x85,0x7f,
0x7a,0x74,0x71,0x6c,0x6a,0x69,0x68,0x68,0x69,0x6c,0x71,0x73,0x76,0x7b,0x80,0x84,
0x87,0x8a,0x8c,0x8f,0x90,0x91,0x92,0x94,0x92,0x93,0x92,0x95,0x95,0x99,0x98,0x9e,
0x9a,0x85,0x88,0x81,0x84,0x7c,0x6f,0x64,0x65,0x65,0x5e,0x62,0x61,0x64,0x6a,0x6f,
0x74,0x81,0x84,0x86,0x8a,0x90,0x94,0x96,0x92,0x8d,0x8e,0x8b,0x85,0x7f,0x79,0x74,
0x73,0x6e,0x6b,0x6a,0x69,0x67,0x68,0x6c,0x71,0x75,0x76,0x79,0x7f,0x85,0x89,0x8c,
0x8d,0x90,0x93,0x94,0x96,0x95,0x95,0x96,0x96,0x97,0x98,0x9a,0x9b,0x9e,0x87,0x83,
0x85,0x7f,0x7f,0x71,0x66,0x61,0x65,0x5f,0x60,0x63,0x62,0x69,0x6f,0x73,0x7f,0x86,
0x86,0x8b,0x8f,0x94,0x96,0x94,0x8e,0x8d,0x8c,0x85,0x80,0x7a,0x74,0x71,0x6e,0x6b,
0x6a,0x69,0x68,0x6a,0x6e,0x72,0x75,0x76,0x79,0x7f,0x85,0x86,0x88,0x89,0x8c,0x8e,
0x8f,0x8f,0x91,0x90,0x91,0x92,0x94,0x95,0x96,0x97,0x9c,0xa3,0x8c,0x89,0x83,0x81,
0x83,0x77,0x69,0x62,0x65,0x5f,0x62,0x60,0x61,0x67,0x6c,0x6f,0x7b,0x83,0x85,0x88,
0x8c,0x92,0x96,0x96,0x8e,0x8d,0x8c,0x88,0x83,0x7d,0x76,0x74,0x70,0x6d,0x6a,0x6a,
0x67,0x67,0x69,0x6e,0x73,0x75,0x76,0x7b,0x81,0x86,0x8a,0x8c,0x8e,0x91,0x94,0x94,
0x95,0x95,0x96,0x94,0x96,0x97,0x9c,0x98,0x9e,0x93,0x81,0x88,0x82,0x81,0x76,0x6b,
0x61,0x65,0x63,0x5c,0x62,0x62,0x66,0x6c,0x71,0x78,0x84,0x85,0x87,0x8d,0x93,0x95,
0x95,0x90,0x8c,0x8d,0x88,0x81,0x7c,0x77,0x73,0x70,0x6b,0x6a,0x6a,0x69,0x69,0x6c,
0x6f,0x73,0x75,0x78,0x7c,0x82,0x86,0x88,0x8a,0x8b,0x8e,0x8f,0x91,0x91,0x92,0x90,
0x91,0x92,0x95,0x95,0x98,0x97,0xa0,0x9a,0x85,0x88,0x81,0x84,0x7c,0x70,0x64,0x65,
0x64,0x5d,0x62,0x62,0x66,0x6b,0x6e,0x74,0x81,0x84,0x86,0x8b,0x90,0x94,0x96,0x92,
0x8c,0x8d,0x89,0x83,0x7e,0x78,0x75,0x72,0x6d,0x6a,0x6b,0x6a,0x69,0x6a,0x6d,0x71,
0x74,0x77,0x7b,0x81,0x84,0x88,0x8a,0x8d,0x90,0x92,0x92,0x94,0x94,0x93,0x93,0x95,
0x96,0x99,0x9a,0x9b,0xa0,0x8a,0x86,0x84,0x83,0x81,0x74,0x66,0x60,0x66,0x5f,0x60,
0x61,0x61,0x68,0x6e,0x73,0x7e,0x85,0x85,0x8a,0x8f,0x94,0x96,0x94,0x8e,0x8d,0x8b,
0x86,0x80,0x7a,0x75,0x72,0x6f,0x6b,0x6a,0x6a,0x68,0x69,0x6b,0x70,0x74,0x76,0x79,
0x7e,0x84,0x87,0x8a,0x8b,0x8e,0x90,0x92,0x91,0x94,0x93,0x93,0x91,0x94,0x97,0x99,
0x97,0x9b,0x9d,0x88,0x88,0x81,0x81,0x7f,0x73,0x67,0x62,0x67,0x60,0x63,0x61,0x63,
0x6b,0x70,0x73,0x7e,0x84,0x86,0x8a,0x8e,0x92,0x95,0x93,0x8c,0x8b,0x89,0x85,0x7f,
0x7a,0x75,0x73,0x6f,0x6c,0x6a,0x6a,0x69,0x6a,0x6e,0x71,0x75,0x77,0x79,0x7f,0x84,
0x87,0x8a,0x8a,0x8d,0x8f,0x91,0x91,0x92,0x91,0x92,0x92,0x94,0x96,0x99,0x97,0x9b,
0x9b,0x8a,0x89,0x82,0x81,0x7d,0x72,0x67,0x63,0x64,0x5f,0x62,0x62,0x64,0x6a,0x6f,
0x74,0x7e,0x84,0x86,0x8b,0x8e,0x92,0x94,0x92,0x8d,0x8c,0x89,0x84,0x7f,0x7a,0x75,
0x72,0x6f,0x6c,0x6b,0x6b,0x6a,0x6c,0x6e,0x72,0x76,0x77,0x7a,0x7f,0x83,0x85,0x87,
0x87,0x8b,0x8d,0x8d,0x8d,0x8e,0x8f,0x8f,0x90,0x90,0x94,0x98,0x9b,0x9a,0xa1,0x94,
0x89,0x8a,0x83,0x83,0x79,0x6f,0x63,0x65,0x61,0x5e,0x62,0x60,0x65,0x6b,0x6f,0x76,
0x81,0x83,0x87,0x8c,0x90,0x93,0x95,0x91,0x8d,0x8c,0x88,0x83,0x7f,0x79,0x75,0x72,
0x6d,0x6c,0x6b,0x6b,0x6a,0x6b,0x6d,0x71,0x75,0x77,0x7a,0x7f,0x84,0x87,0x88,0x89,
0x8d,0x8f,0x90,0x90,0x91,0x92,0x93,0x93,0x95,0x97,0x9b,0x99,0xa0,0x96,0x86,0x89,
0x80,0x82,0x79,0x6e,0x63,0x64,0x62,0x5e,0x64,0x61,0x66,0x6c,0x70,0x77,0x82,0x85,
0x87,0x8d,0x90,0x93,0x95,0x90,0x8c,0x8b,0x87,0x82,0x7e,0x77,0x73,0x71,0x6d,0x6c,
0x6b,0x69,0x69,0x6c,0x6f,0x74,0x76,0x78,0x7b,0x81,0x86,0x89,0x8a,0x8b,0x8e,0x91,
0x91,0x92,0x91,0x92,0x93,0x93,0x94,0x99,0x9a,0x9c,0x9f,0x8d,0x86,0x87,0x82,0x81,
0x76,0x69,0x62,0x65,0x60,0x60,0x64,0x61,0x67,0x6d,0x72,0x7c,0x84,0x85,0x89,0x8f,
0x92,0x95,0x94,0x8e,0x8b,0x8a,0x85,0x80,0x7b,0x74,0x72,0x6e,0x6b,0x6a,0x6a,0x6a,
0x6a,0x6e,0x72,0x76,0x78,0x7a,0x7f,0x85,0x89,0x8a,0x8b,0x8d,0x8f,0x91,0x91,0x91,
0x91,0x92,0x93,0x94,0x96,0x9c,0x9a,0x9e,0x96,0x87,0x8a,0x84,0x81,0x79,0x6e,0x65,
0x64,0x63,0x5d,0x62,0x62,0x65,0x6b,0x70,0x77,0x81,0x85,0x87,0x8d,0x91,0x94,0x94,
0x91,0x8d,0x8c,0x88,0x81,0x7d,0x78,0x74,0x70,0x6c,0x6a,0x6a,0x69,0x68,0x6a,0x6f,
0x74,0x76,0x78,0x7c,0x82,0x87,0x8a,0x8b,0x8d,0x8f,0x91,0x91,0x92,0x92,0x93,0x93,
0x94,0x95,0x98,0x99,0x9b,0x9e,0x89,0x86,0x83,0x80,0x80,0x73,0x68,0x61,0x64,0x60,
0x61,0x64,0x62,0x69,0x6f,0x74,0x7e,0x85,0x86,0x89,0x8e,0x92,0x95,0x94,0x8d,0x8a,
0x89,0x84,0x7f,0x7a,0x74,0x71,0x6d,0x6b,0x6a,0x6b,0x69,0x6a,0x6d,0x72,0x75,0x79,
0x7b,0x7f,0x84,0x88,0x8a,0x8c,0x8d,0x8f,0x91,0x90,0x91,0x92,0x94,0x92,0x94,0x95,
0x9a,0x9b,0xa2,0x93,0x83,0x88,0x81,0x84,0x79,0x6c,0x61,0x64,0x63,0x5e,0x63,0x61,
0x65,0x6c,0x70,0x78,0x84,0x86,0x87,0x8c,0x91,0x95,0x96,0x90,0x8a,0x8a,0x87,0x81,
0x7d,0x76,0x73,0x70,0x6c,0x6a,0x6a,0x6a,0x69,0x6b,0x6f,0x74,0x77,0x78,0x7b,0x81,
0x86,0x89,0x8b,0x8c,0x8e,0x91,0x91,0x92,0x91,0x93,0x92,0x93,0x95,0x98,0x9b,0x9d,
0x9e,0x88,0x86,0x86,0x83,0x80,0x71,0x66,0x62,0x66,0x60,0x60,0x62,0x62,0x69,0x6e,
0x73,0x7e,0x85,0x86,0x89,0x8f,0x94,0x96,0x93,0x8d,0x8b,0x8a,0x85,0x7f,0x79,0x74,
0x72,0x6e,0x6b,0x6b,0x6b,0x6a,0x6b,0x6e,0x72,0x77,0x79,0x7b,0x7f,0x85,0x87,0x8a,
0x89,0x8a,0x8c,0x8d,0x8d,0x8d,0x8d,0x8e,0x90,0x90,0x91,0x95,0x9a,0x9b,0xa5,0x91,
0x89,0x8a,0x84,0x87,0x7b,0x6e,0x63,0x67,0x61,0x5f,0x63,0x61,0x65,0x6b,0x6e,0x78,
0x83,0x84,0x86,0x8b,0x90,0x95,0x96,0x90,0x8c,0x8c,0x88,0x82,0x7e,0x78,0x74,0x71,
0x6d,0x6b,0x6c,0x6b,0x69,0x6a,0x6f,0x74,0x77,0x78,0x7b,0x82,0x86,0x89,0x8a,0x8c,
0x8e,0x91,0x91,0x93,0x92,0x95,0x94,0x94,0x96,0x9c,0x9b,0xa1,0x98,0x84,0x88,0x81,
0x82,0x7c,0x6e,0x63,0x61,0x62,0x5d,0x63,0x62,0x63,0x6c,0x70,0x78,0x84,0x87,0x88,
0x8d,0x92,0x95,0x97,0x93,0x8c,0x8a,0x87,0x81,0x7e,0x77,0x71,0x6f,0x6c,0x6b,0x6a,
0x6b,0x6a,0x6c,0x71,0x75,0x79,0x7b,0x7d,0x83,0x87,0x89,0x8a,0x8b,0x8c,0x8c,0x8d,
0x8d,0x8e,0x8d,0x8d,0x8f,0x92,0x94,0x98,0x99,0xa1,0x99,0x89,0x8a,0x84,0x86,0x7e,
0x71,0x65,0x64,0x64,0x5f,0x62,0x61,0x64,0x6a,0x6e,0x75,0x80,0x85,0x86,0x8a,0x8f,
0x93,0x95,0x92,0x8c,0x8b,0x88,0x83,0x7f,0x79,0x74,0x71,0x6d,0x6c,0x6c,0x6b,0x69,
0x6b,0x6f,0x74,0x77,0x79,0x7b,0x81,0x85,0x87,0x89,0x8a,0x8b,0x8d,0x8e,0x8f,0x8f,
0x8f,0x91,0x91,0x93,0x96,0x9a,0x9b,0xa2,0x92,0x86,0x87,0x82,0x84,0x79,0x6c,0x61,
0x64,0x61,0x5f,0x64,0x62,0x66,0x6c,0x71,0x7a,0x85,0x87,0x88,0x8c,0x92,0x95,0x96,
0x90,0x8a,0x89,0x86,0x80,0x7b,0x75,0x71,0x6f,0x6c,0x6a,0x6b,0x6b,0x6b,0x6e,0x72,
0x76,0x7a,0x7d,0x7f,0x84,0x86,0x89,0x8a,0x8b,0x8b,0x8b,0x8b,0x8c,0x8d,0x8d,0x8d,
0x8f,0x91,0x94,0x99,0x9b,0xa2,0x91,0x87,0x87,0x84,0x87,0x7a,0x6e,0x62,0x66,0x63,
0x61,0x64,0x61,0x66,0x6b,0x71,0x79,0x82,0x85,0x87,0x8c,0x90,0x94,0x95,0x90,0x8b,
0x8a,0x86,0x82,0x7d,0x76,0x73,0x70,0x6d,0x6c,0x6c,0x6a,0x6a,0x6d,0x72,0x75,0x78,
0x79,0x7e,0x82,0x86,0x89,0x8a,0x8b,0x8d,0x8f,0x90,0x92,0x91,0x93,0x93,0x93,0x95,
0x9b,0x9a,0xa3,0x91,0x83,0x85,0x81,0x82,0x77,0x6c,0x60,0x64,0x62,0x5f,0x64,0x64,
0x67,0x6d,0x73,0x7c,0x86,0x88,0x89,0x8d,0x93,0x96,0x95,0x90,0x8a,0x89,0x85,0x7f,
0x7b,0x75,0x71,0x6d,0x6b,0x6a,0x6b,0x6c,0x6b,0x6d,0x73,0x77,0x7b,0x7c,0x7f,0x84,
0x88,0x8a,0x8b,0x8c,0x8c,0x8d,0x8d,0x8e,0x8d,0x8f,0x8f,0x91,0x92,0x97,0x98,0xa0,
0x9d,0x87,0x87,0x82,0x86,0x80,0x74,0x66,0x63,0x66,0x60,0x64,0x63,0x64,0x6a,0x6f,
0x75,0x81,0x87,0x87,0x8a,0x8e,0x93,0x96,0x93,0x8c,0x8a,0x89,0x83,0x7f,0x78,0x73,
0x71,0x6e,0x6c,0x6c,0x6c,0x6c,0x6c,0x6f,0x74,0x78,0x7b,0x7b,0x80,0x85,0x88,0x89,
0x8a,0x8a,0x8e,0x8e,0x90,0x8f,0x90,0x90,0x91,0x93,0x96,0x9a,0x9b,0xa3,0x8d,0x87,
0x84,0x81,0x84,0x78,0x6c,0x61,0x65,0x60,0x61,0x64,0x63,0x68,0x6e,0x73,0x7c,0x86,
0x88,0x8a,0x8e,0x92,0x95,0x96,0x90,0x8a,0x89,0x84,0x7f,0x7a,0x74,0x71,0x6e,0x6b,
0x6b,0x6c,0x6c,0x6c,0x6f,0x73,0x76,0x7a,0x7c,0x7f,0x84,0x87,0x88,0x8b,0x8b,0x8d,
0x8e,0x8f,0x8f,0x90,0x91,0x90,0x93,0x95,0x9a,0x9c,0xa3,0x8f,0x86,0x86,0x82,0x85,
0x77,0x6b,0x60,0x64,0x60,0x60,0x64,0x62,0x67,0x6c,0x72,0x7c,0x86,0x88,0x89,0x8d,
0x92,0x97,0x97,0x90,0x8a,0x89,0x85,0x80,0x7a,0x74,0x70,0x6e,0x6a,0x6a,0x6a,0x6a,
0x6a,0x6b,0x71,0x76,0x7a,0x7c,0x7f,0x84,0x8a,0x8b,0x8d,0x8d,0x91,0x91,0x92,0x91,
0x92,0x91,0x93,0x92,0x96,0x99,0x9c,0xa0,0x83,0x84,0x80,0x83,0x81,0x72,0x66,0x5e,
0x66,0x5f,0x64,0x65,0x65,0x6a,0x70,0x76,0x81,0x8a,0x88,0x8a,0x8f,0x94,0x96,0x94,
0x8c,0x88,0x87,0x82,0x7d,0x78,0x73,0x6f,0x6c,0x69,0x6b,0x6d,0x6c,0x6d,0x70,0x74,
0x78,0x7c,0x7e,0x82,0x85,0x88,0x89,0x8b,0x8a,0x8c,0x8d,0x8d,0x8e,0x8f,0x8f,0x8e,
0x91,0x94,0x9a,0x99,0xa4,0x91,0x85,0x86,0x82,0x86,0x7b,0x6f,0x60,0x65,0x63,0x61,
0x66,0x62,0x66,0x6d,0x72,0x7a,0x85,0x87,0x88,0x8c,0x91,0x94,0x96,0x90,0x89,0x88,
0x85,0x80,0x7c,0x75,0x71,0x6f,0x6d,0x6b,0x6d,0x6c,0x6b,0x6d,0x71,0x76,0x7a,0x7b,
0x7d,0x82,0x87,0x89,0x8c,0x8c,0x8e,0x90,0x91,0x91,0x92,0x94,0x92,0x93,0x94,0x99,
0x9a,0xa2,0x8e,0x81,0x85,0x80,0x83,0x77,0x6c,0x60,0x66,0x63,0x61,0x66,0x65,0x68,
0x6f,0x74,0x7c,0x88,0x89,0x88,0x8d,0x92,0x95,0x95,0x8e,0x88,0x87,0x84,0x7d,0x7a,
0x75,0x70,0x6e,0x6b,0x6b,0x6e,0x6e,0x6d,0x6e,0x73,0x78,0x7c,0x7d,0x7f,0x84,0x87,
0x89,0x8a,0x8b,0x8c,0x8e,0x8d,0x8f,0x8f,0x91,0x8f,0x92,0x92,0x98,0x98,0xa0,0x97,
0x85,0x88,0x81,0x85,0x7d,0x72,0x65,0x64,0x65,0x60,0x66,0x65,0x66,0x6c,0x71,0x77,
0x83,0x87,0x88,0x8b,0x8f,0x93,0x95,0x92,0x8a,0x88,0x85,0x80,0x7c,0x77,0x72,0x6f,
0x6d,0x6c,0x6d,0x6d,0x6c,0x6c,0x70,0x75,0x79,0x7c,0x7e,0x81,0x86,0x88,0x8b,0x8d,
0x8e,0x90,0x90,0x91,0x92,0x94,0x92,0x93,0x93,0x97,0x98,0xa0,0x96,0x81,0x83,0x80,
0x81,0x7c,0x6f,0x63,0x64,0x65,0x60,0x66,0x68,0x68,0x6e,0x73,0x79,0x85,0x8a,0x88,
0x8a,0x8f,0x92,0x94,0x90,0x88,0x85,0x84,0x7e,0x7a,0x76,0x71,0x6f,0x6d,0x6c,0x6e,
0x70,0x6e,0x6e,0x72,0x77,0x7b,0x7d,0x7e,0x82,0x86,0x88,0x88,0x89,0x8a,0x8c,0x8c,
0x8d,0x8d,0x90,0x8f,0x90,0x90,0x96,0x98,0x9d,0xa2,0x89,0x87,0x84,0x83,0x83,0x79,
0x6b,0x62,0x67,0x60,0x63,0x67,0x65,0x69,0x6f,0x72,0x7c,0x87,0x87,0x88,0x8c,0x8f,
0x93,0x94,0x8d,0x87,0x87,0x83,0x7f,0x7c,0x75,0x72,0x70,0x6d,0x6e,0x70,0x6f,0x6e,
0x70,0x74,0x78,0x7b,0x7c,0x7d,0x82,0x84,0x86,0x87,0x87,0x88,0x89,0x8a,0x8a,0x8c,
0x8c,0x8c,0x8d,0x90,0x90,0x92,0x93,0x98,0x97,0x8d,0x85,0x81,0x82,0x80,0x79,0x6e,
0x69,0x69,0x68,0x68,0x68,0x6b,0x6f,0x72,0x75,0x7b,0x83,0x86,0x88,0x89,0x8a,0x8d,
0x8d,0x89,0x85,0x83,0x81,0x7d,0x79,0x75,0x74,0x72,0x6f,0x6e,0x6f,0x70,0x71,0x73,
0x76,0x7a,0x7d,0x7f,0x81,0x86,0x89,0x8d,0x8e,0x8f,0x8f,0x92,0x92,0x93,0x92,0x93,
0x93,0x93,0x96,0x98,0xa0,0x8c,0x80,0x7d,0x7c,0x80,0x78,0x6a,0x5f,0x63,0x62,0x64,
0x68,0x69,0x6c,0x72,0x75,0x7e,0x8a,0x8c,0x8a,0x8c,0x8f,0x93,0x93,0x8b,0x84,0x83,
0x80,0x7b,0x77,0x73,0x70,0x6e,0x6c,0x6d,0x72,0x73,0x71,0x72,0x76,0x7d,0x80,0x80,
0x80,0x84,0x86,0x88,0x87,0x86,0x87,0x88,0x87,0x88,0x89,0x89,0x8a,0x8b,0x8c,0x8f,
0x94,0x95,0x99,0x96,0x8d,0x89,0x86,0x85,0x81,0x7a,0x70,0x6b,0x6b,0x68,0x68,0x69,
0x6a,0x6d,0x70,0x75,0x7b,0x81,0x84,0x86,0x89,0x8b,0x8e,0x8d,0x8a,0x86,0x85,0x82,
0x7f,0x7b,0x78,0x75,0x71,0x70,0x6f,0x70,0x70,0x70,0x71,0x75,0x79,0x7b,0x7e,0x81,
0x85,0x88,0x8c,0x8e,0x90,0x91,0x92,0x93,0x95,0x93,0x93,0x92,0x93,0x95,0x95,0x9a,
0x8c,0x83,0x7c,0x79,0x7b,0x77,0x6e,0x63,0x63,0x63,0x66,0x6b,0x6c,0x6e,0x74,0x78,
0x7f,0x88,0x8b,0x8b,0x8b,0x8d,0x8f,0x8f,0x8b,0x84,0x80,0x7d,0x7a,0x77,0x73,0x70,
0x6e,0x6d,0x6e,0x70,0x72,0x73,0x73,0x77,0x7b,0x80,0x82,0x83,0x84,0x87,0x88,0x8a,
0x8b,0x8b,0x8a,0x8a,0x8b,0x8e,0x8f,0x8d,0x8d,0x8e,0x93,0x96,0x9f,0x93,0x86,0x82,
0x7f,0x83,0x7f,0x75,0x68,0x66,0x64,0x65,0x6a,0x6a,0x6a,0x6e,0x71,0x78,0x83,0x87,
0x87,0x88,0x8a,0x8e,0x91,0x8e,0x88,0x84,0x82,0x7f,0x7c,0x78,0x73,0x70,0x6e,0x6f,
0x71,0x70,0x6f,0x6f,0x72,0x77,0x7c,0x7d,0x7e,0x81,0x84,0x88,0x8b,0x8c,0x8d,0x8e,
0x8d,0x8e,0x91,0x92,0x90,0x8f,0x8e,0x94,0x94,0x9b,0x97,0x85,0x80,0x7c,0x80,0x7d,
0x76,0x68,0x63,0x66,0x65,0x69,0x6b,0x6b,0x6f,0x74,0x79,0x82,0x89,0x89,0x89,0x8b,
0x8e,0x90,0x8f,0x88,0x82,0x81,0x7d,0x7a,0x76,0x72,0x70,0x6f,0x6d,0x6e,0x70,0x72,
0x72,0x74,0x77,0x7c,0x80,0x81,0x82,0x85,0x88,0x8b,0x8c,0x8c,0x8d,0x8d,0x8e,0x8e,
0x91,0x90,0x90,0x8e,0x92,0x93,0x9d,0x98,0x83,0x81,0x7d,0x82,0x7e,0x75,0x68,0x66,
0x68,0x64,0x69,0x6b,0x6c,0x70,0x72,0x77,0x82,0x89,0x88,0x87,0x8a,0x8e,0x91,0x8f,
0x88,0x83,0x82,0x7e,0x7b,0x78,0x74,0x71,0x6f,0x6e,0x70,0x73,0x72,0x71,0x73,0x77,
0x7c,0x80,0x81,0x82,0x84,0x87,0x89,0x8b,0x8c,0x8c,0x8b,0x8c,0x8d,0x8f,0x8f,0x8f,
0x8f,0x91,0x93,0x96,0x9f,0x8c,0x84,0x7f,0x7f,0x83,0x7c,0x70,0x64,0x68,0x65,0x68,
0x6b,0x6a,0x6d,0x71,0x73,0x7b,0x86,0x88,0x87,0x88,0x8a,0x8f,0x91,0x8b,0x85,0x83,
0x81,0x7e,0x7a,0x76,0x73,0x71,0x6e,0x6e,0x71,0x71,0x71,0x71,0x74,0x7a,0x7e,0x80,
0x81,0x84,0x87,0x8a,0x8c,0x8e,0x8f,0x8f,0x8f,0x90,0x93,0x91,0x92,0x90,0x93,0x91,
0x9b,0x97,0x83,0x82,0x7c,0x7f,0x7d,0x76,0x69,0x66,0x68,0x64,0x6a,0x6c,0x6d,0x71,
0x73,0x77,0x82,0x89,0x88,0x88,0x8a,0x8c,0x90,0x8e,0x88,0x83,0x81,0x7d,0x7b,0x78,
0x74,0x71,0x6e,0x6d,0x70,0x73,0x72,0x71,0x73,0x77,0x7d,0x80,0x80,0x82,0x85,0x87,
0x89,0x8c,0x8c,0x8e,0x8c,0x8d,0x8e,0x91,0x90,0x8f,0x8e,0x92,0x93,0x9a,0x99,0x83,
0x82,0x7e,0x82,0x80,0x77,0x6a,0x65,0x69,0x65,0x6a,0x6c,0x6b,0x6e,0x72,0x75,0x80,
0x88,0x86,0x86,0x89,0x8c,0x90,0x8f,0x88,0x84,0x83,0x7f,0x7c,0x79,0x75,0x72,0x6f,
0x6d,0x6f,0x71,0x71,0x6f,0x71,0x75,0x7b,0x7e,0x80,0x81,0x85,0x88,0x8b,0x8d,0x8e,
0x8f,0x8e,0x8f,0x90,0x93,0x91,0x91,0x90,0x93,0x93,0x9b,0x8e,0x80,0x80,0x7e,0x81,
0x7a,0x71,0x66,0x68,0x68,0x67,0x6b,0x6c,0x6e,0x71,0x74,0x7a,0x85,0x89,0x87,0x87,
0x8b,0x8e,0x91,0x8b,0x85,0x83,0x82,0x7d,0x7a,0x77,0x73,0x71,0x6f,0x6f,0x71,0x73,
0x72,0x72,0x74,0x79,0x7c,0x7f,0x7f,0x82,0x84,0x86,0x87,0x88,0x89,0x8a,0x8a,0x8a,
0x8b,0x8c,0x8e,0x8d,0x8e,0x8f,0x94,0x95,0x9c,0x90,0x84,0x84,0x83,0x85,0x7d,0x75,
0x68,0x6b,0x69,0x67,0x6a,0x6a,0x6b,0x6f,0x72,0x77,0x82,0x85,0x84,0x86,0x8a,0x8d,
0x90,0x8c,0x87,0x85,0x84,0x80,0x7d,0x79,0x76,0x74,0x71,0x70,0x70,0x71,0x70,0x70,
0x73,0x76,0x7a,0x7c,0x7e,0x81,0x86,0x88,0x8b,0x8b,0x8e,0x8f,0x90,0x8f,0x91,0x92,
0x91,0x90,0x90,0x94,0x94,0x9c,0x8a,0x80,0x81,0x7f,0x80,0x7a,0x71,0x66,0x6a,0x67,
0x67,0x6c,0x6d,0x6e,0x72,0x75,0x7b,0x86,0x88,0x87,0x89,0x8c,0x8e,0x8f,0x8b,0x85,
0x84,0x82,0x7d,0x7b,0x77,0x73,0x71,0x70,0x70,0x72,0x73,0x72,0x73,0x76,0x7b,0x7e,
0x7f,0x80,0x83,0x85,0x87,0x88,0x88,0x88,0x88,0x88,0x89,0x8c,0x8b,0x8c,0x8b,0x8e,
0x8d,0x94,0x93,0x9c,0x95,0x86,0x85,0x82,0x86,0x81,0x7a,0x6b,0x6a,0x6a,0x68,0x6b,
0x6b,0x6b,0x6d,0x71,0x75,0x7e,0x84,0x84,0x84,0x88,0x8b,0x8f,0x8e,0x88,0x85,0x85,
0x82,0x7f,0x7c,0x78,0x76,0x74,0x71,0x71,0x72,0x71,0x71,0x72,0x75,0x78,0x7b,0x7c,
0x7e,0x82,0x85,0x87,0x8a,0x8b,0x8d,0x8e,0x8f,0x8f,0x92,0x91,0x91,0x90,0x92,0x93,
0x98,0x96,0x84,0x81,0x7f,0x82,0x7e,0x76,0x6a,0x67,0x6a,0x67,0x69,0x6b,0x6d,0x6f,
0x73,0x77,0x80,0x87,0x87,0x86,0x89,0x8c,0x8f,0x8e,0x88,0x84,0x83,0x80,0x7c,0x79,
0x76,0x74,0x71,0x70,0x71,0x73,0x71,0x71,0x73,0x77,0x7b,0x7d,0x7d,0x80,0x83,0x85,
0x87,0x88,0x8a,0x8a,0x8a,0x8a,0x8c,0x8d,0x8f,0x8d,0x8e,0x8d,0x93,0x93,0x9a,0x93,
0x84,0x84,0x81,0x83,0x7e,0x78,0x6a,0x6a,0x6a,0x67,0x6b,0x6c,0x6b,0x6e,0x72,0x76,
0x80,0x85,0x84,0x85,0x89,0x8c,0x8f,0x8d,0x88,0x85,0x84,0x81,0x7e,0x7b,0x77,0x75,
0x72,0x71,0x72,0x73,0x72,0x70,0x72,0x76,0x79,0x7c,0x7c,0x7f,0x81,0x85,0x87,0x89,
0x8a,0x8b,0x8b,0x8c,0x8e,0x90,0x8f,0x8d,0x8e,0x91,0x93,0x96,0x9a,0x88,0x83,0x80,
0x81,0x81,0x7b,0x70,0x68,0x6b,0x67,0x6a,0x6c,0x6c,0x6d,0x71,0x74,0x7c,0x84,0x85,
0x85,0x87,0x8a,0x8e,0x8f,0x8a,0x85,0x84,0x82,0x80,0x7d,0x78,0x75,0x74,0x72,0x72,
0x73,0x73,0x73,0x72,0x75,0x78,0x7c,0x7d,0x7e,0x80,0x82,0x86,0x88,0x89,0x89,0x8a,
0x8a,0x8c,0x8d,0x8f,0x8d,0x8e,0x8d,0x91,0x93,0x98,0x99,0x87,0x84,0x81,0x84,0x81,
0x7b,0x6f,0x69,0x6c,0x69,0x6b,0x6c,0x6c,0x6e,0x72,0x74,0x7c,0x83,0x84,0x84,0x86,
0x8a,0x8e,0x8e,0x89,0x85,0x84,0x83,0x80,0x7d,0x79,0x76,0x74,0x72,0x71,0x72,0x72,
0x71,0x71,0x74,0x78,0x7c,0x7d,0x7e,0x81,0x85,0x89,0x8b,0x8b,0x8d,0x8d,0x8e,0x8f,
0x91,0x90,0x90,0x8f,0x90,0x91,0x95,0x99,0x88,0x82,0x7e,0x81,0x81,0x7b,0x70,0x67,
0x6b,0x69,0x6c,0x6d,0x6d,0x6f,0x72,0x75,0x7d,0x85,0x86,0x84,0x86,0x89,0x8e,0x8e,
0x8a,0x84,0x83,0x82,0x7f,0x7c,0x78,0x75,0x73,0x71,0x71,0x74,0x74,0x73,0x72,0x74,
0x7a,0x7f,0x7f,0x7f,0x81,0x84,0x88,0x89,0x89,0x8a,0x8b,0x8b,0x8c,0x8d,0x8f,0x8e,
0x8d,0x8c,0x91,0x93,0x99,0x8f,0x83,0x81,0x81,0x84,0x7d,0x77,0x6c,0x6c,0x6b,0x6a,
0x6d,0x6e,0x6e,0x6f,0x72,0x78,0x80,0x84,0x82,0x83,0x87,0x8b,0x8d,0x8a,0x86,0x84,
0x84,0x81,0x7e,0x7b,0x78,0x75,0x72,0x71,0x72,0x73,0x71,0x71,0x73,0x78,0x7b,0x7d,
0x7e,0x80,0x84,0x88,0x8b,0x8c,0x8d,0x8d,0x8f,0x8f,0x92,0x91,0x91,0x90,0x90,0x90,
0x96,0x94,0x84,0x81,0x7e,0x80,0x7d,0x77,0x6b,0x69,0x6b,0x68,0x6b,0x6d,0x6e,0x70,
0x73,0x76,0x7e,0x85,0x85,0x84,0x87,0x8a,0x8d,0x8d,0x87,0x84,0x83,0x82,0x7e,0x7b,
0x78,0x75,0x73,0x71,0x71,0x73,0x73,0x71,0x72,0x75,0x7b,0x7d,0x7e,0x7f,0x83,0x87,
0x89,0x8a,0x8a,0x8d,0x8e,0x8d,0x8e,0x90,0x8f,0x8f,0x8c,0x8e,0x90,0x97,0x93,0x84,
0x80,0x7f,0x83,0x80,0x7a,0x6e,0x6b,0x6d,0x6a,0x6c,0x6e,0x6e,0x6f,0x71,0x74,0x7c,
0x83,0x83,0x82,0x84,0x88,0x8c,0x8b,0x87,0x84,0x84,0x82,0x7f,0x7d,0x7a,0x77,0x74,
0x71,0x71,0x73,0x73,0x71,0x72,0x75,0x79,0x7c,0x7e,0x7f,0x84,0x87,0x8a,0x8b,0x8e,
0x8f,0x91,0x90,0x91,0x92,0x93,0x92,0x91,0x90,0x93,0x92,0x86,0x80,0x7e,0x7f,0x7d,
0x77,0x6e,0x6a,0x6c,0x6a,0x6b,0x6d,0x6f,0x71,0x73,0x75,0x7c,0x83,0x85,0x85,0x86,
0x88,0x8c,0x8c,0x88,0x85,0x84,0x82,0x7e,0x7b,0x78,0x76,0x74,0x71,0x71,0x72,0x73,
0x72,0x73,0x75,0x79,0x7d,0x7f,0x82,0x84,0x87,0x8a,0x8c,0x8e,0x8f,0x90,0x90,0x92,
0x92,0x92,0x91,0x91,0x8f,0x94,0x92,0x86,0x81,0x7e,0x7f,0x7d,0x78,0x6e,0x6b,0x6c,
0x6a,0x6c,0x6e,0x6f,0x70,0x73,0x74,0x7b,0x82,0x84,0x85,0x85,0x87,0x8a,0x8c,0x89,
0x86,0x84,0x81,0x7f,0x7c,0x79,0x77,0x74,0x71,0x70,0x72,0x73,0x74,0x73,0x75,0x79,
0x7d,0x81,0x82,0x85,0x88,0x8b,0x8e,0x90,0x91,0x92,0x93,0x93,0x93,0x93,0x94,0x93,
0x93,0x92,0x8a,0x83,0x7f,0x7d,0x7b,0x79,0x71,0x6a,0x6a,0x69,0x6a,0x6d,0x6e,0x6e,
0x71,0x74,0x79,0x7f,0x83,0x85,0x86,0x87,0x88,0x8b,0x8b,0x88,0x84,0x81,0x7e,0x7d,
0x7b,0x78,0x74,0x71,0x70,0x71,0x73,0x74,0x75,0x75,0x78,0x7c,0x80,0x82,0x84,0x86,
0x89,0x8c,0x8e,0x8f,0x91,0x91,0x90,0x91,0x92,0x93,0x92,0x90,0x91,0x90,0x88,0x83,
0x7f,0x7d,0x7b,0x78,0x6f,0x6c,0x6c,0x6a,0x6b,0x6c,0x6e,0x70,0x73,0x74,0x79,0x7f,
0x83,0x84,0x84,0x85,0x87,0x89,0x87,0x84,0x82,0x7f,0x7c,0x7a,0x78,0x77,0x75,0x73,
0x72,0x74,0x76,0x78,0x79,0x7a,0x7d,0x80,0x83,0x86,0x88,0x8a,0x8c,0x8d,0x8f,0x91,
0x92,0x92,0x91,0x91,0x91,0x93,0x94,0x91,0x89,0x83,0x80,0x7f,0x7d,0x78,0x71,0x6b,
0x6a,0x69,0x6b,0x6c,0x6d,0x6e,0x6f,0x73,0x78,0x7f,0x81,0x82,0x83,0x85,0x87,0x89,
0x88,0x85,0x82,0x7f,0x7e,0x7c,0x7a,0x78,0x75,0x73,0x72,0x74,0x76,0x77,0x77,0x79,
0x7c,0x7f,0x82,0x85,0x88,0x8a,0x8c,0x8e,0x90,0x92,0x93,0x92,0x91,0x92,0x92,0x93,
0x93,0x91,0x8b,0x84,0x81,0x7f,0x7e,0x79,0x73,0x6d,0x6a,0x69,0x6a,0x6c,0x6d,0x6d,
0x6e,0x72,0x76,0x7c,0x80,0x82,0x82,0x83,0x85,0x88,0x88,0x86,0x83,0x80,0x7e,0x7d,
0x7c,0x7a,0x77,0x75,0x74,0x76,0x77,0x79,0x79,0x7b,0x7c,0x7f,0x83,0x86,0x89,0x8a,
0x8b,0x8c,0x90,0x92,0x92,0x90,0x90,0x90,0x91,0x92,0x91,0x90,0x8a,0x84,0x7f,0x7f,
0x7d,0x7b,0x75,0x6f,0x6b,0x6b,0x6c,0x6d,0x6e,0x6e,0x6f,0x71,0x75,0x7a,0x7e,0x80,
0x80,0x81,0x83,0x86,0x86,0x85,0x83,0x80,0x7f,0x7e,0x7d,0x7c,0x7a,0x78,0x77,0x78,
0x7a,0x7b,0x7c,0x7c,0x7e,0x82,0x85,0x87,0x89,0x8a,0x8c,0x8e,0x90,0x91,0x91,0x90,
0x90,0x8f,0x8f,0x90,0x8f,0x8c,0x88,0x82,0x7f,0x7d,0x7b,0x78,0x74,0x6f,0x6d,0x6d,
0x6d,0x6f,0x6f,0x70,0x71,0x73,0x76,0x7a,0x7e,0x7f,0x7f,0x80,0x82,0x83,0x84,0x83,
0x81,0x7f,0x7e,0x7d,0x7d,0x7c,0x7c,0x7a,0x79,0x7a,0x7c,0x7e,0x7f,0x80,0x81,0x83,
0x85,0x89,0x8a,0x8b,0x8b,0x8c,0x8d,0x8e,0x8f,0x8f,0x8e,0x8d,0x8c,0x8b,0x89,0x88,
0x85,0x81,0x7e,0x7a,0x78,0x76,0x74,0x70,0x6f,0x6e,0x6f,0x70,0x71,0x72,0x73,0x76,
0x78,0x7b,0x7d,0x7f,0x7f,0x80,0x80,0x81,0x82,0x81,0x80,0x7f,0x7e,0x7d,0x7d,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7f,0x81,0x83,0x84,0x84,0x86,0x87,0x89,0x8a,0x8b,0x8a,0x8b,
0x8b,0x8b,0x8b,0x8b,0x89,0x89,0x88,0x86,0x84,0x82,0x7f,0x7d,0x7b,0x78,0x77,0x75,
0x74,0x73,0x72,0x73,0x74,0x75,0x75,0x77,0x79,0x7b,0x7c,0x7d,0x7e,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7c,0x7d,0x7d,0x7e,0x7f,0x80,0x81,0x82,
0x83,0x83,0x85,0x86,0x88,0x88,0x89,0x89,0x89,0x89,0x89,0x89,0x89,0x87,0x87,0x86,
0x84,0x83,0x81,0x80,0x7e,0x7c,0x7a,0x79,0x78,0x78,0x77,0x76,0x75,0x76,0x77,0x78,
0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,
0x7d,0x7d,0x7d,0x7e,0x7f,0x7f,0x7f,0x80,0x81,0x83,0x84,0x85,0x85,0x86,0x85,0x86,
0x86,0x86,0x86,0x86,0x85,0x84,0x84,0x83,0x83,0x82,0x81,0x7f,0x7f,0x7e,0x7e,0x7d,
0x7b,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7b,0x7a,0x7a,0x7b,0x7d,0x7e,0x7f,0x7f,0x7f,
0x7f,0x80,0x80,0x81,0x80,0x7f,0x7e,0x7e,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7f,0x7f,
0x80,0x81,0x81,0x82,0x82,0x83,0x84,0x85,0x84,0x84,0x84,0x85,0x84,0x84,0x84,0x83,
0x83,0x81,0x81,0x81,0x80,0x7f,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7b,0x7c,
0x7c,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x80,
0x80,0x7f,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x81,0x81,0x81,0x81,
0x81,0x82,0x83,0x83,0x83,0x83,0x82,0x82,0x82,0x82,0x82,0x81,0x81,0x7f,0x7f,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7d,0x7c,0x7d,0x7d,0x7e,0x7f,0x7e,0x7e,0x7e,0x7f,0x7f,0x80,
0x80,0x80,0x80,0x7f,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x7f,
0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x81,0x81,0x81,0x81,0x81,0x81,
0x81,0x81,0x81,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x81,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,
0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,
0x80,0x80,0x81,0x81,0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,
0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,
0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7d,
0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x80,0x81,0x81,0x80,0x80,0x80,0x80,
0x80,0x7f,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7e,0x80,
0x7f,0x7f,0x7f,0x7e,0x7f,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,
0x80,0x80,0x81,0x81,0x80,0x81,0x81,0x80,0x80,0x80,0x7f,0x80,0x80,0x81,0x80,0x80,
0x80,0x7f,0x80,0x80,0x81,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x81,0x7f,0x80,0x7e,0x7e,
0x7f,0x7e,0x81,0x7f,0x80,0x7e,0x7e,0x80,0x7e,0x81,0x7f,0x80,0x7e,0x7f,0x7f,0x7e,
0x80,0x7f,0x80,0x7f,0x7e,0x7f,0x7f,0x80,0x81,0x81,0x81,0x81,0x80,0x7f,0x80,0x80,
0x82,0x80,0x81,0x80,0x80,0x80,0x7f,0x81,0x80,0x81,0x7f,0x7f,0x7f,0x7f,0x7f,0x81,
0x80,0x81,0x80,0x7f,0x7e,0x7f,0x7f,0x80,0x81,0x7f,0x81,0x7e,0x7f,0x80,0x7f,0x81,
0x80,0x80,0x7f,0x7f,0x7e,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x80,
0x80,0x7e,0x80,0x7f,0x80,0x80,0x80,0x81,0x7f,0x81,0x80,0x80,0x80,0x80,0x81,0x81,
0x7e,0x80,0x7e,0x7f,0x81,0x7f,0x82,0x7e,0x80,0x7e,0x7e,0x82,0x7e,0x82,0x7f,0x7e,
0x80,0x7c,0x81,0x7f,0x7f,0x80,0x7d,0x80,0x7c,0x81,0x7e,0x7f,0x80,0x7d,0x81,0x7d,
0x7f,0x81,0x7d,0x81,0x7e,0x80,0x80,0x7f,0x81,0x7e,0x81,0x7f,0x80,0x81,0x80,0x80,
0x7f,0x7f,0x80,0x7f,0x82,0x7e,0x82,0x7e,0x7f,0x80,0x7d,0x82,0x7e,0x82,0x7f,0x7f,
0x80,0x7e,0x80,0x7f,0x81,0x7f,0x7f,0x80,0x7c,0x80,0x7e,0x80,0x7f,0x80,0x7e,0x7d,
0x80,0x7e,0x80,0x80,0x7f,0x80,0x7d,0x80,0x7e,0x80,0x81,0x7f,0x82,0x7d,0x81,0x7c,
0x80,0x81,0x80,0x83,0x7e,0x7e,0x7d,0x7f,0x80,0x80,0x83,0x7f,0x7e,0x7f,0x7d,0x80,
0x81,0x81,0x81,0x7f,0x7d,0x7f,0x7e,0x81,0x84,0x80,0x81,0x7e,0x7c,0x7f,0x7e,0x83,
0x7f,0x82,0x7e,0x7e,0x7e,0x7d,0x82,0x80,0x82,0x7f,0x7f,0x7d,0x7e,0x7f,0x80,0x81,
0x82,0x7c,0x7f,0x7d,0x7f,0x80,0x7f,0x83,0x7e,0x81,0x7e,0x7f,0x80,0x82,0x80,0x81,
0x7f,0x7e,0x7e,0x7c,0x82,0x7e,0x81,0x81,0x7d,0x81,0x7e,0x7f,0x81,0x80,0x82,0x7d,
0x81,0x7e,0x7f,0x80,0x80,0x81,0x7f,0x82,0x7d,0x80,0x80,0x7f,0x82,0x7f,0x81,0x7e,
0x7e,0x82,0x7d,0x83,0x7d,0x80,0x7f,0x7e,0x80,0x7f,0x81,0x7e,0x7f,0x7e,0x7f,0x7e,
0x83,0x7f,0x82,0x7f,0x80,0x7e,0x80,0x82,0x7f,0x82,0x7e,0x81,0x7e,0x80,0x7f,0x81,
0x7f,0x81,0x80,0x7e,0x82,0x7d,0x81,0x7f,0x7f,0x81,0x7e,0x81,0x7f,0x7f,0x81,0x7e,
0x7f,0x80,0x7f,0x82,0x7e,0x81,0x80,0x7c,0x83,0x7d,0x81,0x7f,0x81,0x7f,0x7e,0x80,
0x7e,0x81,0x7e,0x83,0x7e,0x7e,0x81,0x7e,0x80,0x7e,0x82,0x80,0x7f,0x82,0x7e,0x81,
0x80,0x7f,0x80,0x7f,0x80,0x81,0x7f,0x80,0x7f,0x7f,0x80,0x81,0x7f,0x7f,0x7f,0x7f,
0x80,0x80,0x7f,0x7f,0x83,0x7d,0x82,0x7e,0x80,0x7f,0x81,0x80,0x7f,0x82,0x7e,0x82,
0x7e,0x81,0x7e,0x84,0x7e,0x81,0x80,0x7d,0x81,0x7c,0x83,0x7e,0x81,0x80,0x7d,0x80,
0x7f,0x81,0x80,0x82,0x7e,0x80,0x80,0x7d,0x81,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x80,
0x81,0x7c,0x84,0x7d,0x7f,0x81,0x7c,0x84,0x7a,0x84,0x7c,0x82,0x80,0x7e,0x82,0x7c,
0x82,0x7e,0x7f,0x82,0x7e,0x7f,0x80,0x7d,0x81,0x7e,0x82,0x7d,0x81,0x7f,0x7e,0x82,
0x7c,0x82,0x7d,0x82,0x7d,0x81,0x7f,0x7e,0x82,0x7c,0x83,0x7c,0x83,0x7d,0x7f,0x7f,
0x7d,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7d,0x81,0x7e,0x81,0x7f,0x81,0x7c,0x81,
0x7f,0x80,0x80,0x7f,0x81,0x7d,0x81,0x7c,0x81,0x7f,0x80,0x80,0x81,0x7d,0x80,0x7f,
0x7e,0x82,0x7d,0x83,0x7c,0x81,0x7e,0x7e,0x82,0x7d,0x84,0x7c,0x82,0x7d,0x7f,0x80,
0x7d,0x83,0x7d,0x81,0x7e,0x7e,0x7f,0x7e,0x80,0x7f,0x80,0x80,0x7e,0x80,0x7f,0x80,
0x80,0x7f,0x81,0x7e,0x80,0x80,0x7f,0x81,0x7e,0x82,0x7f,0x80,0x7e,0x7f,0x81,0x7d,
0x82,0x7c,0x82,0x7d,0x80,0x80,0x7d,0x82,0x7c,0x82,0x7d,0x81,0x7e,0x80,0x80,0x7f,
0x82,0x7d,0x81,0x7e,0x81,0x7d,0x82,0x7e,0x80,0x7f,0x7e,0x80,0x7e,0x80,0x80,0x7f,
0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x82,0x7e,0x80,0x7e,0x80,0x81,0x80,0x80,0x7f,
0x80,0x7f,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x80,0x7e,0x81,0x7e,0x80,0x80,
0x7e,0x81,0x7e,0x80,0x7f,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x81,0x80,0x80,0x7f,
0x7f,0x80,0x7d,0x81,0x7f,0x80,0x80,0x7e,0x81,0x7e,0x81,0x7f,0x80,0x80,0x7f,0x81,
0x7f,0x7f,0x81,0x7f,0x7f,0x80,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x81,0x80,0x80,
0x81,0x7e,0x81,0x7e,0x81,0x80,0x80,0x80,0x7f,0x81,0x7e,0x81,0x7d,0x82,0x7e,0x7f,
0x81,0x7d,0x81,0x7f,0x81,0x80,0x7f,0x82,0x7e,0x81,0x7e,0x80,0x80,0x7f,0x81,0x7e,
0x82,0x7c,0x81,0x7e,0x81,0x7f,0x81,0x80,0x7e,0x80,0x7e,0x82,0x7e,0x80,0x7f,0x80,
0x80,0x80,0x81,0x7e,0x81,0x7e,0x80,0x80,0x7e,0x82,0x7d,0x81,0x7f,0x80,0x7f,0x80,
0x7f,0x7f,0x80,0x7e,0x81,0x7e,0x80,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x81,0x7d,0x82,
0x7d,0x82,0x7f,0x80,0x81,0x7c,0x82,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7e,0x81,
0x7f,0x81,0x7f,0x81,0x7e,0x80,0x7f,0x7f,0x81,0x80,0x81,0x7f,0x80,0x7f,0x7e,0x82,
0x7e,0x80,0x80,0x7e,0x81,0x7d,0x81,0x7e,0x81,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x80,
0x80,0x80,0x80,0x7f,0x7f,0x80,0x7e,0x81,0x7e,0x81,0x7e,0x7e,0x80,0x7e,0x7e,0x81,
0x7f,0x80,0x80,0x7f,0x80,0x7e,0x82,0x7f,0x80,0x80,0x7e,0x80,0x7e,0x80,0x7f,0x80,
0x81,0x7e,0x7f,0x7e,0x80,0x7f,0x82,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x82,0x7e,0x82,
0x7d,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x81,0x7e,0x81,0x7f,
0x80,0x7f,0x7e,0x80,0x7f,0x80,0x80,0x80,0x7e,0x80,0x7e,0x81,0x7e,0x80,0x80,0x7e,
0x80,0x7d,0x82,0x7d,0x81,0x80,0x80,0x81,0x7d,0x83,0x7d,0x81,0x7f,0x7f,0x80,0x7e,
0x81,0x7f,0x80,0x80,0x7f,0x81,0x7e,0x80,0x81,0x7e,0x82,0x7d,0x80,0x7f,0x7f,0x80,
0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x81,0x80,0x7e,0x82,0x7c,0x82,0x7d,0x81,
0x81,0x7f,0x81,0x7d,0x81,0x7d,0x81,0x7f,0x81,0x7f,0x80,0x7f,0x7e,0x80,0x7e,0x82,
0x7f,0x81,0x7f,0x80,0x7f,0x7e,0x81,0x7f,0x7f,0x81,0x7f,0x80,0x80,0x7f,0x82,0x7f,
0x80,0x81,0x7e,0x81,0x7e,0x81,0x7e,0x82,0x7e,0x80,0x80,0x7e,0x82,0x7c,0x84,0x7d,
0x81,0x80,0x80,0x80,0x7f,0x81,0x7e,0x81,0x80,0x7f,0x80,0x7e,0x81,0x7e,0x80,0x80,
0x7e,0x80,0x7f,0x7f,0x81,0x7f,0x80,0x80,0x7e,0x82,0x7c,0x83,0x7e,0x81,0x80,0x7f,
0x81,0x7e,0x82,0x7e,0x81,0x7e,0x82,0x7d,0x81,0x7e,0x80,0x81,0x7e,0x83,0x7e,0x81,
0x7e,0x80,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x81,0x7f,0x81,0x7f,
0x81,0x7e,0x81,0x80,0x7e,0x82,0x7d,0x82,0x7e,0x81,0x80,0x7d,0x81,0x7d,0x80,0x7f,
0x80,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x81,0x7f,0x81,0x7f,0x7f,0x80,0x7f,0x81,0x7f,
0x81,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x7f,0x81,0x80,0x7f,0x7f,0x80,0x80,0x7e,0x81,
0x80,0x7e,0x7f,0x7f,0x80,0x7e,0x82,0x7e,0x81,0x7f,0x7f,0x80,0x7d,0x82,0x7d,0x82,
0x7f,0x7f,0x80,0x7d,0x81,0x7e,0x81,0x7f,0x7f,0x80,0x7d,0x80,0x7f,0x81,0x7e,0x81,
0x80,0x7e,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7e,0x81,0x7d,0x81,0x7d,0x81,0x7f,
0x7f,0x81,0x7d,0x80,0x7e,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,
0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x81,0x7e,0x80,0x7e,0x81,0x7f,
0x7f,0x81,0x7d,0x81,0x7d,0x81,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x81,0x7f,0x80,0x7f,
0x80,0x80,0x7f,0x81,0x7f,0x80,0x7e,0x80,0x7e,0x80,0x80,0x7e,0x80,0x7f,0x80,0x7e,
0x81,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7e,0x81,0x7e,0x80,0x7f,0x80,
0x7e,0x80,0x7f,0x7e,0x81,0x7f,0x80,0x7e,0x80,0x7e,0x7f,0x80,0x7e,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x80,0x80,
0x7e,0x81,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x81,0x7f,0x7f,0x81,0x7e,0x80,0x7f,0x7f,
0x80,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7e,0x81,0x7e,0x80,0x7f,0x81,0x7f,0x80,0x81,
0x7e,0x81,0x7e,0x81,0x7e,0x81,0x80,0x7f,0x80,0x7f,0x7f,0x81,0x7f,0x81,0x7f,0x80,
0x80,0x7e,0x81,0x7e,0x80,0x80,0x80,0x7f,0x7f,0x81,0x7f,0x7f,0x82,0x7e,0x81,0x7f,
0x80,0x7f,0x80,0x81,0x7e,0x82,0x7e,0x81,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,
0x80,0x80,0x7f,0x80,0x80,0x80,0x80,0x80,0x81,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x80,0x7f,0x81,0x7f,0x80,0x80,0x7f,0x80,0x7e,0x80,0x80,0x7f,0x81,0x7f,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,
0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x81,0x7f,0x80,0x7f,
0x81,0x7f,0x80,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7e,0x80,
0x7f,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x7f,0x80,0x7f,0x81,0x7e,0x7f,0x80,0x7f,
0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x7e,0x7f,0x7f,
0x7f,0x80,0x80,0x80,0x7e,0x80,0x7e,0x80,0x80,0x80,0x80,0x7e,0x80,0x7e,0x7f,0x80,
0x7f,0x80,0x80,0x7e,0x80,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x81,0x7f,0x7f,0x80,0x7e,0x80,
0x7f,0x80,0x7f,0x7e,0x80,0x7d,0x81,0x7e,0x7f,0x81,0x7e,0x80,0x7f,0x80,0x80,0x7e,
0x81,0x7d,0x81,0x7f,0x7f,0x80,0x7e,0x81,0x7d,0x81,0x7e,0x80,0x80,0x7f,0x80,0x7f,
0x81,0x7e,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,
0x7f,0x81,0x7f,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x81,0x7f,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,0x81,0x7f,0x80,0x80,0x7f,0x80,0x7f,
0x81,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,0x7f,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7e,0x81,0x7f,0x82,0x7e,0x80,0x7f,
0x7f,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x7e,0x81,0x7f,0x80,0x80,0x7f,0x80,0x7e,
0x81,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,
0x80,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x80,
0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x81,
0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7e,0x81,0x7e,0x81,0x7e,0x80,0x7e,0x80,0x80,
0x7f,0x81,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7e,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x7e,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x7f,0x7f,0x80,0x80,0x7f,0x80,0x7e,0x80,0x7e,0x80,0x7e,0x80,0x7f,0x7f,
0x7f,0x7f,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,
0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x81,0x7e,0x80,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x7f,0x81,
0x7e,0x81,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x81,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x81,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,
0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x80,0x7f,0x7f,0x80,
0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,
0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x7f,
0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,
0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,
0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x80,
0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x80,
0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x7f,0x80,0x80,0x80,0x80,0x80,
0x80,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80
};
const byte soundWow[] ={
0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,
0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x81,0x81,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x80,0x81,0x80,0x80,0x80,0x7f,
0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x80,
0x80,0x7e,0x80,0x7e,0x81,0x78,0x79,0x82,0x7b,0x83,0x82,0x84,0x80,0x82,0x7f,0x80,
0x7e,0x80,0x7e,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7f,0x7f,
0x7f,0x7f,0x7f,0x7f,0x7f,0x7a,0x76,0x7e,0x7a,0x80,0x81,0x86,0x83,0x84,0x81,0x80,
0x7d,0x7f,0x7f,0x80,0x7e,0x7d,0x80,0x80,0x83,0x83,0x85,0x83,0x82,0x81,0x75,0x7e,
0x79,0x7d,0x7f,0x83,0x82,0x84,0x82,0x80,0x80,0x7d,0x80,0x7c,0x80,0x7f,0x80,0x80,
0x81,0x7f,0x7f,0x7e,0x7e,0x80,0x7f,0x81,0x7f,0x81,0x7f,0x80,0x7f,0x81,0x7f,0x81,
0x80,0x81,0x80,0x81,0x80,0x81,0x81,0x80,0x7e,0x7f,0x7e,0x7f,0x81,0x80,0x81,0x7f,
0x80,0x7e,0x7f,0x7e,0x80,0x7e,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,
0x7f,0x81,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x81,
0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x81,0x80,
0x80,0x7f,0x7f,0x80,0x80,0x7f,0x82,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,
0x7f,0x80,0x7e,0x80,0x7e,0x81,0x7f,0x81,0x7f,0x81,0x80,0x7f,0x80,0x7e,0x7f,0x7f,
0x7f,0x7e,0x7e,0x7f,0x7f,0x80,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x81,0x80,0x81,
0x7f,0x80,0x7f,0x7e,0x7f,0x81,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,
0x7f,0x7f,0x7f,0x7e,0x80,0x7f,0x80,0x80,0x7e,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x80,
0x80,0x81,0x80,0x81,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x7e,0x80,0x7e,0x80,0x80,
0x7f,0x81,0x80,0x81,0x81,0x81,0x80,0x81,0x7e,0x80,0x7f,0x7d,0x7f,0x7d,0x7e,0x7e,
0x7e,0x7f,0x7e,0x7f,0x80,0x81,0x81,0x82,0x83,0x81,0x81,0x81,0x7e,0x7f,0x7e,0x7d,
0x7d,0x7d,0x7b,0x7d,0x7b,0x7e,0x7e,0x81,0x82,0x84,0x88,0x89,0x8a,0x88,0x86,0x81,
0x7c,0x7a,0x75,0x75,0x75,0x74,0x76,0x77,0x78,0x7a,0x7c,0x82,0x88,0x8f,0x97,0x9b,
0x9d,0x98,0x8d,0x83,0x77,0x6e,0x63,0x60,0x61,0x5e,0x68,0x6f,0x79,0x85,0x8e,0x96,
0x9d,0xa2,0xa5,0xa8,0x9c,0x8f,0x7f,0x6a,0x4e,0x4e,0x46,0x4e,0x68,0x77,0x8c,0x99,
0x99,0x97,0x90,0x8f,0x91,0x99,0x9c,0x97,0x8c,0x7e,0x71,0x59,0x58,0x58,0x5b,0x6f,
0x7c,0x87,0x8f,0x8e,0x8c,0x8d,0x8f,0x96,0xa0,0xa5,0x98,0x8a,0x76,0x64,0x55,0x52,
0x5b,0x65,0x74,0x84,0x8c,0x8e,0x8c,0x8a,0x8a,0x8f,0x99,0xa4,0xa5,0x98,0x82,0x71,
0x5a,0x4c,0x52,0x5c,0x6c,0x7f,0x8c,0x90,0x8d,0x88,0x85,0x8a,0x94,0xa2,0xaa,0xa4,
0x8d,0x75,0x60,0x46,0x49,0x53,0x63,0x7e,0x8e,0x95,0x95,0x8a,0x83,0x84,0x8d,0x9b,
0xad,0xa9,0x95,0x7e,0x61,0x4b,0x44,0x4d,0x64,0x7a,0x8f,0x98,0x92,0x89,0x83,0x82,
0x8c,0x9f,0xad,0xaa,0x95,0x7a,0x5e,0x46,0x43,0x55,0x68,0x82,0x95,0x96,0x8f,0x84,
0x7d,0x83,0x91,0xa2,0xb0,0xa5,0x90,0x70,0x59,0x43,0x4a,0x5e,0x74,0x8c,0x96,0x95,
0x87,0x7e,0x7d,0x86,0x9a,0xad,0xaa,0x98,0x7c,0x5b,0x4c,0x44,0x5a,0x75,0x8b,0x9a,
0x99,0x89,0x79,0x78,0x7e,0x91,0xaa,0xad,0x9c,0x80,0x5f,0x47,0x41,0x56,0x74,0x90,
0xa2,0xa1,0x8f,0x7b,0x74,0x7c,0x8e,0xaa,0xaa,0x99,0x7f,0x56,0x43,0x3f,0x58,0x79,
0x97,0xa7,0xa2,0x8f,0x76,0x74,0x7d,0x95,0xaf,0xa6,0x95,0x71,0x47,0x3b,0x40,0x5f,
0x86,0xa3,0xa9,0x9f,0x89,0x76,0x7b,0x8c,0xa3,0xb1,0x9e,0x80,0x59,0x35,0x38,0x4e,
0x73,0x99,0xab,0xa2,0x8f,0x7b,0x76,0x89,0xa5,0xbb,0xb2,0x90,0x67,0x37,0x23,0x3a,
0x60,0x8d,0xad,0xaf,0x96,0x7c,0x6f,0x7a,0x9a,0xbc,0xc5,0xa1,0x7f,0x4d,0x1f,0x30,
0x58,0x7c,0xa2,0xb3,0x94,0x78,0x6c,0x73,0x91,0xb7,0xcd,0xad,0x87,0x5a,0x29,0x2a,
0x54,0x7c,0x9d,0xb0,0x9a,0x75,0x66,0x6f,0x8b,0xb1,0xcb,0xb1,0x84,0x5d,0x2e,0x31,
0x57,0x87,0xa2,0xad,0x98,0x75,0x61,0x6e,0x8c,0xac,0xc3,0xb1,0x7d,0x55,0x35,0x31,
0x57,0x8e,0xa9,0xaa,0x9f,0x7b,0x63,0x71,0x90,0xa5,0xbd,0xaa,0x73,0x50,0x36,0x35,
0x5a,0x94,0xa9,0xa7,0x9c,0x7b,0x67,0x76,0x99,0xad,0xb9,0xa1,0x6b,0x48,0x2f,0x3a,
0x65,0x96,0xa9,0xa2,0x93,0x79,0x6d,0x82,0xa3,0xb2,0xba,0x8e,0x5e,0x3e,0x2d,0x44,
0x74,0x9e,0xa5,0x9c,0x89,0x76,0x73,0x8e,0xae,0xb6,0xae,0x7b,0x53,0x39,0x36,0x56,
0x82,0x9d,0x9c,0x90,0x80,0x79,0x81,0xa1,0xb2,0xb7,0x9f,0x66,0x45,0x37,0x47,0x67,
0x8d,0x9c,0x90,0x7f,0x7c,0x80,0x8d,0xaa,0xb7,0xb1,0x8a,0x57,0x47,0x3d,0x51,0x73,
0x95,0x96,0x84,0x7f,0x7e,0x80,0x95,0xb6,0xb7,0xae,0x79,0x50,0x3b,0x3e,0x60,0x80,
0x9e,0x95,0x81,0x77,0x7d,0x83,0xa4,0xb8,0xb9,0xa4,0x64,0x47,0x39,0x46,0x6a,0x8b,
0x9a,0x89,0x7a,0x7a,0x83,0x8c,0xac,0xb7,0xb9,0x97,0x57,0x4c,0x3c,0x48,0x72,0x91,
0x90,0x82,0x7e,0x7e,0x82,0x95,0xb2,0xb3,0xb4,0x8d,0x57,0x45,0x41,0x51,0x70,0x8f,
0x8e,0x7d,0x7d,0x89,0x87,0x97,0xb3,0xb7,0xaa,0x77,0x53,0x4b,0x45,0x5e,0x82,0x8f,
0x7f,0x78,0x7e,0x83,0x8b,0xa7,0xb6,0xb5,0xa1,0x5f,0x4f,0x4c,0x4d,0x6d,0x8d,0x8e,
0x73,0x73,0x7e,0x82,0x91,0xb4,0xb4,0xb3,0x90,0x55,0x4b,0x49,0x57,0x74,0x8f,0x88,
0x74,0x7a,0x88,0x87,0x98,0xb5,0xb7,0xa8,0x72,0x53,0x4b,0x4b,0x67,0x85,0x91,0x7f,
0x72,0x78,0x84,0x8b,0xa6,0xb6,0xba,0x97,0x5b,0x54,0x48,0x55,0x76,0x91,0x86,0x70,
0x78,0x81,0x84,0x95,0xb2,0xad,0xad,0x7f,0x54,0x4c,0x53,0x64,0x7c,0x8e,0x83,0x75,
0x7b,0x8e,0x8d,0x9d,0xac,0xb2,0x97,0x5d,0x50,0x52,0x5a,0x71,0x8d,0x8d,0x72,0x70,
0x86,0x8c,0x91,0xae,0xb9,0xac,0x74,0x50,0x51,0x4a,0x63,0x83,0x95,0x7f,0x6e,0x7e,
0x8c,0x88,0x9f,0xb6,0xb2,0x97,0x5b,0x51,0x4a,0x5a,0x74,0x8d,0x8a,0x74,0x72,0x88,
0x8f,0x90,0xac,0xb5,0xac,0x70,0x50,0x57,0x4d,0x63,0x84,0x92,0x7a,0x6f,0x80,0x8d,
0x88,0xa0,0xb8,0xae,0x92,0x65,0x56,0x4d,0x53,0x74,0x88,0x84,0x76,0x79,0x86,0x8c,
0x90,0xab,0xb5,0xad,0x81,0x56,0x52,0x4f,0x5b,0x7a,0x8c,0x7d,0x74,0x84,0x90,0x8a,
0x98,0xb3,0xb3,0x97,0x60,0x55,0x55,0x58,0x71,0x8c,0x85,0x6b,0x75,0x89,0x8e,0x8f,
0xad,0xb3,0xa7,0x77,0x5a,0x57,0x50,0x65,0x7f,0x8b,0x7d,0x73,0x81,0x8d,0x86,0x99,
0xb1,0xb5,0x8e,0x5d,0x59,0x54,0x58,0x74,0x8d,0x85,0x70,0x7b,0x91,0x8c,0x8f,0xa7,
0xb0,0x9c,0x6c,0x56,0x5c,0x5e,0x6b,0x81,0x8a,0x73,0x6d,0x8b,0x96,0x8f,0x9e,0xaf,
0xac,0x82,0x53,0x58,0x5a,0x5e,0x73,0x90,0x84,0x6d,0x7e,0x99,0x90,0x92,0xab,0xae,
0x93,0x5e,0x58,0x5d,0x5a,0x6a,0x85,0x86,0x71,0x74,0x92,0x99,0x8d,0xa2,0xb1,0xa6,
0x72,0x54,0x5c,0x5c,0x62,0x7b,0x88,0x77,0x6d,0x87,0x9d,0x94,0x9a,0xac,0xab,0x8a,
0x5a,0x57,0x5d,0x5d,0x70,0x89,0x83,0x6e,0x75,0x95,0x98,0x94,0xa7,0xb1,0xa0,0x63,
0x4f,0x60,0x60,0x65,0x7f,0x8a,0x73,0x68,0x8a,0xa1,0x94,0x9b,0xad,0xa9,0x78,0x55,
0x60,0x63,0x5f,0x73,0x88,0x79,0x6a,0x7d,0x9e,0x98,0x98,0xa9,0xb1,0x91,0x5c,0x54,
0x61,0x5f,0x69,0x85,0x87,0x6d,0x6d,0x90,0x9d,0x95,0xa3,0xaf,0xa2,0x6d,0x51,0x61,
0x63,0x65,0x79,0x8a,0x77,0x66,0x7d,0x9e,0x99,0x9c,0xab,0xad,0x88,0x55,0x57,0x67,
0x65,0x6b,0x85,0x83,0x69,0x6b,0x94,0x9f,0x94,0xa4,0xb2,0x9f,0x65,0x54,0x65,0x63,
0x64,0x7e,0x89,0x74,0x64,0x81,0x9c,0x97,0x9e,0xaf,0xad,0x83,0x55,0x54,0x61,0x64,
0x74,0x86,0x83,0x6b,0x73,0x94,0x9d,0x98,0xa6,0xad,0x99,0x64,0x51,0x60,0x64,0x69,
0x7c,0x88,0x75,0x69,0x85,0x9d,0x97,0x9c,0xaf,0xab,0x79,0x4f,0x59,0x66,0x65,0x74,
0x8b,0x7f,0x65,0x74,0x9a,0x9c,0x97,0xa9,0xaf,0x90,0x5f,0x54,0x63,0x66,0x6c,0x7f,
0x84,0x70,0x6a,0x8a,0x9f,0x98,0x9e,0xaf,0xa5,0x75,0x50,0x5a,0x62,0x6a,0x7a,0x88,
0x7a,0x68,0x78,0x99,0x9e,0x9d,0xa7,0xab,0x8f,0x5a,0x4f,0x62,0x68,0x6f,0x7f,0x85,
0x70,0x6c,0x8c,0xa0,0x9c,0xa2,0xac,0xa0,0x6c,0x50,0x5c,0x66,0x6a,0x7a,0x85,0x77,
0x67,0x7f,0x9c,0x9c,0x9d,0xad,0xae,0x85,0x56,0x55,0x60,0x62,0x70,0x84,0x83,0x6d,
0x71,0x91,0x9d,0x97,0xa2,0xb2,0x9e,0x6a,0x50,0x5e,0x63,0x68,0x7a,0x88,0x76,0x67,
0x7f,0x9e,0x9b,0x9c,0xaa,0xa9,0x83,0x55,0x58,0x69,0x6b,0x6f,0x80,0x80,0x6b,0x6f,
0x92,0x9f,0x99,0xa3,0xae,0x9a,0x66,0x51,0x5f,0x6c,0x6f,0x7a,0x82,0x73,0x69,0x82,
0x9c,0x9a,0x9c,0xab,0xa5,0x7e,0x59,0x57,0x66,0x6c,0x7a,0x82,0x7a,0x6b,0x74,0x91,
0x9b,0x99,0xa3,0xaa,0x98,0x6b,0x54,0x60,0x69,0x6c,0x77,0x81,0x77,0x70,0x84,0x9a,
0x98,0x99,0xa9,0xa6,0x83,0x5b,0x58,0x64,0x67,0x71,0x81,0x7f,0x6e,0x75,0x90,0x9b,
0x97,0xa2,0xae,0x9c,0x6b,0x56,0x5e,0x66,0x69,0x79,0x83,0x76,0x6d,0x84,0x99,0x98,
0x99,0xa8,0xaa,0x88,0x5f,0x58,0x65,0x63,0x6b,0x7c,0x82,0x72,0x76,0x8e,0x9b,0x94,
0x9e,0xad,0xa0,0x74,0x57,0x61,0x66,0x66,0x73,0x82,0x78,0x6d,0x80,0x98,0x97,0x95,
0xa6,0xaa,0x8f,0x66,0x59,0x63,0x66,0x6b,0x78,0x80,0x75,0x73,0x89,0x99,0x96,0x9a,
0xa8,0xa1,0x81,0x5f,0x5e,0x65,0x67,0x6e,0x78,0x7b,0x77,0x7e,0x91,0x96,0x95,0xa1,
0xa6,0x99,0x76,0x5b,0x5b,0x65,0x6e,0x74,0x7b,0x7b,0x77,0x82,0x93,0x99,0x9c,0xa4,
0xa6,0x8b,0x62,0x58,0x62,0x67,0x6d,0x76,0x7d,0x7a,0x7d,0x8d,0x96,0x96,0x9d,0xa6,
0x9f,0x7b,0x5a,0x59,0x64,0x68,0x70,0x7b,0x7f,0x7a,0x82,0x92,0x99,0x99,0xa1,0xa0,
0x90,0x69,0x5b,0x60,0x68,0x6e,0x72,0x7a,0x7d,0x7d,0x88,0x93,0x99,0x9f,0xa2,0xa0,
0x7f,0x5e,0x58,0x64,0x6c,0x6e,0x77,0x7e,0x79,0x7f,0x8f,0x9a,0x9b,0x9f,0xa2,0x97,
0x72,0x59,0x5c,0x67,0x6b,0x70,0x7e,0x80,0x79,0x83,0x94,0x99,0x99,0x9e,0xa3,0x88,
0x61,0x5b,0x68,0x6e,0x6c,0x73,0x7c,0x79,0x79,0x8a,0x99,0x9c,0x9f,0xa2,0x9b,0x7a,
0x60,0x5e,0x63,0x6b,0x6f,0x79,0x7d,0x7c,0x81,0x8d,0x95,0x9b,0xa0,0xa2,0x93,0x72,
0x5b,0x5f,0x66,0x6a,0x70,0x7b,0x7f,0x7b,0x82,0x91,0x99,0x9d,0x9f,0xa1,0x88,0x64,
0x5a,0x65,0x6c,0x6c,0x75,0x7d,0x79,0x79,0x8a,0x97,0x9c,0x9e,0xa6,0x9c,0x79,0x5d,
0x5d,0x66,0x6a,0x6f,0x79,0x7f,0x79,0x7e,0x8e,0x98,0x97,0x9b,0xa1,0x98,0x74,0x5c,
0x60,0x68,0x6a,0x6d,0x7a,0x7f,0x7b,0x82,0x92,0x9a,0x9d,0x9e,0xa2,0x8d,0x6b,0x5d,
0x61,0x69,0x6c,0x72,0x7b,0x7c,0x7c,0x87,0x94,0x98,0x99,0xa0,0xa1,0x84,0x63,0x5b,
0x66,0x6a,0x6e,0x76,0x7d,0x7a,0x7b,0x8a,0x97,0x9a,0x9c,0xa0,0x9a,0x7b,0x60,0x5f,
0x68,0x6c,0x6c,0x75,0x7e,0x7d,0x7f,0x8c,0x98,0x9a,0x9c,0xa0,0x98,0x75,0x5b,0x5f,
0x69,0x6c,0x6f,0x7a,0x7e,0x79,0x7e,0x91,0x9b,0x9e,0x9d,0xa0,0x8f,0x6b,0x5c,0x62,
0x6b,0x6d,0x70,0x7a,0x7d,0x7b,0x85,0x92,0x9a,0x9a,0x9d,0x9e,0x8c,0x68,0x5e,0x67,
0x68,0x66,0x70,0x7f,0x7f,0x7c,0x89,0x96,0x99,0x9d,0xa0,0x9d,0x7d,0x60,0x61,0x69,
0x6a,0x6b,0x75,0x7d,0x7b,0x7e,0x8b,0x94,0x99,0x9c,0xa2,0x9c,0x7b,0x5f,0x5c,0x66,
0x6b,0x70,0x79,0x7d,0x79,0x80,0x8f,0x97,0x99,0x9e,0xa0,0x92,0x72,0x64,0x66,0x67,
0x67,0x6d,0x7a,0x7d,0x7b,0x83,0x90,0x96,0x9b,0xa1,0xa2,0x90,0x6f,0x5f,0x63,0x67,
0x6c,0x73,0x7b,0x79,0x78,0x85,0x92,0x96,0x9a,0xa2,0xa4,0x8b,0x6c,0x5f,0x63,0x65,
0x6b,0x76,0x7b,0x77,0x7b,0x88,0x93,0x95,0x9a,0xa2,0xa3,0x89,0x69,0x5f,0x62,0x66,
0x6e,0x77,0x7b,0x77,0x7a,0x86,0x92,0x98,0x9d,0xa4,0xa2,0x87,0x66,0x5d,0x61,0x65,
0x6f,0x78,0x7c,0x77,0x7a,0x89,0x92,0x94,0x9b,0xa6,0xa2,0x86,0x68,0x5e,0x5f,0x65,
0x70,0x79,0x7a,0x78,0x7c,0x89,0x90,0x95,0x9f,0xa5,0x9f,0x85,0x65,0x5f,0x63,0x65,
0x6c,0x79,0x7c,0x77,0x7b,0x8c,0x92,0x95,0x9b,0xa8,0xa2,0x82,0x65,0x61,0x62,0x65,
0x6e,0x79,0x7a,0x77,0x7d,0x8b,0x91,0x94,0x9c,0xa7,0xa7,0x87,0x64,0x59,0x5e,0x66,
0x6e,0x7a,0x7f,0x78,0x79,0x88,0x91,0x93,0x99,0xa6,0xa8,0x89,0x66,0x5f,0x61,0x61,
0x68,0x78,0x7f,0x7a,0x7b,0x88,0x8f,0x92,0x99,0xa7,0xa7,0x8f,0x6b,0x5d,0x5d,0x61,
0x69,0x75,0x7e,0x7b,0x7a,0x86,0x91,0x93,0x98,0xa4,0xad,0x97,0x6d,0x5a,0x57,0x5d,
0x66,0x77,0x84,0x80,0x79,0x82,0x8c,0x90,0x95,0xa4,0xac,0x9d,0x72,0x5a,0x58,0x5b,
0x63,0x75,0x83,0x82,0x79,0x82,0x8d,0x8f,0x92,0xa2,0xb1,0xa6,0x7a,0x58,0x53,0x56,
0x60,0x74,0x87,0x86,0x7b,0x7c,0x89,0x8d,0x8f,0x9d,0xb0,0xae,0x89,0x5c,0x52,0x53,
0x5b,0x6c,0x83,0x8a,0x80,0x7c,0x87,0x8a,0x8b,0x98,0xaf,0xb6,0x93,0x62,0x51,0x52,
0x56,0x66,0x83,0x8f,0x81,0x76,0x81,0x8a,0x89,0x92,0xad,0xb9,0xa0,0x71,0x55,0x50,
0x4f,0x5e,0x7b,0x90,0x88,0x7a,0x7a,0x83,0x83,0x8c,0xa6,0xb8,0xb6,0x89,0x59,0x4d,
0x4f,0x57,0x6d,0x89,0x93,0x82,0x78,0x7c,0x84,0x85,0x95,0xaf,0xbf,0xa8,0x71,0x50,
0x4d,0x52,0x5e,0x7a,0x91,0x8c,0x79,0x77,0x80,0x83,0x83,0x9d,0xba,0xc1,0x99,0x5b,
0x47,0x4e,0x57,0x6c,0x8b,0x92,0x7f,0x73,0x7b,0x81,0x82,0x89,0xa3,0xbb,0xbf,0x93,
0x55,0x45,0x4b,0x5c,0x7d,0x98,0x8b,0x6d,0x68,0x7d,0x85,0x85,0x88,0x9f,0xb6,0xc0,
0x9b,0x5c,0x42,0x49,0x5b,0x7a,0x9b,0x98,0x6f,0x5e,0x73,0x85,0x81,0x7e,0x97,0xb4,
0xc7,0xb4,0x74,0x45,0x3f,0x4d,0x70,0x9a,0xa5,0x7d,0x5f,0x69,0x7d,0x7e,0x7a,0x86,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80
};
void setup() {
attachInterrupt(INTIR, irInt, CHANGE);
analogWriteFrequency(16000);
pinMode(LED1_M1F, OUTPUT);
pinMode(LED2_M0F, OUTPUT);
pinMode(LED3_M0B, OUTPUT);
pinMode(LED4_M1B, OUTPUT);
pinMode(LED5, OUTPUT);
pinMode(LED6, OUTPUT);
pinMode(LED_R, OUTPUT);
pinMode(LED_G, OUTPUT);
pinMode(LED_B, OUTPUT);
pinMode(SERVO_PIN, OUTPUT);
digitalWrite(LED5, LED_OFF);
digitalWrite(LED6, LED_OFF);
freeMotor();
randomSeed((unsigned int)analogRead(BATT));
Serial.begin(115200);
Wire.begin();
Wire.beginTransmission(0x68); //Gyro sensor
Wire.write(0x6B); // Power management register
Wire.write(0); // wake up MPU-6050
Wire.endTransmission();
SD2.begin(27);
checkVoltage();
selectMode();
delay(100);
readEEPROMbal();
readEEPROMadhoc();
resetPara();
resetVar();
openFiles();
digitalWrite(LED6, LED_ON);
calibGyro();
digitalWrite(LED6, LED_OFF);
pinMode(TONE_PIN, OUTPUT);
analogWrite(TONE_PIN, 0);
delay(10);
if (fGreet) soundStartSD(fGreet, fsizeGreet, vGreet);
else soundStart(soundGreet, sizeof(soundGreet), 70);
while (soundBusy);
if (demoMode==2) soundStartSD(fDemo, fsizeDemo, vDemo);
if (debug) soundStartSD(fDebug, fsizeDebug, vDebug);
}
void loop(){
time0=micros();
getIR();
getGyro();
pendulum();
servoHead();
randomPlay();
if (pendPhase!=-1) monitorVoltage();
counter += 1;
if (counter >= 100) {
counter = 0;
counterSec++;
if (debug) digitalWrite(LED6, LED_ON);
if (serialMonitor) sendSerial();
digitalWrite(LED6, LED_OFF);
}
while (micros() - time0 < pendInterval);
}
void pendulum() {
switch (pendPhase) {
case -1: //wait until upright
calcTarget();
if (upright()) {
pendPhase =0;
digitalWrite(LED5, LED_OFF);
}
break;
case 0: //calib Acc
resetVar();
demoDelayCounter=0;
demoPhase=0;
delay(1300);
if (!upright()) pendPhase=2;
else {
digitalWrite(LED6, LED_ON);
calibAcc();
digitalWrite(LED6, LED_OFF);
if (upright()) pendPhase=1;
else pendPhase=2;
}
break;
case 1: //run
if (!standing()) {
if (musicPlaying) soundStop=true;
soundStart(soundWow, sizeof(soundWow), 70);
pendPhase=6;
}
// else if (bVolt<2.0) resetMotor();
else {
if (demoMode==2) demo8();
calcTarget();
boolean ok=pendDrive();
if (!ok) {
if (musicPlaying) soundStop=true;
delay(1300);
pendPhase=2;
}
}
break;
case 2: //wait until upright
freeMotor();
if (upright()) pendPhase=0;
break;
case 6: //fell
if (laid() && !soundBusy) pendPhase=8;
break;
case 8:
soundStartSD(fTipover, fsizeTipover, vTipover);
pendPhase=2;
break;
}
}
void openFiles() {
fGreet=SD2.open("kon168m.wav");
fsizeGreet=fGreet.size();
vGreet=getVolume(SD2.open("kon168m.ini"));
fStop=SD2.open("tom168m.wav");
fsizeStop=fStop.size();
vStop=getVolume(SD2.open("tom168m.ini"));
fRight=SD2.open("mig168m.wav");
fsizeRight=fRight.size();
vRight=getVolume(SD2.open("mig168m.ini"));
fLeft=SD2.open("hid168m.wav");
fsizeLeft=fLeft.size();
vLeft=getVolume(SD2.open("hid168m.ini"));
fForward=SD2.open("sus168m.wav");
fsizeForward=fForward.size();
vForward=getVolume(SD2.open("sus168m.ini"));
fBack=SD2.open("bac168m.wav");
fsizeBack=fBack.size();
vBack=getVolume(SD2.open("bac168m.ini"));
fSpin=SD2.open("maw168m.wav");
fsizeSpin=fSpin.size();
vSpin=getVolume(SD2.open("maw168m.ini"));
fAccel=SD2.open("kaso168m.wav");
fsizeAccel=fAccel.size();
vAccel=getVolume(SD2.open("kaso168m.ini"));
fTipover=SD2.open("koro168m.wav");
fsizeTipover=fTipover.size();
vTipover=getVolume(SD2.open("koro168m.ini"));
fDemo=SD2.open("demo168m.wav");
fsizeDemo=fDemo.size();
vDemo=getVolume(SD2.open("demo168m.ini"));
fDebug=SD2.open("debu168m.wav");
fsizeDebug=fDebug.size();
vDebug=getVolume(SD2.open("debu168m.ini"));
fBattery=SD2.open("denc168m.wav");
fsizeBattery=fBattery.size();
vBattery=getVolume(SD2.open("denc168m.ini"));
fReplace=SD2.open("kouk168m.wav");
fsizeReplace=fReplace.size();
vReplace=getVolume(SD2.open("kouk168m.ini"));
voiceFile[0]=SD2.open(soundVoice[0]);
if (voiceFile[0]) {
fsizeVoice[0]=voiceFile[0].size();
vVoice[0]=getVolume(SD2.open(soundVoiceIni[0]));
if (serialMonitor) {Serial.print(soundVoice[0]);Serial.print(" size=");Serial.println(fsizeVoice[0]);}
minVoiceFile=0;
}
for (int i=1; i<sizeof(soundVoice)/2; i++) {
voiceFile[i]=SD2.open(soundVoice[i]);
if (voiceFile[i]) {
fsizeVoice[i]=voiceFile[i].size();
vVoice[i]=getVolume(SD2.open(soundVoiceIni[i]));
if (serialMonitor) {Serial.print(soundVoice[i]);Serial.print(" size=");Serial.println(fsizeVoice[i]);}
maxVoiceFile=i;
}
}
if (minVoiceFile==-1 && maxVoiceFile>=1) minVoiceFile=1;
for (int i=0; i<sizeof(soundMusic)/2; i++) {
musicFile[i]=SD2.open(soundMusic[i]);
if (musicFile[i]) {
fsizeMusic[i]=musicFile[i].size();
vMusic[i]=getVolume(SD2.open(soundMusicIni[i]));
if (serialMonitor) {Serial.print(soundMusic[i]);Serial.print(" size=");Serial.println(fsizeMusic[i]);}
minMusicFile=0;
maxMusicFile=i;
}
}
}
int getVolume(File f) {
if (f) {
int vol=0;
while(f.available()) {
char c=f.read();
if (c>=0x30 && c<0x39) vol=vol*10+c-0x30;
}
f.close();
if (vol>=0 && vol<=100) return vol;
else return 10;
}
else return 10;
}
void randomPlay() {
if (!randomSoundOn || minVoiceFile==-1) return;
switch (soundPhase) {
case 1:
if (!soundBusy) {
counterSec0=counterSec;
soundInterval=(int)random(MINSINTERVAL, MAXSINTERVAL+1);
soundPhase=2;
}
break;
case 2:
if (counterSec-counterSec0>soundInterval) {
soundId=(int)random(minVoiceFile, maxVoiceFile+1);
soundStartSD(voiceFile[soundId], fsizeVoice[soundId], vVoice[soundId]);
if (soundId==0) {
if (minMusicFile!=-1 && demoMode==0) soundPhase=3;
else soundPhase=1;
}
else soundPhase=1;
}
break;
case 3:
if (!soundBusy) {
musicPlaying=true;
int id=(int)random(minMusicFile, maxMusicFile+1);
soundStartSD(musicFile[id], fsizeMusic[id], vMusic[id]);
soundPhase=1;
}
break;
}
}
void servoHead() {
switch(servoPhase) {
case 1:
servoDrive();
if (servoComplete) {
servoComplete=false;
servoPhase=2;
}
break;
case 2:
servoContinue(90.0, 1.0);
servoPhase=3;
break;
case 3:
servoDrive();
if (servoComplete) {
servoComplete=false;
servoPhase=4;
}
break;
case 4:
break;
}
}
void servoStart(double ang, double stp) {
servoPhase=1;
servoContinue(ang, stp);
}
void servoContinue(double ang, double stp) {
if (ang<servoAngTarget) stp=-stp;
servoAngDestination=ang;
servoAngStep=stp;
}
void servoDrive() {
if (servoAngStep>=0) {
if (servoAngDestination-servoAngStep>servoAngTarget) servoAngTarget+=servoAngStep;
else {
servoAngTarget=servoAngDestination;
servoComplete=true;
}
}
else {
if (servoAngDestination-servoAngStep<servoAngTarget) servoAngTarget+=servoAngStep;
else {
servoAngTarget=servoAngDestination;
servoComplete=true;
}
}
servoPulseWidth=600+(int)(servoAngTarget*10.0);
digitalWrite(SERVO_PIN, HIGH);
delayMicroseconds(servoPulseWidth);
digitalWrite(SERVO_PIN, LOW);
}
void calcTarget() {
if (spinContinuous) spinTarget += spinStep;
else {
if (spinTarget < spinDestination) spinTarget += spinStep;
if (spinTarget > spinDestination) spinTarget -= spinStep;
}
moveTarget -= moveStep * moveRate;
}
boolean pendDrive() {
varSpd += power * pendClk;
varDst += Kdst * (varSpd * pendClk - moveTarget);
varIang += KIang * varAng * pendClk;
varIdst += KIdst * varDst * pendClk;
power = varIang + varIdst + varDst + (Kspd * varSpd) + (Kang * varAng) + (Komg * varOmg);
if (abs(power) > 5000.0) counterOverSpd +=1;
else counterOverSpd=0;
if (counterOverSpd > maxOverSpd) {
resetMotor();
resetVar();
return false;
}
spinPower = (spinAngle - spinTarget) * Kspin;
powerL = power - spinPower;
powerR = power + spinPower;
motor();
return true;
}
void motor() {
ipowerL = (int) (constrain(powerL * mechFactorL * battFactor, -maxSpd, maxSpd));
if (ipowerL > 0) {
if (motorLdir == 1) drvMotorL(ipowerL);
else drvMotorL(ipowerL + backlashSpd); //compensate backlash
motorLdir = 1;
}
else if (ipowerL < 0) {
if (motorLdir == -1) drvMotorL(ipowerL);
else drvMotorL(ipowerL - backlashSpd);
motorLdir = -1;
}
else {
drvMotorL(0);
motorLdir = 0;
}
ipowerR = (int) (constrain(powerR * mechFactorR * battFactor, -maxSpd, maxSpd));
if (ipowerR > 0) {
if (motorRdir == 1) drvMotorR(ipowerR);
else drvMotorR(ipowerR + backlashSpd); //compensate backlash
motorRdir = 1;
}
else if (ipowerR < 0) {
if (motorRdir == -1) drvMotorR(ipowerR);
else drvMotorR(ipowerR - backlashSpd);
motorRdir = -1;
}
else {
drvMotorR(0);
motorRdir = 0;
}
}
void drvMotorL(int pwm) {
switch (MotorConfig) {
case 0: drvMotor1(pwm);
break;
case 1: drvMotor1(-pwm);
break;
case 2: drvMotor1(pwm);
break;
case 3: drvMotor1(-pwm);
break;
}
}
void drvMotorR(int pwm) {
switch (MotorConfig) {
case 0: drvMotor0(pwm);
break;
case 1: drvMotor0(-pwm);
break;
case 2: drvMotor0(-pwm);
break;
case 3: drvMotor0(pwm);
break;
}
}
void drvMotor0(int pwm) {
if (pwm >0) {
digitalWrite(LED3_M0B,LOW);
analogWrite(LED2_M0F,constrain(pwm+drvHLbalance, 0,PWMMAX));
}
else if (pwm < 0) {
digitalWrite(LED3_M0B,HIGH);
analogWrite(LED2_M0F,constrain(PWMMAX+pwm, 0,PWMMAX));
}
else {
pinMode(LED2_M0F, OUTPUT);
digitalWrite(LED2_M0F,HIGH);
digitalWrite(LED3_M0B,HIGH);
}
}
void drvMotor1(int pwm) {
if (pwm >0) {
digitalWrite(LED4_M1B,LOW);
analogWrite(LED1_M1F,constrain(pwm+drvHLbalance, 0,PWMMAX));
}
else if (pwm < 0) {
digitalWrite(LED4_M1B,HIGH);
analogWrite(LED1_M1F,constrain(PWMMAX+pwm, 0,PWMMAX));
}
else {
pinMode(LED1_M1F, OUTPUT);
digitalWrite(LED1_M1F,HIGH);
digitalWrite(LED4_M1B,HIGH);
}
}
void getGyro() {
readGyro();
snsGyroY = (gyroDataY - gyroOffsetY) * gyroLSB;
varOmg = (gyroDataZ - gyroOffsetZ) * gyroLSB; // unit:deg/sec
snsAccX = (accDataX - accOffsetX) * accLSB; //unit:g
spinAngle += snsGyroY * pendClk;
varAng += (varOmg + (snsAccX * 57.3 - varAng) * cutoff ) * pendClk;
//angle filter accX=g*sin(ang) -> accX/g=sin(ang)=ang [rad] (if ang is small) -> ang=accX*57.3[deg]
// varAng += varOmg * pendClk;
}
void readGyro() {
Wire.beginTransmission(0x68);
Wire.write(0x3B);
Wire.endTransmission();
Wire.requestFrom(0x68, 14);
accX=Wire.read()<<8|Wire.read(); //0x3B
accY=Wire.read()<<8|Wire.read(); //0x3D
accZ=Wire.read()<<8|Wire.read(); //0x3F
temp=Wire.read()<<8|Wire.read(); //0x41
gyroX=Wire.read()<<8|Wire.read(); //0x43
gyroY=Wire.read()<<8|Wire.read(); //0x45
gyroZ=Wire.read()<<8|Wire.read(); //0x47
gyroDataY = (double) gyroY;
gyroDataZ = -(double) gyroX;
accDataX = -(double) accZ;
aveAccX = aveAccX * 0.9 + accDataX * 0.1;
accDataY = -(double) accY;
aveAccY = aveAccY * 0.9 + accDataY * 0.1;
}
boolean laid() {
if (abs(aveAccX) >13000.0) return true;
else return false;
}
boolean upright() {
if (abs(aveAccY) >13000.0) return true;
else return false;
}
boolean standing() {
if (abs(aveAccY) >8000.0 && abs(varAng) < 40.0) return true;
else {
resetMotor();
resetVar();
return false;
}
}
void calibAcc() {
accOffsetX=0.0;
for (int i=1; i <= 30; i++) {
readGyro();
accOffsetX += accDataX;
delay(20);
}
accOffsetX /= 30.0;
}
void calibGyro() {
gyroOffsetZ=gyroOffsetY=0.0;
for (int i=1; i <= 30; i++) {
readGyro();
gyroOffsetZ += gyroDataZ;
gyroOffsetY += gyroDataY;
delay(20);
}
gyroOffsetY /= 30.0;
gyroOffsetZ /= 30.0;
}
void resetPara() {
Kang=150.0;
Komg=3.0;
KIang=1300.0;
Kspin=15.0;
Kdst=80.0;
Kspd=3.5;
KIdst=0.0;
mechFactorR=0.38;
mechFactorL=0.38;
backlashSpd=30;
}
void resetVar() {
power=0.0;
moveTarget=0.0;
spinDestination=0.0;
spinTarget=0.0;
spinAngle=0.0;
varAng=0.0;
varOmg=0.0;
varDst=0.0;
varSpd=0.0;
varIang=0.0;
varIdst=0.0;
counterOverSpd=0;
spinContinuous=false;
moveRate=0.0;
}
void resetMotor() {
drvMotorL(0);
drvMotorR(0);
}
void freeMotor() {
pinMode(LED2_M0F, OUTPUT);
pinMode(LED1_M1F, OUTPUT);
digitalWrite(LED2_M0F, LOW);
digitalWrite(LED3_M0B, LOW);
digitalWrite(LED1_M1F, LOW);
digitalWrite(LED4_M1B, LOW);
}
void checkVoltage() {
monitorVoltage();
if (serialMonitor) {Serial.print("Batt=");Serial.println(bVolt);}
if (!usbPower && bVolt<3.8) {
soundStartSD(fBattery, fsizeBattery, vBattery);
blinkLED(5); //Batt Low
soundStartSD(fReplace, fsizeReplace, vReplace);
blinkLED(45);
}
}
void blinkLED(int n) {
for (int i=0; i<n; i++) {
digitalWrite(LED6, LED_ON);
delay(10);
digitalWrite(LED6, LED_OFF);
delay(200);
}
}
void monitorVoltage() {
bVolt=getBattVolt();
aveVolt = aveVolt * 0.98 + bVolt * 0.02;
if (bVolt<minVolt) minVolt=bVolt;
if (bVolt<0.5) { //USB POWER
usbPower=true;
battFactor=1.3;
setColor(0,0,1);
}
else {
battFactor = 18.0 / aveVolt / aveVolt;
// battFactor = 4.5 / aveVolt;
// battFactor = 4.5 / bVolt;
if (bVolt<3.6) setColor(1,0,1);
else if (bVolt<4.0) setColor(1,0,0);
else if (bVolt<4.4) setColor(1,1,0);
else setColor(0,1,0);
}
}
double getBattVolt() {
return ((double) analogRead(BATT)) * 0.0064516; // analogRead / 1023.0 * 6.6;
}
void selectMode() {
pinMode(SW1_SINT_PIN, INPUT_PULLUP);
pinMode(SW2_IRINT_PIN, INPUT_PULLUP);
delay(10);
if (digitalRead(SW1_SINT_PIN) == LOW) { //debug
debug=true;
serialMonitor=true;
spinStep=0.0;
blinkLED(1);
while(digitalRead(SW1_SINT_PIN)==LOW);
}
else if (digitalRead(SW2_IRINT_PIN) == LOW) { //demo
demoMode=2;
blinkLED(2);
while(digitalRead(SW2_IRINT_PIN) == LOW);
}
else spinStep=0.0;
pinMode(SW1_SINT_PIN, INPUT);
pinMode(SW2_IRINT_PIN, INPUT);
}
void demo8() {
switch (demoPhase) {
case 0:
demoDelayCounter=200;
demoPhase=1;
break;
case 1:
if (demoDelayCounter>1) demoDelayCounter--;
else {
moveRate=3.0;
spinStep=0.5;
spinDestination += 270.0;
demoPhase=2;
}
break;
case 2:
if (abs(spinTarget-spinDestination)<5.0) {
demoDelayCounter=100;
moveRate=5.0;
demoPhase=3;
}
break;
case 3:
if (demoDelayCounter>1) demoDelayCounter--;
else {
moveRate=3.0;
spinDestination -= 270.0;
demoPhase=4;
}
break;
case 4:
if (abs(spinTarget-spinDestination)<5.0) {
demoDelayCounter=100;
moveRate=5.0;
demoPhase=1;
}
break;
}
}
void setColor(int r, int g, int b) {
digitalWrite(LED_R, r);
digitalWrite(LED_G, g);
digitalWrite(LED_B, b);
}
void readEEPROMbal() {
if (EEPROM.read(0)==HCODE) {
drvHLbalance=EEPROM.read(1);
if (serialMonitor) {Serial.print("drvHLbal=");Serial.println(drvHLbalance);}
}
else {
drvHLbalance=30;
noInterrupts();
EEPROM.write(0, HCODE);
EEPROM.write(1, drvHLbalance);
interrupts();
}
}
void writeEEPROMbal() {
noInterrupts();
EEPROM.write(1, drvHLbalance);
interrupts();
}
void readEEPROMadhoc() {
if (EEPROM.read(2)==HCODE) {
for (int i=0; i<ADHOC_IR_MAX; i++) {
ADHOC_CUSTOMER[i]=EEPROM.read(3+i*4)<<8|EEPROM.read(4+i*4);
ADHOC_IR[i]=EEPROM.read(5+i*4)<<8|EEPROM.read(6+i*4);
if (serialMonitor) {
Serial.print("CUST=");Serial.print(ADHOC_CUSTOMER[i],HEX);Serial.print(" CODE=");Serial.println(ADHOC_IR[i],HEX);
}
}
}
}
void writeEEPROMadhoc() {
noInterrupts();
EEPROM.write(2, HCODE);
for (int i=0; i<ADHOC_IR_MAX; i++) {
EEPROM.write(3+i*4, (byte)((ADHOC_CUSTOMER[i]>>8)&0xFF));
EEPROM.write(4+i*4, (byte)(ADHOC_CUSTOMER[i]&0xFF));
EEPROM.write(5+i*4, (byte)((ADHOC_IR[i]>>8)&0xFF));
EEPROM.write(6+i*4, (byte)(ADHOC_IR[i]&0xFF));
}
interrupts();
}
void sendSerial () {
Serial.print(micros()-time0);
Serial.print(" phase=");Serial.print(pendPhase);
Serial.print(" accX="); Serial.print(aveAccX);
Serial.print(" accY="); Serial.print(aveAccY);
Serial.print(" ang=");Serial.print(varAng);
// Serial.print(" temp = "); Serial.print(temp/340.0+36.53);
Serial.print(" drvBal="); Serial.print(drvHLbalance);
Serial.print(" mVolt="); Serial.print(minVolt);
Serial.print(", ");
Serial.print(micros()-time0);
Serial.println();
}
void getIR() {
if (!(irStarted && (micros()-irMicroOff>10000))) return;
if ((irDataOn[0]>1800) && musicPlaying) soundStop=true;
irStarted=false;
irDecoding=true;
if (irDataOn[0]>7000) { //NEC
if (irOffIndex >=33) {
decodeNECAEHA();
printIrData("NEC");
}
}
else if (irDataOn[0]>2600) { //AEHA
if (irOffIndex >=41) {
decodeNECAEHA();
printIrData("AEHA");
}
}
else if (irDataOn[0]>1800) { //SONY
if (irOnIndex >=12) {
decodeSONY();
printIrData("SONY");
}
}
if (irReady) {
irReady=false;
lastIrTime=millis();
if (adhoc_ir_num>=0 && adhoc_ir_num<ADHOC_IR_MAX && pendPhase==-1) regIR();
else irCommand();
}
irDecoding=false;
}
void irCommand() {
if (
((ircode==AKI_REMO_CENTER)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_CENTER])&&(customer_code==ADHOC_CUSTOMER[IR_CENTER])) ) {
if (pendPhase!=-1) {
if (abs(moveRate)>1.0 || abs(spinStep)>0.1) {
if (fStop) soundStartSD(fStop, fsizeStop, vStop);
else tone(TONE_PIN, 500, 100);
}
button=IR_CENTER;
demoMode=0;
spinContinuous=false;
spinStep=0.0;
moveRate=0.0;
spinDestination = spinTarget;
}
}
else if (
((ircode==AKI_REMO_RIGHT)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_RIGHT])&&(customer_code==ADHOC_CUSTOMER[IR_RIGHT])) ) {
if (pendPhase==-1) {
servoStart(60.0, 0.5);
drvMotorR(-80);
delay(1000);
drvMotorR(0);
}
else if (demoMode==0) {
servoStart(headRight, 3.0);
if (button!=IR_RIGHT && fRight) soundStartSD(fRight, fsizeRight, vRight);
else tone(TONE_PIN, 2000, 100);
button=IR_RIGHT;
if (spinContinuous) spinDestination=spinTarget;
spinContinuous=false;
spinStep=0.6;
spinDestination -= 30.0;
}
}
else if (
((ircode==AKI_REMO_LEFT)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_LEFT])&&(customer_code==ADHOC_CUSTOMER[IR_LEFT])) ) {
if (pendPhase==-1) {
servoStart(120.0, 0.5);
drvMotorL(-80);
delay(1000);
drvMotorL(0);
}
else if (demoMode==0) {
servoStart(headLeft, 3.0);
if (button!=IR_LEFT && fLeft) soundStartSD(fLeft, fsizeLeft, vLeft);
else tone(TONE_PIN, 2000, 100);
button=IR_LEFT;
if (spinContinuous) spinDestination=spinTarget;
spinContinuous=false;
spinStep=0.6;
spinDestination += 30.0;
}
}
else if (
((ircode==AKI_REMO_UP)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_UP])&&(customer_code==ADHOC_CUSTOMER[IR_UP])) ) {
if (pendPhase!=-1 && demoMode==0) {
button=IR_UP;
if (abs(moveRate)<1.0 && fForward) soundStartSD(fForward, fsizeForward, vForward);
else if (abs(moveRate)>10.0 && fAccel) soundStartSD(fAccel, fsizeAccel, vAccel);
else tone(TONE_PIN, 1000, 100);
moveRate+=4.0;
}
}
else if (
((ircode==AKI_REMO_DOWN)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_DOWN])&&(customer_code==ADHOC_CUSTOMER[IR_DOWN])) ) {
if (pendPhase!=-1 && demoMode==0) {
button=IR_DOWN;
if (abs(moveRate)<1.0 && fBack) soundStartSD(fBack, fsizeBack, vBack);
else tone(TONE_PIN, 1000, 100);
moveRate-=4.0;
}
}
else if (
((ircode==AKI_REMO_UL)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_CIRL])&&(customer_code==ADHOC_CUSTOMER[IR_CIRL])) ) {
if (pendPhase!=-1 && demoMode==0) {
button=IR_CIRL;
if (abs(spinStep)<0.1 && fSpin) soundStartSD(fSpin, fsizeSpin, vSpin);
else tone(TONE_PIN, 2000, 20);
if (!spinContinuous) spinStep=0.0;
spinContinuous=true;
spinStep+=0.3;
}
}
else if (
((ircode==AKI_REMO_UR)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_CIRR])&&(customer_code==ADHOC_CUSTOMER[IR_CIRR])) ) {
if (pendPhase!=-1 && demoMode==0) {
button=IR_CIRR;
if (abs(spinStep)<0.1 && fSpin) soundStartSD(fSpin, fsizeSpin, vSpin);
else tone(TONE_PIN, 2000, 20);
if (!spinContinuous) spinStep=0.0;
spinContinuous=true;
spinStep-=0.3;
}
}
else if (
((ircode==AKI_REMO_DL)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_BALF])&&(customer_code==ADHOC_CUSTOMER[IR_BALF])) ) {
if (demoMode==0) {
if (moveRate==0.0 && spinTarget==spinDestination) {
if (drvHLbalance>=-100) {
tone(TONE_PIN, 4000, 10);
drvHLbalance-=5;
setColor(1,1,1);
digitalWrite(LED5,LED_ON);
writeEEPROMbal();
digitalWrite(LED5,LED_OFF);
}
else tone(TONE_PIN, 4000, 40);
}
}
}
else if (
((ircode==AKI_REMO_DR)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_BALB])&&(customer_code==ADHOC_CUSTOMER[IR_BALB])) ) {
if (demoMode==0) {
if (moveRate==0.0 && spinTarget==spinDestination) {
if (drvHLbalance<=100) {
tone(TONE_PIN, 4000, 10);
drvHLbalance+=5;
setColor(1,1,1);
digitalWrite(LED5,LED_ON);
writeEEPROMbal();
digitalWrite(LED5,LED_OFF);
}
else tone(TONE_PIN, 4000, 40);
}
}
}
else {
if (pendPhase == -1 && debug && adhoc_ir_num==-1) {
setColor(1,1,1);
digitalWrite(LED5, LED_ON);
randomSoundOn=false;
adhoc_ir_num=0;
}
}
}
void regIR() {
// Ad hoc IR code registration
if (adhoc_ir_num<ADHOC_IR_MAX) {
ADHOC_IR[adhoc_ir_num]=ircode;
ADHOC_CUSTOMER[adhoc_ir_num]=customer_code;
if (serialMonitor) {
Serial.print("set ADHOC_IR[");
Serial.print(adhoc_ir_num);
Serial.print("] = ");
Serial.println(ircode, HEX);
Serial.print("set ADHOC_CUSTOMER[");
Serial.print(adhoc_ir_num);
Serial.print("] = ");
Serial.println(customer_code, HEX);
}
if (adhoc_ir_num==0) adhoc_ir_num++;
else if (ADHOC_IR[adhoc_ir_num-1]!=ircode) adhoc_ir_num++;
for (int i=1; i<=adhoc_ir_num; i++) {
digitalWrite(LED5, LED_OFF);
delay(200);
digitalWrite(LED5, LED_ON);
delay(100);
}
if (adhoc_ir_num==ADHOC_IR_MAX) {
writeEEPROMadhoc();
digitalWrite(LED5, LED_OFF);
randomSoundOn=true;
}
}
}
void irInt() {
if (millis()-lastIrTime<MINIRINTERVAL) return;
if (irDecoding) return;
if (pendPhase!=-1) digitalWrite(LED5, LED_ON);
if (digitalRead(SW2_IRINT_PIN) == IRON) {
irMicroOn=micros();
if (irStarted) {
irDataOff[irOffIndex]=irMicroOn-irMicroOff;
irOffIndex++;
if (irOffIndex>=IRBUFFLEN) irStarted=false;
}
else {
irStarted=true;
irOnIndex=0;
irOffIndex=0;
irMicroOff=irMicroOn;
}
}
else {
irMicroOff=micros();
irDataOn[irOnIndex]=irMicroOff-irMicroOn;
irOnIndex++;
if (irOnIndex>=IRBUFFLEN) irStarted=false;
}
digitalWrite(LED5, LED_OFF);
}
void decodeNECAEHA() {
int len=irOffIndex/8;
int idx=1;
for (int i=0; i<len; i++) {
irData[i]=0;
for (int j=0; j<8; j++) {
irData[i]>>=1;
if (irDataOff[idx]>1000) irData[i]|=0x80;
idx++;
}
}
customer_code=irData[0]<<8|irData[1];
ircode=irData[len-2]<<8|irData[len-1];
irReady=true;
}
void decodeSONY() {
byte data=0;
for (int i=1; i<=7; i++) {
if (irDataOn[i]>900) data|=0x80;
data>>=1;
}
unsigned int addr=0;
int idx=8;
for (int i=0; i<16; i++) {
addr>>=1;
if (idx<irOnIndex && irDataOn[idx]<1800) {
if (irDataOn[idx]>900) addr|=0x8000;
idx++;
}
}
customer_code=addr;
ircode=(unsigned int)data;
irReady=true;
}
void printIrData(String s) {
if (!serialMonitor) return;
/*
for (int i=0; i<irOffIndex; i++) {
Serial.print(irDataOn[i]);Serial.print(" ");Serial.println(irDataOff[i]);
}
Serial.println("");
*/
Serial.println(s);
Serial.print("Customer=");Serial.println(customer_code, HEX);
Serial.print("Code=");Serial.println(ircode, HEX);
}
void soundIntSD() {
if (filePointer<fileSize && !soundStop) {
byte d=sdfile.read();
filePointer++;
if (soundGain!=10) {
int di=(int)d-128;
di=(di*soundGain)/10;
d=(byte)constrain((di+128), 10, 250);
}
else d=constrain(d, 10, 250);
analogWrite(TONE_PIN, d);
}
else {
detachInterrupt(INTSOUND);
analogWrite(TONE_PIN, 0);
musicPlaying=false;
soundBusy=false;
}
}
void soundStartSD(File s, unsigned long sz, int gain) {
if (soundBusy || !s) return;
sdfile=s;
fileSize=sz;
soundBusy=true;
soundStop=false;
if (sdfile.seek(44)) {
soundGain=gain;
filePointer=44;
attachInterrupt(INTSOUND, soundIntSD, RISING);
analogWrite(TONE_PIN, 128);
}
}
void soundStart(const byte* ptr, unsigned long sz, int gain) {
if (soundBusy) return;
counterSec0=counterSec;
soundBusy=true;
soundIndex=0;
soundPtr=ptr;
soundSize=sz;
soundGain=gain;
attachInterrupt(INTSOUND, soundInt, RISING);
analogWrite(TONE_PIN, 128);
}
void soundInt() {
byte d=soundPtr[soundIndex];
if (soundGain!=10) {
int di=(int)d-128;
di=(di*soundGain)/10;
d=(byte)constrain((di+128), 10, 250);
}
else d=constrain(d, 10, 250);
analogWrite(TONE_PIN, d);
soundIndex++;
if (soundIndex>=soundSize) {
detachInterrupt(INTSOUND);
analogWrite(TONE_PIN, 0);
soundBusy=false;
}
}

2017年7月10日月曜日

GR-ADZUKIで倒立振子ロボADZUMIN v41

//ADZUMIN Inverted Pendulum Robot
//Copyright MAENOH! & KIRAKULABO 2017
//wheele dia ~= 58mm
//Gear ratio ~= 114 (TAMIYA Double Gear Box)
//Battery: Alkaline x 3
//MPU/Driver: GR-ADZUKI
//Gyro/Acc: MPU6050 (I2C)
//Adhoc IR remote control registration during laying just after power up.
//SW1: Stand still with debug and serialMonito on (1 blink)
//SW2: demo (2 blinks)
//Default: Stand still (no blink)
#include "Arduino.h"
#include <Wire.h>
#include <EEPROM.h>
#include <SD.h>
#define LED_R 22
#define LED_G 23
#define LED_B 24
#define HCODE 0x4D //M
#define PWMMAX 255
#define M1F 6
#define M0F 9
#define M0B 10
#define M1B 11
#define LED1_M1F 6
#define LED2_M0F 9
#define LED3_M0B 10
#define LED4_M1B 11
#define LED5 12
#define LED6 13
#define LED_ON 1
#define LED_OFF 0
#define SW1 3
#define SW2 2
#define GP2Y A0
#define BATT A1
#define TONE_PIN 5
#define AKI_REMO_CUSTOMER (0x10EF)
#define AKI_REMO_POWER (0xD827)
#define AKI_REMO_A (0xF807)
#define AKI_REMO_B (0x7887)
#define AKI_REMO_C (0x58A7)
#define AKI_REMO_UP (0xA05F)
#define AKI_REMO_DOWN (0x00FF)
#define AKI_REMO_RIGHT (0x807F)
#define AKI_REMO_LEFT (0x10EF)
#define AKI_REMO_CENTER (0x20DF)
#define AKI_REMO_UR (0x21DE)
#define AKI_REMO_UL (0xB14E)
#define AKI_REMO_DR (0x817E)
#define AKI_REMO_DL (0x11EE)
#define SW_ON 0
#define SW_OFF 1
#define SOUTPIN 5
#define SINTPIN 3
#define INTSOUND 1
#define IRIN 2 // IR RECEIVE PIN
#define INTIR 0 // IR RECEIVE interrupt number
#define IRON LOW
#define IROFF HIGH
#define IRBUFFLEN 200
// Ad hoc IR code
#define IR_UP 1
#define IR_DOWN 7
#define IR_RIGHT 5
#define IR_LEFT 3
#define IR_CENTER 4
#define IR_CIRL 0
#define IR_CIRR 2
#define IR_BALF 6
#define IR_BALB 8
#define ADHOC_IR_MAX 9
#define MAXSINTERVAL 15
#define MINSINTERVAL 5
unsigned int ADHOC_CUSTOMER[ADHOC_IR_MAX] = {0xFFFF,0xFFFF,0XFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF}; //1,2,3,4,5,6,7,8,9
unsigned int ADHOC_IR[ADHOC_IR_MAX] = {0xFFFF,0xFFFF,0XFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF}; // 1,2,3,4,5,6,7,8,9
int adhoc_ir_num=-1;
void selectMode();
void sendSerial();
void resetPara();
void resetVar();
void getGyro();
void readGyro();
void calibGyro();
void calibAcc();
void calcTarget();
void drive();
void motor();
void resetMotor();
boolean laid();
boolean upright();
boolean standing();
void drvMotorL(int pwm);
void drvMotorR(int pwm);
void checkVoltage();
void monitorVoltage();
double getBattVolt();
void blinkLED(int n);
void setColor(int r, int g, int b);
void readEEPROMbal();
void writeEEPROMbal();
void readEEPROMadhoc();
void writeEEPROMadhoc();
void demo8();
void getIR();
void regIR();
void printIrData();
void decodeNECAEHA();
void decodeSONY();
void irInt();
void irCommand();
void printIrData(String s);
void soundIntSD();
void soundInt();
void soundStartSD(File s, int gain);
void soundStart(const byte* ptr, unsigned long sz, int gain);
void servoStart(double ang, double stp);
void servoContinue(double ang, double stp);
void servoDrive();
void pendulum();
void servoHead();
void randomPlay();
void openFiles();
int button=0;
volatile unsigned long irMicroOn;
volatile unsigned long irMicroOff;
volatile unsigned int irDataOn[200];
volatile unsigned int irDataOff[200];
volatile int irOnIndex=0;
volatile int irOffIndex=0;
volatile boolean irStarted=false;
volatile boolean irDecoding=false;
volatile unsigned long lastIrTime=0;
boolean irReady=false;
byte irData[30];
unsigned int ircode;
unsigned int customer_code;
int MotorConfig = 0; // 0 to 3
int accX, accY, accZ, temp, gyroX, gyroY, gyroZ;
int counter=0;
volatile int counterSec=0;
volatile int counterSec0=0;
unsigned long time1=0;
unsigned long time0=0;
double power, powerR, powerL;
double snsGyroY, snsAccX;
double varAng, varOmg, varSpd, varDst, varIang, varIdst;
double gyroOffsetY, gyroOffsetZ, accOffsetX;
double gyroDataY, gyroDataZ, accDataX, accDataY;
double gyroLSB=1.0/131.0; // deg/sec
double accLSB=1.0/16384.0; // g
double pendClk = 0.01; // in sec,
unsigned long pendInterval = 10000; // in usec
double cutoff = 0.1; // 2 * PI * f (f=Hz) //0.1
double Kang, Komg, Kdst, Kspd, Kspin, KIang, KIdst;
double spinPower;
double moveTarget, moveRate=0.0; //moveRate 0:stop, +:forward, -:backward
double moveStep = 0.0013;
double spinDestination, spinTarget;
double spinStep = 0.0;
double spinAngle;
boolean spinContinuous=false;
int pendPhase=-1;
int ipowerR = 0;
int ipowerL = 0;
int motorRdir=0; //stop 1:+ -1:-
int motorLdir=0; //stop
int backlashSpd;
double mechFactorR, mechFactorL;
double battFactor=1.3; // 2016.07.14
double bVolt;
double maxSpd=250.0;
int counterOverSpd;
int maxOverSpd=15;
double aveAccX=0.0;
double aveAccY=0.0;
boolean debug=false;
boolean serialMonitor=false;
double aveVolt=4.5;
boolean usbPower=false;
int8_t drvHLbalance=0;
int demoPhase=0;
int demoDelayCounter=0;
int demoMode=0;
int servoPhase=1;
boolean servoComplete=false;
int servoPulseWidth=1500;
double servoAngDestination=90.0;
double servoAngTarget=90.0;
double servoAngStep=1.0;
int servoWidth=1500; //in usec
File voiceFile[11];
File musicFile[10];
File sdfile;
File fGreet, fStop, fRight, fLeft, fForward, fBack, fSpin, fAccel, fTipover, fDemo, fDebug, fBattery, fReplace;
volatile boolean soundBusy=false;
volatile unsigned long soundIndex=0;
volatile const byte *soundPtr;
volatile unsigned long soundSize;
volatile int soundGain=10; //10=100%
boolean soundSD;
boolean soundFlg=false;
int soundInterval=MAXSINTERVAL;
volatile boolean soundStop=false;
int soundId;
boolean musicPlaying=false;
boolean soundOn=true;
boolean randomSoundOn=true;
int soundPhase=1;
int maxVoiceFile=0;
int minVoiceFile=-1;
int maxMusicFile=0;
int minMusicFile=-1;
const char *soundVoice[] = {"vmu_168m.wav", "v1_168m.wav", "v2_168m.wav", "v3_168m.wav", "v4_168m.wav", "v5_168m.wav", "v6_168m.wav", "v7_168m.wav", "v8_168m.wav", "v9_168m.wav", "v10_168m.wav"};
const char *soundMusic[] = {"mu1_168m.wav", "mu2_168m.wav", "mu3_168m.wav", "mu4_168m.wav", "mu5_168m.wav", "mu6_168m.wav", "mu7_168m.wav", "mu8_168m.wav", "mu9_168m.wav", "mu10_168m.wav"};
const double headLeft=150.0;
const double headRight=30.0;
const byte soundGreet[] = {
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x75,0x74,0x71,0x6e,
0x6f,0x73,0x7b,0x81,0x8b,0x8e,0x8e,0x8c,0x8a,0x86,0x80,0x7e,0x80,0x7f,0x81,0x80,
0x80,0x7f,0x7e,0x80,0x78,0x77,0x76,0x7c,0x7f,0x84,0x8d,0x8f,0x95,0x92,0x8e,0x86,
0x80,0x7d,0x79,0x79,0x7c,0x7f,0x80,0x80,0x7d,0x79,0x7a,0x7a,0x7d,0x7f,0x84,0x87,
0x88,0x88,0x87,0x85,0x85,0x81,0x72,0x67,0x60,0x61,0x68,0x76,0x85,0x90,0x98,0x96,
0x8c,0x81,0x7d,0x7e,0x80,0x86,0x89,0x8b,0x8a,0x88,0x81,0x76,0x78,0x77,0x7c,0x82,
0x8a,0x91,0x92,0x8d,0x80,0x73,0x6a,0x69,0x6a,0x71,0x7b,0x84,0x85,0x84,0x80,0x7a,
0x75,0x73,0x74,0x73,0x77,0x7b,0x7f,0x81,0x87,0x8d,0x90,0x91,0x8f,0x8a,0x82,0x7c,
0x77,0x71,0x70,0x74,0x79,0x81,0x8d,0x9a,0xa1,0xa2,0x9c,0x93,0x85,0x78,0x70,0x6a,
0x69,0x6a,0x6d,0x6d,0x6f,0x72,0x72,0x71,0x75,0x7d,0x85,0x8e,0x96,0x97,0x93,0x8c,
0x84,0x78,0x72,0x73,0x76,0x7b,0x7f,0x80,0x80,0x80,0x7f,0x7e,0x76,0x71,0x6d,0x70,
0x78,0x81,0x8d,0x94,0x98,0x94,0x8e,0x84,0x7f,0x7e,0x7f,0x81,0x84,0x88,0x89,0x87,
0x83,0x7b,0x72,0x6c,0x6a,0x6b,0x6e,0x78,0x7f,0x86,0x8b,0x8e,0x8f,0x8e,0x8b,0x87,
0x83,0x7d,0x77,0x70,0x68,0x62,0x60,0x63,0x6a,0x78,0x89,0x96,0xa1,0xa3,0xa1,0x98,
0x91,0x8a,0x86,0x82,0x86,0x7e,0x7d,0x76,0x57,0x52,0x50,0x60,0x78,0xa2,0xbe,0xc9,
0xc8,0xac,0x83,0x60,0x57,0x57,0x66,0x7c,0x90,0x92,0x8b,0x7d,0x67,0x56,0x57,0x5f,
0x6d,0x81,0x95,0x9b,0x94,0x89,0x7b,0x70,0x6f,0x78,0x80,0x88,0x88,0x82,0x72,0x68,
0x64,0x69,0x73,0x83,0x90,0x95,0x98,0x91,0x8e,0x8b,0x93,0x9d,0x9f,0xa1,0x95,0x82,
0x6a,0x5c,0x5c,0x67,0x87,0x92,0x97,0x94,0x7d,0x65,0x53,0x5e,0x75,0x9b,0xbc,0xbc,
0xa9,0x92,0x75,0x5a,0x4d,0x50,0x5d,0x6d,0x7c,0x81,0x7d,0x7a,0x74,0x6b,0x66,0x6c,
0x78,0x83,0x8a,0x8c,0x89,0x80,0x7b,0x76,0x76,0x7a,0x83,0x8a,0x8c,0x8d,0x8d,0x8c,
0x88,0x8d,0x91,0x9a,0xa3,0xad,0xad,0xa6,0xa3,0xa2,0xa4,0xa4,0x8b,0x66,0x50,0x3c,
0x33,0x33,0x3f,0x53,0x6d,0x8c,0x9a,0x9e,0xa4,0xa8,0x9f,0x91,0x87,0x7a,0x72,0x6d,
0x64,0x58,0x52,0x54,0x58,0x5c,0x66,0x74,0x82,0x8a,0x90,0x90,0x8c,0x89,0x87,0x84,
0x83,0x86,0x8a,0x88,0x87,0x89,0x8b,0x8b,0x8e,0x90,0x94,0x9b,0xa2,0xaa,0xa8,0xb0,
0xa8,0xac,0x8f,0x66,0x57,0x3d,0x39,0x45,0x5b,0x69,0x84,0x94,0x8e,0x86,0x81,0x82,
0x7d,0x84,0x8e,0x91,0x92,0x91,0x81,0x6b,0x5b,0x54,0x50,0x54,0x62,0x74,0x7d,0x83,
0x81,0x7c,0x75,0x77,0x7a,0x7d,0x87,0x91,0x93,0x8b,0x84,0x7c,0x77,0x78,0x7c,0x86,
0x8e,0x97,0x9b,0x96,0x99,0x97,0x9e,0xa3,0xb0,0xb6,0xb5,0xb0,0x7e,0x5f,0x55,0x40,
0x38,0x4b,0x5d,0x6a,0x80,0x89,0x80,0x81,0x8c,0x8a,0x87,0x94,0x9f,0x96,0x8d,0x81,
0x6a,0x5c,0x5b,0x5b,0x5d,0x67,0x73,0x75,0x72,0x73,0x77,0x7a,0x82,0x8a,0x8e,0x90,
0x8f,0x87,0x7c,0x76,0x77,0x7a,0x7c,0x7e,0x80,0x7d,0x79,0x74,0x76,0x7c,0x8a,0x97,
0xa2,0xab,0xb5,0xbb,0xbd,0xc1,0xc2,0xc1,0xa0,0x72,0x45,0x2d,0x26,0x2a,0x3d,0x50,
0x70,0x88,0x8f,0x80,0x7f,0x8e,0x9a,0xa7,0xa9,0xa8,0xa2,0x97,0x7f,0x5b,0x46,0x45,
0x4d,0x54,0x5f,0x6b,0x72,0x78,0x79,0x77,0x7b,0x89,0x95,0x97,0x96,0x90,0x88,0x7d,
0x75,0x71,0x74,0x7b,0x82,0x83,0x82,0x80,0x83,0x85,0x8e,0x9b,0xab,0xbb,0xc6,0xd0,
0xd0,0xcb,0x9c,0x78,0x5a,0x32,0x25,0x30,0x40,0x59,0x6c,0x6e,0x70,0x70,0x80,0x89,
0x96,0xb0,0xbf,0xbb,0xa5,0x8a,0x6f,0x5b,0x56,0x57,0x5f,0x68,0x71,0x69,0x58,0x56,
0x5b,0x6b,0x7d,0x93,0x9f,0xa2,0x9c,0x8d,0x7c,0x75,0x7a,0x80,0x84,0x85,0x82,0x77,
0x6c,0x65,0x67,0x72,0x87,0x99,0xa6,0xaf,0xb5,0xb7,0xbd,0xc6,0xd1,0xde,0xb9,0x84,
0x5c,0x35,0x18,0x17,0x2a,0x45,0x6c,0x76,0x74,0x6e,0x7b,0x8f,0x97,0xab,0xbc,0xc5,
0xb9,0x9b,0x76,0x5b,0x53,0x53,0x55,0x58,0x63,0x69,0x63,0x54,0x56,0x67,0x7e,0x93,
0x9f,0xa3,0xa0,0x9b,0x88,0x77,0x74,0x7d,0x7f,0x7e,0x7a,0x74,0x70,0x6e,0x6f,0x78,
0x88,0x9d,0xac,0xb2,0xb9,0xbc,0xc4,0xcf,0xe5,0xb4,0x7f,0x77,0x3b,0x19,0x27,0x37,
0x4c,0x61,0x78,0x63,0x62,0x7b,0x7a,0x85,0xad,0xc8,0xb7,0xb4,0xa5,0x89,0x6d,0x57,
0x54,0x57,0x69,0x65,0x59,0x4f,0x4d,0x5f,0x68,0x75,0x8e,0xa8,0xa8,0x9a,0x8d,0x7d,
0x7d,0x81,0x80,0x7c,0x85,0x88,0x7d,0x6a,0x6b,0x72,0x7b,0x89,0x9b,0xab,0xb1,0xb0,
0xa5,0xb1,0xb4,0xc8,0xc6,0xb2,0x83,0x4e,0x35,0x1b,0x31,0x4f,0x63,0x68,0x6f,0x69,
0x5d,0x71,0x85,0x96,0xb0,0xbe,0xb9,0xa6,0x97,0x7f,0x6a,0x5b,0x53,0x54,0x5f,0x67,
0x5e,0x5a,0x55,0x5a,0x6b,0x7f,0x92,0xa3,0xab,0x9e,0x8e,0x82,0x7b,0x7b,0x7f,0x84,
0x80,0x81,0x7b,0x72,0x6f,0x78,0x85,0x94,0xa3,0xad,0xb4,0xbc,0xc2,0xc6,0xd0,0xae,
0x96,0x74,0x49,0x3b,0x38,0x3d,0x44,0x56,0x4e,0x4a,0x52,0x60,0x77,0x92,0xaf,0xb6,
0xba,0xb2,0xa0,0x90,0x85,0x7f,0x76,0x6f,0x62,0x58,0x4d,0x48,0x49,0x53,0x65,0x78,
0x88,0x91,0x95,0x95,0x94,0x8f,0x90,0x90,0x8f,0x8a,0x83,0x78,0x70,0x6c,0x6c,0x70,
0x7b,0x87,0x91,0x9b,0xa1,0xa8,0xaf,0xbd,0xc7,0xda,0xc4,0xa9,0x8d,0x5d,0x4c,0x42,
0x43,0x49,0x57,0x58,0x4c,0x4f,0x54,0x64,0x7c,0x96,0xa7,0xaf,0xb2,0xa4,0x97,0x8b,
0x85,0x7f,0x7a,0x70,0x63,0x58,0x4d,0x4a,0x4e,0x5b,0x6b,0x79,0x82,0x87,0x8b,0x8e,
0x8f,0x91,0x93,0x94,0x90,0x8c,0x85,0x7f,0x7f,0x7e,0x80,0x84,0x8a,0x8f,0x97,0x9f,
0xaa,0xb4,0xc5,0xc7,0xac,0x9a,0x79,0x60,0x58,0x55,0x57,0x5c,0x61,0x54,0x4b,0x4e,
0x57,0x6b,0x83,0x95,0x9e,0xa2,0x9e,0x94,0x8c,0x8a,0x8b,0x8b,0x83,0x77,0x68,0x5a,
0x51,0x51,0x59,0x65,0x74,0x7a,0x79,0x79,0x7c,0x80,0x88,0x92,0x97,0x96,0x92,0x88,
0x7f,0x7d,0x80,0x84,0x89,0x8d,0x8e,0x8e,0x91,0x95,0xa3,0xb2,0xc3,0xca,0xb0,0x9d,
0x7e,0x63,0x5c,0x5b,0x60,0x62,0x67,0x55,0x47,0x47,0x4d,0x62,0x7c,0x91,0x99,0x9e,
0x98,0x8d,0x8a,0x8c,0x90,0x92,0x8e,0x7e,0x6f,0x60,0x56,0x54,0x5c,0x68,0x71,0x77,
0x73,0x72,0x73,0x78,0x80,0x8b,0x93,0x96,0x94,0x8d,0x86,0x85,0x87,0x8a,0x8e,0x90,
0x90,0x91,0x93,0x95,0xa2,0xa9,0xb9,0xb9,0xa1,0x95,0x78,0x68,0x65,0x66,0x67,0x6a,
0x6b,0x57,0x4c,0x4c,0x52,0x65,0x7c,0x8a,0x8e,0x93,0x8d,0x86,0x88,0x8c,0x90,0x94,
0x8e,0x80,0x73,0x67,0x5f,0x5f,0x65,0x6b,0x72,0x70,0x6c,0x6c,0x6e,0x74,0x7f,0x8a,
0x90,0x93,0x90,0x8a,0x88,0x8a,0x8e,0x93,0x96,0x97,0x95,0x95,0x94,0x9b,0xa3,0xaf,
0xb1,0xa3,0x97,0x80,0x70,0x6a,0x66,0x69,0x6c,0x6c,0x60,0x55,0x52,0x54,0x61,0x72,
0x7e,0x86,0x8b,0x88,0x83,0x85,0x89,0x8e,0x93,0x91,0x87,0x7d,0x72,0x69,0x67,0x6c,
0x70,0x74,0x73,0x6f,0x6c,0x6c,0x70,0x77,0x82,0x88,0x8c,0x8b,0x88,0x85,0x87,0x8b,
0x8f,0x93,0x96,0x96,0x93,0x93,0x96,0x9c,0xa4,0xaf,0xa9,0x9d,0x93,0x7e,0x74,0x70,
0x6e,0x6f,0x71,0x6c,0x5d,0x58,0x56,0x59,0x65,0x72,0x79,0x7e,0x82,0x7e,0x7e,0x83,
0x88,0x8e,0x91,0x8f,0x87,0x80,0x77,0x73,0x73,0x75,0x77,0x77,0x72,0x6e,0x6c,0x6c,
0x70,0x77,0x7e,0x82,0x86,0x86,0x84,0x86,0x89,0x8b,0x90,0x93,0x95,0x94,0x95,0x94,
0x97,0x99,0xa1,0xa1,0x98,0x95,0x86,0x7e,0x7a,0x78,0x74,0x75,0x73,0x67,0x62,0x5f,
0x5f,0x64,0x6c,0x71,0x73,0x79,0x77,0x79,0x7b,0x80,0x84,0x88,0x89,0x86,0x86,0x80,
0x7f,0x7d,0x7e,0x7e,0x7f,0x7c,0x78,0x76,0x74,0x75,0x77,0x7a,0x7c,0x7e,0x7f,0x7e,
0x7f,0x83,0x85,0x8a,0x8d,0x8f,0x8f,0x91,0x8f,0x92,0x95,0x9a,0x9c,0x97,0x94,0x8b,
0x85,0x82,0x7f,0x7d,0x7c,0x7a,0x72,0x6c,0x68,0x66,0x69,0x6d,0x71,0x72,0x75,0x74,
0x74,0x76,0x79,0x7e,0x82,0x85,0x84,0x84,0x81,0x81,0x80,0x81,0x83,0x83,0x82,0x7f,
0x7e,0x7b,0x7b,0x7d,0x7d,0x7d,0x7e,0x7d,0x7d,0x7e,0x80,0x82,0x85,0x86,0x88,0x89,
0x8b,0x8b,0x8d,0x8e,0x90,0x91,0x90,0x8d,0x89,0x87,0x84,0x83,0x81,0x7f,0x7d,0x79,
0x75,0x72,0x71,0x71,0x72,0x73,0x73,0x74,0x73,0x74,0x75,0x77,0x7a,0x7d,0x7f,0x80,
0x80,0x80,0x81,0x81,0x83,0x83,0x83,0x82,0x7f,0x7d,0x7c,0x7c,0x7e,0x7e,0x80,0x7f,
0x7f,0x7d,0x7e,0x80,0x80,0x84,0x86,0x85,0x87,0x87,0x87,0x8a,0x8a,0x8d,0x8c,0x8b,
0x8a,0x85,0x85,0x83,0x83,0x83,0x82,0x80,0x7d,0x7a,0x77,0x76,0x76,0x76,0x76,0x76,
0x76,0x75,0x76,0x75,0x76,0x79,0x7b,0x7d,0x7f,0x80,0x80,0x81,0x81,0x81,0x82,0x82,
0x81,0x80,0x80,0x7f,0x7d,0x7f,0x7d,0x7e,0x7e,0x7d,0x7e,0x7f,0x80,0x81,0x81,0x82,
0x82,0x83,0x83,0x85,0x86,0x87,0x89,0x87,0x88,0x87,0x85,0x84,0x84,0x83,0x83,0x83,
0x82,0x80,0x7f,0x7d,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,0x78,0x78,0x77,0x78,0x79,0x7b,
0x7c,0x7e,0x7e,0x7f,0x7e,0x7f,0x7e,0x80,0x7f,0x82,0x81,0x80,0x80,0x7e,0x7d,0x7d,
0x7e,0x7e,0x80,0x7e,0x7f,0x7d,0x80,0x80,0x81,0x84,0x83,0x83,0x85,0x84,0x85,0x88,
0x87,0x88,0x86,0x85,0x83,0x81,0x82,0x81,0x81,0x81,0x80,0x7f,0x7e,0x7d,0x7d,0x7c,
0x7c,0x7c,0x7b,0x79,0x78,0x78,0x78,0x79,0x7a,0x7c,0x7c,0x7c,0x7b,0x7c,0x7c,0x7e,
0x82,0x82,0x83,0x82,0x80,0x7f,0x7f,0x7e,0x80,0x7f,0x7f,0x7f,0x7d,0x7e,0x7f,0x80,
0x82,0x84,0x83,0x84,0x84,0x83,0x85,0x85,0x88,0x88,0x87,0x87,0x84,0x83,0x81,0x81,
0x80,0x80,0x80,0x7f,0x7e,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7d,0x7c,0x7b,0x7a,0x7b,
0x7b,0x7c,0x7c,0x7c,0x7b,0x7a,0x7b,0x7c,0x7e,0x80,0x81,0x81,0x81,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x7f,0x81,0x7f,0x7e,0x80,0x7e,0x81,0x81,0x82,0x83,0x83,0x84,0x82,
0x85,0x84,0x84,0x86,0x85,0x84,0x83,0x82,0x81,0x80,0x81,0x80,0x7f,0x7f,0x7d,0x7d,
0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7d,0x7c,0x7d,0x7b,0x7c,
0x7c,0x7c,0x7e,0x7c,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x80,0x7e,0x82,0x80,
0x81,0x80,0x80,0x81,0x80,0x83,0x81,0x84,0x83,0x83,0x82,0x84,0x82,0x83,0x83,0x82,
0x83,0x81,0x82,0x80,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7e,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7d,0x7d,0x7c,0x7e,0x7d,0x7f,0x80,
0x80,0x80,0x7f,0x81,0x7f,0x80,0x80,0x81,0x7e,0x81,0x81,0x80,0x80,0x81,0x81,0x81,
0x83,0x83,0x81,0x83,0x84,0x81,0x83,0x82,0x82,0x81,0x82,0x80,0x80,0x80,0x7f,0x80,
0x7f,0x7f,0x7f,0x7f,0x7e,0x7f,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7e,0x80,0x7c,0x7f,
0x7e,0x7e,0x7f,0x7e,0x7f,0x7d,0x80,0x7d,0x7f,0x7e,0x80,0x7e,0x81,0x7f,0x80,0x80,
0x7e,0x81,0x7d,0x82,0x7e,0x82,0x81,0x81,0x81,0x80,0x81,0x7f,0x82,0x81,0x81,0x81,
0x81,0x81,0x80,0x80,0x81,0x80,0x7f,0x80,0x81,0x7f,0x7f,0x7f,0x7e,0x7d,0x7f,0x7d,
0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7e,0x81,0x7d,0x81,0x7e,0x7e,0x81,0x7e,
0x80,0x7f,0x7e,0x7f,0x7d,0x80,0x80,0x7e,0x81,0x81,0x7e,0x80,0x81,0x7f,0x80,0x81,
0x80,0x81,0x80,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,0x81,0x80,0x81,0x80,0x81,0x7f,
0x80,0x80,0x7f,0x7f,0x80,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x80,0x7c,0x81,
0x7e,0x7f,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x7e,0x81,0x7d,0x7f,0x7e,
0x80,0x7f,0x80,0x83,0x7e,0x81,0x82,0x7d,0x80,0x82,0x7f,0x81,0x83,0x80,0x7f,0x82,
0x7e,0x7f,0x80,0x80,0x7f,0x7f,0x81,0x80,0x7f,0x81,0x80,0x80,0x7f,0x81,0x7e,0x7f,
0x7f,0x7e,0x7f,0x7e,0x80,0x7f,0x80,0x7d,0x80,0x7e,0x7f,0x81,0x80,0x7f,0x82,0x7f,
0x80,0x81,0x7e,0x81,0x7f,0x81,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x82,0x7e,0x81,
0x7e,0x82,0x7e,0x81,0x82,0x7f,0x80,0x81,0x81,0x7c,0x84,0x7d,0x7f,0x80,0x7d,0x81,
0x7f,0x7f,0x81,0x7e,0x80,0x81,0x80,0x80,0x7f,0x81,0x7f,0x7e,0x82,0x7e,0x7e,0x81,
0x7c,0x80,0x7e,0x7e,0x82,0x7e,0x82,0x7f,0x7f,0x82,0x7c,0x83,0x7f,0x7f,0x84,0x7b,
0x83,0x7f,0x7d,0x84,0x79,0x82,0x7d,0x7e,0x84,0x7d,0x81,0x82,0x7f,0x7d,0x84,0x7d,
0x81,0x80,0x81,0x7e,0x7f,0x7f,0x7d,0x80,0x7d,0x80,0x7e,0x7f,0x7e,0x81,0x7f,0x80,
0x7e,0x82,0x7d,0x80,0x7f,0x7f,0x80,0x7e,0x81,0x7d,0x81,0x7c,0x81,0x7e,0x7f,0x80,
0x7e,0x81,0x7f,0x80,0x80,0x81,0x81,0x80,0x7f,0x83,0x7c,0x81,0x7f,0x7f,0x80,0x7c,
0x85,0x79,0x83,0x7f,0x7f,0x83,0x7b,0x83,0x7f,0x81,0x7f,0x81,0x80,0x7e,0x81,0x7d,
0x7d,0x80,0x7b,0x82,0x7c,0x7f,0x82,0x7a,0x85,0x7d,0x7e,0x86,0x79,0x80,0x83,0x7b,
0x83,0x7f,0x82,0x7d,0x7c,0x84,0x7a,0x7f,0x82,0x7d,0x82,0x7c,0x84,0x7c,0x7f,0x86,
0x7c,0x82,0x81,0x81,0x7d,0x83,0x7e,0x7f,0x80,0x7e,0x82,0x7d,0x82,0x7d,0x7f,0x80,
0x7d,0x83,0x7e,0x80,0x82,0x7d,0x7e,0x82,0x7c,0x81,0x7d,0x80,0x80,0x78,0x83,0x7d,
0x7c,0x7f,0x83,0x7b,0x82,0x82,0x7d,0x82,0x7d,0x83,0x7e,0x81,0x81,0x80,0x7d,0x80,
0x7f,0x7e,0x7f,0x82,0x7e,0x7f,0x83,0x7a,0x85,0x7b,0x85,0x81,0x80,0x82,0x7f,0x81,
0x7c,0x83,0x7e,0x80,0x7e,0x82,0x7c,0x7f,0x81,0x7f,0x80,0x81,0x7f,0x80,0x7f,0x80,
0x7e,0x80,0x80,0x7f,0x83,0x7a,0x82,0x7e,0x7a,0x81,0x7c,0x80,0x80,0x7e,0x83,0x7d,
0x80,0x81,0x7d,0x83,0x80,0x80,0x82,0x7d,0x83,0x7c,0x83,0x7e,0x7f,0x82,0x78,0x86,
0x79,0x84,0x80,0x7f,0x83,0x7f,0x81,0x7e,0x80,0x82,0x7c,0x82,0x82,0x7d,0x7f,0x7e,
0x83,0x79,0x84,0x80,0x7d,0x7f,0x83,0x7d,0x7f,0x83,0x7e,0x81,0x7d,0x83,0x7c,0x80,
0x81,0x7b,0x83,0x7b,0x7f,0x80,0x7c,0x83,0x7d,0x85,0x7b,0x84,0x7f,0x7d,0x84,0x7e,
0x83,0x80,0x82,0x7c,0x80,0x80,0x7e,0x82,0x83,0x7a,0x85,0x7d,0x7b,0x88,0x7a,0x84,
0x81,0x7b,0x86,0x7b,0x80,0x82,0x7d,0x83,0x7d,0x7f,0x82,0x7c,0x82,0x7e,0x80,0x7e,
0x7f,0x82,0x7c,0x83,0x7f,0x7e,0x80,0x81,0x7a,0x85,0x7a,0x7f,0x82,0x78,0x83,0x7c,
0x81,0x83,0x7c,0x80,0x84,0x7a,0x82,0x85,0x7d,0x82,0x84,0x7e,0x7f,0x81,0x83,0x7b,
0x83,0x80,0x7e,0x7d,0x80,0x82,0x7d,0x82,0x7d,0x7e,0x81,0x7e,0x82,0x82,0x7d,0x81,
0x7e,0x81,0x7a,0x83,0x7e,0x80,0x80,0x7d,0x83,0x7a,0x80,0x85,0x77,0x83,0x81,0x79,
0x82,0x7e,0x7f,0x7f,0x82,0x7b,0x83,0x7a,0x85,0x7a,0x82,0x81,0x79,0x88,0x78,0x84,
0x81,0x7d,0x81,0x7f,0x7e,0x83,0x7d,0x83,0x80,0x7d,0x83,0x7c,0x7f,0x83,0x79,0x83,
0x7d,0x7f,0x82,0x7a,0x85,0x7a,0x81,0x81,0x7b,0x87,0x7c,0x7e,0x85,0x79,0x84,0x7b,
0x81,0x7e,0x7c,0x85,0x7b,0x81,0x80,0x7e,0x7e,0x82,0x7f,0x7e,0x80,0x81,0x7e,0x7f,
0x83,0x7d,0x7e,0x80,0x7d,0x7e,0x80,0x7e,0x82,0x7e,0x7f,0x82,0x7e,0x80,0x81,0x80,
0x80,0x82,0x7d,0x82,0x7f,0x81,0x7f,0x81,0x7e,0x7e,0x82,0x7d,0x80,0x80,0x7c,0x81,
0x7f,0x7e,0x83,0x7c,0x83,0x7e,0x7e,0x81,0x7e,0x7d,0x81,0x7c,0x81,0x7f,0x7d,0x83,
0x7b,0x7e,0x83,0x7b,0x7f,0x83,0x7c,0x86,0x7d,0x7f,0x83,0x7c,0x83,0x7f,0x80,0x82,
0x7d,0x81,0x7f,0x7d,0x82,0x7f,0x7d,0x82,0x7c,0x81,0x81,0x80,0x81,0x7f,0x82,0x80,
0x7f,0x80,0x81,0x7c,0x83,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x82,0x7d,0x83,0x80,0x7e,
0x82,0x81,0x7b,0x84,0x7e,0x7d,0x82,0x7d,0x7e,0x82,0x7d,0x7e,0x81,0x7d,0x80,0x7f,
0x80,0x7f,0x82,0x7f,0x81,0x7f,0x80,0x82,0x7c,0x81,0x80,0x7e,0x81,0x81,0x7e,0x81,
0x81,0x7d,0x82,0x80,0x7e,0x81,0x80,0x81,0x7f,0x80,0x80,0x81,0x7d,0x80,0x7f,0x7e,
0x81,0x7d,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,0x80,0x80,0x80,0x80,0x82,0x7d,0x82,
0x7f,0x7f,0x81,0x7f,0x81,0x7d,0x81,0x7f,0x7e,0x81,0x80,0x7f,0x82,0x7f,0x80,0x80,
0x81,0x81,0x80,0x81,0x7f,0x7f,0x80,0x7e,0x7f,0x80,0x7d,0x80,0x7c,0x80,0x7f,0x80,
0x81,0x7f,0x80,0x7f,0x7e,0x80,0x81,0x7e,0x81,0x7f,0x7d,0x7f,0x7e,0x80,0x7f,0x7f,
0x80,0x7d,0x82,0x7f,0x80,0x83,0x80,0x80,0x81,0x81,0x80,0x80,0x81,0x81,0x80,0x80,
0x81,0x81,0x7f,0x82,0x80,0x7f,0x81,0x7f,0x7f,0x7f,0x80,0x7f,0x7e,0x80,0x7d,0x7f,
0x7c,0x7f,0x7e,0x7d,0x80,0x7d,0x7e,0x7f,0x7f,0x7f,0x7e,0x7f,0x80,0x7c,0x81,0x7f,
0x7d,0x7e,0x7f,0x7d,0x80,0x80,0x7f,0x81,0x80,0x82,0x81,0x82,0x83,0x82,0x81,0x84,
0x81,0x81,0x83,0x82,0x80,0x81,0x81,0x80,0x81,0x81,0x81,0x7e,0x7f,0x7f,0x7e,0x7f,
0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7d,0x7c,0x7c,0x7c,0x7a,0x7c,0x7a,0x7b,0x7c,
0x7b,0x7d,0x7c,0x7e,0x7e,0x7d,0x7f,0x7e,0x7f,0x80,0x80,0x81,0x80,0x81,0x82,0x80,
0x82,0x83,0x83,0x84,0x84,0x85,0x85,0x85,0x85,0x86,0x86,0x85,0x86,0x84,0x84,0x83,
0x83,0x83,0x82,0x81,0x80,0x7f,0x7d,0x7d,0x7d,0x7b,0x7b,0x79,0x77,0x77,0x76,0x75,
0x75,0x76,0x74,0x75,0x76,0x76,0x78,0x79,0x7a,0x7c,0x7d,0x7f,0x80,0x81,0x83,0x83,
0x84,0x85,0x86,0x86,0x87,0x86,0x88,0x86,0x88,0x87,0x85,0x87,0x86,0x86,0x88,0x88,
0x88,0x89,0x88,0x89,0x87,0x87,0x85,0x82,0x82,0x7e,0x7c,0x7b,0x78,0x76,0x74,0x72,
0x71,0x70,0x70,0x70,0x70,0x71,0x72,0x73,0x74,0x76,0x78,0x7a,0x7c,0x7e,0x7f,0x80,
0x81,0x82,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x89,0x89,0x89,0x87,0x89,0x88,0x89,
0x8a,0x89,0x8b,0x89,0x8b,0x8d,0x8c,0x8e,0x8a,0x86,0x84,0x7f,0x7e,0x7d,0x7c,0x7a,
0x79,0x73,0x70,0x6d,0x6c,0x6c,0x6f,0x6f,0x70,0x71,0x70,0x6f,0x71,0x74,0x78,0x7c,
0x7f,0x81,0x82,0x82,0x82,0x83,0x85,0x87,0x89,0x89,0x88,0x86,0x84,0x83,0x84,0x85,
0x86,0x88,0x87,0x87,0x88,0x86,0x89,0x8a,0x8d,0x90,0x92,0x94,0x8e,0x8b,0x86,0x82,
0x82,0x81,0x80,0x7e,0x7d,0x76,0x70,0x6e,0x6b,0x6c,0x6f,0x70,0x70,0x71,0x70,0x6e,
0x6f,0x72,0x75,0x79,0x7d,0x7f,0x7f,0x80,0x81,0x80,0x83,0x86,0x88,0x88,0x88,0x86,
0x83,0x83,0x81,0x82,0x83,0x84,0x84,0x84,0x83,0x84,0x84,0x88,0x8a,0x8c,0x90,0x91,
0x93,0x95,0x92,0x8d,0x8d,0x86,0x84,0x84,0x7f,0x7e,0x7c,0x77,0x6f,0x6e,0x6b,0x6a,
0x6c,0x6e,0x6d,0x6f,0x70,0x6f,0x70,0x74,0x76,0x79,0x7d,0x7d,0x7e,0x7f,0x80,0x80,
0x83,0x84,0x84,0x85,0x84,0x83,0x82,0x82,0x81,0x81,0x82,0x82,0x82,0x82,0x81,0x83,
0x84,0x87,0x89,0x8b,0x8d,0x90,0x91,0x94,0x99,0x95,0x92,0x91,0x89,0x85,0x84,0x7f,
0x7c,0x7d,0x77,0x70,0x6e,0x69,0x66,0x68,0x6a,0x69,0x6d,0x70,0x6f,0x70,0x73,0x73,
0x77,0x7c,0x7e,0x81,0x83,0x84,0x82,0x83,0x84,0x84,0x86,0x86,0x86,0x84,0x83,0x80,
0x7f,0x7e,0x7f,0x80,0x80,0x81,0x81,0x83,0x84,0x86,0x89,0x8c,0x8e,0x94,0x95,0x99,
0x9b,0x94,0x93,0x8c,0x88,0x85,0x83,0x7e,0x7e,0x7b,0x72,0x6d,0x69,0x66,0x66,0x68,
0x68,0x6a,0x6d,0x6d,0x6d,0x70,0x73,0x76,0x7b,0x7f,0x80,0x83,0x84,0x84,0x84,0x85,
0x85,0x86,0x87,0x85,0x84,0x82,0x80,0x7e,0x7e,0x7d,0x7e,0x7e,0x7f,0x7f,0x81,0x82,
0x84,0x88,0x8a,0x8e,0x91,0x94,0x96,0x9d,0x9a,0x96,0x94,0x8d,0x88,0x87,0x83,0x7e,
0x7f,0x79,0x70,0x6c,0x68,0x63,0x65,0x68,0x66,0x69,0x6d,0x6b,0x6c,0x71,0x73,0x77,
0x7d,0x7f,0x81,0x84,0x86,0x84,0x86,0x87,0x87,0x88,0x87,0x85,0x84,0x82,0x80,0x7e,
0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x80,0x81,0x85,0x86,0x8a,0x8f,0x91,0x95,0x98,0x9e,
0x9c,0x98,0x96,0x8e,0x8a,0x88,0x84,0x7e,0x7f,0x79,0x70,0x6d,0x67,0x63,0x64,0x67,
0x64,0x68,0x6c,0x6b,0x6d,0x71,0x73,0x78,0x7d,0x80,0x82,0x85,0x86,0x86,0x87,0x87,
0x88,0x88,0x86,0x85,0x83,0x81,0x7f,0x7e,0x7c,0x7c,0x7c,0x7b,0x7c,0x7d,0x7f,0x81,
0x84,0x87,0x8a,0x8f,0x91,0x95,0x97,0x9e,0xa0,0x99,0x9a,0x91,0x8b,0x89,0x86,0x7e,
0x80,0x7d,0x71,0x6e,0x69,0x63,0x62,0x67,0x64,0x66,0x6c,0x6b,0x6b,0x6f,0x72,0x75,
0x7c,0x80,0x82,0x85,0x87,0x86,0x86,0x88,0x88,0x89,0x88,0x87,0x84,0x81,0x7f,0x7c,
0x7a,0x7a,0x7b,0x7a,0x7a,0x7b,0x7c,0x7d,0x81,0x83,0x88,0x8c,0x91,0x93,0x96,0x99,
0x9f,0xa2,0x9a,0x9c,0x93,0x8d,0x8a,0x85,0x7f,0x7f,0x7d,0x70,0x6c,0x67,0x61,0x60,
0x64,0x62,0x64,0x6b,0x6a,0x6a,0x6e,0x72,0x75,0x7c,0x81,0x82,0x87,0x87,0x87,0x86,
0x88,0x88,0x89,0x89,0x87,0x85,0x81,0x7f,0x7b,0x7a,0x79,0x7a,0x79,0x78,0x79,0x7a,
0x7b,0x7e,0x81,0x85,0x8b,0x8f,0x91,0x95,0x9a,0x9d,0xa3,0x9e,0x9c,0x98,0x8f,0x8c,
0x87,0x82,0x7e,0x7e,0x73,0x6c,0x67,0x61,0x5f,0x61,0x63,0x62,0x68,0x6a,0x68,0x6c,
0x70,0x74,0x79,0x81,0x83,0x85,0x89,0x88,0x87,0x88,0x8a,0x8a,0x8a,0x89,0x86,0x83,
0x80,0x7d,0x7a,0x7a,0x7a,0x7a,0x78,0x79,0x78,0x7a,0x7b,0x7f,0x83,0x87,0x8c,0x90,
0x91,0x95,0x9a,0x9e,0xa3,0x9e,0x9d,0x97,0x8f,0x8c,0x85,0x80,0x7f,0x7c,0x72,0x6c,
0x66,0x60,0x60,0x61,0x60,0x63,0x68,0x69,0x69,0x6d,0x70,0x75,0x7b,0x81,0x83,0x87,
0x8a,0x89,0x88,0x8a,0x8a,0x8a,0x8a,0x89,0x86,0x82,0x7f,0x7b,0x79,0x78,0x79,0x78,
0x78,0x78,0x79,0x7a,0x7c,0x80,0x84,0x89,0x8f,0x91,0x93,0x9a,0x9b,0xa2,0xa5,0x9d,
0x9e,0x96,0x8e,0x89,0x85,0x7e,0x7d,0x7a,0x6d,0x69,0x63,0x5e,0x5d,0x60,0x60,0x63,
0x69,0x69,0x6a,0x6e,0x73,0x77,0x7e,0x84,0x87,0x8b,0x8c,0x8b,0x8a,0x8b,0x8b,0x8b,
0x8a,0x88,0x85,0x81,0x7d,0x79,0x77,0x77,0x77,0x76,0x76,0x77,0x77,0x79,0x7b,0x7f,
0x84,0x89,0x8e,0x91,0x95,0x98,0x9c,0xa0,0xa6,0x9f,0x9f,0x99,0x8e,0x8b,0x85,0x7f,
0x7c,0x7b,0x6f,0x69,0x64,0x5d,0x5c,0x5e,0x60,0x62,0x69,0x6a,0x6b,0x6f,0x73,0x77,
0x7d,0x85,0x87,0x8b,0x8d,0x8b,0x8a,0x8b,0x8b,0x8a,0x8b,0x89,0x85,0x81,0x7d,0x79,
0x76,0x76,0x76,0x76,0x76,0x76,0x77,0x78,0x7b,0x7e,0x84,0x89,0x8e,0x92,0x95,0x98,
0x9c,0xa1,0xa6,0xa0,0x9f,0x99,0x8e,0x8b,0x85,0x7d,0x7c,0x7b,0x6f,0x69,0x64,0x5c,
0x5c,0x60,0x60,0x62,0x6a,0x6b,0x6b,0x70,0x73,0x77,0x7f,0x86,0x88,0x8b,0x8e,0x8c,
0x89,0x8b,0x8b,0x8a,0x8b,0x89,0x84,0x81,0x7d,0x78,0x75,0x76,0x75,0x75,0x75,0x75,
0x75,0x76,0x78,0x7b,0x81,0x87,0x8c,0x90,0x93,0x95,0x98,0x9b,0xa1,0xa6,0xa0,0x9f,
0x98,0x8d,0x87,0x83,0x7c,0x79,0x7b,0x6f,0x68,0x65,0x5e,0x5b,0x60,0x61,0x63,0x6b,
0x6e,0x6d,0x71,0x76,0x79,0x7e,0x86,0x88,0x8b,0x8d,0x8c,0x89,0x8a,0x8a,0x88,0x88,
0x87,0x83,0x7f,0x7c,0x77,0x74,0x74,0x75,0x74,0x75,0x76,0x76,0x77,0x7a,0x7e,0x83,
0x89,0x8d,0x90,0x94,0x97,0x9a,0x9d,0xa4,0xa3,0x9c,0x9b,0x92,0x89,0x86,0x81,0x7a,
0x7b,0x77,0x6a,0x66,0x63,0x5d,0x5e,0x63,0x63,0x67,0x6e,0x6e,0x6e,0x73,0x79,0x7c,
0x83,0x89,0x8a,0x8c,0x8e,0x8a,0x87,0x89,0x8a,0x87,0x87,0x85,0x80,0x7c,0x79,0x74,
0x73,0x74,0x74,0x74,0x75,0x75,0x75,0x77,0x7b,0x7e,0x84,0x8a,0x8e,0x90,0x93,0x95,
0x98,0x9b,0xa2,0xa3,0x9e,0x9b,0x93,0x8a,0x84,0x82,0x7d,0x7b,0x7a,0x70,0x68,0x64,
0x60,0x5f,0x63,0x67,0x69,0x6e,0x70,0x70,0x71,0x77,0x7c,0x81,0x88,0x8b,0x8c,0x8b,
0x8a,0x87,0x86,0x88,0x88,0x87,0x86,0x82,0x7d,0x79,0x76,0x74,0x75,0x76,0x76,0x76,
0x75,0x75,0x75,0x78,0x7c,0x82,0x87,0x8b,0x8e,0x90,0x91,0x94,0x98,0x9b,0xa2,0xa1,
0x9b,0x97,0x90,0x88,0x83,0x83,0x7e,0x7d,0x7a,0x70,0x69,0x66,0x64,0x63,0x68,0x6a,
0x6d,0x70,0x70,0x70,0x72,0x78,0x7d,0x82,0x87,0x89,0x89,0x88,0x87,0x85,0x86,0x88,
0x88,0x87,0x85,0x81,0x7d,0x7a,0x77,0x77,0x77,0x78,0x77,0x76,0x75,0x75,0x76,0x78,
0x7b,0x80,0x84,0x87,0x89,0x8b,0x8d,0x90,0x93,0x97,0x9b,0x9d,0x99,0x94,0x8f,0x8a,
0x86,0x84,0x83,0x81,0x7e,0x78,0x71,0x6d,0x6b,0x6a,0x6c,0x6e,0x70,0x72,0x73,0x72,
0x72,0x75,0x79,0x7d,0x80,0x83,0x84,0x84,0x84,0x83,0x84,0x85,0x86,0x87,0x86,0x85,
0x83,0x80,0x7d,0x7b,0x7b,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x79,0x7a,0x7c,0x7f,0x82,
0x84,0x86,0x87,0x88,0x8a,0x8c,0x8f,0x92,0x91,0x8f,0x8c,0x89,0x87,0x85,0x83,0x83,
0x83,0x80,0x7c,0x78,0x77,0x76,0x75,0x75,0x76,0x77,0x78,0x78,0x77,0x78,0x79,0x7a,
0x7c,0x7e,0x7f,0x80,0x81,0x80,0x80,0x80,0x81,0x82,0x82,0x81,0x81,0x80,0x7f,0x7e,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7d,0x7e,0x7f,0x80,0x80,
0x81,0x82,0x83,0x85,0x87,0x88,0x89,0x88,0x87,0x87,0x87,0x87,0x87,0x87,0x87,0x85,
0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7c,0x7b,0x7a,0x7a,0x7a,0x7a,0x7a,
0x7a,0x7b,0x7b,0x7b,0x7b,0x7b,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,
0x7d,0x7d,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7d,0x7e,0x7e,0x7f,0x80,0x81,0x83,
0x84,0x86,0x88,0x88,0x88,0x87,0x88,0x88,0x88,0x88,0x88,0x87,0x85,0x84,0x82,0x81,
0x80,0x7f,0x7f,0x7e,0x7e,0x7c,0x7b,0x7a,0x7a,0x7a,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7c,0x7d,0x7e,0x7e,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,
0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7c,0x7d,0x7d,0x7e,0x7f,0x80,0x82,0x83,0x85,0x87,
0x88,0x89,0x89,0x89,0x89,0x89,0x89,0x89,0x88,0x87,0x86,0x84,0x83,0x82,0x81,0x80,
0x7f,0x7e,0x7d,0x7c,0x7b,0x7a,0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,
0x7d,0x7e,0x7e,0x7e,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,
0x7b,0x7b,0x7b,0x7c,0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x83,0x85,0x87,0x88,0x89,0x89,
0x89,0x89,0x89,0x89,0x89,0x88,0x87,0x85,0x84,0x83,0x82,0x80,0x7f,0x7e,0x7e,0x7d,
0x7c,0x7c,0x7b,0x7b,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,
0x7b,0x7c,0x7d,0x7e,0x7e,0x7f,0x80,0x81,0x82,0x84,0x86,0x88,0x89,0x89,0x89,0x89,
0x89,0x89,0x89,0x88,0x88,0x86,0x85,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7f,0x7e,0x7c,
0x7c,0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7b,
0x7c,0x7d,0x7e,0x7e,0x7f,0x80,0x81,0x82,0x84,0x86,0x88,0x89,0x88,0x88,0x88,0x88,
0x88,0x88,0x87,0x86,0x85,0x84,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7c,0x7b,
0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7c,0x7b,0x7b,0x7b,0x7a,0x7a,0x7b,0x7b,0x7c,
0x7c,0x7d,0x7e,0x7f,0x80,0x81,0x82,0x84,0x86,0x88,0x88,0x88,0x88,0x88,0x88,0x89,
0x88,0x88,0x87,0x85,0x84,0x83,0x82,0x80,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x7b,
0x7b,0x7c,0x7c,0x7c,0x7d,0x7d,0x7c,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7f,0x7e,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x7a,0x7a,0x7a,0x7b,0x7c,
0x7c,0x7d,0x7e,0x7f,0x80,0x82,0x84,0x86,0x88,0x89,0x89,0x89,0x89,0x89,0x89,0x89,
0x89,0x88,0x86,0x85,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x7b,0x7b,
0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7f,0x7f,0x80,0x7f,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7b,0x7a,0x7a,0x79,0x79,0x79,0x7a,0x7b,0x7b,0x7c,
0x7d,0x7e,0x7f,0x80,0x82,0x84,0x86,0x88,0x89,0x89,0x89,0x89,0x89,0x89,0x8a,0x89,
0x89,0x87,0x86,0x84,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,
0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x79,0x79,0x79,0x7a,0x7a,0x7b,0x7c,
0x7d,0x7e,0x7f,0x81,0x82,0x84,0x86,0x88,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,
0x89,0x87,0x86,0x85,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,
0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x78,0x79,0x79,0x7a,0x7b,0x7b,
0x7c,0x7d,0x7f,0x80,0x82,0x84,0x86,0x88,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,0x89,
0x89,0x87,0x86,0x84,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7b,0x7b,
0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x7e,0x7e,0x7e,
0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x79,0x78,0x78,0x79,0x79,0x7a,0x7b,
0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x84,0x86,0x88,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,
0x89,0x89,0x87,0x86,0x84,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x7b,
0x7b,0x7b,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x7f,0x7e,0x7e,
0x7e,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x79,0x78,0x78,0x78,0x79,0x7a,0x7a,
0x7b,0x7d,0x7e,0x7f,0x80,0x81,0x83,0x85,0x87,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,
0x8a,0x8a,0x89,0x87,0x86,0x84,0x83,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7b,
0x7b,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7e,
0x7e,0x7e,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x7a,
0x7b,0x7c,0x7d,0x7e,0x7f,0x80,0x82,0x84,0x85,0x87,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,
0x8a,0x8a,0x89,0x88,0x87,0x85,0x84,0x83,0x82,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7c,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,0x79,0x79,0x79,0x79,0x7a,
0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x80,0x82,0x83,0x85,0x87,0x89,0x8a,0x8a,0x8a,0x8a,
0x8a,0x8a,0x8a,0x8a,0x89,0x88,0x86,0x85,0x84,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7a,0x7a,0x7a,0x79,0x79,0x79,0x79,0x79,
0x79,0x7a,0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x81,0x83,0x84,0x86,0x88,0x8a,0x8b,0x8b,
0x8b,0x8b,0x8a,0x8a,0x8a,0x89,0x88,0x87,0x85,0x84,0x82,0x81,0x7f,0x7e,0x7e,0x7d,
0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,0x78,
0x78,0x78,0x78,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x80,0x81,0x83,0x85,0x87,0x89,0x8a,
0x8b,0x8b,0x8b,0x8b,0x8b,0x8b,0x8a,0x89,0x88,0x86,0x85,0x84,0x82,0x81,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7c,0x7c,0x7b,0x7a,0x7a,0x79,0x78,0x78,
0x78,0x78,0x78,0x78,0x79,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x84,0x86,
0x88,0x89,0x8b,0x8b,0x8b,0x8b,0x8b,0x8b,0x8a,0x89,0x89,0x87,0x86,0x85,0x84,0x82,
0x81,0x80,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7a,0x7a,
0x79,0x79,0x78,0x78,0x78,0x78,0x78,0x79,0x79,0x7a,0x7b,0x7b,0x7d,0x7e,0x7f,0x81,
0x82,0x84,0x86,0x88,0x8a,0x8b,0x8c,0x8b,0x8c,0x8b,0x8b,0x8b,0x8a,0x89,0x88,0x87,
0x85,0x84,0x82,0x81,0x7f,0x7f,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,
0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,
0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,0x78,0x78,0x78,0x78,0x79,0x7a,0x7a,0x7b,0x7d,
0x7e,0x7f,0x81,0x83,0x84,0x86,0x88,0x8a,0x8b,0x8c,0x8c,0x8c,0x8c,0x8b,0x8b,0x8a,
0x89,0x87,0x86,0x85,0x84,0x82,0x81,0x80,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,
0x7d,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,0x77,0x77,0x78,0x78,0x78,0x79,
0x7a,0x7b,0x7c,0x7e,0x7f,0x80,0x82,0x84,0x85,0x87,0x89,0x8b,0x8c,0x8c,0x8c,0x8c,
0x8b,0x8b,0x8a,0x89,0x88,0x87,0x86,0x84,0x83,0x82,0x80,0x7f,0x7e,0x7e,0x7d,0x7c,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x78,0x77,0x77,0x77,
0x78,0x78,0x79,0x79,0x7a,0x7b,0x7c,0x7e,0x7f,0x81,0x82,0x84,0x86,0x87,0x89,0x8b,
0x8c,0x8c,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x86,0x85,0x84,0x83,0x81,0x80,0x7f,
0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x79,0x79,0x78,0x77,
0x77,0x77,0x77,0x77,0x77,0x78,0x78,0x79,0x7a,0x7b,0x7d,0x7e,0x7f,0x81,0x83,0x84,
0x86,0x88,0x89,0x8b,0x8c,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x87,0x86,0x84,
0x84,0x82,0x81,0x80,0x7f,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7d,0x7c,0x7d,0x7d,0x7d,
0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,
0x79,0x79,0x78,0x78,0x77,0x77,0x77,0x78,0x78,0x78,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,
0x80,0x81,0x83,0x85,0x86,0x88,0x8a,0x8c,0x8c,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,
0x88,0x86,0x85,0x84,0x83,0x82,0x81,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,
0x7d,0x7c,0x7b,0x7a,0x7a,0x79,0x78,0x77,0x77,0x77,0x77,0x77,0x77,0x78,0x79,0x79,
0x7a,0x7b,0x7d,0x7e,0x7f,0x81,0x83,0x84,0x86,0x88,0x8a,0x8b,0x8d,0x8d,0x8d,0x8d,
0x8c,0x8c,0x8b,0x8a,0x89,0x87,0x86,0x85,0x84,0x82,0x81,0x80,0x7f,0x7e,0x7d,0x7c,
0x7c,0x7c,0x7b,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x77,0x77,0x76,0x76,0x76,
0x77,0x77,0x78,0x79,0x79,0x7b,0x7c,0x7d,0x7f,0x80,0x82,0x83,0x85,0x87,0x89,0x8b,
0x8c,0x8d,0x8e,0x8d,0x8d,0x8c,0x8b,0x8a,0x89,0x88,0x86,0x85,0x84,0x83,0x81,0x80,
0x7f,0x7e,0x7d,0x7d,0x7c,0x7a,0x78,0x78,0x7a,0x7d,0x80,0x81,0x7f,0x7d,0x7a,0x7a,
0x7b,0x7f,0x83,0x85,0x84,0x80,0x7c,0x79,0x79,0x7a,0x7c,0x7d,0x7d,0x7a,0x76,0x72,
0x71,0x72,0x75,0x78,0x79,0x78,0x77,0x76,0x76,0x78,0x7d,0x81,0x84,0x84,0x83,0x83,
0x86,0x8a,0x8f,0x92,0x90,0x8b,0x8b,0x8f,0x92,0x90,0x8b,0x85,0x84,0x85,0x86,0x83,
0x7f,0x7a,0x7b,0x7d,0x7c,0x78,0x77,0x78,0x7b,0x7c,0x7a,0x79,0x7b,0x7e,0x80,0x80,
0x7e,0x7f,0x82,0x84,0x82,0x80,0x81,0x83,0x82,0x80,0x7e,0x7d,0x7f,0x7e,0x7b,0x78,
0x78,0x78,0x78,0x75,0x72,0x74,0x77,0x76,0x74,0x74,0x76,0x79,0x7a,0x79,0x7a,0x7d,
0x80,0x81,0x81,0x83,0x86,0x89,0x89,0x8a,0x8c,0x92,0x91,0x8a,0x8c,0x93,0x94,0x8a,
0x86,0x88,0x8b,0x88,0x81,0x7d,0x7f,0x80,0x7e,0x7c,0x76,0x77,0x7b,0x7c,0x77,0x77,
0x7b,0x7c,0x7c,0x7d,0x7e,0x7f,0x80,0x80,0x82,0x83,0x81,0x81,0x82,0x82,0x82,0x81,
0x7e,0x7e,0x7f,0x7e,0x7a,0x78,0x79,0x79,0x77,0x75,0x74,0x75,0x75,0x74,0x75,0x75,
0x76,0x78,0x79,0x7a,0x7b,0x7d,0x7f,0x81,0x82,0x85,0x86,0x87,0x88,0x8c,0x8d,0x8f,
0x91,0x8c,0x8f,0x94,0x93,0x89,0x8a,0x8c,0x8b,0x86,0x82,0x81,0x81,0x80,0x7c,0x7e,
0x7a,0x78,0x7a,0x7b,0x78,0x79,0x7b,0x79,0x7d,0x7f,0x7e,0x7d,0x81,0x82,0x82,0x82,
0x82,0x82,0x83,0x82,0x81,0x82,0x7f,0x7f,0x7e,0x7d,0x7b,0x79,0x79,0x78,0x77,0x76,
0x74,0x73,0x74,0x75,0x74,0x74,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7e,0x7f,0x81,0x83,
0x84,0x84,0x88,0x89,0x8c,0x8c,0x91,0x8f,0x8a,0x92,0x94,0x8e,0x88,0x8e,0x8a,0x88,
0x86,0x83,0x82,0x80,0x7f,0x7d,0x7e,0x78,0x7a,0x7a,0x7a,0x79,0x7a,0x79,0x7a,0x7e,
0x7d,0x7c,0x7f,0x81,0x80,0x81,0x82,0x82,0x81,0x82,0x82,0x81,0x80,0x7f,0x7e,0x7e,
0x7c,0x7a,0x79,0x78,0x77,0x75,0x75,0x73,0x73,0x74,0x73,0x73,0x74,0x75,0x76,0x77,
0x78,0x79,0x7b,0x7d,0x7e,0x81,0x82,0x84,0x85,0x88,0x88,0x8c,0x8c,0x91,0x8e,0x8a,
0x93,0x93,0x8e,0x89,0x8f,0x89,0x89,0x86,0x83,0x82,0x81,0x7f,0x7d,0x7f,0x78,0x7a,
0x7a,0x7a,0x79,0x7b,0x79,0x7b,0x7e,0x7d,0x7d,0x80,0x81,0x80,0x82,0x82,0x82,0x82,
0x83,0x82,0x81,0x81,0x7f,0x7e,0x7d,0x7c,0x79,0x79,0x78,0x76,0x75,0x74,0x74,0x73,
0x74,0x73,0x73,0x74,0x75,0x75,0x77,0x78,0x79,0x7a,0x7d,0x7e,0x80,0x82,0x82,0x85,
0x86,0x89,0x88,0x8c,0x8c,0x91,0x8d,0x8c,0x93,0x92,0x8c,0x8a,0x8f,0x88,0x88,0x86,
0x84,0x82,0x81,0x7e,0x7e,0x7e,0x79,0x7a,0x7b,0x7b,0x79,0x7b,0x7b,0x7d,0x7e,0x7e,
0x7e,0x81,0x81,0x80,0x83,0x83,0x81,0x82,0x83,0x82,0x80,0x80,0x7e,0x7e,0x7d,0x7b,
0x79,0x79,0x77,0x75,0x75,0x74,0x73,0x72,0x73,0x73,0x73,0x73,0x74,0x76,0x77,0x77,
0x7a,0x7b,0x7d,0x7e,0x81,0x82,0x84,0x85,0x87,0x89,0x89,0x8d,0x8d,0x92,0x8a,0x8f,
0x93,0x90,0x8b,0x8d,0x8d,0x87,0x89,0x84,0x84,0x81,0x81,0x7d,0x80,0x7c,0x7a,0x7c,
0x7c,0x7b,0x7a,0x7c,0x7c,0x7f,0x7e,0x7f,0x7f,0x82,0x81,0x82,0x83,0x82,0x82,0x82,
0x83,0x81,0x80,0x7f,0x7e,0x7d,0x7c,0x7a,0x79,0x78,0x77,0x76,0x75,0x74,0x73,0x73,
0x73,0x73,0x74,0x74,0x75,0x76,0x77,0x78,0x7a,0x7c,0x7d,0x7f,0x80,0x82,0x83,0x86,
0x85,0x88,0x89,0x8d,0x8b,0x8f,0x8f,0x8a,0x90,0x91,0x8e,0x88,0x8f,0x89,0x88,0x87,
0x84,0x83,0x82,0x81,0x7f,0x80,0x7b,0x7d,0x7d,0x7d,0x7b,0x7d,0x7d,0x7d,0x7f,0x7f,
0x7f,0x80,0x81,0x81,0x82,0x82,0x81,0x81,0x82,0x81,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,
0x79,0x78,0x78,0x76,0x75,0x75,0x74,0x73,0x73,0x73,0x73,0x74,0x74,0x75,0x76,0x77,
0x78,0x7a,0x7c,0x7d,0x7e,0x80,0x82,0x84,0x85,0x86,0x87,0x8a,0x8c,0x8b,0x90,0x8a,
0x8e,0x92,0x8f,0x8a,0x8d,0x8c,0x87,0x89,0x85,0x84,0x81,0x82,0x7f,0x80,0x7d,0x7c,
0x7d,0x7d,0x7c,0x7b,0x7d,0x7c,0x7e,0x7f,0x7f,0x7e,0x80,0x80,0x81,0x81,0x81,0x80,
0x81,0x81,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x79,0x78,0x78,0x77,0x75,0x74,0x74,0x73,
0x73,0x73,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7e,0x7f,0x81,0x82,
0x85,0x84,0x87,0x88,0x8a,0x8a,0x8d,0x8f,0x88,0x90,0x92,0x8d,0x89,0x8e,0x8a,0x88,
0x88,0x84,0x84,0x82,0x82,0x80,0x82,0x7c,0x7d,0x7f,0x7d,0x7b,0x7d,0x7e,0x7d,0x7f,
0x7f,0x7f,0x80,0x81,0x80,0x81,0x81,0x80,0x80,0x82,0x81,0x7f,0x7f,0x7e,0x7d,0x7c,
0x7b,0x79,0x79,0x77,0x76,0x76,0x75,0x73,0x73,0x74,0x73,0x73,0x74,0x75,0x75,0x77,
0x77,0x78,0x7a,0x7c,0x7d,0x7f,0x80,0x82,0x83,0x85,0x85,0x87,0x89,0x8b,0x8a,0x8e,
0x8e,0x8a,0x92,0x90,0x8c,0x8b,0x8f,0x88,0x8a,0x88,0x85,0x84,0x83,0x82,0x81,0x81,
0x7b,0x7f,0x7e,0x7d,0x7b,0x7e,0x7d,0x7d,0x7f,0x7f,0x7f,0x80,0x81,0x80,0x82,0x81,
0x80,0x81,0x82,0x7f,0x7f,0x7f,0x7e,0x7c,0x7c,0x7a,0x79,0x79,0x77,0x76,0x75,0x74,
0x73,0x74,0x73,0x72,0x73,0x74,0x75,0x75,0x77,0x77,0x79,0x7a,0x7c,0x7d,0x7f,0x80,
0x82,0x83,0x84,0x85,0x88,0x88,0x8a,0x8b,0x8c,0x8f,0x8a,0x90,0x90,0x8d,0x8a,0x8e,
0x89,0x88,0x8a,0x86,0x85,0x83,0x83,0x81,0x82,0x7d,0x7e,0x7f,0x7e,0x7c,0x7e,0x7e,
0x7d,0x7f,0x7f,0x7f,0x7f,0x81,0x80,0x81,0x81,0x80,0x80,0x81,0x80,0x7f,0x7e,0x7e,
0x7c,0x7c,0x7a,0x79,0x78,0x77,0x76,0x75,0x74,0x73,0x73,0x73,0x73,0x73,0x74,0x74,
0x75,0x76,0x77,0x78,0x7a,0x7b,0x7d,0x7e,0x80,0x81,0x83,0x84,0x85,0x86,0x89,0x88,
0x8b,0x8b,0x8e,0x8c,0x8c,0x91,0x8e,0x8c,0x8b,0x8e,0x88,0x8a,0x86,0x86,0x83,0x83,
0x82,0x81,0x80,0x7d,0x80,0x7e,0x7e,0x7c,0x7f,0x7d,0x7e,0x7f,0x7f,0x7f,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x7e,0x7e,0x7d,0x7d,0x7b,0x7a,0x79,0x78,0x77,0x76,
0x75,0x74,0x73,0x73,0x73,0x73,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,
0x7d,0x7f,0x80,0x82,0x83,0x84,0x86,0x87,0x89,0x89,0x8b,0x8b,0x8f,0x8a,0x8e,0x91,
0x8d,0x8b,0x8d,0x8b,0x88,0x8b,0x86,0x86,0x83,0x84,0x81,0x82,0x7e,0x7e,0x80,0x7e,
0x7d,0x7d,0x7f,0x7d,0x7f,0x7f,0x7f,0x7e,0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x7f,
0x7e,0x7e,0x7d,0x7c,0x7b,0x7a,0x78,0x78,0x77,0x76,0x75,0x74,0x73,0x73,0x73,0x72,
0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x7a,0x7b,0x7d,0x7e,0x7f,0x80,0x82,0x83,0x85,
0x86,0x88,0x88,0x8a,0x8b,0x8c,0x8e,0x8a,0x8f,0x90,0x8d,0x8b,0x8d,0x8a,0x89,0x89,
0x86,0x86,0x84,0x83,0x83,0x82,0x7e,0x7f,0x80,0x7e,0x7d,0x7f,0x7f,0x7e,0x7f,0x80,
0x7e,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7e,0x7e,0x7e,0x7d,0x7b,0x7b,0x7a,
0x78,0x78,0x77,0x76,0x75,0x74,0x74,0x73,0x73,0x73,0x73,0x74,0x74,0x75,0x76,0x77,
0x78,0x79,0x7b,0x7c,0x7d,0x7e,0x80,0x81,0x83,0x83,0x85,0x86,0x87,0x88,0x8a,0x8a,
0x8d,0x8e,0x8a,0x90,0x90,0x8d,0x8c,0x8e,0x8b,0x89,0x8a,0x87,0x86,0x84,0x84,0x82,
0x83,0x7e,0x7f,0x80,0x7f,0x7d,0x7e,0x7e,0x7d,0x7f,0x7f,0x7e,0x7e,0x80,0x7f,0x80,
0x7f,0x7f,0x7f,0x80,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x78,0x78,0x77,0x76,0x75,
0x75,0x74,0x74,0x73,0x73,0x73,0x74,0x75,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7e,
0x7f,0x80,0x81,0x83,0x84,0x85,0x87,0x88,0x89,0x8a,0x8b,0x8d,0x8c,0x8c,0x90,0x8e,
0x8c,0x8c,0x8d,0x89,0x8a,0x89,0x87,0x85,0x85,0x83,0x82,0x81,0x7f,0x80,0x7f,0x7f,
0x7d,0x7f,0x7e,0x7e,0x7f,0x7f,0x7e,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,
0x7d,0x7d,0x7c,0x7b,0x7b,0x79,0x78,0x78,0x77,0x75,0x75,0x74,0x74,0x73,0x74,0x73,
0x73,0x74,0x75,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x83,
0x84,0x86,0x87,0x88,0x88,0x8a,0x8b,0x8e,0x89,0x8e,0x90,0x8d,0x8c,0x8d,0x8c,0x89,
0x8b,0x87,0x87,0x85,0x85,0x82,0x83,0x80,0x7f,0x81,0x7f,0x7d,0x7e,0x7f,0x7c,0x7f,
0x7f,0x7e,0x7d,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7f,0x7e,0x7d,0x7d,0x7c,0x7b,0x7b,
0x7a,0x78,0x78,0x77,0x76,0x75,0x75,0x74,0x74,0x74,0x73,0x73,0x73,0x74,0x75,0x75,
0x76,0x77,0x79,0x7a,0x7b,0x7c,0x7d,0x7f,0x81,0x82,0x83,0x84,0x85,0x86,0x88,0x88,
0x8a,0x8a,0x8d,0x8b,0x8b,0x8f,0x8e,0x8c,0x8b,0x8d,0x89,0x8a,0x89,0x87,0x85,0x85,
0x84,0x83,0x82,0x7f,0x80,0x80,0x7f,0x7e,0x7f,0x7e,0x7e,0x7f,0x7f,0x7e,0x7f,0x80,
0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7d,0x7d,0x7d,0x7b,0x7b,0x7a,0x79,0x78,0x78,
0x76,0x75,0x75,0x74,0x74,0x73,0x73,0x73,0x74,0x74,0x74,0x75,0x76,0x77,0x79,0x79,
0x7b,0x7c,0x7e,0x7f,0x80,0x81,0x83,0x84,0x86,0x86,0x88,0x89,0x89,0x8b,0x8c,0x8e,
0x8b,0x90,0x8f,0x8e,0x8c,0x8e,0x8c,0x8a,0x8b,0x88,0x87,0x86,0x85,0x83,0x84,0x80,
0x80,0x81,0x7f,0x7e,0x7f,0x7f,0x7d,0x7f,0x7f,0x7e,0x7e,0x80,0x7f,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7c,0x7c,0x7b,0x79,0x79,0x78,0x77,0x76,0x75,0x74,
0x73,0x73,0x73,0x73,0x73,0x73,0x74,0x75,0x75,0x76,0x78,0x79,0x7a,0x7c,0x7d,0x7e,
0x80,0x81,0x82,0x84,0x85,0x86,0x87,0x88,0x89,0x8b,0x8b,0x8c,0x8e,0x8b,0x8f,0x8f,
0x8e,0x8c,0x8d,0x8c,0x8a,0x8a,0x88,0x86,0x85,0x85,0x83,0x83,0x80,0x80,0x80,0x80,
0x7e,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x7e,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x79,0x78,0x78,0x76,0x75,0x74,0x74,0x73,0x73,0x72,
0x72,0x72,0x73,0x73,0x74,0x74,0x76,0x77,0x79,0x7a,0x7b,0x7c,0x7e,0x80,0x81,0x82,
0x83,0x85,0x86,0x87,0x87,0x89,0x8a,0x8b,0x8b,0x8c,0x8b,0x8c,0x8f,0x8d,0x8c,0x8b,
0x8c,0x89,0x8a,0x88,0x87,0x85,0x85,0x84,0x83,0x81,0x80,0x81,0x80,0x7f,0x7e,0x80,
0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7d,0x7d,
0x7c,0x7b,0x7a,0x79,0x78,0x77,0x76,0x75,0x74,0x74,0x73,0x73,0x72,0x72,0x72,0x73,
0x73,0x74,0x74,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7e,0x7f,0x80,0x82,0x83,0x85,0x85,
0x86,0x87,0x89,0x89,0x8a,0x8b,0x8b,0x8c,0x8b,0x8d,0x8e,0x8d,0x8c,0x8c,0x8b,0x8a,
0x8a,0x88,0x86,0x86,0x85,0x84,0x83,0x82,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x80,
0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7d,0x7d,0x7d,0x7b,0x7b,
0x7a,0x78,0x77,0x77,0x76,0x75,0x74,0x73,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,
0x75,0x75,0x77,0x78,0x79,0x7b,0x7c,0x7e,0x7f,0x80,0x81,0x83,0x84,0x85,0x86,0x87,
0x88,0x89,0x8a,0x8a,0x8b,0x8c,0x8c,0x8c,0x8d,0x8d,0x8d,0x8b,0x8c,0x8a,0x8a,0x88,
0x88,0x87,0x86,0x85,0x84,0x84,0x82,0x82,0x81,0x81,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x7b,0x7a,0x79,
0x77,0x77,0x76,0x75,0x74,0x73,0x72,0x72,0x72,0x71,0x72,0x72,0x73,0x73,0x74,0x75,
0x76,0x78,0x79,0x7a,0x7c,0x7d,0x7f,0x80,0x81,0x83,0x84,0x85,0x86,0x87,0x87,0x88,
0x89,0x89,0x8a,0x8b,0x8c,0x8b,0x8c,0x8d,0x8d,0x8c,0x8c,0x8c,0x8a,0x8a,0x89,0x89,
0x87,0x86,0x85,0x85,0x84,0x83,0x83,0x82,0x82,0x81,0x81,0x81,0x81,0x81,0x80,0x80,
0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x79,0x78,0x77,0x76,
0x75,0x75,0x74,0x73,0x72,0x72,0x71,0x72,0x71,0x72,0x72,0x73,0x74,0x75,0x76,0x77,
0x78,0x7a,0x7b,0x7d,0x7e,0x7f,0x80,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,
0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8d,0x8d,0x8c,0x8b,0x8b,0x8b,0x8a,0x8a,0x87,0x88,
0x86,0x86,0x85,0x84,0x83,0x83,0x83,0x82,0x82,0x81,0x81,0x81,0x81,0x80,0x80,0x80,
0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x7a,0x79,0x78,0x77,0x76,0x75,0x75,
0x74,0x73,0x72,0x72,0x71,0x71,0x71,0x72,0x72,0x72,0x73,0x74,0x75,0x76,0x77,0x79,
0x7a,0x7b,0x7d,0x7e,0x7f,0x81,0x82,0x83,0x84,0x85,0x86,0x86,0x87,0x88,0x88,0x89,
0x8a,0x8b,0x8b,0x8b,0x8c,0x8c,0x8d,0x8d,0x8c,0x8b,0x8b,0x8b,0x8a,0x89,0x88,0x87,
0x87,0x86,0x85,0x84,0x83,0x83,0x82,0x82,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x78,0x78,0x77,0x76,0x75,0x75,0x74,
0x73,0x73,0x72,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x7a,
0x7b,0x7d,0x7e,0x7f,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x87,0x88,0x89,0x89,0x8a,
0x8a,0x8b,0x8c,0x8c,0x8d,0x8d,0x8d,0x8c,0x8c,0x8c,0x8b,0x8a,0x8a,0x89,0x88,0x87,
0x86,0x86,0x85,0x84,0x83,0x83,0x82,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7e,0x7e,
0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x78,0x78,0x77,0x76,0x76,0x75,0x74,0x74,
0x73,0x73,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7b,
0x7c,0x7d,0x7f,0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8b,
0x8b,0x8c,0x8c,0x8d,0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8a,0x8a,0x89,0x88,0x87,
0x86,0x85,0x84,0x84,0x83,0x82,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,
0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x78,0x77,0x76,0x75,0x75,0x74,0x73,
0x73,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,0x74,0x75,0x76,0x77,0x79,0x7a,0x7c,
0x7d,0x7e,0x7f,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x89,0x8a,0x8b,
0x8b,0x8c,0x8c,0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x88,0x87,
0x86,0x85,0x84,0x83,0x83,0x82,0x81,0x80,0x80,0x80,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,
0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x78,0x78,0x77,0x76,0x75,0x75,0x74,0x73,0x73,
0x72,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,
0x7d,0x7f,0x80,0x81,0x82,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8e,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x87,0x86,
0x85,0x85,0x84,0x83,0x82,0x82,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,
0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x77,0x76,0x76,0x75,0x74,0x74,0x73,0x73,
0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x73,0x74,0x75,0x76,0x78,0x79,0x7a,0x7c,0x7d,
0x7e,0x80,0x81,0x82,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8a,0x8a,0x89,0x88,0x87,0x86,
0x85,0x84,0x83,0x83,0x82,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,
0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x73,0x73,0x73,
0x72,0x72,0x72,0x72,0x72,0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x7a,0x7b,0x7c,0x7e,
0x7f,0x80,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8d,0x8d,0x8d,0x8d,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x88,0x87,0x86,
0x85,0x84,0x83,0x82,0x81,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,
0x7b,0x7b,0x7a,0x7a,0x79,0x78,0x78,0x77,0x76,0x76,0x75,0x75,0x74,0x73,0x73,0x72,
0x72,0x72,0x72,0x72,0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7d,0x7e,
0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x86,0x85,
0x84,0x83,0x82,0x82,0x81,0x80,0x80,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,
0x7a,0x7a,0x79,0x79,0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x73,0x73,0x72,
0x72,0x72,0x72,0x72,0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7d,0x7e,
0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8b,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x8a,0x89,0x88,0x87,0x86,0x85,0x84,
0x83,0x82,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7b,
0x7a,0x7a,0x79,0x79,0x78,0x78,0x77,0x76,0x76,0x75,0x75,0x74,0x73,0x73,0x73,0x72,
0x72,0x72,0x73,0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7d,0x7e,0x7f,
0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8b,0x8b,0x8c,0x8c,0x8d,
0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x87,0x87,0x86,0x85,0x84,
0x83,0x82,0x81,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,
0x7b,0x7a,0x7a,0x79,0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x73,0x73,0x73,
0x73,0x73,0x74,0x74,0x75,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7d,0x7f,0x80,0x81,
0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x89,0x8a,0x8b,0x8b,0x8c,0x8c,0x8d,0x8d,
0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8a,0x8a,0x89,0x88,0x87,0x86,0x85,0x84,0x83,
0x82,0x81,0x81,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,
0x7a,0x7a,0x79,0x79,0x78,0x77,0x77,0x76,0x76,0x75,0x74,0x74,0x74,0x73,0x73,0x73,
0x73,0x73,0x74,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7b,0x7d,0x7e,0x7f,0x81,0x82,
0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8d,0x8d,
0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x88,0x87,0x86,0x85,0x84,0x83,0x82,0x81,
0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,
0x79,0x79,0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x74,0x73,0x73,0x73,0x73,
0x73,0x74,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x83,
0x84,0x85,0x86,0x87,0x88,0x89,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8c,0x8c,
0x8c,0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x86,0x85,0x84,0x84,0x83,0x82,0x81,0x81,
0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,
0x79,0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x74,0x73,0x73,0x73,0x73,0x74,
0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7b,0x7c,0x7e,0x7f,0x80,0x82,0x83,0x84,0x85,
0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8c,0x8c,0x8c,0x8b,
0x8b,0x8a,0x8a,0x89,0x88,0x87,0x86,0x86,0x85,0x84,0x83,0x82,0x82,0x81,0x80,0x80,
0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,
0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x74,0x74,0x74,0x74,0x74,0x74,0x75,
0x76,0x76,0x77,0x78,0x7a,0x7b,0x7c,0x7d,0x7f,0x80,0x81,0x82,0x83,0x84,0x85,0x86,
0x87,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8c,0x8c,0x8b,0x8b,0x8a,0x8a,
0x89,0x88,0x88,0x87,0x86,0x85,0x84,0x83,0x82,0x82,0x81,0x81,0x80,0x7f,0x7f,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,
0x77,0x77,0x76,0x76,0x75,0x75,0x74,0x74,0x74,0x74,0x74,0x75,0x75,0x76,0x76,0x77,
0x78,0x79,0x7a,0x7b,0x7d,0x7e,0x7f,0x80,0x81,0x83,0x84,0x85,0x86,0x87,0x87,0x88,
0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8c,0x8c,0x8b,0x8b,0x8a,0x8a,0x89,0x88,
0x87,0x86,0x86,0x85,0x84,0x83,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,
0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,0x77,0x77,
0x76,0x76,0x75,0x75,0x74,0x74,0x74,0x74,0x74,0x75,0x75,0x76,0x77,0x77,0x78,0x79,
0x7b,0x7c,0x7d,0x7e,0x7f,0x80,0x81,0x83,0x84,0x85,0x86,0x87,0x87,0x88,0x89,0x8a,
0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8b,0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x86,0x86,
0x85,0x84,0x83,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,
0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x79,0x78,0x78,0x77,0x77,0x76,
0x76,0x75,0x75,0x75,0x75,0x75,0x75,0x76,0x76,0x77,0x78,0x78,0x79,0x7a,0x7c,0x7d,
0x7e,0x7f,0x80,0x81,0x82,0x84,0x85,0x86,0x87,0x87,0x88,0x89,0x8a,0x8a,0x8b,0x8c,
0x8c,0x8c,0x8c,0x8b,0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x86,0x85,0x84,0x84,0x83,
0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,
0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x79,0x78,0x78,0x77,0x77,0x76,0x76,0x76,0x75,
0x75,0x75,0x75,0x76,0x76,0x76,0x77,0x78,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x80,
0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x89,0x8a,0x8b,0x8b,0x8b,0x8b,0x8b,
0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x87,0x86,0x85,0x84,0x83,0x82,0x82,0x81,0x81,
0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,
0x7a,0x7a,0x79,0x79,0x79,0x78,0x78,0x77,0x77,0x76,0x76,0x76,0x76,0x76,0x76,0x76,
0x76,0x76,0x77,0x78,0x78,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x80,0x81,0x82,0x83,0x84,
0x85,0x86,0x87,0x87,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8b,0x8b,0x8b,0x8a,0x8a,0x89,
0x89,0x88,0x87,0x87,0x86,0x85,0x84,0x83,0x83,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,
0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,
0x79,0x78,0x78,0x77,0x77,0x77,0x76,0x76,0x76,0x76,0x76,0x76,0x76,0x77,0x77,0x78,
0x79,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,
0x88,0x88,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,0x89,0x89,0x88,0x88,0x87,0x86,
0x86,0x85,0x84,0x83,0x82,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,
0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,0x79,0x78,0x78,0x78,
0x77,0x77,0x77,0x77,0x76,0x76,0x76,0x77,0x77,0x77,0x78,0x79,0x79,0x7a,0x7b,0x7c,
0x7d,0x7e,0x7f,0x80,0x81,0x82,0x83,0x84,0x84,0x85,0x86,0x87,0x87,0x88,0x89,0x89,
0x89,0x89,0x89,0x89,0x89,0x89,0x88,0x88,0x88,0x87,0x86,0x86,0x85,0x84,0x84,0x83,
0x82,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,
0x7c,0x7b,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,0x79,0x79,0x78,0x78,0x78,0x77,0x77,0x77,
0x77,0x77,0x78,0x78,0x78,0x79,0x79,0x7a,0x7b,0x7c,0x7c,0x7d,0x7e,0x7f,0x80,0x81,
0x82,0x83,0x83,0x84,0x85,0x86,0x86,0x87,0x87,0x88,0x88,0x89,0x89,0x89,0x89,0x89,
0x88,0x88,0x88,0x87,0x87,0x86,0x85,0x85,0x84,0x83,0x83,0x82,0x82,0x81,0x81,0x80,
0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7a,
0x7a,0x7a,0x79,0x79,0x79,0x79,0x78,0x78,0x78,0x78,0x78,0x78,0x78,0x78,0x78,0x79,
0x79,0x7a,0x7a,0x7b,0x7c,0x7d,0x7d,0x7e,0x7f,0x80,0x81,0x82,0x82,0x83,0x84,0x84,
0x85,0x86,0x86,0x87,0x87,0x88,0x88,0x88,0x88,0x88,0x88,0x88,0x88,0x87,0x87,0x86,
0x86,0x85,0x85,0x84,0x84,0x83,0x82,0x82,0x81,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,
0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x7a,0x7a,0x7b,0x7b,0x7c,0x7d,
0x7d,0x7e,0x7f,0x7f,0x80,0x81,0x82,0x82,0x83,0x84,0x84,0x85,0x86,0x86,0x86,0x87,
0x87,0x87,0x87,0x87,0x87,0x87,0x87,0x86,0x86,0x85,0x85,0x85,0x84,0x83,0x83,0x82,
0x82,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,
0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,
0x7a,0x7a,0x7a,0x7b,0x7b,0x7b,0x7c,0x7c,0x7d,0x7d,0x7e,0x7f,0x7f,0x80,0x80,0x81,
0x82,0x82,0x83,0x84,0x84,0x85,0x85,0x86,0x86,0x86,0x86,0x86,0x86,0x86,0x86,0x86,
0x85,0x85,0x85,0x84,0x84,0x83,0x83,0x83,0x82,0x82,0x81,0x81,0x81,0x80,0x80,0x7f,
0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,
0x7b,0x7b,0x7b,0x7b,0x7b,0x7a,0x7a,0x7b,0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,0x7d,
0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x80,0x80,0x81,0x81,0x82,0x82,0x83,0x83,0x84,0x84,
0x85,0x85,0x85,0x85,0x85,0x85,0x85,0x85,0x85,0x85,0x84,0x84,0x84,0x83,0x83,0x83,
0x82,0x82,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,
0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7b,0x7b,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x7f,0x80,0x80,
0x81,0x81,0x82,0x82,0x82,0x83,0x83,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,
0x84,0x84,0x83,0x83,0x83,0x82,0x82,0x82,0x81,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,
0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7f,
0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x81,0x81,0x81,0x82,0x82,0x82,0x83,0x83,0x83,
0x83,0x83,0x83,0x83,0x83,0x83,0x83,0x83,0x83,0x83,0x82,0x82,0x82,0x81,0x81,0x81,
0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,
0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x81,0x81,0x81,0x81,
0x81,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x81,
0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,
0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x81,
0x81,0x81,0x81,0x81,0x81,0x81,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x81,
0x81,0x81,0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,
0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,
0x80,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,
0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x7f,
0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,
0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,
0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x81,0x81,0x81,0x81,0x81,0x82,0x82,0x82,
0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x81,0x81,0x81,0x81,0x81,0x81,
0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,
0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x81,
0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,
0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x81,0x81,0x81,0x81,0x81,
0x81,0x81,0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7e,0x7f,0x7f,0x7f,0x7e,0x7e,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x80,0x81,0x7a,0x7b,0x7a,0x7c,0x7c,0x7d,0x7e,0x7d,0x81,0x7f,0x81,
0x81,0x82,0x83,0x82,0x86,0x84,0x84,0x83,0x81,0x82,0x82,0x82,0x80,0x80,0x80,0x7e,
0x80,0x80,0x7e,0x7e,0x7d,0x7e,0x7c,0x7f,0x7f,0x7e,0x7f,0x7f,0x80,0x80,0x81,0x80,
0x7f,0x82,0x81,0x81,0x81,0x81,0x80,0x80,0x81,0x80,0x80,0x81,0x80,0x7b,0x7c,0x7c,
0x7c,0x7b,0x7b,0x7b,0x7a,0x7f,0x7d,0x7e,0x7f,0x7f,0x80,0x80,0x83,0x81,0x82,0x82,
0x80,0x82,0x82,0x82,0x7f,0x80,0x81,0x7f,0x81,0x80,0x7e,0x7e,0x7f,0x7e,0x7d,0x7f,
0x7e,0x7d,0x7e,0x7e,0x7f,0x7f,0x80,0x7f,0x80,0x82,0x82,0x82,0x84,0x84,0x85,0x86,
0x86,0x86,0x86,0x87,0x86,0x86,0x87,0x87,0x87,0x87,0x86,0x86,0x87,0x87,0x86,0x85,
0x84,0x83,0x82,0x82,0x80,0x7e,0x7d,0x7b,0x79,0x78,0x77,0x75,0x74,0x73,0x74,0x73,
0x73,0x72,0x73,0x74,0x75,0x76,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7c,0x7d,0x7e,0x7f,
0x81,0x81,0x82,0x83,0x84,0x84,0x85,0x86,0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8a,
0x8a,0x8c,0x8d,0x8e,0x8e,0x8f,0x8f,0x8c,0x8b,0x8b,0x8b,0x89,0x85,0x81,0x7f,0x7e,
0x7b,0x77,0x74,0x72,0x71,0x6f,0x6e,0x6e,0x6d,0x6e,0x6e,0x6f,0x71,0x74,0x75,0x76,
0x79,0x7c,0x7f,0x80,0x81,0x83,0x85,0x86,0x86,0x86,0x86,0x85,0x83,0x81,0x81,0x80,
0x7e,0x7b,0x79,0x78,0x78,0x77,0x76,0x76,0x77,0x78,0x7a,0x7c,0x7f,0x82,0x83,0x86,
0x89,0x8e,0x91,0x94,0x94,0x9a,0x9d,0x94,0x98,0x94,0x96,0x92,0x8c,0x87,0x81,0x82,
0x79,0x75,0x71,0x6d,0x6c,0x67,0x65,0x66,0x67,0x67,0x67,0x6a,0x6e,0x71,0x75,0x76,
0x7c,0x81,0x83,0x86,0x87,0x8b,0x8d,0x8d,0x8d,0x8c,0x8c,0x89,0x85,0x83,0x81,0x7f,
0x7a,0x76,0x74,0x73,0x72,0x70,0x70,0x72,0x73,0x77,0x79,0x7d,0x80,0x85,0x8a,0x8e,
0x92,0x98,0x9b,0x9d,0xa1,0x9b,0x9b,0x9b,0x9a,0x96,0x8e,0x89,0x81,0x80,0x78,0x71,
0x6d,0x68,0x65,0x62,0x60,0x60,0x61,0x62,0x63,0x68,0x6d,0x71,0x76,0x79,0x7f,0x85,
0x89,0x8c,0x8f,0x91,0x93,0x94,0x93,0x92,0x90,0x8d,0x89,0x86,0x82,0x7f,0x7b,0x75,
0x72,0x70,0x6e,0x6b,0x69,0x69,0x6a,0x6c,0x6d,0x71,0x75,0x79,0x7d,0x82,0x86,0x8c,
0x90,0x94,0x97,0x9c,0x9d,0xa0,0xa1,0xa5,0xa6,0x97,0x98,0x92,0x93,0x8d,0x82,0x79,
0x72,0x73,0x69,0x65,0x61,0x5e,0x60,0x5e,0x5e,0x63,0x67,0x69,0x6d,0x73,0x7a,0x81,
0x85,0x86,0x8c,0x92,0x93,0x93,0x92,0x93,0x93,0x91,0x8c,0x88,0x85,0x80,0x7a,0x75,
0x72,0x6f,0x6b,0x67,0x67,0x68,0x6b,0x6c,0x6f,0x74,0x7a,0x80,0x85,0x8a,0x90,0x96,
0x9a,0x9e,0xa2,0xa6,0xa7,0xaa,0xa5,0x9b,0x9d,0x99,0x93,0x8a,0x80,0x78,0x73,0x6d,
0x64,0x5f,0x5c,0x59,0x59,0x59,0x5a,0x5f,0x63,0x67,0x6e,0x77,0x7d,0x83,0x87,0x8d,
0x94,0x97,0x97,0x98,0x98,0x98,0x96,0x92,0x8d,0x88,0x83,0x7e,0x7a,0x75,0x70,0x6b,
0x68,0x67,0x67,0x67,0x67,0x69,0x6d,0x71,0x75,0x7a,0x80,0x86,0x8b,0x8f,0x95,0x99,
0x9d,0x9e,0xa0,0xa2,0xa4,0xa4,0xa5,0xa3,0x93,0x94,0x8d,0x89,0x84,0x78,0x70,0x69,
0x67,0x60,0x5d,0x5b,0x58,0x5c,0x5e,0x61,0x67,0x6c,0x71,0x78,0x80,0x86,0x8c,0x8f,
0x91,0x96,0x98,0x98,0x96,0x93,0x90,0x8d,0x89,0x83,0x7f,0x7a,0x72,0x6e,0x6a,0x68,
0x67,0x64,0x63,0x65,0x69,0x6d,0x71,0x76,0x7c,0x83,0x8b,0x8f,0x96,0x9a,0x9f,0xa1,
0xa3,0xa5,0xa7,0xa8,0xa6,0xa6,0x99,0x92,0x90,0x89,0x83,0x77,0x6d,0x66,0x63,0x5e,
0x58,0x57,0x56,0x58,0x5d,0x5f,0x65,0x6c,0x72,0x78,0x81,0x88,0x8e,0x92,0x94,0x97,
0x9b,0x9a,0x97,0x94,0x90,0x8c,0x87,0x81,0x7b,0x76,0x71,0x6c,0x69,0x65,0x63,0x63,
0x63,0x66,0x69,0x6c,0x70,0x76,0x7d,0x84,0x8a,0x8f,0x94,0x99,0x9e,0xa0,0xa2,0xa2,
0xa4,0xa3,0xa3,0xa2,0xa5,0x98,0x8b,0x8a,0x85,0x83,0x77,0x6b,0x63,0x63,0x60,0x5a,
0x59,0x59,0x5b,0x60,0x63,0x68,0x72,0x76,0x7b,0x82,0x8a,0x90,0x94,0x94,0x95,0x98,
0x98,0x94,0x8f,0x8b,0x88,0x83,0x7c,0x77,0x73,0x6e,0x68,0x66,0x65,0x66,0x65,0x64,
0x68,0x6e,0x73,0x76,0x7b,0x81,0x8a,0x8f,0x93,0x97,0x9c,0x9e,0xa1,0xa1,0xa1,0xa1,
0xa1,0xa1,0xa0,0xa0,0x90,0x88,0x87,0x81,0x7d,0x73,0x68,0x63,0x61,0x5e,0x5a,0x5c,
0x5c,0x5f,0x64,0x67,0x70,0x77,0x7b,0x80,0x88,0x8e,0x93,0x94,0x93,0x95,0x97,0x93,
0x8f,0x8a,0x86,0x82,0x7c,0x77,0x72,0x6f,0x6a,0x68,0x67,0x66,0x67,0x68,0x6b,0x6f,
0x73,0x78,0x7c,0x81,0x87,0x8c,0x91,0x94,0x98,0x9a,0x9d,0x9e,0x9e,0x9e,0x9d,0x9d,
0x9e,0x9f,0x9b,0x8a,0x88,0x85,0x81,0x7c,0x6f,0x68,0x64,0x64,0x5e,0x5d,0x5e,0x5f,
0x63,0x66,0x6b,0x74,0x7a,0x7c,0x83,0x8a,0x90,0x93,0x92,0x91,0x94,0x94,0x90,0x8b,
0x87,0x83,0x80,0x7a,0x75,0x72,0x6f,0x6a,0x68,0x68,0x69,0x6a,0x6a,0x6c,0x71,0x77,
0x7b,0x7f,0x83,0x8a,0x8f,0x93,0x96,0x99,0x9b,0x9e,0x9e,0x9e,0x9e,0x9e,0x9e,0xa0,
0xa0,0x90,0x86,0x82,0x84,0x7e,0x75,0x66,0x62,0x63,0x60,0x5c,0x5b,0x5e,0x61,0x67,
0x69,0x73,0x7a,0x7e,0x81,0x89,0x90,0x95,0x95,0x91,0x92,0x95,0x92,0x8c,0x86,0x81,
0x7f,0x79,0x74,0x6f,0x6d,0x6a,0x66,0x65,0x68,0x6a,0x6b,0x6b,0x71,0x78,0x7c,0x7f,
0x83,0x89,0x8f,0x93,0x95,0x98,0x9b,0x9c,0x9d,0x9c,0x9d,0x9b,0x9c,0x9d,0xa0,0x99,
0x87,0x84,0x82,0x80,0x7b,0x6d,0x63,0x62,0x61,0x5f,0x5d,0x5f,0x5f,0x65,0x69,0x6f,
0x79,0x7d,0x80,0x86,0x8d,0x92,0x96,0x93,0x91,0x93,0x91,0x8c,0x87,0x81,0x7d,0x79,
0x73,0x6f,0x6d,0x6a,0x66,0x66,0x67,0x69,0x6c,0x6e,0x71,0x76,0x7c,0x81,0x85,0x88,
0x8e,0x92,0x96,0x98,0x9a,0x9b,0x9b,0x9a,0x9b,0x9d,0x9e,0x9c,0x9f,0x99,0x86,0x86,
0x81,0x81,0x7a,0x6c,0x63,0x61,0x61,0x5c,0x5d,0x5d,0x5f,0x65,0x6a,0x6f,0x7a,0x7f,
0x82,0x88,0x8e,0x94,0x96,0x94,0x91,0x93,0x91,0x8c,0x86,0x80,0x7b,0x77,0x72,0x6e,
0x6c,0x69,0x66,0x64,0x66,0x6b,0x6e,0x6e,0x70,0x77,0x7e,0x83,0x85,0x89,0x8e,0x93,
0x97,0x98,0x9a,0x9b,0x9b,0x9b,0x9c,0x9e,0x9e,0x9c,0xa0,0x95,0x88,0x86,0x80,0x7f,
0x77,0x6c,0x62,0x61,0x5f,0x5c,0x5e,0x5e,0x61,0x67,0x6b,0x72,0x7d,0x81,0x85,0x8b,
0x90,0x94,0x97,0x94,0x92,0x92,0x8e,0x8a,0x84,0x7e,0x79,0x75,0x70,0x6c,0x6b,0x69,
0x67,0x66,0x67,0x6c,0x70,0x72,0x75,0x79,0x7f,0x85,0x89,0x89,0x8d,0x90,0x94,0x96,
0x97,0x96,0x97,0x97,0x97,0x99,0x99,0x9a,0x9a,0x9f,0x8b,0x89,0x84,0x7f,0x80,0x73,
0x6c,0x62,0x66,0x5e,0x61,0x60,0x60,0x65,0x6a,0x6d,0x77,0x7f,0x80,0x87,0x8b,0x91,
0x93,0x96,0x90,0x91,0x8f,0x8b,0x87,0x81,0x7c,0x78,0x74,0x70,0x6d,0x6b,0x69,0x67,
0x69,0x6a,0x6e,0x70,0x72,0x77,0x7d,0x81,0x85,0x88,0x8d,0x91,0x95,0x96,0x98,0x9a,
0x9c,0x9c,0x9b,0x9a,0x9d,0x9e,0xa2,0x9c,0x85,0x86,0x82,0x81,0x7a,0x6b,0x61,0x60,
0x61,0x5b,0x5e,0x5d,0x5f,0x66,0x6c,0x71,0x7e,0x82,0x85,0x8b,0x92,0x97,0x99,0x95,
0x91,0x92,0x90,0x8a,0x83,0x7c,0x77,0x73,0x6f,0x6c,0x69,0x67,0x62,0x64,0x68,0x6d,
0x6f,0x70,0x74,0x7c,0x83,0x87,0x8a,0x8e,0x91,0x96,0x98,0x99,0x9a,0x99,0x99,0x9a,
0x9b,0x9b,0x9d,0x9c,0x9f,0x8b,0x83,0x81,0x7f,0x7f,0x70,0x65,0x5c,0x62,0x5f,0x5e,
0x5e,0x5f,0x65,0x6d,0x70,0x79,0x83,0x85,0x8a,0x8e,0x95,0x98,0x97,0x91,0x90,0x8f,
0x8b,0x84,0x7d,0x76,0x73,0x6f,0x6b,0x69,0x68,0x67,0x66,0x68,0x6a,0x70,0x72,0x76,
0x7a,0x80,0x84,0x89,0x8a,0x8f,0x91,0x94,0x94,0x96,0x97,0x97,0x97,0x98,0x98,0x9a,
0x9c,0x9c,0xa0,0x87,0x88,0x82,0x80,0x7d,0x71,0x67,0x5f,0x64,0x5a,0x60,0x5f,0x61,
0x64,0x6c,0x6f,0x7c,0x82,0x83,0x8a,0x8f,0x95,0x95,0x96,0x8f,0x91,0x8e,0x88,0x83,
0x7f,0x78,0x73,0x6e,0x6c,0x6a,0x69,0x65,0x63,0x67,0x6c,0x72,0x73,0x74,0x79,0x81,
0x87,0x8b,0x8c,0x8f,0x91,0x95,0x96,0x98,0x97,0x96,0x95,0x97,0x97,0x9b,0x9a,0x9c,
0x9b,0x85,0x87,0x81,0x81,0x7c,0x70,0x64,0x61,0x64,0x5d,0x60,0x60,0x61,0x67,0x6e,
0x71,0x7e,0x82,0x85,0x8a,0x90,0x94,0x96,0x94,0x8f,0x8f,0x8d,0x87,0x81,0x7b,0x76,
0x73,0x6f,0x6c,0x69,0x68,0x66,0x67,0x69,0x6d,0x71,0x73,0x75,0x7c,0x81,0x86,0x89,
0x8c,0x90,0x93,0x95,0x96,0x97,0x96,0x98,0x99,0x9b,0x99,0x9c,0x9a,0xa2,0x93,0x85,
0x85,0x7f,0x80,0x75,0x6a,0x60,0x63,0x5f,0x5d,0x5f,0x60,0x64,0x6c,0x6e,0x77,0x82,
0x85,0x89,0x8d,0x93,0x96,0x98,0x92,0x8f,0x8f,0x8b,0x84,0x7e,0x78,0x74,0x70,0x6b,
0x69,0x69,0x68,0x67,0x68,0x6a,0x6f,0x74,0x77,0x7a,0x80,0x83,0x88,0x8b,0x8e,0x91,
0x93,0x93,0x95,0x96,0x96,0x96,0x95,0x97,0x98,0x9b,0x9b,0xa3,0x8c,0x85,0x84,0x82,
0x82,0x75,0x69,0x60,0x65,0x5e,0x60,0x61,0x60,0x65,0x6b,0x6f,0x7a,0x83,0x83,0x88,
0x8d,0x93,0x96,0x96,0x90,0x8f,0x8e,0x89,0x84,0x7e,0x78,0x74,0x70,0x6c,0x6b,0x6a,
0x68,0x66,0x68,0x6c,0x71,0x74,0x76,0x7a,0x7f,0x84,0x89,0x8b,0x8e,0x91,0x94,0x96,
0x98,0x97,0x98,0x98,0x99,0x99,0x9c,0x9a,0x9f,0x9b,0x84,0x85,0x80,0x81,0x79,0x6d,
0x61,0x60,0x62,0x5b,0x60,0x60,0x63,0x69,0x6e,0x74,0x81,0x84,0x87,0x8c,0x92,0x96,
0x97,0x94,0x8e,0x8f,0x8c,0x85,0x7f,0x79,0x75,0x71,0x6c,0x69,0x68,0x68,0x66,0x67,
0x69,0x6f,0x74,0x76,0x79,0x7f,0x84,0x88,0x8b,0x8d,0x90,0x92,0x94,0x94,0x96,0x95,
0x97,0x94,0x96,0x96,0x9a,0x99,0xa2,0x90,0x83,0x87,0x80,0x82,0x73,0x6b,0x61,0x67,
0x5f,0x5c,0x60,0x60,0x66,0x6b,0x6f,0x77,0x84,0x83,0x88,0x8c,0x94,0x95,0x96,0x90,
0x8e,0x8f,0x89,0x83,0x7d,0x78,0x73,0x70,0x6b,0x6a,0x69,0x67,0x67,0x6b,0x6e,0x71,
0x73,0x77,0x7c,0x82,0x84,0x88,0x8a,0x8d,0x8f,0x91,0x92,0x93,0x94,0x92,0x94,0x95,
0x97,0x97,0x99,0x9a,0xa2,0x8e,0x86,0x86,0x80,0x83,0x75,0x6a,0x61,0x65,0x5f,0x5f,
0x61,0x60,0x66,0x6b,0x6e,0x79,0x82,0x83,0x88,0x8d,0x93,0x96,0x96,0x90,0x8e,0x8d,
0x89,0x83,0x7d,0x77,0x74,0x70,0x6c,0x6a,0x69,0x67,0x68,0x6a,0x6d,0x72,0x75,0x77,
0x7b,0x81,0x85,0x8a,0x8b,0x8d,0x90,0x94,0x93,0x95,0x94,0x96,0x96,0x97,0x97,0x9a,
0x9b,0x9f,0x9b,0x84,0x87,0x83,0x82,0x7c,0x6e,0x64,0x61,0x63,0x5c,0x60,0x60,0x62,
0x68,0x6e,0x74,0x81,0x84,0x86,0x8b,0x92,0x96,0x97,0x94,0x8e,0x8e,0x8b,0x85,0x7f,
0x7a,0x74,0x71,0x6c,0x6a,0x69,0x68,0x68,0x69,0x6c,0x71,0x73,0x76,0x7b,0x80,0x84,
0x87,0x8a,0x8c,0x8f,0x90,0x91,0x92,0x94,0x92,0x93,0x92,0x95,0x95,0x99,0x98,0x9e,
0x9a,0x85,0x88,0x81,0x84,0x7c,0x6f,0x64,0x65,0x65,0x5e,0x62,0x61,0x64,0x6a,0x6f,
0x74,0x81,0x84,0x86,0x8a,0x90,0x94,0x96,0x92,0x8d,0x8e,0x8b,0x85,0x7f,0x79,0x74,
0x73,0x6e,0x6b,0x6a,0x69,0x67,0x68,0x6c,0x71,0x75,0x76,0x79,0x7f,0x85,0x89,0x8c,
0x8d,0x90,0x93,0x94,0x96,0x95,0x95,0x96,0x96,0x97,0x98,0x9a,0x9b,0x9e,0x87,0x83,
0x85,0x7f,0x7f,0x71,0x66,0x61,0x65,0x5f,0x60,0x63,0x62,0x69,0x6f,0x73,0x7f,0x86,
0x86,0x8b,0x8f,0x94,0x96,0x94,0x8e,0x8d,0x8c,0x85,0x80,0x7a,0x74,0x71,0x6e,0x6b,
0x6a,0x69,0x68,0x6a,0x6e,0x72,0x75,0x76,0x79,0x7f,0x85,0x86,0x88,0x89,0x8c,0x8e,
0x8f,0x8f,0x91,0x90,0x91,0x92,0x94,0x95,0x96,0x97,0x9c,0xa3,0x8c,0x89,0x83,0x81,
0x83,0x77,0x69,0x62,0x65,0x5f,0x62,0x60,0x61,0x67,0x6c,0x6f,0x7b,0x83,0x85,0x88,
0x8c,0x92,0x96,0x96,0x8e,0x8d,0x8c,0x88,0x83,0x7d,0x76,0x74,0x70,0x6d,0x6a,0x6a,
0x67,0x67,0x69,0x6e,0x73,0x75,0x76,0x7b,0x81,0x86,0x8a,0x8c,0x8e,0x91,0x94,0x94,
0x95,0x95,0x96,0x94,0x96,0x97,0x9c,0x98,0x9e,0x93,0x81,0x88,0x82,0x81,0x76,0x6b,
0x61,0x65,0x63,0x5c,0x62,0x62,0x66,0x6c,0x71,0x78,0x84,0x85,0x87,0x8d,0x93,0x95,
0x95,0x90,0x8c,0x8d,0x88,0x81,0x7c,0x77,0x73,0x70,0x6b,0x6a,0x6a,0x69,0x69,0x6c,
0x6f,0x73,0x75,0x78,0x7c,0x82,0x86,0x88,0x8a,0x8b,0x8e,0x8f,0x91,0x91,0x92,0x90,
0x91,0x92,0x95,0x95,0x98,0x97,0xa0,0x9a,0x85,0x88,0x81,0x84,0x7c,0x70,0x64,0x65,
0x64,0x5d,0x62,0x62,0x66,0x6b,0x6e,0x74,0x81,0x84,0x86,0x8b,0x90,0x94,0x96,0x92,
0x8c,0x8d,0x89,0x83,0x7e,0x78,0x75,0x72,0x6d,0x6a,0x6b,0x6a,0x69,0x6a,0x6d,0x71,
0x74,0x77,0x7b,0x81,0x84,0x88,0x8a,0x8d,0x90,0x92,0x92,0x94,0x94,0x93,0x93,0x95,
0x96,0x99,0x9a,0x9b,0xa0,0x8a,0x86,0x84,0x83,0x81,0x74,0x66,0x60,0x66,0x5f,0x60,
0x61,0x61,0x68,0x6e,0x73,0x7e,0x85,0x85,0x8a,0x8f,0x94,0x96,0x94,0x8e,0x8d,0x8b,
0x86,0x80,0x7a,0x75,0x72,0x6f,0x6b,0x6a,0x6a,0x68,0x69,0x6b,0x70,0x74,0x76,0x79,
0x7e,0x84,0x87,0x8a,0x8b,0x8e,0x90,0x92,0x91,0x94,0x93,0x93,0x91,0x94,0x97,0x99,
0x97,0x9b,0x9d,0x88,0x88,0x81,0x81,0x7f,0x73,0x67,0x62,0x67,0x60,0x63,0x61,0x63,
0x6b,0x70,0x73,0x7e,0x84,0x86,0x8a,0x8e,0x92,0x95,0x93,0x8c,0x8b,0x89,0x85,0x7f,
0x7a,0x75,0x73,0x6f,0x6c,0x6a,0x6a,0x69,0x6a,0x6e,0x71,0x75,0x77,0x79,0x7f,0x84,
0x87,0x8a,0x8a,0x8d,0x8f,0x91,0x91,0x92,0x91,0x92,0x92,0x94,0x96,0x99,0x97,0x9b,
0x9b,0x8a,0x89,0x82,0x81,0x7d,0x72,0x67,0x63,0x64,0x5f,0x62,0x62,0x64,0x6a,0x6f,
0x74,0x7e,0x84,0x86,0x8b,0x8e,0x92,0x94,0x92,0x8d,0x8c,0x89,0x84,0x7f,0x7a,0x75,
0x72,0x6f,0x6c,0x6b,0x6b,0x6a,0x6c,0x6e,0x72,0x76,0x77,0x7a,0x7f,0x83,0x85,0x87,
0x87,0x8b,0x8d,0x8d,0x8d,0x8e,0x8f,0x8f,0x90,0x90,0x94,0x98,0x9b,0x9a,0xa1,0x94,
0x89,0x8a,0x83,0x83,0x79,0x6f,0x63,0x65,0x61,0x5e,0x62,0x60,0x65,0x6b,0x6f,0x76,
0x81,0x83,0x87,0x8c,0x90,0x93,0x95,0x91,0x8d,0x8c,0x88,0x83,0x7f,0x79,0x75,0x72,
0x6d,0x6c,0x6b,0x6b,0x6a,0x6b,0x6d,0x71,0x75,0x77,0x7a,0x7f,0x84,0x87,0x88,0x89,
0x8d,0x8f,0x90,0x90,0x91,0x92,0x93,0x93,0x95,0x97,0x9b,0x99,0xa0,0x96,0x86,0x89,
0x80,0x82,0x79,0x6e,0x63,0x64,0x62,0x5e,0x64,0x61,0x66,0x6c,0x70,0x77,0x82,0x85,
0x87,0x8d,0x90,0x93,0x95,0x90,0x8c,0x8b,0x87,0x82,0x7e,0x77,0x73,0x71,0x6d,0x6c,
0x6b,0x69,0x69,0x6c,0x6f,0x74,0x76,0x78,0x7b,0x81,0x86,0x89,0x8a,0x8b,0x8e,0x91,
0x91,0x92,0x91,0x92,0x93,0x93,0x94,0x99,0x9a,0x9c,0x9f,0x8d,0x86,0x87,0x82,0x81,
0x76,0x69,0x62,0x65,0x60,0x60,0x64,0x61,0x67,0x6d,0x72,0x7c,0x84,0x85,0x89,0x8f,
0x92,0x95,0x94,0x8e,0x8b,0x8a,0x85,0x80,0x7b,0x74,0x72,0x6e,0x6b,0x6a,0x6a,0x6a,
0x6a,0x6e,0x72,0x76,0x78,0x7a,0x7f,0x85,0x89,0x8a,0x8b,0x8d,0x8f,0x91,0x91,0x91,
0x91,0x92,0x93,0x94,0x96,0x9c,0x9a,0x9e,0x96,0x87,0x8a,0x84,0x81,0x79,0x6e,0x65,
0x64,0x63,0x5d,0x62,0x62,0x65,0x6b,0x70,0x77,0x81,0x85,0x87,0x8d,0x91,0x94,0x94,
0x91,0x8d,0x8c,0x88,0x81,0x7d,0x78,0x74,0x70,0x6c,0x6a,0x6a,0x69,0x68,0x6a,0x6f,
0x74,0x76,0x78,0x7c,0x82,0x87,0x8a,0x8b,0x8d,0x8f,0x91,0x91,0x92,0x92,0x93,0x93,
0x94,0x95,0x98,0x99,0x9b,0x9e,0x89,0x86,0x83,0x80,0x80,0x73,0x68,0x61,0x64,0x60,
0x61,0x64,0x62,0x69,0x6f,0x74,0x7e,0x85,0x86,0x89,0x8e,0x92,0x95,0x94,0x8d,0x8a,
0x89,0x84,0x7f,0x7a,0x74,0x71,0x6d,0x6b,0x6a,0x6b,0x69,0x6a,0x6d,0x72,0x75,0x79,
0x7b,0x7f,0x84,0x88,0x8a,0x8c,0x8d,0x8f,0x91,0x90,0x91,0x92,0x94,0x92,0x94,0x95,
0x9a,0x9b,0xa2,0x93,0x83,0x88,0x81,0x84,0x79,0x6c,0x61,0x64,0x63,0x5e,0x63,0x61,
0x65,0x6c,0x70,0x78,0x84,0x86,0x87,0x8c,0x91,0x95,0x96,0x90,0x8a,0x8a,0x87,0x81,
0x7d,0x76,0x73,0x70,0x6c,0x6a,0x6a,0x6a,0x69,0x6b,0x6f,0x74,0x77,0x78,0x7b,0x81,
0x86,0x89,0x8b,0x8c,0x8e,0x91,0x91,0x92,0x91,0x93,0x92,0x93,0x95,0x98,0x9b,0x9d,
0x9e,0x88,0x86,0x86,0x83,0x80,0x71,0x66,0x62,0x66,0x60,0x60,0x62,0x62,0x69,0x6e,
0x73,0x7e,0x85,0x86,0x89,0x8f,0x94,0x96,0x93,0x8d,0x8b,0x8a,0x85,0x7f,0x79,0x74,
0x72,0x6e,0x6b,0x6b,0x6b,0x6a,0x6b,0x6e,0x72,0x77,0x79,0x7b,0x7f,0x85,0x87,0x8a,
0x89,0x8a,0x8c,0x8d,0x8d,0x8d,0x8d,0x8e,0x90,0x90,0x91,0x95,0x9a,0x9b,0xa5,0x91,
0x89,0x8a,0x84,0x87,0x7b,0x6e,0x63,0x67,0x61,0x5f,0x63,0x61,0x65,0x6b,0x6e,0x78,
0x83,0x84,0x86,0x8b,0x90,0x95,0x96,0x90,0x8c,0x8c,0x88,0x82,0x7e,0x78,0x74,0x71,
0x6d,0x6b,0x6c,0x6b,0x69,0x6a,0x6f,0x74,0x77,0x78,0x7b,0x82,0x86,0x89,0x8a,0x8c,
0x8e,0x91,0x91,0x93,0x92,0x95,0x94,0x94,0x96,0x9c,0x9b,0xa1,0x98,0x84,0x88,0x81,
0x82,0x7c,0x6e,0x63,0x61,0x62,0x5d,0x63,0x62,0x63,0x6c,0x70,0x78,0x84,0x87,0x88,
0x8d,0x92,0x95,0x97,0x93,0x8c,0x8a,0x87,0x81,0x7e,0x77,0x71,0x6f,0x6c,0x6b,0x6a,
0x6b,0x6a,0x6c,0x71,0x75,0x79,0x7b,0x7d,0x83,0x87,0x89,0x8a,0x8b,0x8c,0x8c,0x8d,
0x8d,0x8e,0x8d,0x8d,0x8f,0x92,0x94,0x98,0x99,0xa1,0x99,0x89,0x8a,0x84,0x86,0x7e,
0x71,0x65,0x64,0x64,0x5f,0x62,0x61,0x64,0x6a,0x6e,0x75,0x80,0x85,0x86,0x8a,0x8f,
0x93,0x95,0x92,0x8c,0x8b,0x88,0x83,0x7f,0x79,0x74,0x71,0x6d,0x6c,0x6c,0x6b,0x69,
0x6b,0x6f,0x74,0x77,0x79,0x7b,0x81,0x85,0x87,0x89,0x8a,0x8b,0x8d,0x8e,0x8f,0x8f,
0x8f,0x91,0x91,0x93,0x96,0x9a,0x9b,0xa2,0x92,0x86,0x87,0x82,0x84,0x79,0x6c,0x61,
0x64,0x61,0x5f,0x64,0x62,0x66,0x6c,0x71,0x7a,0x85,0x87,0x88,0x8c,0x92,0x95,0x96,
0x90,0x8a,0x89,0x86,0x80,0x7b,0x75,0x71,0x6f,0x6c,0x6a,0x6b,0x6b,0x6b,0x6e,0x72,
0x76,0x7a,0x7d,0x7f,0x84,0x86,0x89,0x8a,0x8b,0x8b,0x8b,0x8b,0x8c,0x8d,0x8d,0x8d,
0x8f,0x91,0x94,0x99,0x9b,0xa2,0x91,0x87,0x87,0x84,0x87,0x7a,0x6e,0x62,0x66,0x63,
0x61,0x64,0x61,0x66,0x6b,0x71,0x79,0x82,0x85,0x87,0x8c,0x90,0x94,0x95,0x90,0x8b,
0x8a,0x86,0x82,0x7d,0x76,0x73,0x70,0x6d,0x6c,0x6c,0x6a,0x6a,0x6d,0x72,0x75,0x78,
0x79,0x7e,0x82,0x86,0x89,0x8a,0x8b,0x8d,0x8f,0x90,0x92,0x91,0x93,0x93,0x93,0x95,
0x9b,0x9a,0xa3,0x91,0x83,0x85,0x81,0x82,0x77,0x6c,0x60,0x64,0x62,0x5f,0x64,0x64,
0x67,0x6d,0x73,0x7c,0x86,0x88,0x89,0x8d,0x93,0x96,0x95,0x90,0x8a,0x89,0x85,0x7f,
0x7b,0x75,0x71,0x6d,0x6b,0x6a,0x6b,0x6c,0x6b,0x6d,0x73,0x77,0x7b,0x7c,0x7f,0x84,
0x88,0x8a,0x8b,0x8c,0x8c,0x8d,0x8d,0x8e,0x8d,0x8f,0x8f,0x91,0x92,0x97,0x98,0xa0,
0x9d,0x87,0x87,0x82,0x86,0x80,0x74,0x66,0x63,0x66,0x60,0x64,0x63,0x64,0x6a,0x6f,
0x75,0x81,0x87,0x87,0x8a,0x8e,0x93,0x96,0x93,0x8c,0x8a,0x89,0x83,0x7f,0x78,0x73,
0x71,0x6e,0x6c,0x6c,0x6c,0x6c,0x6c,0x6f,0x74,0x78,0x7b,0x7b,0x80,0x85,0x88,0x89,
0x8a,0x8a,0x8e,0x8e,0x90,0x8f,0x90,0x90,0x91,0x93,0x96,0x9a,0x9b,0xa3,0x8d,0x87,
0x84,0x81,0x84,0x78,0x6c,0x61,0x65,0x60,0x61,0x64,0x63,0x68,0x6e,0x73,0x7c,0x86,
0x88,0x8a,0x8e,0x92,0x95,0x96,0x90,0x8a,0x89,0x84,0x7f,0x7a,0x74,0x71,0x6e,0x6b,
0x6b,0x6c,0x6c,0x6c,0x6f,0x73,0x76,0x7a,0x7c,0x7f,0x84,0x87,0x88,0x8b,0x8b,0x8d,
0x8e,0x8f,0x8f,0x90,0x91,0x90,0x93,0x95,0x9a,0x9c,0xa3,0x8f,0x86,0x86,0x82,0x85,
0x77,0x6b,0x60,0x64,0x60,0x60,0x64,0x62,0x67,0x6c,0x72,0x7c,0x86,0x88,0x89,0x8d,
0x92,0x97,0x97,0x90,0x8a,0x89,0x85,0x80,0x7a,0x74,0x70,0x6e,0x6a,0x6a,0x6a,0x6a,
0x6a,0x6b,0x71,0x76,0x7a,0x7c,0x7f,0x84,0x8a,0x8b,0x8d,0x8d,0x91,0x91,0x92,0x91,
0x92,0x91,0x93,0x92,0x96,0x99,0x9c,0xa0,0x83,0x84,0x80,0x83,0x81,0x72,0x66,0x5e,
0x66,0x5f,0x64,0x65,0x65,0x6a,0x70,0x76,0x81,0x8a,0x88,0x8a,0x8f,0x94,0x96,0x94,
0x8c,0x88,0x87,0x82,0x7d,0x78,0x73,0x6f,0x6c,0x69,0x6b,0x6d,0x6c,0x6d,0x70,0x74,
0x78,0x7c,0x7e,0x82,0x85,0x88,0x89,0x8b,0x8a,0x8c,0x8d,0x8d,0x8e,0x8f,0x8f,0x8e,
0x91,0x94,0x9a,0x99,0xa4,0x91,0x85,0x86,0x82,0x86,0x7b,0x6f,0x60,0x65,0x63,0x61,
0x66,0x62,0x66,0x6d,0x72,0x7a,0x85,0x87,0x88,0x8c,0x91,0x94,0x96,0x90,0x89,0x88,
0x85,0x80,0x7c,0x75,0x71,0x6f,0x6d,0x6b,0x6d,0x6c,0x6b,0x6d,0x71,0x76,0x7a,0x7b,
0x7d,0x82,0x87,0x89,0x8c,0x8c,0x8e,0x90,0x91,0x91,0x92,0x94,0x92,0x93,0x94,0x99,
0x9a,0xa2,0x8e,0x81,0x85,0x80,0x83,0x77,0x6c,0x60,0x66,0x63,0x61,0x66,0x65,0x68,
0x6f,0x74,0x7c,0x88,0x89,0x88,0x8d,0x92,0x95,0x95,0x8e,0x88,0x87,0x84,0x7d,0x7a,
0x75,0x70,0x6e,0x6b,0x6b,0x6e,0x6e,0x6d,0x6e,0x73,0x78,0x7c,0x7d,0x7f,0x84,0x87,
0x89,0x8a,0x8b,0x8c,0x8e,0x8d,0x8f,0x8f,0x91,0x8f,0x92,0x92,0x98,0x98,0xa0,0x97,
0x85,0x88,0x81,0x85,0x7d,0x72,0x65,0x64,0x65,0x60,0x66,0x65,0x66,0x6c,0x71,0x77,
0x83,0x87,0x88,0x8b,0x8f,0x93,0x95,0x92,0x8a,0x88,0x85,0x80,0x7c,0x77,0x72,0x6f,
0x6d,0x6c,0x6d,0x6d,0x6c,0x6c,0x70,0x75,0x79,0x7c,0x7e,0x81,0x86,0x88,0x8b,0x8d,
0x8e,0x90,0x90,0x91,0x92,0x94,0x92,0x93,0x93,0x97,0x98,0xa0,0x96,0x81,0x83,0x80,
0x81,0x7c,0x6f,0x63,0x64,0x65,0x60,0x66,0x68,0x68,0x6e,0x73,0x79,0x85,0x8a,0x88,
0x8a,0x8f,0x92,0x94,0x90,0x88,0x85,0x84,0x7e,0x7a,0x76,0x71,0x6f,0x6d,0x6c,0x6e,
0x70,0x6e,0x6e,0x72,0x77,0x7b,0x7d,0x7e,0x82,0x86,0x88,0x88,0x89,0x8a,0x8c,0x8c,
0x8d,0x8d,0x90,0x8f,0x90,0x90,0x96,0x98,0x9d,0xa2,0x89,0x87,0x84,0x83,0x83,0x79,
0x6b,0x62,0x67,0x60,0x63,0x67,0x65,0x69,0x6f,0x72,0x7c,0x87,0x87,0x88,0x8c,0x8f,
0x93,0x94,0x8d,0x87,0x87,0x83,0x7f,0x7c,0x75,0x72,0x70,0x6d,0x6e,0x70,0x6f,0x6e,
0x70,0x74,0x78,0x7b,0x7c,0x7d,0x82,0x84,0x86,0x87,0x87,0x88,0x89,0x8a,0x8a,0x8c,
0x8c,0x8c,0x8d,0x90,0x90,0x92,0x93,0x98,0x97,0x8d,0x85,0x81,0x82,0x80,0x79,0x6e,
0x69,0x69,0x68,0x68,0x68,0x6b,0x6f,0x72,0x75,0x7b,0x83,0x86,0x88,0x89,0x8a,0x8d,
0x8d,0x89,0x85,0x83,0x81,0x7d,0x79,0x75,0x74,0x72,0x6f,0x6e,0x6f,0x70,0x71,0x73,
0x76,0x7a,0x7d,0x7f,0x81,0x86,0x89,0x8d,0x8e,0x8f,0x8f,0x92,0x92,0x93,0x92,0x93,
0x93,0x93,0x96,0x98,0xa0,0x8c,0x80,0x7d,0x7c,0x80,0x78,0x6a,0x5f,0x63,0x62,0x64,
0x68,0x69,0x6c,0x72,0x75,0x7e,0x8a,0x8c,0x8a,0x8c,0x8f,0x93,0x93,0x8b,0x84,0x83,
0x80,0x7b,0x77,0x73,0x70,0x6e,0x6c,0x6d,0x72,0x73,0x71,0x72,0x76,0x7d,0x80,0x80,
0x80,0x84,0x86,0x88,0x87,0x86,0x87,0x88,0x87,0x88,0x89,0x89,0x8a,0x8b,0x8c,0x8f,
0x94,0x95,0x99,0x96,0x8d,0x89,0x86,0x85,0x81,0x7a,0x70,0x6b,0x6b,0x68,0x68,0x69,
0x6a,0x6d,0x70,0x75,0x7b,0x81,0x84,0x86,0x89,0x8b,0x8e,0x8d,0x8a,0x86,0x85,0x82,
0x7f,0x7b,0x78,0x75,0x71,0x70,0x6f,0x70,0x70,0x70,0x71,0x75,0x79,0x7b,0x7e,0x81,
0x85,0x88,0x8c,0x8e,0x90,0x91,0x92,0x93,0x95,0x93,0x93,0x92,0x93,0x95,0x95,0x9a,
0x8c,0x83,0x7c,0x79,0x7b,0x77,0x6e,0x63,0x63,0x63,0x66,0x6b,0x6c,0x6e,0x74,0x78,
0x7f,0x88,0x8b,0x8b,0x8b,0x8d,0x8f,0x8f,0x8b,0x84,0x80,0x7d,0x7a,0x77,0x73,0x70,
0x6e,0x6d,0x6e,0x70,0x72,0x73,0x73,0x77,0x7b,0x80,0x82,0x83,0x84,0x87,0x88,0x8a,
0x8b,0x8b,0x8a,0x8a,0x8b,0x8e,0x8f,0x8d,0x8d,0x8e,0x93,0x96,0x9f,0x93,0x86,0x82,
0x7f,0x83,0x7f,0x75,0x68,0x66,0x64,0x65,0x6a,0x6a,0x6a,0x6e,0x71,0x78,0x83,0x87,
0x87,0x88,0x8a,0x8e,0x91,0x8e,0x88,0x84,0x82,0x7f,0x7c,0x78,0x73,0x70,0x6e,0x6f,
0x71,0x70,0x6f,0x6f,0x72,0x77,0x7c,0x7d,0x7e,0x81,0x84,0x88,0x8b,0x8c,0x8d,0x8e,
0x8d,0x8e,0x91,0x92,0x90,0x8f,0x8e,0x94,0x94,0x9b,0x97,0x85,0x80,0x7c,0x80,0x7d,
0x76,0x68,0x63,0x66,0x65,0x69,0x6b,0x6b,0x6f,0x74,0x79,0x82,0x89,0x89,0x89,0x8b,
0x8e,0x90,0x8f,0x88,0x82,0x81,0x7d,0x7a,0x76,0x72,0x70,0x6f,0x6d,0x6e,0x70,0x72,
0x72,0x74,0x77,0x7c,0x80,0x81,0x82,0x85,0x88,0x8b,0x8c,0x8c,0x8d,0x8d,0x8e,0x8e,
0x91,0x90,0x90,0x8e,0x92,0x93,0x9d,0x98,0x83,0x81,0x7d,0x82,0x7e,0x75,0x68,0x66,
0x68,0x64,0x69,0x6b,0x6c,0x70,0x72,0x77,0x82,0x89,0x88,0x87,0x8a,0x8e,0x91,0x8f,
0x88,0x83,0x82,0x7e,0x7b,0x78,0x74,0x71,0x6f,0x6e,0x70,0x73,0x72,0x71,0x73,0x77,
0x7c,0x80,0x81,0x82,0x84,0x87,0x89,0x8b,0x8c,0x8c,0x8b,0x8c,0x8d,0x8f,0x8f,0x8f,
0x8f,0x91,0x93,0x96,0x9f,0x8c,0x84,0x7f,0x7f,0x83,0x7c,0x70,0x64,0x68,0x65,0x68,
0x6b,0x6a,0x6d,0x71,0x73,0x7b,0x86,0x88,0x87,0x88,0x8a,0x8f,0x91,0x8b,0x85,0x83,
0x81,0x7e,0x7a,0x76,0x73,0x71,0x6e,0x6e,0x71,0x71,0x71,0x71,0x74,0x7a,0x7e,0x80,
0x81,0x84,0x87,0x8a,0x8c,0x8e,0x8f,0x8f,0x8f,0x90,0x93,0x91,0x92,0x90,0x93,0x91,
0x9b,0x97,0x83,0x82,0x7c,0x7f,0x7d,0x76,0x69,0x66,0x68,0x64,0x6a,0x6c,0x6d,0x71,
0x73,0x77,0x82,0x89,0x88,0x88,0x8a,0x8c,0x90,0x8e,0x88,0x83,0x81,0x7d,0x7b,0x78,
0x74,0x71,0x6e,0x6d,0x70,0x73,0x72,0x71,0x73,0x77,0x7d,0x80,0x80,0x82,0x85,0x87,
0x89,0x8c,0x8c,0x8e,0x8c,0x8d,0x8e,0x91,0x90,0x8f,0x8e,0x92,0x93,0x9a,0x99,0x83,
0x82,0x7e,0x82,0x80,0x77,0x6a,0x65,0x69,0x65,0x6a,0x6c,0x6b,0x6e,0x72,0x75,0x80,
0x88,0x86,0x86,0x89,0x8c,0x90,0x8f,0x88,0x84,0x83,0x7f,0x7c,0x79,0x75,0x72,0x6f,
0x6d,0x6f,0x71,0x71,0x6f,0x71,0x75,0x7b,0x7e,0x80,0x81,0x85,0x88,0x8b,0x8d,0x8e,
0x8f,0x8e,0x8f,0x90,0x93,0x91,0x91,0x90,0x93,0x93,0x9b,0x8e,0x80,0x80,0x7e,0x81,
0x7a,0x71,0x66,0x68,0x68,0x67,0x6b,0x6c,0x6e,0x71,0x74,0x7a,0x85,0x89,0x87,0x87,
0x8b,0x8e,0x91,0x8b,0x85,0x83,0x82,0x7d,0x7a,0x77,0x73,0x71,0x6f,0x6f,0x71,0x73,
0x72,0x72,0x74,0x79,0x7c,0x7f,0x7f,0x82,0x84,0x86,0x87,0x88,0x89,0x8a,0x8a,0x8a,
0x8b,0x8c,0x8e,0x8d,0x8e,0x8f,0x94,0x95,0x9c,0x90,0x84,0x84,0x83,0x85,0x7d,0x75,
0x68,0x6b,0x69,0x67,0x6a,0x6a,0x6b,0x6f,0x72,0x77,0x82,0x85,0x84,0x86,0x8a,0x8d,
0x90,0x8c,0x87,0x85,0x84,0x80,0x7d,0x79,0x76,0x74,0x71,0x70,0x70,0x71,0x70,0x70,
0x73,0x76,0x7a,0x7c,0x7e,0x81,0x86,0x88,0x8b,0x8b,0x8e,0x8f,0x90,0x8f,0x91,0x92,
0x91,0x90,0x90,0x94,0x94,0x9c,0x8a,0x80,0x81,0x7f,0x80,0x7a,0x71,0x66,0x6a,0x67,
0x67,0x6c,0x6d,0x6e,0x72,0x75,0x7b,0x86,0x88,0x87,0x89,0x8c,0x8e,0x8f,0x8b,0x85,
0x84,0x82,0x7d,0x7b,0x77,0x73,0x71,0x70,0x70,0x72,0x73,0x72,0x73,0x76,0x7b,0x7e,
0x7f,0x80,0x83,0x85,0x87,0x88,0x88,0x88,0x88,0x88,0x89,0x8c,0x8b,0x8c,0x8b,0x8e,
0x8d,0x94,0x93,0x9c,0x95,0x86,0x85,0x82,0x86,0x81,0x7a,0x6b,0x6a,0x6a,0x68,0x6b,
0x6b,0x6b,0x6d,0x71,0x75,0x7e,0x84,0x84,0x84,0x88,0x8b,0x8f,0x8e,0x88,0x85,0x85,
0x82,0x7f,0x7c,0x78,0x76,0x74,0x71,0x71,0x72,0x71,0x71,0x72,0x75,0x78,0x7b,0x7c,
0x7e,0x82,0x85,0x87,0x8a,0x8b,0x8d,0x8e,0x8f,0x8f,0x92,0x91,0x91,0x90,0x92,0x93,
0x98,0x96,0x84,0x81,0x7f,0x82,0x7e,0x76,0x6a,0x67,0x6a,0x67,0x69,0x6b,0x6d,0x6f,
0x73,0x77,0x80,0x87,0x87,0x86,0x89,0x8c,0x8f,0x8e,0x88,0x84,0x83,0x80,0x7c,0x79,
0x76,0x74,0x71,0x70,0x71,0x73,0x71,0x71,0x73,0x77,0x7b,0x7d,0x7d,0x80,0x83,0x85,
0x87,0x88,0x8a,0x8a,0x8a,0x8a,0x8c,0x8d,0x8f,0x8d,0x8e,0x8d,0x93,0x93,0x9a,0x93,
0x84,0x84,0x81,0x83,0x7e,0x78,0x6a,0x6a,0x6a,0x67,0x6b,0x6c,0x6b,0x6e,0x72,0x76,
0x80,0x85,0x84,0x85,0x89,0x8c,0x8f,0x8d,0x88,0x85,0x84,0x81,0x7e,0x7b,0x77,0x75,
0x72,0x71,0x72,0x73,0x72,0x70,0x72,0x76,0x79,0x7c,0x7c,0x7f,0x81,0x85,0x87,0x89,
0x8a,0x8b,0x8b,0x8c,0x8e,0x90,0x8f,0x8d,0x8e,0x91,0x93,0x96,0x9a,0x88,0x83,0x80,
0x81,0x81,0x7b,0x70,0x68,0x6b,0x67,0x6a,0x6c,0x6c,0x6d,0x71,0x74,0x7c,0x84,0x85,
0x85,0x87,0x8a,0x8e,0x8f,0x8a,0x85,0x84,0x82,0x80,0x7d,0x78,0x75,0x74,0x72,0x72,
0x73,0x73,0x73,0x72,0x75,0x78,0x7c,0x7d,0x7e,0x80,0x82,0x86,0x88,0x89,0x89,0x8a,
0x8a,0x8c,0x8d,0x8f,0x8d,0x8e,0x8d,0x91,0x93,0x98,0x99,0x87,0x84,0x81,0x84,0x81,
0x7b,0x6f,0x69,0x6c,0x69,0x6b,0x6c,0x6c,0x6e,0x72,0x74,0x7c,0x83,0x84,0x84,0x86,
0x8a,0x8e,0x8e,0x89,0x85,0x84,0x83,0x80,0x7d,0x79,0x76,0x74,0x72,0x71,0x72,0x72,
0x71,0x71,0x74,0x78,0x7c,0x7d,0x7e,0x81,0x85,0x89,0x8b,0x8b,0x8d,0x8d,0x8e,0x8f,
0x91,0x90,0x90,0x8f,0x90,0x91,0x95,0x99,0x88,0x82,0x7e,0x81,0x81,0x7b,0x70,0x67,
0x6b,0x69,0x6c,0x6d,0x6d,0x6f,0x72,0x75,0x7d,0x85,0x86,0x84,0x86,0x89,0x8e,0x8e,
0x8a,0x84,0x83,0x82,0x7f,0x7c,0x78,0x75,0x73,0x71,0x71,0x74,0x74,0x73,0x72,0x74,
0x7a,0x7f,0x7f,0x7f,0x81,0x84,0x88,0x89,0x89,0x8a,0x8b,0x8b,0x8c,0x8d,0x8f,0x8e,
0x8d,0x8c,0x91,0x93,0x99,0x8f,0x83,0x81,0x81,0x84,0x7d,0x77,0x6c,0x6c,0x6b,0x6a,
0x6d,0x6e,0x6e,0x6f,0x72,0x78,0x80,0x84,0x82,0x83,0x87,0x8b,0x8d,0x8a,0x86,0x84,
0x84,0x81,0x7e,0x7b,0x78,0x75,0x72,0x71,0x72,0x73,0x71,0x71,0x73,0x78,0x7b,0x7d,
0x7e,0x80,0x84,0x88,0x8b,0x8c,0x8d,0x8d,0x8f,0x8f,0x92,0x91,0x91,0x90,0x90,0x90,
0x96,0x94,0x84,0x81,0x7e,0x80,0x7d,0x77,0x6b,0x69,0x6b,0x68,0x6b,0x6d,0x6e,0x70,
0x73,0x76,0x7e,0x85,0x85,0x84,0x87,0x8a,0x8d,0x8d,0x87,0x84,0x83,0x82,0x7e,0x7b,
0x78,0x75,0x73,0x71,0x71,0x73,0x73,0x71,0x72,0x75,0x7b,0x7d,0x7e,0x7f,0x83,0x87,
0x89,0x8a,0x8a,0x8d,0x8e,0x8d,0x8e,0x90,0x8f,0x8f,0x8c,0x8e,0x90,0x97,0x93,0x84,
0x80,0x7f,0x83,0x80,0x7a,0x6e,0x6b,0x6d,0x6a,0x6c,0x6e,0x6e,0x6f,0x71,0x74,0x7c,
0x83,0x83,0x82,0x84,0x88,0x8c,0x8b,0x87,0x84,0x84,0x82,0x7f,0x7d,0x7a,0x77,0x74,
0x71,0x71,0x73,0x73,0x71,0x72,0x75,0x79,0x7c,0x7e,0x7f,0x84,0x87,0x8a,0x8b,0x8e,
0x8f,0x91,0x90,0x91,0x92,0x93,0x92,0x91,0x90,0x93,0x92,0x86,0x80,0x7e,0x7f,0x7d,
0x77,0x6e,0x6a,0x6c,0x6a,0x6b,0x6d,0x6f,0x71,0x73,0x75,0x7c,0x83,0x85,0x85,0x86,
0x88,0x8c,0x8c,0x88,0x85,0x84,0x82,0x7e,0x7b,0x78,0x76,0x74,0x71,0x71,0x72,0x73,
0x72,0x73,0x75,0x79,0x7d,0x7f,0x82,0x84,0x87,0x8a,0x8c,0x8e,0x8f,0x90,0x90,0x92,
0x92,0x92,0x91,0x91,0x8f,0x94,0x92,0x86,0x81,0x7e,0x7f,0x7d,0x78,0x6e,0x6b,0x6c,
0x6a,0x6c,0x6e,0x6f,0x70,0x73,0x74,0x7b,0x82,0x84,0x85,0x85,0x87,0x8a,0x8c,0x89,
0x86,0x84,0x81,0x7f,0x7c,0x79,0x77,0x74,0x71,0x70,0x72,0x73,0x74,0x73,0x75,0x79,
0x7d,0x81,0x82,0x85,0x88,0x8b,0x8e,0x90,0x91,0x92,0x93,0x93,0x93,0x93,0x94,0x93,
0x93,0x92,0x8a,0x83,0x7f,0x7d,0x7b,0x79,0x71,0x6a,0x6a,0x69,0x6a,0x6d,0x6e,0x6e,
0x71,0x74,0x79,0x7f,0x83,0x85,0x86,0x87,0x88,0x8b,0x8b,0x88,0x84,0x81,0x7e,0x7d,
0x7b,0x78,0x74,0x71,0x70,0x71,0x73,0x74,0x75,0x75,0x78,0x7c,0x80,0x82,0x84,0x86,
0x89,0x8c,0x8e,0x8f,0x91,0x91,0x90,0x91,0x92,0x93,0x92,0x90,0x91,0x90,0x88,0x83,
0x7f,0x7d,0x7b,0x78,0x6f,0x6c,0x6c,0x6a,0x6b,0x6c,0x6e,0x70,0x73,0x74,0x79,0x7f,
0x83,0x84,0x84,0x85,0x87,0x89,0x87,0x84,0x82,0x7f,0x7c,0x7a,0x78,0x77,0x75,0x73,
0x72,0x74,0x76,0x78,0x79,0x7a,0x7d,0x80,0x83,0x86,0x88,0x8a,0x8c,0x8d,0x8f,0x91,
0x92,0x92,0x91,0x91,0x91,0x93,0x94,0x91,0x89,0x83,0x80,0x7f,0x7d,0x78,0x71,0x6b,
0x6a,0x69,0x6b,0x6c,0x6d,0x6e,0x6f,0x73,0x78,0x7f,0x81,0x82,0x83,0x85,0x87,0x89,
0x88,0x85,0x82,0x7f,0x7e,0x7c,0x7a,0x78,0x75,0x73,0x72,0x74,0x76,0x77,0x77,0x79,
0x7c,0x7f,0x82,0x85,0x88,0x8a,0x8c,0x8e,0x90,0x92,0x93,0x92,0x91,0x92,0x92,0x93,
0x93,0x91,0x8b,0x84,0x81,0x7f,0x7e,0x79,0x73,0x6d,0x6a,0x69,0x6a,0x6c,0x6d,0x6d,
0x6e,0x72,0x76,0x7c,0x80,0x82,0x82,0x83,0x85,0x88,0x88,0x86,0x83,0x80,0x7e,0x7d,
0x7c,0x7a,0x77,0x75,0x74,0x76,0x77,0x79,0x79,0x7b,0x7c,0x7f,0x83,0x86,0x89,0x8a,
0x8b,0x8c,0x90,0x92,0x92,0x90,0x90,0x90,0x91,0x92,0x91,0x90,0x8a,0x84,0x7f,0x7f,
0x7d,0x7b,0x75,0x6f,0x6b,0x6b,0x6c,0x6d,0x6e,0x6e,0x6f,0x71,0x75,0x7a,0x7e,0x80,
0x80,0x81,0x83,0x86,0x86,0x85,0x83,0x80,0x7f,0x7e,0x7d,0x7c,0x7a,0x78,0x77,0x78,
0x7a,0x7b,0x7c,0x7c,0x7e,0x82,0x85,0x87,0x89,0x8a,0x8c,0x8e,0x90,0x91,0x91,0x90,
0x90,0x8f,0x8f,0x90,0x8f,0x8c,0x88,0x82,0x7f,0x7d,0x7b,0x78,0x74,0x6f,0x6d,0x6d,
0x6d,0x6f,0x6f,0x70,0x71,0x73,0x76,0x7a,0x7e,0x7f,0x7f,0x80,0x82,0x83,0x84,0x83,
0x81,0x7f,0x7e,0x7d,0x7d,0x7c,0x7c,0x7a,0x79,0x7a,0x7c,0x7e,0x7f,0x80,0x81,0x83,
0x85,0x89,0x8a,0x8b,0x8b,0x8c,0x8d,0x8e,0x8f,0x8f,0x8e,0x8d,0x8c,0x8b,0x89,0x88,
0x85,0x81,0x7e,0x7a,0x78,0x76,0x74,0x70,0x6f,0x6e,0x6f,0x70,0x71,0x72,0x73,0x76,
0x78,0x7b,0x7d,0x7f,0x7f,0x80,0x80,0x81,0x82,0x81,0x80,0x7f,0x7e,0x7d,0x7d,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7f,0x81,0x83,0x84,0x84,0x86,0x87,0x89,0x8a,0x8b,0x8a,0x8b,
0x8b,0x8b,0x8b,0x8b,0x89,0x89,0x88,0x86,0x84,0x82,0x7f,0x7d,0x7b,0x78,0x77,0x75,
0x74,0x73,0x72,0x73,0x74,0x75,0x75,0x77,0x79,0x7b,0x7c,0x7d,0x7e,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7c,0x7d,0x7d,0x7e,0x7f,0x80,0x81,0x82,
0x83,0x83,0x85,0x86,0x88,0x88,0x89,0x89,0x89,0x89,0x89,0x89,0x89,0x87,0x87,0x86,
0x84,0x83,0x81,0x80,0x7e,0x7c,0x7a,0x79,0x78,0x78,0x77,0x76,0x75,0x76,0x77,0x78,
0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,
0x7d,0x7d,0x7d,0x7e,0x7f,0x7f,0x7f,0x80,0x81,0x83,0x84,0x85,0x85,0x86,0x85,0x86,
0x86,0x86,0x86,0x86,0x85,0x84,0x84,0x83,0x83,0x82,0x81,0x7f,0x7f,0x7e,0x7e,0x7d,
0x7b,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7b,0x7a,0x7a,0x7b,0x7d,0x7e,0x7f,0x7f,0x7f,
0x7f,0x80,0x80,0x81,0x80,0x7f,0x7e,0x7e,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7f,0x7f,
0x80,0x81,0x81,0x82,0x82,0x83,0x84,0x85,0x84,0x84,0x84,0x85,0x84,0x84,0x84,0x83,
0x83,0x81,0x81,0x81,0x80,0x7f,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7b,0x7c,
0x7c,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x80,
0x80,0x7f,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x81,0x81,0x81,0x81,
0x81,0x82,0x83,0x83,0x83,0x83,0x82,0x82,0x82,0x82,0x82,0x81,0x81,0x7f,0x7f,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7d,0x7c,0x7d,0x7d,0x7e,0x7f,0x7e,0x7e,0x7e,0x7f,0x7f,0x80,
0x80,0x80,0x80,0x7f,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x7f,
0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x81,0x81,0x81,0x81,0x81,0x81,
0x81,0x81,0x81,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x81,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,
0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,
0x80,0x80,0x81,0x81,0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,
0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,
0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7d,
0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x80,0x81,0x81,0x80,0x80,0x80,0x80,
0x80,0x7f,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7e,0x80,
0x7f,0x7f,0x7f,0x7e,0x7f,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,
0x80,0x80,0x81,0x81,0x80,0x81,0x81,0x80,0x80,0x80,0x7f,0x80,0x80,0x81,0x80,0x80,
0x80,0x7f,0x80,0x80,0x81,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x81,0x7f,0x80,0x7e,0x7e,
0x7f,0x7e,0x81,0x7f,0x80,0x7e,0x7e,0x80,0x7e,0x81,0x7f,0x80,0x7e,0x7f,0x7f,0x7e,
0x80,0x7f,0x80,0x7f,0x7e,0x7f,0x7f,0x80,0x81,0x81,0x81,0x81,0x80,0x7f,0x80,0x80,
0x82,0x80,0x81,0x80,0x80,0x80,0x7f,0x81,0x80,0x81,0x7f,0x7f,0x7f,0x7f,0x7f,0x81,
0x80,0x81,0x80,0x7f,0x7e,0x7f,0x7f,0x80,0x81,0x7f,0x81,0x7e,0x7f,0x80,0x7f,0x81,
0x80,0x80,0x7f,0x7f,0x7e,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x80,
0x80,0x7e,0x80,0x7f,0x80,0x80,0x80,0x81,0x7f,0x81,0x80,0x80,0x80,0x80,0x81,0x81,
0x7e,0x80,0x7e,0x7f,0x81,0x7f,0x82,0x7e,0x80,0x7e,0x7e,0x82,0x7e,0x82,0x7f,0x7e,
0x80,0x7c,0x81,0x7f,0x7f,0x80,0x7d,0x80,0x7c,0x81,0x7e,0x7f,0x80,0x7d,0x81,0x7d,
0x7f,0x81,0x7d,0x81,0x7e,0x80,0x80,0x7f,0x81,0x7e,0x81,0x7f,0x80,0x81,0x80,0x80,
0x7f,0x7f,0x80,0x7f,0x82,0x7e,0x82,0x7e,0x7f,0x80,0x7d,0x82,0x7e,0x82,0x7f,0x7f,
0x80,0x7e,0x80,0x7f,0x81,0x7f,0x7f,0x80,0x7c,0x80,0x7e,0x80,0x7f,0x80,0x7e,0x7d,
0x80,0x7e,0x80,0x80,0x7f,0x80,0x7d,0x80,0x7e,0x80,0x81,0x7f,0x82,0x7d,0x81,0x7c,
0x80,0x81,0x80,0x83,0x7e,0x7e,0x7d,0x7f,0x80,0x80,0x83,0x7f,0x7e,0x7f,0x7d,0x80,
0x81,0x81,0x81,0x7f,0x7d,0x7f,0x7e,0x81,0x84,0x80,0x81,0x7e,0x7c,0x7f,0x7e,0x83,
0x7f,0x82,0x7e,0x7e,0x7e,0x7d,0x82,0x80,0x82,0x7f,0x7f,0x7d,0x7e,0x7f,0x80,0x81,
0x82,0x7c,0x7f,0x7d,0x7f,0x80,0x7f,0x83,0x7e,0x81,0x7e,0x7f,0x80,0x82,0x80,0x81,
0x7f,0x7e,0x7e,0x7c,0x82,0x7e,0x81,0x81,0x7d,0x81,0x7e,0x7f,0x81,0x80,0x82,0x7d,
0x81,0x7e,0x7f,0x80,0x80,0x81,0x7f,0x82,0x7d,0x80,0x80,0x7f,0x82,0x7f,0x81,0x7e,
0x7e,0x82,0x7d,0x83,0x7d,0x80,0x7f,0x7e,0x80,0x7f,0x81,0x7e,0x7f,0x7e,0x7f,0x7e,
0x83,0x7f,0x82,0x7f,0x80,0x7e,0x80,0x82,0x7f,0x82,0x7e,0x81,0x7e,0x80,0x7f,0x81,
0x7f,0x81,0x80,0x7e,0x82,0x7d,0x81,0x7f,0x7f,0x81,0x7e,0x81,0x7f,0x7f,0x81,0x7e,
0x7f,0x80,0x7f,0x82,0x7e,0x81,0x80,0x7c,0x83,0x7d,0x81,0x7f,0x81,0x7f,0x7e,0x80,
0x7e,0x81,0x7e,0x83,0x7e,0x7e,0x81,0x7e,0x80,0x7e,0x82,0x80,0x7f,0x82,0x7e,0x81,
0x80,0x7f,0x80,0x7f,0x80,0x81,0x7f,0x80,0x7f,0x7f,0x80,0x81,0x7f,0x7f,0x7f,0x7f,
0x80,0x80,0x7f,0x7f,0x83,0x7d,0x82,0x7e,0x80,0x7f,0x81,0x80,0x7f,0x82,0x7e,0x82,
0x7e,0x81,0x7e,0x84,0x7e,0x81,0x80,0x7d,0x81,0x7c,0x83,0x7e,0x81,0x80,0x7d,0x80,
0x7f,0x81,0x80,0x82,0x7e,0x80,0x80,0x7d,0x81,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x80,
0x81,0x7c,0x84,0x7d,0x7f,0x81,0x7c,0x84,0x7a,0x84,0x7c,0x82,0x80,0x7e,0x82,0x7c,
0x82,0x7e,0x7f,0x82,0x7e,0x7f,0x80,0x7d,0x81,0x7e,0x82,0x7d,0x81,0x7f,0x7e,0x82,
0x7c,0x82,0x7d,0x82,0x7d,0x81,0x7f,0x7e,0x82,0x7c,0x83,0x7c,0x83,0x7d,0x7f,0x7f,
0x7d,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7d,0x81,0x7e,0x81,0x7f,0x81,0x7c,0x81,
0x7f,0x80,0x80,0x7f,0x81,0x7d,0x81,0x7c,0x81,0x7f,0x80,0x80,0x81,0x7d,0x80,0x7f,
0x7e,0x82,0x7d,0x83,0x7c,0x81,0x7e,0x7e,0x82,0x7d,0x84,0x7c,0x82,0x7d,0x7f,0x80,
0x7d,0x83,0x7d,0x81,0x7e,0x7e,0x7f,0x7e,0x80,0x7f,0x80,0x80,0x7e,0x80,0x7f,0x80,
0x80,0x7f,0x81,0x7e,0x80,0x80,0x7f,0x81,0x7e,0x82,0x7f,0x80,0x7e,0x7f,0x81,0x7d,
0x82,0x7c,0x82,0x7d,0x80,0x80,0x7d,0x82,0x7c,0x82,0x7d,0x81,0x7e,0x80,0x80,0x7f,
0x82,0x7d,0x81,0x7e,0x81,0x7d,0x82,0x7e,0x80,0x7f,0x7e,0x80,0x7e,0x80,0x80,0x7f,
0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x82,0x7e,0x80,0x7e,0x80,0x81,0x80,0x80,0x7f,
0x80,0x7f,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x80,0x7e,0x81,0x7e,0x80,0x80,
0x7e,0x81,0x7e,0x80,0x7f,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x81,0x80,0x80,0x7f,
0x7f,0x80,0x7d,0x81,0x7f,0x80,0x80,0x7e,0x81,0x7e,0x81,0x7f,0x80,0x80,0x7f,0x81,
0x7f,0x7f,0x81,0x7f,0x7f,0x80,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x81,0x80,0x80,
0x81,0x7e,0x81,0x7e,0x81,0x80,0x80,0x80,0x7f,0x81,0x7e,0x81,0x7d,0x82,0x7e,0x7f,
0x81,0x7d,0x81,0x7f,0x81,0x80,0x7f,0x82,0x7e,0x81,0x7e,0x80,0x80,0x7f,0x81,0x7e,
0x82,0x7c,0x81,0x7e,0x81,0x7f,0x81,0x80,0x7e,0x80,0x7e,0x82,0x7e,0x80,0x7f,0x80,
0x80,0x80,0x81,0x7e,0x81,0x7e,0x80,0x80,0x7e,0x82,0x7d,0x81,0x7f,0x80,0x7f,0x80,
0x7f,0x7f,0x80,0x7e,0x81,0x7e,0x80,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x81,0x7d,0x82,
0x7d,0x82,0x7f,0x80,0x81,0x7c,0x82,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7e,0x81,
0x7f,0x81,0x7f,0x81,0x7e,0x80,0x7f,0x7f,0x81,0x80,0x81,0x7f,0x80,0x7f,0x7e,0x82,
0x7e,0x80,0x80,0x7e,0x81,0x7d,0x81,0x7e,0x81,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x80,
0x80,0x80,0x80,0x7f,0x7f,0x80,0x7e,0x81,0x7e,0x81,0x7e,0x7e,0x80,0x7e,0x7e,0x81,
0x7f,0x80,0x80,0x7f,0x80,0x7e,0x82,0x7f,0x80,0x80,0x7e,0x80,0x7e,0x80,0x7f,0x80,
0x81,0x7e,0x7f,0x7e,0x80,0x7f,0x82,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x82,0x7e,0x82,
0x7d,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x81,0x7e,0x81,0x7f,
0x80,0x7f,0x7e,0x80,0x7f,0x80,0x80,0x80,0x7e,0x80,0x7e,0x81,0x7e,0x80,0x80,0x7e,
0x80,0x7d,0x82,0x7d,0x81,0x80,0x80,0x81,0x7d,0x83,0x7d,0x81,0x7f,0x7f,0x80,0x7e,
0x81,0x7f,0x80,0x80,0x7f,0x81,0x7e,0x80,0x81,0x7e,0x82,0x7d,0x80,0x7f,0x7f,0x80,
0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x81,0x80,0x7e,0x82,0x7c,0x82,0x7d,0x81,
0x81,0x7f,0x81,0x7d,0x81,0x7d,0x81,0x7f,0x81,0x7f,0x80,0x7f,0x7e,0x80,0x7e,0x82,
0x7f,0x81,0x7f,0x80,0x7f,0x7e,0x81,0x7f,0x7f,0x81,0x7f,0x80,0x80,0x7f,0x82,0x7f,
0x80,0x81,0x7e,0x81,0x7e,0x81,0x7e,0x82,0x7e,0x80,0x80,0x7e,0x82,0x7c,0x84,0x7d,
0x81,0x80,0x80,0x80,0x7f,0x81,0x7e,0x81,0x80,0x7f,0x80,0x7e,0x81,0x7e,0x80,0x80,
0x7e,0x80,0x7f,0x7f,0x81,0x7f,0x80,0x80,0x7e,0x82,0x7c,0x83,0x7e,0x81,0x80,0x7f,
0x81,0x7e,0x82,0x7e,0x81,0x7e,0x82,0x7d,0x81,0x7e,0x80,0x81,0x7e,0x83,0x7e,0x81,
0x7e,0x80,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x81,0x7f,0x81,0x7f,
0x81,0x7e,0x81,0x80,0x7e,0x82,0x7d,0x82,0x7e,0x81,0x80,0x7d,0x81,0x7d,0x80,0x7f,
0x80,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x81,0x7f,0x81,0x7f,0x7f,0x80,0x7f,0x81,0x7f,
0x81,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x7f,0x81,0x80,0x7f,0x7f,0x80,0x80,0x7e,0x81,
0x80,0x7e,0x7f,0x7f,0x80,0x7e,0x82,0x7e,0x81,0x7f,0x7f,0x80,0x7d,0x82,0x7d,0x82,
0x7f,0x7f,0x80,0x7d,0x81,0x7e,0x81,0x7f,0x7f,0x80,0x7d,0x80,0x7f,0x81,0x7e,0x81,
0x80,0x7e,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7e,0x81,0x7d,0x81,0x7d,0x81,0x7f,
0x7f,0x81,0x7d,0x80,0x7e,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,
0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x81,0x7e,0x80,0x7e,0x81,0x7f,
0x7f,0x81,0x7d,0x81,0x7d,0x81,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x81,0x7f,0x80,0x7f,
0x80,0x80,0x7f,0x81,0x7f,0x80,0x7e,0x80,0x7e,0x80,0x80,0x7e,0x80,0x7f,0x80,0x7e,
0x81,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7e,0x81,0x7e,0x80,0x7f,0x80,
0x7e,0x80,0x7f,0x7e,0x81,0x7f,0x80,0x7e,0x80,0x7e,0x7f,0x80,0x7e,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x80,0x80,
0x7e,0x81,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x81,0x7f,0x7f,0x81,0x7e,0x80,0x7f,0x7f,
0x80,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7e,0x81,0x7e,0x80,0x7f,0x81,0x7f,0x80,0x81,
0x7e,0x81,0x7e,0x81,0x7e,0x81,0x80,0x7f,0x80,0x7f,0x7f,0x81,0x7f,0x81,0x7f,0x80,
0x80,0x7e,0x81,0x7e,0x80,0x80,0x80,0x7f,0x7f,0x81,0x7f,0x7f,0x82,0x7e,0x81,0x7f,
0x80,0x7f,0x80,0x81,0x7e,0x82,0x7e,0x81,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,
0x80,0x80,0x7f,0x80,0x80,0x80,0x80,0x80,0x81,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x80,0x7f,0x81,0x7f,0x80,0x80,0x7f,0x80,0x7e,0x80,0x80,0x7f,0x81,0x7f,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,
0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x81,0x7f,0x80,0x7f,
0x81,0x7f,0x80,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7e,0x80,
0x7f,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x7f,0x80,0x7f,0x81,0x7e,0x7f,0x80,0x7f,
0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x7e,0x7f,0x7f,
0x7f,0x80,0x80,0x80,0x7e,0x80,0x7e,0x80,0x80,0x80,0x80,0x7e,0x80,0x7e,0x7f,0x80,
0x7f,0x80,0x80,0x7e,0x80,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x81,0x7f,0x7f,0x80,0x7e,0x80,
0x7f,0x80,0x7f,0x7e,0x80,0x7d,0x81,0x7e,0x7f,0x81,0x7e,0x80,0x7f,0x80,0x80,0x7e,
0x81,0x7d,0x81,0x7f,0x7f,0x80,0x7e,0x81,0x7d,0x81,0x7e,0x80,0x80,0x7f,0x80,0x7f,
0x81,0x7e,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,
0x7f,0x81,0x7f,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x81,0x7f,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,0x81,0x7f,0x80,0x80,0x7f,0x80,0x7f,
0x81,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,0x7f,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7e,0x81,0x7f,0x82,0x7e,0x80,0x7f,
0x7f,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x7e,0x81,0x7f,0x80,0x80,0x7f,0x80,0x7e,
0x81,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,
0x80,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x80,
0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x81,
0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7e,0x81,0x7e,0x81,0x7e,0x80,0x7e,0x80,0x80,
0x7f,0x81,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7e,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x7e,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x7f,0x7f,0x80,0x80,0x7f,0x80,0x7e,0x80,0x7e,0x80,0x7e,0x80,0x7f,0x7f,
0x7f,0x7f,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,
0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x81,0x7e,0x80,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x7f,0x81,
0x7e,0x81,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x81,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x81,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,
0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x80,0x7f,0x7f,0x80,
0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,
0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x7f,
0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,
0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,
0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x80,
0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x80,
0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x7f,0x80,0x80,0x80,0x80,0x80,
0x80,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80
};
const byte soundWow[] ={
0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,
0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x81,0x81,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x80,0x81,0x80,0x80,0x80,0x7f,
0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x80,
0x80,0x7e,0x80,0x7e,0x81,0x78,0x79,0x82,0x7b,0x83,0x82,0x84,0x80,0x82,0x7f,0x80,
0x7e,0x80,0x7e,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7f,0x7f,
0x7f,0x7f,0x7f,0x7f,0x7f,0x7a,0x76,0x7e,0x7a,0x80,0x81,0x86,0x83,0x84,0x81,0x80,
0x7d,0x7f,0x7f,0x80,0x7e,0x7d,0x80,0x80,0x83,0x83,0x85,0x83,0x82,0x81,0x75,0x7e,
0x79,0x7d,0x7f,0x83,0x82,0x84,0x82,0x80,0x80,0x7d,0x80,0x7c,0x80,0x7f,0x80,0x80,
0x81,0x7f,0x7f,0x7e,0x7e,0x80,0x7f,0x81,0x7f,0x81,0x7f,0x80,0x7f,0x81,0x7f,0x81,
0x80,0x81,0x80,0x81,0x80,0x81,0x81,0x80,0x7e,0x7f,0x7e,0x7f,0x81,0x80,0x81,0x7f,
0x80,0x7e,0x7f,0x7e,0x80,0x7e,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,
0x7f,0x81,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x81,
0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x81,0x80,
0x80,0x7f,0x7f,0x80,0x80,0x7f,0x82,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,
0x7f,0x80,0x7e,0x80,0x7e,0x81,0x7f,0x81,0x7f,0x81,0x80,0x7f,0x80,0x7e,0x7f,0x7f,
0x7f,0x7e,0x7e,0x7f,0x7f,0x80,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x81,0x80,0x81,
0x7f,0x80,0x7f,0x7e,0x7f,0x81,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,
0x7f,0x7f,0x7f,0x7e,0x80,0x7f,0x80,0x80,0x7e,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x80,
0x80,0x81,0x80,0x81,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x7e,0x80,0x7e,0x80,0x80,
0x7f,0x81,0x80,0x81,0x81,0x81,0x80,0x81,0x7e,0x80,0x7f,0x7d,0x7f,0x7d,0x7e,0x7e,
0x7e,0x7f,0x7e,0x7f,0x80,0x81,0x81,0x82,0x83,0x81,0x81,0x81,0x7e,0x7f,0x7e,0x7d,
0x7d,0x7d,0x7b,0x7d,0x7b,0x7e,0x7e,0x81,0x82,0x84,0x88,0x89,0x8a,0x88,0x86,0x81,
0x7c,0x7a,0x75,0x75,0x75,0x74,0x76,0x77,0x78,0x7a,0x7c,0x82,0x88,0x8f,0x97,0x9b,
0x9d,0x98,0x8d,0x83,0x77,0x6e,0x63,0x60,0x61,0x5e,0x68,0x6f,0x79,0x85,0x8e,0x96,
0x9d,0xa2,0xa5,0xa8,0x9c,0x8f,0x7f,0x6a,0x4e,0x4e,0x46,0x4e,0x68,0x77,0x8c,0x99,
0x99,0x97,0x90,0x8f,0x91,0x99,0x9c,0x97,0x8c,0x7e,0x71,0x59,0x58,0x58,0x5b,0x6f,
0x7c,0x87,0x8f,0x8e,0x8c,0x8d,0x8f,0x96,0xa0,0xa5,0x98,0x8a,0x76,0x64,0x55,0x52,
0x5b,0x65,0x74,0x84,0x8c,0x8e,0x8c,0x8a,0x8a,0x8f,0x99,0xa4,0xa5,0x98,0x82,0x71,
0x5a,0x4c,0x52,0x5c,0x6c,0x7f,0x8c,0x90,0x8d,0x88,0x85,0x8a,0x94,0xa2,0xaa,0xa4,
0x8d,0x75,0x60,0x46,0x49,0x53,0x63,0x7e,0x8e,0x95,0x95,0x8a,0x83,0x84,0x8d,0x9b,
0xad,0xa9,0x95,0x7e,0x61,0x4b,0x44,0x4d,0x64,0x7a,0x8f,0x98,0x92,0x89,0x83,0x82,
0x8c,0x9f,0xad,0xaa,0x95,0x7a,0x5e,0x46,0x43,0x55,0x68,0x82,0x95,0x96,0x8f,0x84,
0x7d,0x83,0x91,0xa2,0xb0,0xa5,0x90,0x70,0x59,0x43,0x4a,0x5e,0x74,0x8c,0x96,0x95,
0x87,0x7e,0x7d,0x86,0x9a,0xad,0xaa,0x98,0x7c,0x5b,0x4c,0x44,0x5a,0x75,0x8b,0x9a,
0x99,0x89,0x79,0x78,0x7e,0x91,0xaa,0xad,0x9c,0x80,0x5f,0x47,0x41,0x56,0x74,0x90,
0xa2,0xa1,0x8f,0x7b,0x74,0x7c,0x8e,0xaa,0xaa,0x99,0x7f,0x56,0x43,0x3f,0x58,0x79,
0x97,0xa7,0xa2,0x8f,0x76,0x74,0x7d,0x95,0xaf,0xa6,0x95,0x71,0x47,0x3b,0x40,0x5f,
0x86,0xa3,0xa9,0x9f,0x89,0x76,0x7b,0x8c,0xa3,0xb1,0x9e,0x80,0x59,0x35,0x38,0x4e,
0x73,0x99,0xab,0xa2,0x8f,0x7b,0x76,0x89,0xa5,0xbb,0xb2,0x90,0x67,0x37,0x23,0x3a,
0x60,0x8d,0xad,0xaf,0x96,0x7c,0x6f,0x7a,0x9a,0xbc,0xc5,0xa1,0x7f,0x4d,0x1f,0x30,
0x58,0x7c,0xa2,0xb3,0x94,0x78,0x6c,0x73,0x91,0xb7,0xcd,0xad,0x87,0x5a,0x29,0x2a,
0x54,0x7c,0x9d,0xb0,0x9a,0x75,0x66,0x6f,0x8b,0xb1,0xcb,0xb1,0x84,0x5d,0x2e,0x31,
0x57,0x87,0xa2,0xad,0x98,0x75,0x61,0x6e,0x8c,0xac,0xc3,0xb1,0x7d,0x55,0x35,0x31,
0x57,0x8e,0xa9,0xaa,0x9f,0x7b,0x63,0x71,0x90,0xa5,0xbd,0xaa,0x73,0x50,0x36,0x35,
0x5a,0x94,0xa9,0xa7,0x9c,0x7b,0x67,0x76,0x99,0xad,0xb9,0xa1,0x6b,0x48,0x2f,0x3a,
0x65,0x96,0xa9,0xa2,0x93,0x79,0x6d,0x82,0xa3,0xb2,0xba,0x8e,0x5e,0x3e,0x2d,0x44,
0x74,0x9e,0xa5,0x9c,0x89,0x76,0x73,0x8e,0xae,0xb6,0xae,0x7b,0x53,0x39,0x36,0x56,
0x82,0x9d,0x9c,0x90,0x80,0x79,0x81,0xa1,0xb2,0xb7,0x9f,0x66,0x45,0x37,0x47,0x67,
0x8d,0x9c,0x90,0x7f,0x7c,0x80,0x8d,0xaa,0xb7,0xb1,0x8a,0x57,0x47,0x3d,0x51,0x73,
0x95,0x96,0x84,0x7f,0x7e,0x80,0x95,0xb6,0xb7,0xae,0x79,0x50,0x3b,0x3e,0x60,0x80,
0x9e,0x95,0x81,0x77,0x7d,0x83,0xa4,0xb8,0xb9,0xa4,0x64,0x47,0x39,0x46,0x6a,0x8b,
0x9a,0x89,0x7a,0x7a,0x83,0x8c,0xac,0xb7,0xb9,0x97,0x57,0x4c,0x3c,0x48,0x72,0x91,
0x90,0x82,0x7e,0x7e,0x82,0x95,0xb2,0xb3,0xb4,0x8d,0x57,0x45,0x41,0x51,0x70,0x8f,
0x8e,0x7d,0x7d,0x89,0x87,0x97,0xb3,0xb7,0xaa,0x77,0x53,0x4b,0x45,0x5e,0x82,0x8f,
0x7f,0x78,0x7e,0x83,0x8b,0xa7,0xb6,0xb5,0xa1,0x5f,0x4f,0x4c,0x4d,0x6d,0x8d,0x8e,
0x73,0x73,0x7e,0x82,0x91,0xb4,0xb4,0xb3,0x90,0x55,0x4b,0x49,0x57,0x74,0x8f,0x88,
0x74,0x7a,0x88,0x87,0x98,0xb5,0xb7,0xa8,0x72,0x53,0x4b,0x4b,0x67,0x85,0x91,0x7f,
0x72,0x78,0x84,0x8b,0xa6,0xb6,0xba,0x97,0x5b,0x54,0x48,0x55,0x76,0x91,0x86,0x70,
0x78,0x81,0x84,0x95,0xb2,0xad,0xad,0x7f,0x54,0x4c,0x53,0x64,0x7c,0x8e,0x83,0x75,
0x7b,0x8e,0x8d,0x9d,0xac,0xb2,0x97,0x5d,0x50,0x52,0x5a,0x71,0x8d,0x8d,0x72,0x70,
0x86,0x8c,0x91,0xae,0xb9,0xac,0x74,0x50,0x51,0x4a,0x63,0x83,0x95,0x7f,0x6e,0x7e,
0x8c,0x88,0x9f,0xb6,0xb2,0x97,0x5b,0x51,0x4a,0x5a,0x74,0x8d,0x8a,0x74,0x72,0x88,
0x8f,0x90,0xac,0xb5,0xac,0x70,0x50,0x57,0x4d,0x63,0x84,0x92,0x7a,0x6f,0x80,0x8d,
0x88,0xa0,0xb8,0xae,0x92,0x65,0x56,0x4d,0x53,0x74,0x88,0x84,0x76,0x79,0x86,0x8c,
0x90,0xab,0xb5,0xad,0x81,0x56,0x52,0x4f,0x5b,0x7a,0x8c,0x7d,0x74,0x84,0x90,0x8a,
0x98,0xb3,0xb3,0x97,0x60,0x55,0x55,0x58,0x71,0x8c,0x85,0x6b,0x75,0x89,0x8e,0x8f,
0xad,0xb3,0xa7,0x77,0x5a,0x57,0x50,0x65,0x7f,0x8b,0x7d,0x73,0x81,0x8d,0x86,0x99,
0xb1,0xb5,0x8e,0x5d,0x59,0x54,0x58,0x74,0x8d,0x85,0x70,0x7b,0x91,0x8c,0x8f,0xa7,
0xb0,0x9c,0x6c,0x56,0x5c,0x5e,0x6b,0x81,0x8a,0x73,0x6d,0x8b,0x96,0x8f,0x9e,0xaf,
0xac,0x82,0x53,0x58,0x5a,0x5e,0x73,0x90,0x84,0x6d,0x7e,0x99,0x90,0x92,0xab,0xae,
0x93,0x5e,0x58,0x5d,0x5a,0x6a,0x85,0x86,0x71,0x74,0x92,0x99,0x8d,0xa2,0xb1,0xa6,
0x72,0x54,0x5c,0x5c,0x62,0x7b,0x88,0x77,0x6d,0x87,0x9d,0x94,0x9a,0xac,0xab,0x8a,
0x5a,0x57,0x5d,0x5d,0x70,0x89,0x83,0x6e,0x75,0x95,0x98,0x94,0xa7,0xb1,0xa0,0x63,
0x4f,0x60,0x60,0x65,0x7f,0x8a,0x73,0x68,0x8a,0xa1,0x94,0x9b,0xad,0xa9,0x78,0x55,
0x60,0x63,0x5f,0x73,0x88,0x79,0x6a,0x7d,0x9e,0x98,0x98,0xa9,0xb1,0x91,0x5c,0x54,
0x61,0x5f,0x69,0x85,0x87,0x6d,0x6d,0x90,0x9d,0x95,0xa3,0xaf,0xa2,0x6d,0x51,0x61,
0x63,0x65,0x79,0x8a,0x77,0x66,0x7d,0x9e,0x99,0x9c,0xab,0xad,0x88,0x55,0x57,0x67,
0x65,0x6b,0x85,0x83,0x69,0x6b,0x94,0x9f,0x94,0xa4,0xb2,0x9f,0x65,0x54,0x65,0x63,
0x64,0x7e,0x89,0x74,0x64,0x81,0x9c,0x97,0x9e,0xaf,0xad,0x83,0x55,0x54,0x61,0x64,
0x74,0x86,0x83,0x6b,0x73,0x94,0x9d,0x98,0xa6,0xad,0x99,0x64,0x51,0x60,0x64,0x69,
0x7c,0x88,0x75,0x69,0x85,0x9d,0x97,0x9c,0xaf,0xab,0x79,0x4f,0x59,0x66,0x65,0x74,
0x8b,0x7f,0x65,0x74,0x9a,0x9c,0x97,0xa9,0xaf,0x90,0x5f,0x54,0x63,0x66,0x6c,0x7f,
0x84,0x70,0x6a,0x8a,0x9f,0x98,0x9e,0xaf,0xa5,0x75,0x50,0x5a,0x62,0x6a,0x7a,0x88,
0x7a,0x68,0x78,0x99,0x9e,0x9d,0xa7,0xab,0x8f,0x5a,0x4f,0x62,0x68,0x6f,0x7f,0x85,
0x70,0x6c,0x8c,0xa0,0x9c,0xa2,0xac,0xa0,0x6c,0x50,0x5c,0x66,0x6a,0x7a,0x85,0x77,
0x67,0x7f,0x9c,0x9c,0x9d,0xad,0xae,0x85,0x56,0x55,0x60,0x62,0x70,0x84,0x83,0x6d,
0x71,0x91,0x9d,0x97,0xa2,0xb2,0x9e,0x6a,0x50,0x5e,0x63,0x68,0x7a,0x88,0x76,0x67,
0x7f,0x9e,0x9b,0x9c,0xaa,0xa9,0x83,0x55,0x58,0x69,0x6b,0x6f,0x80,0x80,0x6b,0x6f,
0x92,0x9f,0x99,0xa3,0xae,0x9a,0x66,0x51,0x5f,0x6c,0x6f,0x7a,0x82,0x73,0x69,0x82,
0x9c,0x9a,0x9c,0xab,0xa5,0x7e,0x59,0x57,0x66,0x6c,0x7a,0x82,0x7a,0x6b,0x74,0x91,
0x9b,0x99,0xa3,0xaa,0x98,0x6b,0x54,0x60,0x69,0x6c,0x77,0x81,0x77,0x70,0x84,0x9a,
0x98,0x99,0xa9,0xa6,0x83,0x5b,0x58,0x64,0x67,0x71,0x81,0x7f,0x6e,0x75,0x90,0x9b,
0x97,0xa2,0xae,0x9c,0x6b,0x56,0x5e,0x66,0x69,0x79,0x83,0x76,0x6d,0x84,0x99,0x98,
0x99,0xa8,0xaa,0x88,0x5f,0x58,0x65,0x63,0x6b,0x7c,0x82,0x72,0x76,0x8e,0x9b,0x94,
0x9e,0xad,0xa0,0x74,0x57,0x61,0x66,0x66,0x73,0x82,0x78,0x6d,0x80,0x98,0x97,0x95,
0xa6,0xaa,0x8f,0x66,0x59,0x63,0x66,0x6b,0x78,0x80,0x75,0x73,0x89,0x99,0x96,0x9a,
0xa8,0xa1,0x81,0x5f,0x5e,0x65,0x67,0x6e,0x78,0x7b,0x77,0x7e,0x91,0x96,0x95,0xa1,
0xa6,0x99,0x76,0x5b,0x5b,0x65,0x6e,0x74,0x7b,0x7b,0x77,0x82,0x93,0x99,0x9c,0xa4,
0xa6,0x8b,0x62,0x58,0x62,0x67,0x6d,0x76,0x7d,0x7a,0x7d,0x8d,0x96,0x96,0x9d,0xa6,
0x9f,0x7b,0x5a,0x59,0x64,0x68,0x70,0x7b,0x7f,0x7a,0x82,0x92,0x99,0x99,0xa1,0xa0,
0x90,0x69,0x5b,0x60,0x68,0x6e,0x72,0x7a,0x7d,0x7d,0x88,0x93,0x99,0x9f,0xa2,0xa0,
0x7f,0x5e,0x58,0x64,0x6c,0x6e,0x77,0x7e,0x79,0x7f,0x8f,0x9a,0x9b,0x9f,0xa2,0x97,
0x72,0x59,0x5c,0x67,0x6b,0x70,0x7e,0x80,0x79,0x83,0x94,0x99,0x99,0x9e,0xa3,0x88,
0x61,0x5b,0x68,0x6e,0x6c,0x73,0x7c,0x79,0x79,0x8a,0x99,0x9c,0x9f,0xa2,0x9b,0x7a,
0x60,0x5e,0x63,0x6b,0x6f,0x79,0x7d,0x7c,0x81,0x8d,0x95,0x9b,0xa0,0xa2,0x93,0x72,
0x5b,0x5f,0x66,0x6a,0x70,0x7b,0x7f,0x7b,0x82,0x91,0x99,0x9d,0x9f,0xa1,0x88,0x64,
0x5a,0x65,0x6c,0x6c,0x75,0x7d,0x79,0x79,0x8a,0x97,0x9c,0x9e,0xa6,0x9c,0x79,0x5d,
0x5d,0x66,0x6a,0x6f,0x79,0x7f,0x79,0x7e,0x8e,0x98,0x97,0x9b,0xa1,0x98,0x74,0x5c,
0x60,0x68,0x6a,0x6d,0x7a,0x7f,0x7b,0x82,0x92,0x9a,0x9d,0x9e,0xa2,0x8d,0x6b,0x5d,
0x61,0x69,0x6c,0x72,0x7b,0x7c,0x7c,0x87,0x94,0x98,0x99,0xa0,0xa1,0x84,0x63,0x5b,
0x66,0x6a,0x6e,0x76,0x7d,0x7a,0x7b,0x8a,0x97,0x9a,0x9c,0xa0,0x9a,0x7b,0x60,0x5f,
0x68,0x6c,0x6c,0x75,0x7e,0x7d,0x7f,0x8c,0x98,0x9a,0x9c,0xa0,0x98,0x75,0x5b,0x5f,
0x69,0x6c,0x6f,0x7a,0x7e,0x79,0x7e,0x91,0x9b,0x9e,0x9d,0xa0,0x8f,0x6b,0x5c,0x62,
0x6b,0x6d,0x70,0x7a,0x7d,0x7b,0x85,0x92,0x9a,0x9a,0x9d,0x9e,0x8c,0x68,0x5e,0x67,
0x68,0x66,0x70,0x7f,0x7f,0x7c,0x89,0x96,0x99,0x9d,0xa0,0x9d,0x7d,0x60,0x61,0x69,
0x6a,0x6b,0x75,0x7d,0x7b,0x7e,0x8b,0x94,0x99,0x9c,0xa2,0x9c,0x7b,0x5f,0x5c,0x66,
0x6b,0x70,0x79,0x7d,0x79,0x80,0x8f,0x97,0x99,0x9e,0xa0,0x92,0x72,0x64,0x66,0x67,
0x67,0x6d,0x7a,0x7d,0x7b,0x83,0x90,0x96,0x9b,0xa1,0xa2,0x90,0x6f,0x5f,0x63,0x67,
0x6c,0x73,0x7b,0x79,0x78,0x85,0x92,0x96,0x9a,0xa2,0xa4,0x8b,0x6c,0x5f,0x63,0x65,
0x6b,0x76,0x7b,0x77,0x7b,0x88,0x93,0x95,0x9a,0xa2,0xa3,0x89,0x69,0x5f,0x62,0x66,
0x6e,0x77,0x7b,0x77,0x7a,0x86,0x92,0x98,0x9d,0xa4,0xa2,0x87,0x66,0x5d,0x61,0x65,
0x6f,0x78,0x7c,0x77,0x7a,0x89,0x92,0x94,0x9b,0xa6,0xa2,0x86,0x68,0x5e,0x5f,0x65,
0x70,0x79,0x7a,0x78,0x7c,0x89,0x90,0x95,0x9f,0xa5,0x9f,0x85,0x65,0x5f,0x63,0x65,
0x6c,0x79,0x7c,0x77,0x7b,0x8c,0x92,0x95,0x9b,0xa8,0xa2,0x82,0x65,0x61,0x62,0x65,
0x6e,0x79,0x7a,0x77,0x7d,0x8b,0x91,0x94,0x9c,0xa7,0xa7,0x87,0x64,0x59,0x5e,0x66,
0x6e,0x7a,0x7f,0x78,0x79,0x88,0x91,0x93,0x99,0xa6,0xa8,0x89,0x66,0x5f,0x61,0x61,
0x68,0x78,0x7f,0x7a,0x7b,0x88,0x8f,0x92,0x99,0xa7,0xa7,0x8f,0x6b,0x5d,0x5d,0x61,
0x69,0x75,0x7e,0x7b,0x7a,0x86,0x91,0x93,0x98,0xa4,0xad,0x97,0x6d,0x5a,0x57,0x5d,
0x66,0x77,0x84,0x80,0x79,0x82,0x8c,0x90,0x95,0xa4,0xac,0x9d,0x72,0x5a,0x58,0x5b,
0x63,0x75,0x83,0x82,0x79,0x82,0x8d,0x8f,0x92,0xa2,0xb1,0xa6,0x7a,0x58,0x53,0x56,
0x60,0x74,0x87,0x86,0x7b,0x7c,0x89,0x8d,0x8f,0x9d,0xb0,0xae,0x89,0x5c,0x52,0x53,
0x5b,0x6c,0x83,0x8a,0x80,0x7c,0x87,0x8a,0x8b,0x98,0xaf,0xb6,0x93,0x62,0x51,0x52,
0x56,0x66,0x83,0x8f,0x81,0x76,0x81,0x8a,0x89,0x92,0xad,0xb9,0xa0,0x71,0x55,0x50,
0x4f,0x5e,0x7b,0x90,0x88,0x7a,0x7a,0x83,0x83,0x8c,0xa6,0xb8,0xb6,0x89,0x59,0x4d,
0x4f,0x57,0x6d,0x89,0x93,0x82,0x78,0x7c,0x84,0x85,0x95,0xaf,0xbf,0xa8,0x71,0x50,
0x4d,0x52,0x5e,0x7a,0x91,0x8c,0x79,0x77,0x80,0x83,0x83,0x9d,0xba,0xc1,0x99,0x5b,
0x47,0x4e,0x57,0x6c,0x8b,0x92,0x7f,0x73,0x7b,0x81,0x82,0x89,0xa3,0xbb,0xbf,0x93,
0x55,0x45,0x4b,0x5c,0x7d,0x98,0x8b,0x6d,0x68,0x7d,0x85,0x85,0x88,0x9f,0xb6,0xc0,
0x9b,0x5c,0x42,0x49,0x5b,0x7a,0x9b,0x98,0x6f,0x5e,0x73,0x85,0x81,0x7e,0x97,0xb4,
0xc7,0xb4,0x74,0x45,0x3f,0x4d,0x70,0x9a,0xa5,0x7d,0x5f,0x69,0x7d,0x7e,0x7a,0x86,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80
};
void setup() {
attachInterrupt(INTIR, irInt, CHANGE);
analogWriteFrequency(16000);
pinMode(LED1_M1F, OUTPUT);
pinMode(LED2_M0F, OUTPUT);
pinMode(LED3_M0B, OUTPUT);
pinMode(LED4_M1B, OUTPUT);
pinMode(LED5, OUTPUT);
pinMode(LED6, OUTPUT);
pinMode(LED_R, OUTPUT);
pinMode(LED_G, OUTPUT);
pinMode(LED_B, OUTPUT);
pinMode(4, OUTPUT);
pinMode(SW1, INPUT_PULLUP);
pinMode(SW2, INPUT_PULLUP);
digitalWrite(LED1_M1F, LED_OFF);
digitalWrite(LED2_M0F, LED_OFF);
digitalWrite(LED3_M0B, LED_OFF);
digitalWrite(LED4_M1B, LED_OFF);
digitalWrite(LED5, LED_OFF);
digitalWrite(LED6, LED_OFF);
randomSeed((unsigned int)analogRead(BATT));
Serial.begin(115200);
Wire.begin();
Wire.beginTransmission(0x68); //Gyro sensor
Wire.write(0x6B); // Power management register
Wire.write(0); // wake up MPU-6050
Wire.endTransmission(true);
SD2.begin(27);
checkVoltage();
selectMode();
pinMode(SW1, INPUT);
pinMode(SW2, INPUT);
pinMode(SOUTPIN, OUTPUT);
analogWrite(SOUTPIN, 0);
delay(100); //allow gyro to stabilize
readEEPROMbal();
readEEPROMadhoc();
resetPara();
resetVar();
digitalWrite(LED6, LED_ON);
calibGyro();
digitalWrite(LED6, LED_OFF);
soundStart(soundGreet, sizeof(soundGreet), 70);
openFiles();
while (soundBusy);
if (demoMode==2) soundStartSD(fDemo, 70);
if (debug) soundStartSD(fDebug, 70);
}
void loop(){
time0=micros();
getIR();
getGyro();
pendulum();
servoHead();
randomPlay();
if (pendPhase!=-1) monitorVoltage();
counter += 1;
if (counter >= 100) {
counter = 0;
counterSec++;
if (debug) digitalWrite(LED6, LED_ON);
if (serialMonitor) sendSerial();
digitalWrite(LED6, LED_OFF);
}
while (micros() - time0 < pendInterval);
}
void pendulum() {
switch (pendPhase) {
case -1: //wait until upright
calcTarget();
if (upright()) {
pendPhase =0;
digitalWrite(LED5, LED_OFF);
}
break;
case 0: //calib Acc
resetVar();
demoDelayCounter=0;
demoPhase=0;
delay(1300);
if (!upright()) pendPhase=2;
else {
digitalWrite(LED6, LED_ON);
calibAcc();
digitalWrite(LED6, LED_OFF);
if (upright()) pendPhase=1;
else pendPhase=2;
}
break;
case 1: //run
if (!standing()) {
if (musicPlaying) soundStop=true;
soundStart(soundWow, sizeof(soundWow), 70);
pendPhase=6;
}
else {
if (demoMode==2) demo8();
calcTarget();
drive();
if (counterOverSpd > maxOverSpd) {
if (musicPlaying) soundStop=true;
delay(1300);
pendPhase=2;
}
}
break;
case 2: //wait until upright
if (upright()) pendPhase=0;
break;
case 6: //fell
if (laid() && !soundBusy) pendPhase=8;
break;
case 8:
if (soundSD) soundStartSD(fTipover, 70);
pendPhase=2;
break;
}
}
void openFiles() {
fGreet=SD2.open("kon168m.wav");
if (!fGreet) {
soundSD=false;
return;
}
soundSD=true;
fStop=SD2.open("tom168m.wav");
fRight=SD2.open("mig168m.wav");
fLeft=SD2.open("hid168m.wav");
fForward=SD2.open("sus168m.wav");
fBack=SD2.open("bac168m.wav");
fSpin=SD2.open("maw168m.wav");
fAccel=SD2.open("kaso168m.wav");
fTipover=SD2.open("koro168m.wav");
fDemo=SD2.open("demo168m.wav");
fDebug=SD2.open("debu168m.wav");
fBattery=SD2.open("denc168m.wav");
fReplace=SD2.open("kouk168m.wav");
voiceFile[0]=SD2.open(soundVoice[0]);
if (voiceFile[0]) {
if (serialMonitor) Serial.println(soundVoice[0]);
minVoiceFile=0;
}
for (int i=1; i<sizeof(soundVoice)/2; i++) {
voiceFile[i]=SD2.open(soundVoice[i]);
if (voiceFile[i]) {
if (serialMonitor) Serial.println(soundVoice[i]);
maxVoiceFile=i;
}
}
if (minVoiceFile==-1 && maxVoiceFile>=1) minVoiceFile=1;
for (int i=0; i<sizeof(soundMusic)/2; i++) {
musicFile[i]=SD2.open(soundMusic[i]);
if (musicFile[i]) {
if (serialMonitor) Serial.println(soundMusic[i]);
minMusicFile=0;
maxMusicFile=i;
}
}
}
void randomPlay() {
if (!randomSoundOn || minVoiceFile==-1) return;
switch (soundPhase) {
case 1:
if (!soundBusy) {
counterSec0=counterSec;
soundInterval=(int)random(MINSINTERVAL, MAXSINTERVAL+1);
soundPhase=2;
}
break;
case 2:
if (counterSec-counterSec0>soundInterval) {
soundId=random(minVoiceFile, maxVoiceFile+1);
soundStartSD(voiceFile[soundId], 10);
if (soundId==0) {
if (minMusicFile!=-1 && demoMode==0) soundPhase=3;
else soundPhase=1;
}
else soundPhase=1;
}
break;
case 3:
if (!soundBusy) {
musicPlaying=true;
soundStartSD(musicFile[random(minMusicFile, maxMusicFile+1)], 10);
soundPhase=1;
}
break;
}
}
void servoHead() {
switch(servoPhase) {
case 1:
servoDrive();
if (servoComplete) {
servoComplete=false;
servoPhase=2;
}
break;
case 2:
servoContinue(90.0, 1.0);
servoPhase=3;
break;
case 3:
servoDrive();
if (servoComplete) {
servoComplete=false;
servoPhase=4;
}
break;
case 4:
break;
}
}
void servoStart(double ang, double stp) {
servoPhase=1;
servoContinue(ang, stp);
}
void servoContinue(double ang, double stp) {
if (ang<servoAngTarget) stp=-stp;
servoAngDestination=ang;
servoAngStep=stp;
}
void servoDrive() {
if (servoAngStep>=0) {
if (servoAngDestination-servoAngStep>servoAngTarget) servoAngTarget+=servoAngStep;
else {
servoAngTarget=servoAngDestination;
servoComplete=true;
}
}
else {
if (servoAngDestination-servoAngStep<servoAngTarget) servoAngTarget+=servoAngStep;
else {
servoAngTarget=servoAngDestination;
servoComplete=true;
}
}
servoPulseWidth=600+(int)(servoAngTarget*10.0);
digitalWrite(4, HIGH);
delayMicroseconds(servoPulseWidth);
digitalWrite(4, LOW);
}
void calcTarget() {
if (spinContinuous) spinTarget += spinStep;
else {
if (spinTarget < spinDestination) spinTarget += spinStep;
if (spinTarget > spinDestination) spinTarget -= spinStep;
}
moveTarget -= moveStep * moveRate;
}
void drive() {
varSpd += power * pendClk;
varDst += Kdst * (varSpd * pendClk - moveTarget);
varIang += KIang * varAng * pendClk;
varIdst += KIdst * varDst * pendClk;
power = varIang + varIdst + varDst + (Kspd * varSpd) + (Kang * varAng) + (Komg * varOmg);
if (abs(power) > 5000.0) counterOverSpd +=1;
else counterOverSpd=0;
if (counterOverSpd > maxOverSpd) {
resetMotor();
return;
}
spinPower = (spinAngle - spinTarget) * Kspin;
powerR = power - spinPower;
powerL = power + spinPower;
motor();
}
void motor() {
ipowerR = (int) (constrain(powerR * mechFactorR * battFactor, -maxSpd, maxSpd));
if (ipowerR > 0) {
if (motorRdir == 1) drvMotorL(ipowerR);
else drvMotorL(ipowerR + backlashSpd); //compensate backlash
motorRdir = 1;
}
else if (ipowerR < 0) {
if (motorRdir == -1) drvMotorL(ipowerR);
else drvMotorL(ipowerR - backlashSpd);
motorRdir = -1;
}
else {
drvMotorL(0);
motorRdir = 0;
}
ipowerL = (int) (constrain(powerL * mechFactorL * battFactor, -maxSpd, maxSpd));
if (ipowerL > 0) {
if (motorLdir == 1) drvMotorR(ipowerL);
else drvMotorR(ipowerL + backlashSpd); //compensate backlash
motorLdir = 1;
}
else if (ipowerL < 0) {
if (motorLdir == -1) drvMotorR(ipowerL);
else drvMotorR(ipowerL - backlashSpd);
motorLdir = -1;
}
else {
drvMotorR(0);
motorLdir = 0;
}
}
void drvMotor0(int pwm) {
if (pwm >0) {
digitalWrite(M0B,LOW);
analogWrite(M0F,constrain(pwm+drvHLbalance, 0,PWMMAX));
}
else if (pwm < 0) {
digitalWrite(M0B,HIGH);
analogWrite(M0F,constrain(PWMMAX+pwm, 0,PWMMAX));
}
else {
digitalWrite(M0B,LOW);
pinMode(M0F, OUTPUT);
digitalWrite(M0F,LOW);
}
}
void drvMotor1(int pwm) {
if (pwm >0) {
digitalWrite(M1B,LOW);
analogWrite(M1F,constrain(pwm+drvHLbalance, 0,PWMMAX));
}
else if (pwm < 0) {
digitalWrite(M1B,HIGH);
analogWrite(M1F,constrain(PWMMAX+pwm, 0,PWMMAX));
}
else {
digitalWrite(M1B,LOW);
pinMode(M1F, OUTPUT);
digitalWrite(M1F,LOW);
}
}
void drvMotorL(int pwm) {
switch (MotorConfig) {
case 0: drvMotor1(pwm);
break;
case 1: drvMotor1(-pwm);
break;
case 2: drvMotor1(pwm);
break;
case 3: drvMotor1(-pwm);
break;
}
}
void drvMotorR(int pwm) {
switch (MotorConfig) {
case 0: drvMotor0(pwm);
break;
case 1: drvMotor0(-pwm);
break;
case 2: drvMotor0(-pwm);
break;
case 3: drvMotor0(pwm);
break;
}
}
void getGyro() {
readGyro();
snsGyroY = (gyroDataY - gyroOffsetY) * gyroLSB;
varOmg = (gyroDataZ - gyroOffsetZ) * gyroLSB; // unit:deg/sec
snsAccX = (accDataX - accOffsetX) * accLSB; //unit:g
spinAngle += snsGyroY * pendClk;
varAng += (varOmg + (snsAccX * 57.3 - varAng) * cutoff ) * pendClk;
//angle filter accX=g*sin(ang) -> accX/g=sin(ang)=ang [rad] (if ang is small) -> ang=accX*57.3[deg]
// varAng += varOmg * pendClk;
}
void readGyro() {
Wire.beginTransmission(0x68);
Wire.write(0x3B);
Wire.endTransmission(false); //enable incremental read
Wire.requestFrom(0x68, 14, (int)true);
accX=Wire.read()<<8|Wire.read(); //0x3B
accY=Wire.read()<<8|Wire.read(); //0x3D
accZ=Wire.read()<<8|Wire.read(); //0x3F
temp=Wire.read()<<8|Wire.read(); //0x41
gyroX=Wire.read()<<8|Wire.read(); //0x43
gyroY=Wire.read()<<8|Wire.read(); //0x45
gyroZ=Wire.read()<<8|Wire.read(); //0x47
gyroDataY = (double) gyroY;
gyroDataZ = -(double) gyroX;
accDataX = -(double) accZ;
aveAccX = aveAccX * 0.9 + accDataX * 0.1;
accDataY = -(double) accY;
aveAccY = aveAccY * 0.9 + accDataY * 0.1;
}
boolean laid() {
if (abs(aveAccX) >13000.0) return true;
else return false;
}
boolean upright() {
if (abs(aveAccY) >13000.0) return true;
else return false;
}
boolean standing() {
if (abs(aveAccY) >8000.0 && abs(varAng) < 40.0) return true;
else {
resetMotor();
return false;
}
}
void calibAcc() {
accOffsetX=0.0;
for (int i=1; i <= 30; i++) {
readGyro();
accOffsetX += accDataX;
delay(20);
}
accOffsetX /= 30.0;
}
void calibGyro() {
gyroOffsetZ=gyroOffsetY=0.0;
for (int i=1; i <= 30; i++) {
readGyro();
gyroOffsetZ += gyroDataZ;
gyroOffsetY += gyroDataY;
delay(20);
}
gyroOffsetY /= 30.0;
gyroOffsetZ /= 30.0;
}
void resetPara() {
Kang=150.0;
Komg=3.0;
KIang=1200.0;
Kspin=15.0;
Kdst=80.0;
Kspd=3.5;
KIdst=0.0;
mechFactorR=0.4;
mechFactorL=0.4;
backlashSpd=30;
}
void resetVar() {
power=0.0;
moveTarget=0.0;
spinDestination=0.0;
spinTarget=0.0;
spinAngle=0.0;
varAng=0.0;
varOmg=0.0;
varDst=0.0;
varSpd=0.0;
varIang=0.0;
varIdst=0.0;
counterOverSpd=0;
spinContinuous=false;
moveRate=0.0;
}
void resetMotor() {
digitalWrite(M0B,LOW);
pinMode(M0F, OUTPUT);
digitalWrite(M0F,LOW);
digitalWrite(M1B,LOW);
pinMode(M1F, OUTPUT);
digitalWrite(M1F,LOW);
}
void checkVoltage() {
monitorVoltage();
if (serialMonitor) {Serial.print("Batt=");Serial.println(bVolt);}
if (bVolt>=0.5 && bVolt<3.8) {
if (soundSD) soundStartSD(fBattery, 70);
blinkLED(5); //Batt Low
if (soundSD) soundStartSD(fReplace, 70);
blinkLED(45);
}
}
void blinkLED(int n) {
for (int i=0; i<n; i++) {
digitalWrite(LED6, LED_ON);
delay(10);
digitalWrite(LED6, LED_OFF);
delay(200);
}
}
void monitorVoltage() {
bVolt=getBattVolt();
aveVolt = aveVolt * 0.98 + bVolt * 0.02;
if (bVolt<0.5) { //USB POWER
battFactor=1.3;
setColor(0,0,1);
}
else {
battFactor = 18.0 / aveVolt / aveVolt;
// battFactor = 4.5 / aveVolt;
// battFactor = 4.5 / bVolt;
if (bVolt<3.6) setColor(0,0,0);
else if (bVolt<4.0) setColor(1,0,0);
else if (bVolt<4.4) setColor(1,1,0);
else setColor(0,1,0);
}
}
double getBattVolt() {
return ((double) analogRead(BATT)) / 1023.0 * 6.6;
}
void selectMode() {
if (digitalRead(SW1) == LOW) { //debug
debug=true;
serialMonitor=true;
spinStep=0.0;
blinkLED(1);
}
else if (digitalRead(SW2) == LOW) { //demo
demoMode=2;
blinkLED(2);
}
else spinStep=0.0;
}
void demo8() {
switch (demoPhase) {
case 0:
demoDelayCounter=200;
demoPhase=1;
break;
case 1:
if (demoDelayCounter>1) demoDelayCounter--;
else {
moveRate=3.0;
spinStep=0.5;
spinDestination += 270.0;
demoPhase=2;
}
break;
case 2:
if (abs(spinTarget-spinDestination)<5.0) {
demoDelayCounter=100;
moveRate=5.0;
demoPhase=3;
}
break;
case 3:
if (demoDelayCounter>1) demoDelayCounter--;
else {
moveRate=3.0;
spinDestination -= 270.0;
demoPhase=4;
}
break;
case 4:
if (abs(spinTarget-spinDestination)<5.0) {
demoDelayCounter=100;
moveRate=5.0;
demoPhase=1;
}
break;
}
}
void setColor(int r, int g, int b) {
digitalWrite(LED_R, r);
digitalWrite(LED_G, g);
digitalWrite(LED_B, b);
}
void readEEPROMbal() {
if (EEPROM.read(0)==HCODE) {
drvHLbalance=EEPROM.read(1);
if (serialMonitor) {Serial.print("drvHLbal=");Serial.println(drvHLbalance);}
}
else {
drvHLbalance=30;
noInterrupts();
EEPROM.write(0, HCODE);
EEPROM.write(1, drvHLbalance);
interrupts();
}
}
void writeEEPROMbal() {
noInterrupts();
EEPROM.write(1, drvHLbalance);
interrupts();
}
void readEEPROMadhoc() {
if (EEPROM.read(2)==HCODE) {
for (int i=0; i<ADHOC_IR_MAX; i++) {
ADHOC_CUSTOMER[i]=EEPROM.read(3+i*4)<<8|EEPROM.read(4+i*4);
ADHOC_IR[i]=EEPROM.read(5+i*4)<<8|EEPROM.read(6+i*4);
if (serialMonitor) {
Serial.print("CUST=");Serial.print(ADHOC_CUSTOMER[i],HEX);Serial.print(" CODE=");Serial.println(ADHOC_IR[i],HEX);
}
}
}
}
void writeEEPROMadhoc() {
noInterrupts();
EEPROM.write(2, HCODE);
for (int i=0; i<ADHOC_IR_MAX; i++) {
EEPROM.write(3+i*4, (byte)((ADHOC_CUSTOMER[i]>>8)&0xFF));
EEPROM.write(4+i*4, (byte)(ADHOC_CUSTOMER[i]&0xFF));
EEPROM.write(5+i*4, (byte)((ADHOC_IR[i]>>8)&0xFF));
EEPROM.write(6+i*4, (byte)(ADHOC_IR[i]&0xFF));
}
interrupts();
}
void sendSerial () {
Serial.print(micros()-time0);
Serial.print(" phase=");Serial.print(pendPhase);
Serial.print(" accX="); Serial.print(aveAccX);
Serial.print(" accY="); Serial.print(aveAccY);
Serial.print(" ang=");Serial.print(varAng);
// Serial.print(" temp = "); Serial.print(temp/340.0+36.53);
Serial.print(" drvBal="); Serial.print(drvHLbalance);
Serial.print(F(" apinA=")); Serial.print(spinAngle);
Serial.print(F(" batt=")); Serial.print(aveVolt);
Serial.print(", ");
Serial.print(micros()-time0);
Serial.println();
}
void getIR() {
if (!(irStarted && (micros()-irMicroOff>10000))) return;
if ((irDataOn[0]>1800) && musicPlaying) soundStop=true;
irStarted=false;
irDecoding=true;
if (irDataOn[0]>7000) { //NEC
if (irOffIndex >=33) {
decodeNECAEHA();
printIrData("NEC");
}
}
else if (irDataOn[0]>2600) { //AEHA
if (irOffIndex >=41) {
decodeNECAEHA();
printIrData("AEHA");
}
}
else if (irDataOn[0]>1800) { //SONY
if (irOnIndex >=12) {
decodeSONY();
printIrData("SONY");
}
}
if (irReady) {
irReady=false;
lastIrTime=millis();
if (serialMonitor) {
Serial.print("IR code=");Serial.println(ircode, HEX);
Serial.print("Cust Code=");Serial.println(customer_code, HEX);
}
if (adhoc_ir_num>=0 && adhoc_ir_num<ADHOC_IR_MAX && pendPhase==-1) regIR();
else irCommand();
}
irDecoding=false;
}
void irCommand() {
if (
((ircode==AKI_REMO_CENTER)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_CENTER])&&(customer_code==ADHOC_CUSTOMER[IR_CENTER])) ) {
if (pendPhase!=-1) {
if (abs(moveRate)>1.0 || abs(spinStep)>0.1) {
if (soundSD) soundStartSD(fStop, 10);
else tone(TONE_PIN, 500, 100);
}
button=5;
demoMode=0;
spinContinuous=false;
spinStep=0.0;
moveRate=0.0;
spinDestination = spinTarget;
}
}
else if (
((ircode==AKI_REMO_RIGHT)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_RIGHT])&&(customer_code==ADHOC_CUSTOMER[IR_RIGHT])) ) {
if (pendPhase==-1) {
servoStart(60.0, 0.5);
drvMotorR(-80);
delay(1000);
drvMotorR(0);
}
else if (demoMode==0) {
servoStart(headRight, 3.0);
if (button!=6) {
if (soundSD) soundStartSD(fRight, 10);
else tone(TONE_PIN, 2000, 100);
}
button=6;
if (spinContinuous) spinDestination=spinTarget;
spinContinuous=false;
spinStep=0.6;
spinDestination -= 30.0;
}
}
else if (
((ircode==AKI_REMO_LEFT)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_LEFT])&&(customer_code==ADHOC_CUSTOMER[IR_LEFT])) ) {
if (pendPhase==-1) {
servoStart(120.0, 0.5);
drvMotorL(-80);
delay(1000);
drvMotorL(0);
}
else if (demoMode==0) {
servoStart(headLeft, 3.0);
if (button!=4) {
if (soundSD) soundStartSD(fLeft, 10);
else tone(TONE_PIN, 2000, 100);
}
button=4;
if (spinContinuous) spinDestination=spinTarget;
spinContinuous=false;
spinStep=0.6;
spinDestination += 30.0;
}
}
else if (
((ircode==AKI_REMO_UP)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_UP])&&(customer_code==ADHOC_CUSTOMER[IR_UP])) ) {
if (pendPhase!=-1 && demoMode==0) {
button=2;
if (abs(moveRate)<1.0) {
if (soundSD) soundStartSD(fForward, 10);
else tone(TONE_PIN, 1000, 100);
}
if (moveRate>10.0) {
if (soundSD) soundStartSD(fAccel, 70);
else soundStart(soundWow, sizeof(soundWow), 10);
}
moveRate+=4.0;
}
}
else if (
((ircode==AKI_REMO_DOWN)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_DOWN])&&(customer_code==ADHOC_CUSTOMER[IR_DOWN])) ) {
if (pendPhase!=-1 && demoMode==0) {
button=8;
if (abs(moveRate)<1.0) {
if (soundSD) soundStartSD(fBack, 10);
else tone(TONE_PIN, 1000, 100);
}
moveRate-=4.0;
}
}
else if (
((ircode==AKI_REMO_UL)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_CIRL])&&(customer_code==ADHOC_CUSTOMER[IR_CIRL])) ) {
if (pendPhase!=-1 && demoMode==0) {
button=1;
if (abs(spinStep)<0.1) {
if (soundSD) soundStartSD(fSpin, 10);
else tone(TONE_PIN, 2000, 20);
}
if (!spinContinuous) spinStep=0.0;
spinContinuous=true;
spinStep+=0.3;
}
}
else if (
((ircode==AKI_REMO_UR)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_CIRR])&&(customer_code==ADHOC_CUSTOMER[IR_CIRR])) ) {
if (pendPhase!=-1 && demoMode==0) {
button=3;
if (abs(spinStep)<0.1) {
if (soundSD) soundStartSD(fSpin, 10);
else tone(TONE_PIN, 2000, 20);
}
if (!spinContinuous) spinStep=0.0;
spinContinuous=true;
spinStep-=0.3;
}
}
else if (
((ircode==AKI_REMO_DL)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_BALF])&&(customer_code==ADHOC_CUSTOMER[IR_BALF])) ) {
if (demoMode==0) {
if (moveRate==0.0 && spinTarget==spinDestination) {
if (drvHLbalance<100) {
drvHLbalance-=5;
setColor(1,0,1);
digitalWrite(LED5,LED_ON);
writeEEPROMbal();
digitalWrite(LED5,LED_OFF);
}
}
}
}
else if (
((ircode==AKI_REMO_DR)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_BALB])&&(customer_code==ADHOC_CUSTOMER[IR_BALB])) ) {
if (demoMode==0) {
if (moveRate==0.0 && spinTarget==spinDestination) {
if (drvHLbalance>-100) {
drvHLbalance+=5;
setColor(1,0,1);
digitalWrite(LED5,LED_ON);
writeEEPROMbal();
digitalWrite(LED5,LED_OFF);
}
}
}
}
else {
if (pendPhase == -1 && debug && adhoc_ir_num==-1) {
setColor(1,0,1);
digitalWrite(LED5, LED_ON);
randomSoundOn=false;
adhoc_ir_num=0;
}
}
}
void regIR() {
// Ad hoc IR code registration
if (adhoc_ir_num<ADHOC_IR_MAX) {
ADHOC_IR[adhoc_ir_num]=ircode;
ADHOC_CUSTOMER[adhoc_ir_num]=customer_code;
if (serialMonitor) {
Serial.print("set ADHOC_IR[");
Serial.print(adhoc_ir_num);
Serial.print("] = ");
Serial.println(ircode, HEX);
Serial.print("set ADHOC_CUSTOMER[");
Serial.print(adhoc_ir_num);
Serial.print("] = ");
Serial.println(customer_code, HEX);
}
if (adhoc_ir_num==0) adhoc_ir_num++;
else if (ADHOC_IR[adhoc_ir_num-1]!=ircode) adhoc_ir_num++;
for (int i=1; i<=adhoc_ir_num; i++) {
digitalWrite(LED5, LED_OFF);
delay(200);
digitalWrite(LED5, LED_ON);
delay(100);
}
if (adhoc_ir_num==ADHOC_IR_MAX) {
writeEEPROMadhoc();
digitalWrite(LED5, LED_OFF);
randomSoundOn=true;
}
}
}
void irInt() {
if (millis()-lastIrTime<250) return;
if (irDecoding) return;
if (digitalRead(IRIN) == IRON) {
irMicroOn=micros();
if (irStarted) {
irDataOff[irOffIndex]=irMicroOn-irMicroOff;
irOffIndex++;
if (irOffIndex>=IRBUFFLEN) irStarted=false;
}
else {
irStarted=true;
irOnIndex=0;
irOffIndex=0;
irMicroOff=irMicroOn;
}
}
else {
irMicroOff=micros();
irDataOn[irOnIndex]=irMicroOff-irMicroOn;
irOnIndex++;
if (irOnIndex>=IRBUFFLEN) irStarted=false;
}
}
void decodeNECAEHA() {
int len=irOffIndex/8;
int idx=1;
for (int i=0; i<len; i++) {
irData[i]=0;
for (int j=0; j<8; j++) {
irData[i]>>=1;
if (irDataOff[idx]>1000) irData[i]|=0x80;
idx++;
}
}
customer_code=irData[0]<<8|irData[1];
ircode=irData[len-2]<<8|irData[len-1];
irReady=true;
}
void decodeSONY() {
byte data=0;
for (int i=1; i<=7; i++) {
if (irDataOn[i]>900) data|=0x80;
data>>=1;
}
unsigned int addr=0;
int idx=8;
for (int i=0; i<16; i++) {
addr>>=1;
if (idx<irOnIndex && irDataOn[idx]<1800) {
if (irDataOn[idx]>900) addr|=0x8000;
idx++;
}
}
customer_code=addr;
ircode=(unsigned int)data;
irReady=true;
}
void printIrData(String s) {
if (!serialMonitor) return;
Serial.println(s);
Serial.print("Customer=");Serial.println(customer_code, HEX);
Serial.print("Code=");Serial.println(ircode, HEX);
/*
for (int i=0; i<irOffIndex; i++) {
Serial.print(irDataOn[i]);Serial.print(" ");Serial.println(irDataOff[i]);
}
Serial.println("");
*/
}
void soundIntSD() {
if (sdfile.available() && !soundStop) {
byte d=sdfile.read();
if (soundGain!=10) {
int di=(int)d-128;
di=(di*soundGain)/10;
d=(byte)constrain((di+128), 10, 250);
}
else d=constrain(d, 10, 250);
analogWrite(SOUTPIN, d);
}
else {
detachInterrupt(INTSOUND);
analogWrite(SOUTPIN, 0);
musicPlaying=false;
soundBusy=false;
}
}
void soundStartSD(File s, int gain) {
if (soundBusy || !soundSD || !soundOn) return;
sdfile=s;
soundBusy=true;
soundStop=false;
if (sdfile.seek(44)) {
soundGain=gain;
attachInterrupt(INTSOUND, soundIntSD, RISING);
analogWrite(SOUTPIN, 128);
}
}
void soundStart(const byte* ptr, unsigned long sz, int gain) {
if (soundBusy || !soundOn) return;
counterSec0=counterSec;
soundBusy=true;
soundIndex=0;
soundPtr=ptr;
soundSize=sz;
soundGain=gain;
attachInterrupt(INTSOUND, soundInt, RISING);
analogWrite(SOUTPIN, 128);
}
void soundInt() {
byte d=soundPtr[soundIndex];
if (soundGain!=10) {
int di=(int)d-128;
di=(di*soundGain)/10;
d=(byte)constrain((di+128), 10, 250);
}
else d=constrain(d, 10, 250);
analogWrite(SOUTPIN, d);
soundIndex++;
if (soundIndex>=soundSize) {
detachInterrupt(INTSOUND);
analogWrite(SOUTPIN, 0);
soundBusy=false;
}
}

2017年6月21日水曜日

GR-ADZUKIで倒立振子ロボADZUMIN v40

//ADZUMIN Inverted Pendulum Robot
//Copyright MAENOH! & KIRAKULABO 2017
//wheele dia ~= 58mm
//Gear ratio ~= 114 (TAMIYA Double Gear Box)
//Battery: Alkaline x 3
//MPU/Driver: GR-ADZUKI
//Gyro/Acc: MPU6050 (I2C)
//Adhoc IR remote control registration during laying just after power up.
//SW1: Stand still with debug and serialMonito on (1 blink)
//SW2: demo (2 blinks)
//Default: Stand still (no blink)
#include "Arduino.h"
#include <Wire.h>
#include <EEPROM.h>
#include <SD.h>
#define LED_R 22
#define LED_G 23
#define LED_B 24
#define HCODE 0x4D //M
#define PWMMAX 255
#define M1F 6
#define M0F 9
#define M0B 10
#define M1B 11
#define LED1_M1F 6
#define LED2_M0F 9
#define LED3_M0B 10
#define LED4_M1B 11
#define LED5 12
#define LED6 13
#define LED_ON 1
#define LED_OFF 0
#define SW1 3
#define SW2 2
#define GP2Y A0
#define BATT A1
#define TONE_PIN 5
#define AKI_REMO_CUSTOMER (0x10EF)
#define AKI_REMO_POWER (0xD827)
#define AKI_REMO_A (0xF807)
#define AKI_REMO_B (0x7887)
#define AKI_REMO_C (0x58A7)
#define AKI_REMO_UP (0xA05F)
#define AKI_REMO_DOWN (0x00FF)
#define AKI_REMO_RIGHT (0x807F)
#define AKI_REMO_LEFT (0x10EF)
#define AKI_REMO_CENTER (0x20DF)
#define AKI_REMO_UR (0x21DE)
#define AKI_REMO_UL (0xB14E)
#define AKI_REMO_DR (0x817E)
#define AKI_REMO_DL (0x11EE)
#define SW_ON 0
#define SW_OFF 1
#define SOUTPIN 5
#define SINTPIN 3
#define INTSOUND 1
#define IRIN 2 // IR RECEIVE PIN
#define INTIR 0 // IR RECEIVE interrupt number
#define IRON LOW
#define IROFF HIGH
#define IRBUFFLEN 200
// Ad hoc IR code
#define IR_UP 1
#define IR_DOWN 7
#define IR_RIGHT 5
#define IR_LEFT 3
#define IR_CENTER 4
#define IR_CIRL 0
#define IR_CIRR 2
#define IR_BALF 6
#define IR_BALB 8
#define ADHOC_IR_MAX 9
#define MAXSINTERVAL 15
#define MINSINTERVAL 5
unsigned int ADHOC_CUSTOMER[ADHOC_IR_MAX] = {0xFFFF,0xFFFF,0XFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF}; //1,2,3,4,5,6,7,8,9
unsigned int ADHOC_IR[ADHOC_IR_MAX] = {0xFFFF,0xFFFF,0XFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF,0xFFFF}; // 1,2,3,4,5,6,7,8,9
int adhoc_ir_num=-1;
void selectMode();
void sendSerial();
void resetPara();
void resetVar();
void getGyro();
void readGyro();
void calibGyro();
void calibAcc();
void calcTarget();
void drive();
void motor();
void resetMotor();
boolean laid();
boolean upright();
boolean standing();
void drvMotorL(int pwm);
void drvMotorR(int pwm);
void checkVoltage();
void monitorVoltage();
double getBattVolt();
void blinkLED(int n);
void setColor(int r, int g, int b);
void readEEPROMbal();
void writeEEPROMbal();
void readEEPROMadhoc();
void writeEEPROMadhoc();
void demo8();
void getIR();
void regIR();
void printIrData();
void decodeNECAEHA();
void decodeSONY();
void irInt();
void irCommand();
void printIrData(String s);
void soundIntSD();
void soundInt();
void soundStartSD(File s, int gain);
void soundStart(const byte* ptr, unsigned long sz, int gain);
void servoStart(double ang, double stp);
void servoContinue(double ang, double stp);
void servoDrive();
void pendulum();
void servoHead();
void randomPlay();
void openFiles();
int button=0;
volatile unsigned long irMicroOn;
volatile unsigned long irMicroOff;
volatile unsigned int irDataOn[200];
volatile unsigned int irDataOff[200];
volatile int irOnIndex=0;
volatile int irOffIndex=0;
volatile boolean irStarted=false;
volatile boolean irDecoding=false;
volatile unsigned long lastIrTime=0;
boolean irReady=false;
byte irData[30];
unsigned int ircode;
unsigned int customer_code;
int MotorConfig = 0; // 0 to 3
int accX, accY, accZ, temp, gyroX, gyroY, gyroZ;
int counter=0;
volatile int counterSec=0;
volatile int counterSec0=0;
unsigned long time1=0;
unsigned long time0=0;
double power, powerR, powerL;
double snsGyroY, snsAccX;
double varAng, varOmg, varSpd, varDst, varIang, varIdst;
double gyroOffsetY, gyroOffsetZ, accOffsetX;
double gyroDataY, gyroDataZ, accDataX, accDataY;
double gyroLSB=1.0/131.0; // deg/sec
double accLSB=1.0/16384.0; // g
double pendClk = 0.01; // in sec,
unsigned long pendInterval = 10000; // in usec
double cutoff = 0.1; // 2 * PI * f (f=Hz) //0.1
double Kang, Komg, Kdst, Kspd, Kspin, KIang, KIdst;
double spinPower;
double moveTarget, moveRate=0.0; //moveRate 0:stop, +:forward, -:backward
double moveStep = 0.0013;
double spinDestination, spinTarget;
double spinStep = 0.0;
double spinAngle;
boolean spinContinuous=false;
int pendPhase=-1;
int ipowerR = 0;
int ipowerL = 0;
int motorRdir=0; //stop 1:+ -1:-
int motorLdir=0; //stop
int backlashSpd;
double mechFactorR, mechFactorL;
double battFactor=1.3; // 2016.07.14
double bVolt;
double maxSpd=250.0;
int counterOverSpd;
int maxOverSpd=15;
double aveAccX=0.0;
double aveAccY=0.0;
boolean debug=false;
boolean serialMonitor=false;
double aveVolt=4.5;
boolean usbPower=false;
int8_t drvHLbalance=0;
int demoPhase=0;
int demoDelayCounter=0;
int demoMode=0;
int servoPhase=1;
boolean servoComplete=false;
int servoPulseWidth=1500;
double servoAngDestination=90.0;
double servoAngTarget=90.0;
double servoAngStep=1.0;
int servoWidth=1500; //in usec
File voiceFile[11];
File musicFile[10];
File sdfile;
File fGreet, fStop, fRight, fLeft, fForward, fBack, fSpin, fAccel, fTipover, fDemo, fDebug, fBattery, fReplace;
volatile boolean soundBusy=false;
volatile unsigned long soundIndex=0;
volatile const byte *soundPtr;
volatile unsigned long soundSize;
volatile int soundGain=10; //10=100%
boolean soundSD;
boolean soundFlg=false;
int soundInterval=MAXSINTERVAL;
volatile boolean soundStop=false;
int soundId;
boolean musicPlaying=false;
boolean soundOn=true;
boolean randomSoundOn=true;
int soundPhase=1;
int maxVoiceFile=0;
int minVoiceFile=-1;
int maxMusicFile=0;
int minMusicFile=-1;
const char *soundVoice[] = {"vmu_168m.wav", "v1_168m.wav", "v2_168m.wav", "v3_168m.wav", "v4_168m.wav", "v5_168m.wav", "v6_168m.wav", "v7_168m.wav", "v8_168m.wav", "v9_168m.wav", "v10_168m.wav"};
const char *soundMusic[] = {"mu1_168m.wav", "mu2_168m.wav", "mu3_168m.wav", "mu4_168m.wav", "mu5_168m.wav", "mu6_168m.wav", "mu7_168m.wav", "mu8_168m.wav", "mu9_168m.wav", "mu10_168m.wav"};
const double headLeft=150.0;
const double headRight=30.0;
const byte soundGreet[] = {
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x75,0x74,0x71,0x6e,
0x6f,0x73,0x7b,0x81,0x8b,0x8e,0x8e,0x8c,0x8a,0x86,0x80,0x7e,0x80,0x7f,0x81,0x80,
0x80,0x7f,0x7e,0x80,0x78,0x77,0x76,0x7c,0x7f,0x84,0x8d,0x8f,0x95,0x92,0x8e,0x86,
0x80,0x7d,0x79,0x79,0x7c,0x7f,0x80,0x80,0x7d,0x79,0x7a,0x7a,0x7d,0x7f,0x84,0x87,
0x88,0x88,0x87,0x85,0x85,0x81,0x72,0x67,0x60,0x61,0x68,0x76,0x85,0x90,0x98,0x96,
0x8c,0x81,0x7d,0x7e,0x80,0x86,0x89,0x8b,0x8a,0x88,0x81,0x76,0x78,0x77,0x7c,0x82,
0x8a,0x91,0x92,0x8d,0x80,0x73,0x6a,0x69,0x6a,0x71,0x7b,0x84,0x85,0x84,0x80,0x7a,
0x75,0x73,0x74,0x73,0x77,0x7b,0x7f,0x81,0x87,0x8d,0x90,0x91,0x8f,0x8a,0x82,0x7c,
0x77,0x71,0x70,0x74,0x79,0x81,0x8d,0x9a,0xa1,0xa2,0x9c,0x93,0x85,0x78,0x70,0x6a,
0x69,0x6a,0x6d,0x6d,0x6f,0x72,0x72,0x71,0x75,0x7d,0x85,0x8e,0x96,0x97,0x93,0x8c,
0x84,0x78,0x72,0x73,0x76,0x7b,0x7f,0x80,0x80,0x80,0x7f,0x7e,0x76,0x71,0x6d,0x70,
0x78,0x81,0x8d,0x94,0x98,0x94,0x8e,0x84,0x7f,0x7e,0x7f,0x81,0x84,0x88,0x89,0x87,
0x83,0x7b,0x72,0x6c,0x6a,0x6b,0x6e,0x78,0x7f,0x86,0x8b,0x8e,0x8f,0x8e,0x8b,0x87,
0x83,0x7d,0x77,0x70,0x68,0x62,0x60,0x63,0x6a,0x78,0x89,0x96,0xa1,0xa3,0xa1,0x98,
0x91,0x8a,0x86,0x82,0x86,0x7e,0x7d,0x76,0x57,0x52,0x50,0x60,0x78,0xa2,0xbe,0xc9,
0xc8,0xac,0x83,0x60,0x57,0x57,0x66,0x7c,0x90,0x92,0x8b,0x7d,0x67,0x56,0x57,0x5f,
0x6d,0x81,0x95,0x9b,0x94,0x89,0x7b,0x70,0x6f,0x78,0x80,0x88,0x88,0x82,0x72,0x68,
0x64,0x69,0x73,0x83,0x90,0x95,0x98,0x91,0x8e,0x8b,0x93,0x9d,0x9f,0xa1,0x95,0x82,
0x6a,0x5c,0x5c,0x67,0x87,0x92,0x97,0x94,0x7d,0x65,0x53,0x5e,0x75,0x9b,0xbc,0xbc,
0xa9,0x92,0x75,0x5a,0x4d,0x50,0x5d,0x6d,0x7c,0x81,0x7d,0x7a,0x74,0x6b,0x66,0x6c,
0x78,0x83,0x8a,0x8c,0x89,0x80,0x7b,0x76,0x76,0x7a,0x83,0x8a,0x8c,0x8d,0x8d,0x8c,
0x88,0x8d,0x91,0x9a,0xa3,0xad,0xad,0xa6,0xa3,0xa2,0xa4,0xa4,0x8b,0x66,0x50,0x3c,
0x33,0x33,0x3f,0x53,0x6d,0x8c,0x9a,0x9e,0xa4,0xa8,0x9f,0x91,0x87,0x7a,0x72,0x6d,
0x64,0x58,0x52,0x54,0x58,0x5c,0x66,0x74,0x82,0x8a,0x90,0x90,0x8c,0x89,0x87,0x84,
0x83,0x86,0x8a,0x88,0x87,0x89,0x8b,0x8b,0x8e,0x90,0x94,0x9b,0xa2,0xaa,0xa8,0xb0,
0xa8,0xac,0x8f,0x66,0x57,0x3d,0x39,0x45,0x5b,0x69,0x84,0x94,0x8e,0x86,0x81,0x82,
0x7d,0x84,0x8e,0x91,0x92,0x91,0x81,0x6b,0x5b,0x54,0x50,0x54,0x62,0x74,0x7d,0x83,
0x81,0x7c,0x75,0x77,0x7a,0x7d,0x87,0x91,0x93,0x8b,0x84,0x7c,0x77,0x78,0x7c,0x86,
0x8e,0x97,0x9b,0x96,0x99,0x97,0x9e,0xa3,0xb0,0xb6,0xb5,0xb0,0x7e,0x5f,0x55,0x40,
0x38,0x4b,0x5d,0x6a,0x80,0x89,0x80,0x81,0x8c,0x8a,0x87,0x94,0x9f,0x96,0x8d,0x81,
0x6a,0x5c,0x5b,0x5b,0x5d,0x67,0x73,0x75,0x72,0x73,0x77,0x7a,0x82,0x8a,0x8e,0x90,
0x8f,0x87,0x7c,0x76,0x77,0x7a,0x7c,0x7e,0x80,0x7d,0x79,0x74,0x76,0x7c,0x8a,0x97,
0xa2,0xab,0xb5,0xbb,0xbd,0xc1,0xc2,0xc1,0xa0,0x72,0x45,0x2d,0x26,0x2a,0x3d,0x50,
0x70,0x88,0x8f,0x80,0x7f,0x8e,0x9a,0xa7,0xa9,0xa8,0xa2,0x97,0x7f,0x5b,0x46,0x45,
0x4d,0x54,0x5f,0x6b,0x72,0x78,0x79,0x77,0x7b,0x89,0x95,0x97,0x96,0x90,0x88,0x7d,
0x75,0x71,0x74,0x7b,0x82,0x83,0x82,0x80,0x83,0x85,0x8e,0x9b,0xab,0xbb,0xc6,0xd0,
0xd0,0xcb,0x9c,0x78,0x5a,0x32,0x25,0x30,0x40,0x59,0x6c,0x6e,0x70,0x70,0x80,0x89,
0x96,0xb0,0xbf,0xbb,0xa5,0x8a,0x6f,0x5b,0x56,0x57,0x5f,0x68,0x71,0x69,0x58,0x56,
0x5b,0x6b,0x7d,0x93,0x9f,0xa2,0x9c,0x8d,0x7c,0x75,0x7a,0x80,0x84,0x85,0x82,0x77,
0x6c,0x65,0x67,0x72,0x87,0x99,0xa6,0xaf,0xb5,0xb7,0xbd,0xc6,0xd1,0xde,0xb9,0x84,
0x5c,0x35,0x18,0x17,0x2a,0x45,0x6c,0x76,0x74,0x6e,0x7b,0x8f,0x97,0xab,0xbc,0xc5,
0xb9,0x9b,0x76,0x5b,0x53,0x53,0x55,0x58,0x63,0x69,0x63,0x54,0x56,0x67,0x7e,0x93,
0x9f,0xa3,0xa0,0x9b,0x88,0x77,0x74,0x7d,0x7f,0x7e,0x7a,0x74,0x70,0x6e,0x6f,0x78,
0x88,0x9d,0xac,0xb2,0xb9,0xbc,0xc4,0xcf,0xe5,0xb4,0x7f,0x77,0x3b,0x19,0x27,0x37,
0x4c,0x61,0x78,0x63,0x62,0x7b,0x7a,0x85,0xad,0xc8,0xb7,0xb4,0xa5,0x89,0x6d,0x57,
0x54,0x57,0x69,0x65,0x59,0x4f,0x4d,0x5f,0x68,0x75,0x8e,0xa8,0xa8,0x9a,0x8d,0x7d,
0x7d,0x81,0x80,0x7c,0x85,0x88,0x7d,0x6a,0x6b,0x72,0x7b,0x89,0x9b,0xab,0xb1,0xb0,
0xa5,0xb1,0xb4,0xc8,0xc6,0xb2,0x83,0x4e,0x35,0x1b,0x31,0x4f,0x63,0x68,0x6f,0x69,
0x5d,0x71,0x85,0x96,0xb0,0xbe,0xb9,0xa6,0x97,0x7f,0x6a,0x5b,0x53,0x54,0x5f,0x67,
0x5e,0x5a,0x55,0x5a,0x6b,0x7f,0x92,0xa3,0xab,0x9e,0x8e,0x82,0x7b,0x7b,0x7f,0x84,
0x80,0x81,0x7b,0x72,0x6f,0x78,0x85,0x94,0xa3,0xad,0xb4,0xbc,0xc2,0xc6,0xd0,0xae,
0x96,0x74,0x49,0x3b,0x38,0x3d,0x44,0x56,0x4e,0x4a,0x52,0x60,0x77,0x92,0xaf,0xb6,
0xba,0xb2,0xa0,0x90,0x85,0x7f,0x76,0x6f,0x62,0x58,0x4d,0x48,0x49,0x53,0x65,0x78,
0x88,0x91,0x95,0x95,0x94,0x8f,0x90,0x90,0x8f,0x8a,0x83,0x78,0x70,0x6c,0x6c,0x70,
0x7b,0x87,0x91,0x9b,0xa1,0xa8,0xaf,0xbd,0xc7,0xda,0xc4,0xa9,0x8d,0x5d,0x4c,0x42,
0x43,0x49,0x57,0x58,0x4c,0x4f,0x54,0x64,0x7c,0x96,0xa7,0xaf,0xb2,0xa4,0x97,0x8b,
0x85,0x7f,0x7a,0x70,0x63,0x58,0x4d,0x4a,0x4e,0x5b,0x6b,0x79,0x82,0x87,0x8b,0x8e,
0x8f,0x91,0x93,0x94,0x90,0x8c,0x85,0x7f,0x7f,0x7e,0x80,0x84,0x8a,0x8f,0x97,0x9f,
0xaa,0xb4,0xc5,0xc7,0xac,0x9a,0x79,0x60,0x58,0x55,0x57,0x5c,0x61,0x54,0x4b,0x4e,
0x57,0x6b,0x83,0x95,0x9e,0xa2,0x9e,0x94,0x8c,0x8a,0x8b,0x8b,0x83,0x77,0x68,0x5a,
0x51,0x51,0x59,0x65,0x74,0x7a,0x79,0x79,0x7c,0x80,0x88,0x92,0x97,0x96,0x92,0x88,
0x7f,0x7d,0x80,0x84,0x89,0x8d,0x8e,0x8e,0x91,0x95,0xa3,0xb2,0xc3,0xca,0xb0,0x9d,
0x7e,0x63,0x5c,0x5b,0x60,0x62,0x67,0x55,0x47,0x47,0x4d,0x62,0x7c,0x91,0x99,0x9e,
0x98,0x8d,0x8a,0x8c,0x90,0x92,0x8e,0x7e,0x6f,0x60,0x56,0x54,0x5c,0x68,0x71,0x77,
0x73,0x72,0x73,0x78,0x80,0x8b,0x93,0x96,0x94,0x8d,0x86,0x85,0x87,0x8a,0x8e,0x90,
0x90,0x91,0x93,0x95,0xa2,0xa9,0xb9,0xb9,0xa1,0x95,0x78,0x68,0x65,0x66,0x67,0x6a,
0x6b,0x57,0x4c,0x4c,0x52,0x65,0x7c,0x8a,0x8e,0x93,0x8d,0x86,0x88,0x8c,0x90,0x94,
0x8e,0x80,0x73,0x67,0x5f,0x5f,0x65,0x6b,0x72,0x70,0x6c,0x6c,0x6e,0x74,0x7f,0x8a,
0x90,0x93,0x90,0x8a,0x88,0x8a,0x8e,0x93,0x96,0x97,0x95,0x95,0x94,0x9b,0xa3,0xaf,
0xb1,0xa3,0x97,0x80,0x70,0x6a,0x66,0x69,0x6c,0x6c,0x60,0x55,0x52,0x54,0x61,0x72,
0x7e,0x86,0x8b,0x88,0x83,0x85,0x89,0x8e,0x93,0x91,0x87,0x7d,0x72,0x69,0x67,0x6c,
0x70,0x74,0x73,0x6f,0x6c,0x6c,0x70,0x77,0x82,0x88,0x8c,0x8b,0x88,0x85,0x87,0x8b,
0x8f,0x93,0x96,0x96,0x93,0x93,0x96,0x9c,0xa4,0xaf,0xa9,0x9d,0x93,0x7e,0x74,0x70,
0x6e,0x6f,0x71,0x6c,0x5d,0x58,0x56,0x59,0x65,0x72,0x79,0x7e,0x82,0x7e,0x7e,0x83,
0x88,0x8e,0x91,0x8f,0x87,0x80,0x77,0x73,0x73,0x75,0x77,0x77,0x72,0x6e,0x6c,0x6c,
0x70,0x77,0x7e,0x82,0x86,0x86,0x84,0x86,0x89,0x8b,0x90,0x93,0x95,0x94,0x95,0x94,
0x97,0x99,0xa1,0xa1,0x98,0x95,0x86,0x7e,0x7a,0x78,0x74,0x75,0x73,0x67,0x62,0x5f,
0x5f,0x64,0x6c,0x71,0x73,0x79,0x77,0x79,0x7b,0x80,0x84,0x88,0x89,0x86,0x86,0x80,
0x7f,0x7d,0x7e,0x7e,0x7f,0x7c,0x78,0x76,0x74,0x75,0x77,0x7a,0x7c,0x7e,0x7f,0x7e,
0x7f,0x83,0x85,0x8a,0x8d,0x8f,0x8f,0x91,0x8f,0x92,0x95,0x9a,0x9c,0x97,0x94,0x8b,
0x85,0x82,0x7f,0x7d,0x7c,0x7a,0x72,0x6c,0x68,0x66,0x69,0x6d,0x71,0x72,0x75,0x74,
0x74,0x76,0x79,0x7e,0x82,0x85,0x84,0x84,0x81,0x81,0x80,0x81,0x83,0x83,0x82,0x7f,
0x7e,0x7b,0x7b,0x7d,0x7d,0x7d,0x7e,0x7d,0x7d,0x7e,0x80,0x82,0x85,0x86,0x88,0x89,
0x8b,0x8b,0x8d,0x8e,0x90,0x91,0x90,0x8d,0x89,0x87,0x84,0x83,0x81,0x7f,0x7d,0x79,
0x75,0x72,0x71,0x71,0x72,0x73,0x73,0x74,0x73,0x74,0x75,0x77,0x7a,0x7d,0x7f,0x80,
0x80,0x80,0x81,0x81,0x83,0x83,0x83,0x82,0x7f,0x7d,0x7c,0x7c,0x7e,0x7e,0x80,0x7f,
0x7f,0x7d,0x7e,0x80,0x80,0x84,0x86,0x85,0x87,0x87,0x87,0x8a,0x8a,0x8d,0x8c,0x8b,
0x8a,0x85,0x85,0x83,0x83,0x83,0x82,0x80,0x7d,0x7a,0x77,0x76,0x76,0x76,0x76,0x76,
0x76,0x75,0x76,0x75,0x76,0x79,0x7b,0x7d,0x7f,0x80,0x80,0x81,0x81,0x81,0x82,0x82,
0x81,0x80,0x80,0x7f,0x7d,0x7f,0x7d,0x7e,0x7e,0x7d,0x7e,0x7f,0x80,0x81,0x81,0x82,
0x82,0x83,0x83,0x85,0x86,0x87,0x89,0x87,0x88,0x87,0x85,0x84,0x84,0x83,0x83,0x83,
0x82,0x80,0x7f,0x7d,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,0x78,0x78,0x77,0x78,0x79,0x7b,
0x7c,0x7e,0x7e,0x7f,0x7e,0x7f,0x7e,0x80,0x7f,0x82,0x81,0x80,0x80,0x7e,0x7d,0x7d,
0x7e,0x7e,0x80,0x7e,0x7f,0x7d,0x80,0x80,0x81,0x84,0x83,0x83,0x85,0x84,0x85,0x88,
0x87,0x88,0x86,0x85,0x83,0x81,0x82,0x81,0x81,0x81,0x80,0x7f,0x7e,0x7d,0x7d,0x7c,
0x7c,0x7c,0x7b,0x79,0x78,0x78,0x78,0x79,0x7a,0x7c,0x7c,0x7c,0x7b,0x7c,0x7c,0x7e,
0x82,0x82,0x83,0x82,0x80,0x7f,0x7f,0x7e,0x80,0x7f,0x7f,0x7f,0x7d,0x7e,0x7f,0x80,
0x82,0x84,0x83,0x84,0x84,0x83,0x85,0x85,0x88,0x88,0x87,0x87,0x84,0x83,0x81,0x81,
0x80,0x80,0x80,0x7f,0x7e,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7d,0x7c,0x7b,0x7a,0x7b,
0x7b,0x7c,0x7c,0x7c,0x7b,0x7a,0x7b,0x7c,0x7e,0x80,0x81,0x81,0x81,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x7f,0x81,0x7f,0x7e,0x80,0x7e,0x81,0x81,0x82,0x83,0x83,0x84,0x82,
0x85,0x84,0x84,0x86,0x85,0x84,0x83,0x82,0x81,0x80,0x81,0x80,0x7f,0x7f,0x7d,0x7d,
0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7d,0x7c,0x7d,0x7b,0x7c,
0x7c,0x7c,0x7e,0x7c,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x80,0x7e,0x82,0x80,
0x81,0x80,0x80,0x81,0x80,0x83,0x81,0x84,0x83,0x83,0x82,0x84,0x82,0x83,0x83,0x82,
0x83,0x81,0x82,0x80,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7e,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7d,0x7d,0x7c,0x7e,0x7d,0x7f,0x80,
0x80,0x80,0x7f,0x81,0x7f,0x80,0x80,0x81,0x7e,0x81,0x81,0x80,0x80,0x81,0x81,0x81,
0x83,0x83,0x81,0x83,0x84,0x81,0x83,0x82,0x82,0x81,0x82,0x80,0x80,0x80,0x7f,0x80,
0x7f,0x7f,0x7f,0x7f,0x7e,0x7f,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7e,0x80,0x7c,0x7f,
0x7e,0x7e,0x7f,0x7e,0x7f,0x7d,0x80,0x7d,0x7f,0x7e,0x80,0x7e,0x81,0x7f,0x80,0x80,
0x7e,0x81,0x7d,0x82,0x7e,0x82,0x81,0x81,0x81,0x80,0x81,0x7f,0x82,0x81,0x81,0x81,
0x81,0x81,0x80,0x80,0x81,0x80,0x7f,0x80,0x81,0x7f,0x7f,0x7f,0x7e,0x7d,0x7f,0x7d,
0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7e,0x81,0x7d,0x81,0x7e,0x7e,0x81,0x7e,
0x80,0x7f,0x7e,0x7f,0x7d,0x80,0x80,0x7e,0x81,0x81,0x7e,0x80,0x81,0x7f,0x80,0x81,
0x80,0x81,0x80,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,0x81,0x80,0x81,0x80,0x81,0x7f,
0x80,0x80,0x7f,0x7f,0x80,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x80,0x7c,0x81,
0x7e,0x7f,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x7e,0x81,0x7d,0x7f,0x7e,
0x80,0x7f,0x80,0x83,0x7e,0x81,0x82,0x7d,0x80,0x82,0x7f,0x81,0x83,0x80,0x7f,0x82,
0x7e,0x7f,0x80,0x80,0x7f,0x7f,0x81,0x80,0x7f,0x81,0x80,0x80,0x7f,0x81,0x7e,0x7f,
0x7f,0x7e,0x7f,0x7e,0x80,0x7f,0x80,0x7d,0x80,0x7e,0x7f,0x81,0x80,0x7f,0x82,0x7f,
0x80,0x81,0x7e,0x81,0x7f,0x81,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x82,0x7e,0x81,
0x7e,0x82,0x7e,0x81,0x82,0x7f,0x80,0x81,0x81,0x7c,0x84,0x7d,0x7f,0x80,0x7d,0x81,
0x7f,0x7f,0x81,0x7e,0x80,0x81,0x80,0x80,0x7f,0x81,0x7f,0x7e,0x82,0x7e,0x7e,0x81,
0x7c,0x80,0x7e,0x7e,0x82,0x7e,0x82,0x7f,0x7f,0x82,0x7c,0x83,0x7f,0x7f,0x84,0x7b,
0x83,0x7f,0x7d,0x84,0x79,0x82,0x7d,0x7e,0x84,0x7d,0x81,0x82,0x7f,0x7d,0x84,0x7d,
0x81,0x80,0x81,0x7e,0x7f,0x7f,0x7d,0x80,0x7d,0x80,0x7e,0x7f,0x7e,0x81,0x7f,0x80,
0x7e,0x82,0x7d,0x80,0x7f,0x7f,0x80,0x7e,0x81,0x7d,0x81,0x7c,0x81,0x7e,0x7f,0x80,
0x7e,0x81,0x7f,0x80,0x80,0x81,0x81,0x80,0x7f,0x83,0x7c,0x81,0x7f,0x7f,0x80,0x7c,
0x85,0x79,0x83,0x7f,0x7f,0x83,0x7b,0x83,0x7f,0x81,0x7f,0x81,0x80,0x7e,0x81,0x7d,
0x7d,0x80,0x7b,0x82,0x7c,0x7f,0x82,0x7a,0x85,0x7d,0x7e,0x86,0x79,0x80,0x83,0x7b,
0x83,0x7f,0x82,0x7d,0x7c,0x84,0x7a,0x7f,0x82,0x7d,0x82,0x7c,0x84,0x7c,0x7f,0x86,
0x7c,0x82,0x81,0x81,0x7d,0x83,0x7e,0x7f,0x80,0x7e,0x82,0x7d,0x82,0x7d,0x7f,0x80,
0x7d,0x83,0x7e,0x80,0x82,0x7d,0x7e,0x82,0x7c,0x81,0x7d,0x80,0x80,0x78,0x83,0x7d,
0x7c,0x7f,0x83,0x7b,0x82,0x82,0x7d,0x82,0x7d,0x83,0x7e,0x81,0x81,0x80,0x7d,0x80,
0x7f,0x7e,0x7f,0x82,0x7e,0x7f,0x83,0x7a,0x85,0x7b,0x85,0x81,0x80,0x82,0x7f,0x81,
0x7c,0x83,0x7e,0x80,0x7e,0x82,0x7c,0x7f,0x81,0x7f,0x80,0x81,0x7f,0x80,0x7f,0x80,
0x7e,0x80,0x80,0x7f,0x83,0x7a,0x82,0x7e,0x7a,0x81,0x7c,0x80,0x80,0x7e,0x83,0x7d,
0x80,0x81,0x7d,0x83,0x80,0x80,0x82,0x7d,0x83,0x7c,0x83,0x7e,0x7f,0x82,0x78,0x86,
0x79,0x84,0x80,0x7f,0x83,0x7f,0x81,0x7e,0x80,0x82,0x7c,0x82,0x82,0x7d,0x7f,0x7e,
0x83,0x79,0x84,0x80,0x7d,0x7f,0x83,0x7d,0x7f,0x83,0x7e,0x81,0x7d,0x83,0x7c,0x80,
0x81,0x7b,0x83,0x7b,0x7f,0x80,0x7c,0x83,0x7d,0x85,0x7b,0x84,0x7f,0x7d,0x84,0x7e,
0x83,0x80,0x82,0x7c,0x80,0x80,0x7e,0x82,0x83,0x7a,0x85,0x7d,0x7b,0x88,0x7a,0x84,
0x81,0x7b,0x86,0x7b,0x80,0x82,0x7d,0x83,0x7d,0x7f,0x82,0x7c,0x82,0x7e,0x80,0x7e,
0x7f,0x82,0x7c,0x83,0x7f,0x7e,0x80,0x81,0x7a,0x85,0x7a,0x7f,0x82,0x78,0x83,0x7c,
0x81,0x83,0x7c,0x80,0x84,0x7a,0x82,0x85,0x7d,0x82,0x84,0x7e,0x7f,0x81,0x83,0x7b,
0x83,0x80,0x7e,0x7d,0x80,0x82,0x7d,0x82,0x7d,0x7e,0x81,0x7e,0x82,0x82,0x7d,0x81,
0x7e,0x81,0x7a,0x83,0x7e,0x80,0x80,0x7d,0x83,0x7a,0x80,0x85,0x77,0x83,0x81,0x79,
0x82,0x7e,0x7f,0x7f,0x82,0x7b,0x83,0x7a,0x85,0x7a,0x82,0x81,0x79,0x88,0x78,0x84,
0x81,0x7d,0x81,0x7f,0x7e,0x83,0x7d,0x83,0x80,0x7d,0x83,0x7c,0x7f,0x83,0x79,0x83,
0x7d,0x7f,0x82,0x7a,0x85,0x7a,0x81,0x81,0x7b,0x87,0x7c,0x7e,0x85,0x79,0x84,0x7b,
0x81,0x7e,0x7c,0x85,0x7b,0x81,0x80,0x7e,0x7e,0x82,0x7f,0x7e,0x80,0x81,0x7e,0x7f,
0x83,0x7d,0x7e,0x80,0x7d,0x7e,0x80,0x7e,0x82,0x7e,0x7f,0x82,0x7e,0x80,0x81,0x80,
0x80,0x82,0x7d,0x82,0x7f,0x81,0x7f,0x81,0x7e,0x7e,0x82,0x7d,0x80,0x80,0x7c,0x81,
0x7f,0x7e,0x83,0x7c,0x83,0x7e,0x7e,0x81,0x7e,0x7d,0x81,0x7c,0x81,0x7f,0x7d,0x83,
0x7b,0x7e,0x83,0x7b,0x7f,0x83,0x7c,0x86,0x7d,0x7f,0x83,0x7c,0x83,0x7f,0x80,0x82,
0x7d,0x81,0x7f,0x7d,0x82,0x7f,0x7d,0x82,0x7c,0x81,0x81,0x80,0x81,0x7f,0x82,0x80,
0x7f,0x80,0x81,0x7c,0x83,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x82,0x7d,0x83,0x80,0x7e,
0x82,0x81,0x7b,0x84,0x7e,0x7d,0x82,0x7d,0x7e,0x82,0x7d,0x7e,0x81,0x7d,0x80,0x7f,
0x80,0x7f,0x82,0x7f,0x81,0x7f,0x80,0x82,0x7c,0x81,0x80,0x7e,0x81,0x81,0x7e,0x81,
0x81,0x7d,0x82,0x80,0x7e,0x81,0x80,0x81,0x7f,0x80,0x80,0x81,0x7d,0x80,0x7f,0x7e,
0x81,0x7d,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,0x80,0x80,0x80,0x80,0x82,0x7d,0x82,
0x7f,0x7f,0x81,0x7f,0x81,0x7d,0x81,0x7f,0x7e,0x81,0x80,0x7f,0x82,0x7f,0x80,0x80,
0x81,0x81,0x80,0x81,0x7f,0x7f,0x80,0x7e,0x7f,0x80,0x7d,0x80,0x7c,0x80,0x7f,0x80,
0x81,0x7f,0x80,0x7f,0x7e,0x80,0x81,0x7e,0x81,0x7f,0x7d,0x7f,0x7e,0x80,0x7f,0x7f,
0x80,0x7d,0x82,0x7f,0x80,0x83,0x80,0x80,0x81,0x81,0x80,0x80,0x81,0x81,0x80,0x80,
0x81,0x81,0x7f,0x82,0x80,0x7f,0x81,0x7f,0x7f,0x7f,0x80,0x7f,0x7e,0x80,0x7d,0x7f,
0x7c,0x7f,0x7e,0x7d,0x80,0x7d,0x7e,0x7f,0x7f,0x7f,0x7e,0x7f,0x80,0x7c,0x81,0x7f,
0x7d,0x7e,0x7f,0x7d,0x80,0x80,0x7f,0x81,0x80,0x82,0x81,0x82,0x83,0x82,0x81,0x84,
0x81,0x81,0x83,0x82,0x80,0x81,0x81,0x80,0x81,0x81,0x81,0x7e,0x7f,0x7f,0x7e,0x7f,
0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7d,0x7c,0x7c,0x7c,0x7a,0x7c,0x7a,0x7b,0x7c,
0x7b,0x7d,0x7c,0x7e,0x7e,0x7d,0x7f,0x7e,0x7f,0x80,0x80,0x81,0x80,0x81,0x82,0x80,
0x82,0x83,0x83,0x84,0x84,0x85,0x85,0x85,0x85,0x86,0x86,0x85,0x86,0x84,0x84,0x83,
0x83,0x83,0x82,0x81,0x80,0x7f,0x7d,0x7d,0x7d,0x7b,0x7b,0x79,0x77,0x77,0x76,0x75,
0x75,0x76,0x74,0x75,0x76,0x76,0x78,0x79,0x7a,0x7c,0x7d,0x7f,0x80,0x81,0x83,0x83,
0x84,0x85,0x86,0x86,0x87,0x86,0x88,0x86,0x88,0x87,0x85,0x87,0x86,0x86,0x88,0x88,
0x88,0x89,0x88,0x89,0x87,0x87,0x85,0x82,0x82,0x7e,0x7c,0x7b,0x78,0x76,0x74,0x72,
0x71,0x70,0x70,0x70,0x70,0x71,0x72,0x73,0x74,0x76,0x78,0x7a,0x7c,0x7e,0x7f,0x80,
0x81,0x82,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x89,0x89,0x89,0x87,0x89,0x88,0x89,
0x8a,0x89,0x8b,0x89,0x8b,0x8d,0x8c,0x8e,0x8a,0x86,0x84,0x7f,0x7e,0x7d,0x7c,0x7a,
0x79,0x73,0x70,0x6d,0x6c,0x6c,0x6f,0x6f,0x70,0x71,0x70,0x6f,0x71,0x74,0x78,0x7c,
0x7f,0x81,0x82,0x82,0x82,0x83,0x85,0x87,0x89,0x89,0x88,0x86,0x84,0x83,0x84,0x85,
0x86,0x88,0x87,0x87,0x88,0x86,0x89,0x8a,0x8d,0x90,0x92,0x94,0x8e,0x8b,0x86,0x82,
0x82,0x81,0x80,0x7e,0x7d,0x76,0x70,0x6e,0x6b,0x6c,0x6f,0x70,0x70,0x71,0x70,0x6e,
0x6f,0x72,0x75,0x79,0x7d,0x7f,0x7f,0x80,0x81,0x80,0x83,0x86,0x88,0x88,0x88,0x86,
0x83,0x83,0x81,0x82,0x83,0x84,0x84,0x84,0x83,0x84,0x84,0x88,0x8a,0x8c,0x90,0x91,
0x93,0x95,0x92,0x8d,0x8d,0x86,0x84,0x84,0x7f,0x7e,0x7c,0x77,0x6f,0x6e,0x6b,0x6a,
0x6c,0x6e,0x6d,0x6f,0x70,0x6f,0x70,0x74,0x76,0x79,0x7d,0x7d,0x7e,0x7f,0x80,0x80,
0x83,0x84,0x84,0x85,0x84,0x83,0x82,0x82,0x81,0x81,0x82,0x82,0x82,0x82,0x81,0x83,
0x84,0x87,0x89,0x8b,0x8d,0x90,0x91,0x94,0x99,0x95,0x92,0x91,0x89,0x85,0x84,0x7f,
0x7c,0x7d,0x77,0x70,0x6e,0x69,0x66,0x68,0x6a,0x69,0x6d,0x70,0x6f,0x70,0x73,0x73,
0x77,0x7c,0x7e,0x81,0x83,0x84,0x82,0x83,0x84,0x84,0x86,0x86,0x86,0x84,0x83,0x80,
0x7f,0x7e,0x7f,0x80,0x80,0x81,0x81,0x83,0x84,0x86,0x89,0x8c,0x8e,0x94,0x95,0x99,
0x9b,0x94,0x93,0x8c,0x88,0x85,0x83,0x7e,0x7e,0x7b,0x72,0x6d,0x69,0x66,0x66,0x68,
0x68,0x6a,0x6d,0x6d,0x6d,0x70,0x73,0x76,0x7b,0x7f,0x80,0x83,0x84,0x84,0x84,0x85,
0x85,0x86,0x87,0x85,0x84,0x82,0x80,0x7e,0x7e,0x7d,0x7e,0x7e,0x7f,0x7f,0x81,0x82,
0x84,0x88,0x8a,0x8e,0x91,0x94,0x96,0x9d,0x9a,0x96,0x94,0x8d,0x88,0x87,0x83,0x7e,
0x7f,0x79,0x70,0x6c,0x68,0x63,0x65,0x68,0x66,0x69,0x6d,0x6b,0x6c,0x71,0x73,0x77,
0x7d,0x7f,0x81,0x84,0x86,0x84,0x86,0x87,0x87,0x88,0x87,0x85,0x84,0x82,0x80,0x7e,
0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x80,0x81,0x85,0x86,0x8a,0x8f,0x91,0x95,0x98,0x9e,
0x9c,0x98,0x96,0x8e,0x8a,0x88,0x84,0x7e,0x7f,0x79,0x70,0x6d,0x67,0x63,0x64,0x67,
0x64,0x68,0x6c,0x6b,0x6d,0x71,0x73,0x78,0x7d,0x80,0x82,0x85,0x86,0x86,0x87,0x87,
0x88,0x88,0x86,0x85,0x83,0x81,0x7f,0x7e,0x7c,0x7c,0x7c,0x7b,0x7c,0x7d,0x7f,0x81,
0x84,0x87,0x8a,0x8f,0x91,0x95,0x97,0x9e,0xa0,0x99,0x9a,0x91,0x8b,0x89,0x86,0x7e,
0x80,0x7d,0x71,0x6e,0x69,0x63,0x62,0x67,0x64,0x66,0x6c,0x6b,0x6b,0x6f,0x72,0x75,
0x7c,0x80,0x82,0x85,0x87,0x86,0x86,0x88,0x88,0x89,0x88,0x87,0x84,0x81,0x7f,0x7c,
0x7a,0x7a,0x7b,0x7a,0x7a,0x7b,0x7c,0x7d,0x81,0x83,0x88,0x8c,0x91,0x93,0x96,0x99,
0x9f,0xa2,0x9a,0x9c,0x93,0x8d,0x8a,0x85,0x7f,0x7f,0x7d,0x70,0x6c,0x67,0x61,0x60,
0x64,0x62,0x64,0x6b,0x6a,0x6a,0x6e,0x72,0x75,0x7c,0x81,0x82,0x87,0x87,0x87,0x86,
0x88,0x88,0x89,0x89,0x87,0x85,0x81,0x7f,0x7b,0x7a,0x79,0x7a,0x79,0x78,0x79,0x7a,
0x7b,0x7e,0x81,0x85,0x8b,0x8f,0x91,0x95,0x9a,0x9d,0xa3,0x9e,0x9c,0x98,0x8f,0x8c,
0x87,0x82,0x7e,0x7e,0x73,0x6c,0x67,0x61,0x5f,0x61,0x63,0x62,0x68,0x6a,0x68,0x6c,
0x70,0x74,0x79,0x81,0x83,0x85,0x89,0x88,0x87,0x88,0x8a,0x8a,0x8a,0x89,0x86,0x83,
0x80,0x7d,0x7a,0x7a,0x7a,0x7a,0x78,0x79,0x78,0x7a,0x7b,0x7f,0x83,0x87,0x8c,0x90,
0x91,0x95,0x9a,0x9e,0xa3,0x9e,0x9d,0x97,0x8f,0x8c,0x85,0x80,0x7f,0x7c,0x72,0x6c,
0x66,0x60,0x60,0x61,0x60,0x63,0x68,0x69,0x69,0x6d,0x70,0x75,0x7b,0x81,0x83,0x87,
0x8a,0x89,0x88,0x8a,0x8a,0x8a,0x8a,0x89,0x86,0x82,0x7f,0x7b,0x79,0x78,0x79,0x78,
0x78,0x78,0x79,0x7a,0x7c,0x80,0x84,0x89,0x8f,0x91,0x93,0x9a,0x9b,0xa2,0xa5,0x9d,
0x9e,0x96,0x8e,0x89,0x85,0x7e,0x7d,0x7a,0x6d,0x69,0x63,0x5e,0x5d,0x60,0x60,0x63,
0x69,0x69,0x6a,0x6e,0x73,0x77,0x7e,0x84,0x87,0x8b,0x8c,0x8b,0x8a,0x8b,0x8b,0x8b,
0x8a,0x88,0x85,0x81,0x7d,0x79,0x77,0x77,0x77,0x76,0x76,0x77,0x77,0x79,0x7b,0x7f,
0x84,0x89,0x8e,0x91,0x95,0x98,0x9c,0xa0,0xa6,0x9f,0x9f,0x99,0x8e,0x8b,0x85,0x7f,
0x7c,0x7b,0x6f,0x69,0x64,0x5d,0x5c,0x5e,0x60,0x62,0x69,0x6a,0x6b,0x6f,0x73,0x77,
0x7d,0x85,0x87,0x8b,0x8d,0x8b,0x8a,0x8b,0x8b,0x8a,0x8b,0x89,0x85,0x81,0x7d,0x79,
0x76,0x76,0x76,0x76,0x76,0x76,0x77,0x78,0x7b,0x7e,0x84,0x89,0x8e,0x92,0x95,0x98,
0x9c,0xa1,0xa6,0xa0,0x9f,0x99,0x8e,0x8b,0x85,0x7d,0x7c,0x7b,0x6f,0x69,0x64,0x5c,
0x5c,0x60,0x60,0x62,0x6a,0x6b,0x6b,0x70,0x73,0x77,0x7f,0x86,0x88,0x8b,0x8e,0x8c,
0x89,0x8b,0x8b,0x8a,0x8b,0x89,0x84,0x81,0x7d,0x78,0x75,0x76,0x75,0x75,0x75,0x75,
0x75,0x76,0x78,0x7b,0x81,0x87,0x8c,0x90,0x93,0x95,0x98,0x9b,0xa1,0xa6,0xa0,0x9f,
0x98,0x8d,0x87,0x83,0x7c,0x79,0x7b,0x6f,0x68,0x65,0x5e,0x5b,0x60,0x61,0x63,0x6b,
0x6e,0x6d,0x71,0x76,0x79,0x7e,0x86,0x88,0x8b,0x8d,0x8c,0x89,0x8a,0x8a,0x88,0x88,
0x87,0x83,0x7f,0x7c,0x77,0x74,0x74,0x75,0x74,0x75,0x76,0x76,0x77,0x7a,0x7e,0x83,
0x89,0x8d,0x90,0x94,0x97,0x9a,0x9d,0xa4,0xa3,0x9c,0x9b,0x92,0x89,0x86,0x81,0x7a,
0x7b,0x77,0x6a,0x66,0x63,0x5d,0x5e,0x63,0x63,0x67,0x6e,0x6e,0x6e,0x73,0x79,0x7c,
0x83,0x89,0x8a,0x8c,0x8e,0x8a,0x87,0x89,0x8a,0x87,0x87,0x85,0x80,0x7c,0x79,0x74,
0x73,0x74,0x74,0x74,0x75,0x75,0x75,0x77,0x7b,0x7e,0x84,0x8a,0x8e,0x90,0x93,0x95,
0x98,0x9b,0xa2,0xa3,0x9e,0x9b,0x93,0x8a,0x84,0x82,0x7d,0x7b,0x7a,0x70,0x68,0x64,
0x60,0x5f,0x63,0x67,0x69,0x6e,0x70,0x70,0x71,0x77,0x7c,0x81,0x88,0x8b,0x8c,0x8b,
0x8a,0x87,0x86,0x88,0x88,0x87,0x86,0x82,0x7d,0x79,0x76,0x74,0x75,0x76,0x76,0x76,
0x75,0x75,0x75,0x78,0x7c,0x82,0x87,0x8b,0x8e,0x90,0x91,0x94,0x98,0x9b,0xa2,0xa1,
0x9b,0x97,0x90,0x88,0x83,0x83,0x7e,0x7d,0x7a,0x70,0x69,0x66,0x64,0x63,0x68,0x6a,
0x6d,0x70,0x70,0x70,0x72,0x78,0x7d,0x82,0x87,0x89,0x89,0x88,0x87,0x85,0x86,0x88,
0x88,0x87,0x85,0x81,0x7d,0x7a,0x77,0x77,0x77,0x78,0x77,0x76,0x75,0x75,0x76,0x78,
0x7b,0x80,0x84,0x87,0x89,0x8b,0x8d,0x90,0x93,0x97,0x9b,0x9d,0x99,0x94,0x8f,0x8a,
0x86,0x84,0x83,0x81,0x7e,0x78,0x71,0x6d,0x6b,0x6a,0x6c,0x6e,0x70,0x72,0x73,0x72,
0x72,0x75,0x79,0x7d,0x80,0x83,0x84,0x84,0x84,0x83,0x84,0x85,0x86,0x87,0x86,0x85,
0x83,0x80,0x7d,0x7b,0x7b,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x79,0x7a,0x7c,0x7f,0x82,
0x84,0x86,0x87,0x88,0x8a,0x8c,0x8f,0x92,0x91,0x8f,0x8c,0x89,0x87,0x85,0x83,0x83,
0x83,0x80,0x7c,0x78,0x77,0x76,0x75,0x75,0x76,0x77,0x78,0x78,0x77,0x78,0x79,0x7a,
0x7c,0x7e,0x7f,0x80,0x81,0x80,0x80,0x80,0x81,0x82,0x82,0x81,0x81,0x80,0x7f,0x7e,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7d,0x7e,0x7f,0x80,0x80,
0x81,0x82,0x83,0x85,0x87,0x88,0x89,0x88,0x87,0x87,0x87,0x87,0x87,0x87,0x87,0x85,
0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7c,0x7b,0x7a,0x7a,0x7a,0x7a,0x7a,
0x7a,0x7b,0x7b,0x7b,0x7b,0x7b,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,
0x7d,0x7d,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7d,0x7e,0x7e,0x7f,0x80,0x81,0x83,
0x84,0x86,0x88,0x88,0x88,0x87,0x88,0x88,0x88,0x88,0x88,0x87,0x85,0x84,0x82,0x81,
0x80,0x7f,0x7f,0x7e,0x7e,0x7c,0x7b,0x7a,0x7a,0x7a,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7c,0x7d,0x7e,0x7e,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,
0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7c,0x7d,0x7d,0x7e,0x7f,0x80,0x82,0x83,0x85,0x87,
0x88,0x89,0x89,0x89,0x89,0x89,0x89,0x89,0x88,0x87,0x86,0x84,0x83,0x82,0x81,0x80,
0x7f,0x7e,0x7d,0x7c,0x7b,0x7a,0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,
0x7d,0x7e,0x7e,0x7e,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,
0x7b,0x7b,0x7b,0x7c,0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x83,0x85,0x87,0x88,0x89,0x89,
0x89,0x89,0x89,0x89,0x89,0x88,0x87,0x85,0x84,0x83,0x82,0x80,0x7f,0x7e,0x7e,0x7d,
0x7c,0x7c,0x7b,0x7b,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,
0x7b,0x7c,0x7d,0x7e,0x7e,0x7f,0x80,0x81,0x82,0x84,0x86,0x88,0x89,0x89,0x89,0x89,
0x89,0x89,0x89,0x88,0x88,0x86,0x85,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7f,0x7e,0x7c,
0x7c,0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7b,
0x7c,0x7d,0x7e,0x7e,0x7f,0x80,0x81,0x82,0x84,0x86,0x88,0x89,0x88,0x88,0x88,0x88,
0x88,0x88,0x87,0x86,0x85,0x84,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7c,0x7b,
0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7c,0x7b,0x7b,0x7b,0x7a,0x7a,0x7b,0x7b,0x7c,
0x7c,0x7d,0x7e,0x7f,0x80,0x81,0x82,0x84,0x86,0x88,0x88,0x88,0x88,0x88,0x88,0x89,
0x88,0x88,0x87,0x85,0x84,0x83,0x82,0x80,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x7b,
0x7b,0x7c,0x7c,0x7c,0x7d,0x7d,0x7c,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7f,0x7e,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x7a,0x7a,0x7a,0x7b,0x7c,
0x7c,0x7d,0x7e,0x7f,0x80,0x82,0x84,0x86,0x88,0x89,0x89,0x89,0x89,0x89,0x89,0x89,
0x89,0x88,0x86,0x85,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x7b,0x7b,
0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7f,0x7f,0x80,0x7f,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7b,0x7a,0x7a,0x79,0x79,0x79,0x7a,0x7b,0x7b,0x7c,
0x7d,0x7e,0x7f,0x80,0x82,0x84,0x86,0x88,0x89,0x89,0x89,0x89,0x89,0x89,0x8a,0x89,
0x89,0x87,0x86,0x84,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,
0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x79,0x79,0x79,0x7a,0x7a,0x7b,0x7c,
0x7d,0x7e,0x7f,0x81,0x82,0x84,0x86,0x88,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,
0x89,0x87,0x86,0x85,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,
0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x78,0x79,0x79,0x7a,0x7b,0x7b,
0x7c,0x7d,0x7f,0x80,0x82,0x84,0x86,0x88,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,0x89,
0x89,0x87,0x86,0x84,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7b,0x7b,
0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x7e,0x7e,0x7e,
0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x79,0x78,0x78,0x79,0x79,0x7a,0x7b,
0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x84,0x86,0x88,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,
0x89,0x89,0x87,0x86,0x84,0x83,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x7b,
0x7b,0x7b,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x7f,0x7e,0x7e,
0x7e,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x79,0x78,0x78,0x78,0x79,0x7a,0x7a,
0x7b,0x7d,0x7e,0x7f,0x80,0x81,0x83,0x85,0x87,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,
0x8a,0x8a,0x89,0x87,0x86,0x84,0x83,0x81,0x80,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7b,
0x7b,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7e,
0x7e,0x7e,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x7a,
0x7b,0x7c,0x7d,0x7e,0x7f,0x80,0x82,0x84,0x85,0x87,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,
0x8a,0x8a,0x89,0x88,0x87,0x85,0x84,0x83,0x82,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7c,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,0x79,0x79,0x79,0x79,0x7a,
0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x80,0x82,0x83,0x85,0x87,0x89,0x8a,0x8a,0x8a,0x8a,
0x8a,0x8a,0x8a,0x8a,0x89,0x88,0x86,0x85,0x84,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7d,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7a,0x7a,0x7a,0x79,0x79,0x79,0x79,0x79,
0x79,0x7a,0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x81,0x83,0x84,0x86,0x88,0x8a,0x8b,0x8b,
0x8b,0x8b,0x8a,0x8a,0x8a,0x89,0x88,0x87,0x85,0x84,0x82,0x81,0x7f,0x7e,0x7e,0x7d,
0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,0x78,
0x78,0x78,0x78,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x80,0x81,0x83,0x85,0x87,0x89,0x8a,
0x8b,0x8b,0x8b,0x8b,0x8b,0x8b,0x8a,0x89,0x88,0x86,0x85,0x84,0x82,0x81,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7c,0x7c,0x7b,0x7a,0x7a,0x79,0x78,0x78,
0x78,0x78,0x78,0x78,0x79,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x84,0x86,
0x88,0x89,0x8b,0x8b,0x8b,0x8b,0x8b,0x8b,0x8a,0x89,0x89,0x87,0x86,0x85,0x84,0x82,
0x81,0x80,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7a,0x7a,
0x79,0x79,0x78,0x78,0x78,0x78,0x78,0x79,0x79,0x7a,0x7b,0x7b,0x7d,0x7e,0x7f,0x81,
0x82,0x84,0x86,0x88,0x8a,0x8b,0x8c,0x8b,0x8c,0x8b,0x8b,0x8b,0x8a,0x89,0x88,0x87,
0x85,0x84,0x82,0x81,0x7f,0x7f,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,
0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,
0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,0x78,0x78,0x78,0x78,0x79,0x7a,0x7a,0x7b,0x7d,
0x7e,0x7f,0x81,0x83,0x84,0x86,0x88,0x8a,0x8b,0x8c,0x8c,0x8c,0x8c,0x8b,0x8b,0x8a,
0x89,0x87,0x86,0x85,0x84,0x82,0x81,0x80,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,
0x7d,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,0x77,0x77,0x78,0x78,0x78,0x79,
0x7a,0x7b,0x7c,0x7e,0x7f,0x80,0x82,0x84,0x85,0x87,0x89,0x8b,0x8c,0x8c,0x8c,0x8c,
0x8b,0x8b,0x8a,0x89,0x88,0x87,0x86,0x84,0x83,0x82,0x80,0x7f,0x7e,0x7e,0x7d,0x7c,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x78,0x77,0x77,0x77,
0x78,0x78,0x79,0x79,0x7a,0x7b,0x7c,0x7e,0x7f,0x81,0x82,0x84,0x86,0x87,0x89,0x8b,
0x8c,0x8c,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x86,0x85,0x84,0x83,0x81,0x80,0x7f,
0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x79,0x79,0x78,0x77,
0x77,0x77,0x77,0x77,0x77,0x78,0x78,0x79,0x7a,0x7b,0x7d,0x7e,0x7f,0x81,0x83,0x84,
0x86,0x88,0x89,0x8b,0x8c,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x87,0x86,0x84,
0x84,0x82,0x81,0x80,0x7f,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7d,0x7c,0x7d,0x7d,0x7d,
0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,
0x79,0x79,0x78,0x78,0x77,0x77,0x77,0x78,0x78,0x78,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,
0x80,0x81,0x83,0x85,0x86,0x88,0x8a,0x8c,0x8c,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,
0x88,0x86,0x85,0x84,0x83,0x82,0x81,0x7f,0x7f,0x7e,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,
0x7d,0x7c,0x7b,0x7a,0x7a,0x79,0x78,0x77,0x77,0x77,0x77,0x77,0x77,0x78,0x79,0x79,
0x7a,0x7b,0x7d,0x7e,0x7f,0x81,0x83,0x84,0x86,0x88,0x8a,0x8b,0x8d,0x8d,0x8d,0x8d,
0x8c,0x8c,0x8b,0x8a,0x89,0x87,0x86,0x85,0x84,0x82,0x81,0x80,0x7f,0x7e,0x7d,0x7c,
0x7c,0x7c,0x7b,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x77,0x77,0x76,0x76,0x76,
0x77,0x77,0x78,0x79,0x79,0x7b,0x7c,0x7d,0x7f,0x80,0x82,0x83,0x85,0x87,0x89,0x8b,
0x8c,0x8d,0x8e,0x8d,0x8d,0x8c,0x8b,0x8a,0x89,0x88,0x86,0x85,0x84,0x83,0x81,0x80,
0x7f,0x7e,0x7d,0x7d,0x7c,0x7a,0x78,0x78,0x7a,0x7d,0x80,0x81,0x7f,0x7d,0x7a,0x7a,
0x7b,0x7f,0x83,0x85,0x84,0x80,0x7c,0x79,0x79,0x7a,0x7c,0x7d,0x7d,0x7a,0x76,0x72,
0x71,0x72,0x75,0x78,0x79,0x78,0x77,0x76,0x76,0x78,0x7d,0x81,0x84,0x84,0x83,0x83,
0x86,0x8a,0x8f,0x92,0x90,0x8b,0x8b,0x8f,0x92,0x90,0x8b,0x85,0x84,0x85,0x86,0x83,
0x7f,0x7a,0x7b,0x7d,0x7c,0x78,0x77,0x78,0x7b,0x7c,0x7a,0x79,0x7b,0x7e,0x80,0x80,
0x7e,0x7f,0x82,0x84,0x82,0x80,0x81,0x83,0x82,0x80,0x7e,0x7d,0x7f,0x7e,0x7b,0x78,
0x78,0x78,0x78,0x75,0x72,0x74,0x77,0x76,0x74,0x74,0x76,0x79,0x7a,0x79,0x7a,0x7d,
0x80,0x81,0x81,0x83,0x86,0x89,0x89,0x8a,0x8c,0x92,0x91,0x8a,0x8c,0x93,0x94,0x8a,
0x86,0x88,0x8b,0x88,0x81,0x7d,0x7f,0x80,0x7e,0x7c,0x76,0x77,0x7b,0x7c,0x77,0x77,
0x7b,0x7c,0x7c,0x7d,0x7e,0x7f,0x80,0x80,0x82,0x83,0x81,0x81,0x82,0x82,0x82,0x81,
0x7e,0x7e,0x7f,0x7e,0x7a,0x78,0x79,0x79,0x77,0x75,0x74,0x75,0x75,0x74,0x75,0x75,
0x76,0x78,0x79,0x7a,0x7b,0x7d,0x7f,0x81,0x82,0x85,0x86,0x87,0x88,0x8c,0x8d,0x8f,
0x91,0x8c,0x8f,0x94,0x93,0x89,0x8a,0x8c,0x8b,0x86,0x82,0x81,0x81,0x80,0x7c,0x7e,
0x7a,0x78,0x7a,0x7b,0x78,0x79,0x7b,0x79,0x7d,0x7f,0x7e,0x7d,0x81,0x82,0x82,0x82,
0x82,0x82,0x83,0x82,0x81,0x82,0x7f,0x7f,0x7e,0x7d,0x7b,0x79,0x79,0x78,0x77,0x76,
0x74,0x73,0x74,0x75,0x74,0x74,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7e,0x7f,0x81,0x83,
0x84,0x84,0x88,0x89,0x8c,0x8c,0x91,0x8f,0x8a,0x92,0x94,0x8e,0x88,0x8e,0x8a,0x88,
0x86,0x83,0x82,0x80,0x7f,0x7d,0x7e,0x78,0x7a,0x7a,0x7a,0x79,0x7a,0x79,0x7a,0x7e,
0x7d,0x7c,0x7f,0x81,0x80,0x81,0x82,0x82,0x81,0x82,0x82,0x81,0x80,0x7f,0x7e,0x7e,
0x7c,0x7a,0x79,0x78,0x77,0x75,0x75,0x73,0x73,0x74,0x73,0x73,0x74,0x75,0x76,0x77,
0x78,0x79,0x7b,0x7d,0x7e,0x81,0x82,0x84,0x85,0x88,0x88,0x8c,0x8c,0x91,0x8e,0x8a,
0x93,0x93,0x8e,0x89,0x8f,0x89,0x89,0x86,0x83,0x82,0x81,0x7f,0x7d,0x7f,0x78,0x7a,
0x7a,0x7a,0x79,0x7b,0x79,0x7b,0x7e,0x7d,0x7d,0x80,0x81,0x80,0x82,0x82,0x82,0x82,
0x83,0x82,0x81,0x81,0x7f,0x7e,0x7d,0x7c,0x79,0x79,0x78,0x76,0x75,0x74,0x74,0x73,
0x74,0x73,0x73,0x74,0x75,0x75,0x77,0x78,0x79,0x7a,0x7d,0x7e,0x80,0x82,0x82,0x85,
0x86,0x89,0x88,0x8c,0x8c,0x91,0x8d,0x8c,0x93,0x92,0x8c,0x8a,0x8f,0x88,0x88,0x86,
0x84,0x82,0x81,0x7e,0x7e,0x7e,0x79,0x7a,0x7b,0x7b,0x79,0x7b,0x7b,0x7d,0x7e,0x7e,
0x7e,0x81,0x81,0x80,0x83,0x83,0x81,0x82,0x83,0x82,0x80,0x80,0x7e,0x7e,0x7d,0x7b,
0x79,0x79,0x77,0x75,0x75,0x74,0x73,0x72,0x73,0x73,0x73,0x73,0x74,0x76,0x77,0x77,
0x7a,0x7b,0x7d,0x7e,0x81,0x82,0x84,0x85,0x87,0x89,0x89,0x8d,0x8d,0x92,0x8a,0x8f,
0x93,0x90,0x8b,0x8d,0x8d,0x87,0x89,0x84,0x84,0x81,0x81,0x7d,0x80,0x7c,0x7a,0x7c,
0x7c,0x7b,0x7a,0x7c,0x7c,0x7f,0x7e,0x7f,0x7f,0x82,0x81,0x82,0x83,0x82,0x82,0x82,
0x83,0x81,0x80,0x7f,0x7e,0x7d,0x7c,0x7a,0x79,0x78,0x77,0x76,0x75,0x74,0x73,0x73,
0x73,0x73,0x74,0x74,0x75,0x76,0x77,0x78,0x7a,0x7c,0x7d,0x7f,0x80,0x82,0x83,0x86,
0x85,0x88,0x89,0x8d,0x8b,0x8f,0x8f,0x8a,0x90,0x91,0x8e,0x88,0x8f,0x89,0x88,0x87,
0x84,0x83,0x82,0x81,0x7f,0x80,0x7b,0x7d,0x7d,0x7d,0x7b,0x7d,0x7d,0x7d,0x7f,0x7f,
0x7f,0x80,0x81,0x81,0x82,0x82,0x81,0x81,0x82,0x81,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,
0x79,0x78,0x78,0x76,0x75,0x75,0x74,0x73,0x73,0x73,0x73,0x74,0x74,0x75,0x76,0x77,
0x78,0x7a,0x7c,0x7d,0x7e,0x80,0x82,0x84,0x85,0x86,0x87,0x8a,0x8c,0x8b,0x90,0x8a,
0x8e,0x92,0x8f,0x8a,0x8d,0x8c,0x87,0x89,0x85,0x84,0x81,0x82,0x7f,0x80,0x7d,0x7c,
0x7d,0x7d,0x7c,0x7b,0x7d,0x7c,0x7e,0x7f,0x7f,0x7e,0x80,0x80,0x81,0x81,0x81,0x80,
0x81,0x81,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x79,0x78,0x78,0x77,0x75,0x74,0x74,0x73,
0x73,0x73,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7e,0x7f,0x81,0x82,
0x85,0x84,0x87,0x88,0x8a,0x8a,0x8d,0x8f,0x88,0x90,0x92,0x8d,0x89,0x8e,0x8a,0x88,
0x88,0x84,0x84,0x82,0x82,0x80,0x82,0x7c,0x7d,0x7f,0x7d,0x7b,0x7d,0x7e,0x7d,0x7f,
0x7f,0x7f,0x80,0x81,0x80,0x81,0x81,0x80,0x80,0x82,0x81,0x7f,0x7f,0x7e,0x7d,0x7c,
0x7b,0x79,0x79,0x77,0x76,0x76,0x75,0x73,0x73,0x74,0x73,0x73,0x74,0x75,0x75,0x77,
0x77,0x78,0x7a,0x7c,0x7d,0x7f,0x80,0x82,0x83,0x85,0x85,0x87,0x89,0x8b,0x8a,0x8e,
0x8e,0x8a,0x92,0x90,0x8c,0x8b,0x8f,0x88,0x8a,0x88,0x85,0x84,0x83,0x82,0x81,0x81,
0x7b,0x7f,0x7e,0x7d,0x7b,0x7e,0x7d,0x7d,0x7f,0x7f,0x7f,0x80,0x81,0x80,0x82,0x81,
0x80,0x81,0x82,0x7f,0x7f,0x7f,0x7e,0x7c,0x7c,0x7a,0x79,0x79,0x77,0x76,0x75,0x74,
0x73,0x74,0x73,0x72,0x73,0x74,0x75,0x75,0x77,0x77,0x79,0x7a,0x7c,0x7d,0x7f,0x80,
0x82,0x83,0x84,0x85,0x88,0x88,0x8a,0x8b,0x8c,0x8f,0x8a,0x90,0x90,0x8d,0x8a,0x8e,
0x89,0x88,0x8a,0x86,0x85,0x83,0x83,0x81,0x82,0x7d,0x7e,0x7f,0x7e,0x7c,0x7e,0x7e,
0x7d,0x7f,0x7f,0x7f,0x7f,0x81,0x80,0x81,0x81,0x80,0x80,0x81,0x80,0x7f,0x7e,0x7e,
0x7c,0x7c,0x7a,0x79,0x78,0x77,0x76,0x75,0x74,0x73,0x73,0x73,0x73,0x73,0x74,0x74,
0x75,0x76,0x77,0x78,0x7a,0x7b,0x7d,0x7e,0x80,0x81,0x83,0x84,0x85,0x86,0x89,0x88,
0x8b,0x8b,0x8e,0x8c,0x8c,0x91,0x8e,0x8c,0x8b,0x8e,0x88,0x8a,0x86,0x86,0x83,0x83,
0x82,0x81,0x80,0x7d,0x80,0x7e,0x7e,0x7c,0x7f,0x7d,0x7e,0x7f,0x7f,0x7f,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x7e,0x7e,0x7d,0x7d,0x7b,0x7a,0x79,0x78,0x77,0x76,
0x75,0x74,0x73,0x73,0x73,0x73,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,
0x7d,0x7f,0x80,0x82,0x83,0x84,0x86,0x87,0x89,0x89,0x8b,0x8b,0x8f,0x8a,0x8e,0x91,
0x8d,0x8b,0x8d,0x8b,0x88,0x8b,0x86,0x86,0x83,0x84,0x81,0x82,0x7e,0x7e,0x80,0x7e,
0x7d,0x7d,0x7f,0x7d,0x7f,0x7f,0x7f,0x7e,0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x7f,
0x7e,0x7e,0x7d,0x7c,0x7b,0x7a,0x78,0x78,0x77,0x76,0x75,0x74,0x73,0x73,0x73,0x72,
0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x7a,0x7b,0x7d,0x7e,0x7f,0x80,0x82,0x83,0x85,
0x86,0x88,0x88,0x8a,0x8b,0x8c,0x8e,0x8a,0x8f,0x90,0x8d,0x8b,0x8d,0x8a,0x89,0x89,
0x86,0x86,0x84,0x83,0x83,0x82,0x7e,0x7f,0x80,0x7e,0x7d,0x7f,0x7f,0x7e,0x7f,0x80,
0x7e,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7e,0x7e,0x7e,0x7d,0x7b,0x7b,0x7a,
0x78,0x78,0x77,0x76,0x75,0x74,0x74,0x73,0x73,0x73,0x73,0x74,0x74,0x75,0x76,0x77,
0x78,0x79,0x7b,0x7c,0x7d,0x7e,0x80,0x81,0x83,0x83,0x85,0x86,0x87,0x88,0x8a,0x8a,
0x8d,0x8e,0x8a,0x90,0x90,0x8d,0x8c,0x8e,0x8b,0x89,0x8a,0x87,0x86,0x84,0x84,0x82,
0x83,0x7e,0x7f,0x80,0x7f,0x7d,0x7e,0x7e,0x7d,0x7f,0x7f,0x7e,0x7e,0x80,0x7f,0x80,
0x7f,0x7f,0x7f,0x80,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x78,0x78,0x77,0x76,0x75,
0x75,0x74,0x74,0x73,0x73,0x73,0x74,0x75,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7e,
0x7f,0x80,0x81,0x83,0x84,0x85,0x87,0x88,0x89,0x8a,0x8b,0x8d,0x8c,0x8c,0x90,0x8e,
0x8c,0x8c,0x8d,0x89,0x8a,0x89,0x87,0x85,0x85,0x83,0x82,0x81,0x7f,0x80,0x7f,0x7f,
0x7d,0x7f,0x7e,0x7e,0x7f,0x7f,0x7e,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,
0x7d,0x7d,0x7c,0x7b,0x7b,0x79,0x78,0x78,0x77,0x75,0x75,0x74,0x74,0x73,0x74,0x73,
0x73,0x74,0x75,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x83,
0x84,0x86,0x87,0x88,0x88,0x8a,0x8b,0x8e,0x89,0x8e,0x90,0x8d,0x8c,0x8d,0x8c,0x89,
0x8b,0x87,0x87,0x85,0x85,0x82,0x83,0x80,0x7f,0x81,0x7f,0x7d,0x7e,0x7f,0x7c,0x7f,
0x7f,0x7e,0x7d,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7f,0x7e,0x7d,0x7d,0x7c,0x7b,0x7b,
0x7a,0x78,0x78,0x77,0x76,0x75,0x75,0x74,0x74,0x74,0x73,0x73,0x73,0x74,0x75,0x75,
0x76,0x77,0x79,0x7a,0x7b,0x7c,0x7d,0x7f,0x81,0x82,0x83,0x84,0x85,0x86,0x88,0x88,
0x8a,0x8a,0x8d,0x8b,0x8b,0x8f,0x8e,0x8c,0x8b,0x8d,0x89,0x8a,0x89,0x87,0x85,0x85,
0x84,0x83,0x82,0x7f,0x80,0x80,0x7f,0x7e,0x7f,0x7e,0x7e,0x7f,0x7f,0x7e,0x7f,0x80,
0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7d,0x7d,0x7d,0x7b,0x7b,0x7a,0x79,0x78,0x78,
0x76,0x75,0x75,0x74,0x74,0x73,0x73,0x73,0x74,0x74,0x74,0x75,0x76,0x77,0x79,0x79,
0x7b,0x7c,0x7e,0x7f,0x80,0x81,0x83,0x84,0x86,0x86,0x88,0x89,0x89,0x8b,0x8c,0x8e,
0x8b,0x90,0x8f,0x8e,0x8c,0x8e,0x8c,0x8a,0x8b,0x88,0x87,0x86,0x85,0x83,0x84,0x80,
0x80,0x81,0x7f,0x7e,0x7f,0x7f,0x7d,0x7f,0x7f,0x7e,0x7e,0x80,0x7f,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7c,0x7c,0x7b,0x79,0x79,0x78,0x77,0x76,0x75,0x74,
0x73,0x73,0x73,0x73,0x73,0x73,0x74,0x75,0x75,0x76,0x78,0x79,0x7a,0x7c,0x7d,0x7e,
0x80,0x81,0x82,0x84,0x85,0x86,0x87,0x88,0x89,0x8b,0x8b,0x8c,0x8e,0x8b,0x8f,0x8f,
0x8e,0x8c,0x8d,0x8c,0x8a,0x8a,0x88,0x86,0x85,0x85,0x83,0x83,0x80,0x80,0x80,0x80,
0x7e,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x7e,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x79,0x78,0x78,0x76,0x75,0x74,0x74,0x73,0x73,0x72,
0x72,0x72,0x73,0x73,0x74,0x74,0x76,0x77,0x79,0x7a,0x7b,0x7c,0x7e,0x80,0x81,0x82,
0x83,0x85,0x86,0x87,0x87,0x89,0x8a,0x8b,0x8b,0x8c,0x8b,0x8c,0x8f,0x8d,0x8c,0x8b,
0x8c,0x89,0x8a,0x88,0x87,0x85,0x85,0x84,0x83,0x81,0x80,0x81,0x80,0x7f,0x7e,0x80,
0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7d,0x7d,
0x7c,0x7b,0x7a,0x79,0x78,0x77,0x76,0x75,0x74,0x74,0x73,0x73,0x72,0x72,0x72,0x73,
0x73,0x74,0x74,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7e,0x7f,0x80,0x82,0x83,0x85,0x85,
0x86,0x87,0x89,0x89,0x8a,0x8b,0x8b,0x8c,0x8b,0x8d,0x8e,0x8d,0x8c,0x8c,0x8b,0x8a,
0x8a,0x88,0x86,0x86,0x85,0x84,0x83,0x82,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x80,
0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7d,0x7d,0x7d,0x7b,0x7b,
0x7a,0x78,0x77,0x77,0x76,0x75,0x74,0x73,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,
0x75,0x75,0x77,0x78,0x79,0x7b,0x7c,0x7e,0x7f,0x80,0x81,0x83,0x84,0x85,0x86,0x87,
0x88,0x89,0x8a,0x8a,0x8b,0x8c,0x8c,0x8c,0x8d,0x8d,0x8d,0x8b,0x8c,0x8a,0x8a,0x88,
0x88,0x87,0x86,0x85,0x84,0x84,0x82,0x82,0x81,0x81,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7d,0x7c,0x7b,0x7b,0x7a,0x79,
0x77,0x77,0x76,0x75,0x74,0x73,0x72,0x72,0x72,0x71,0x72,0x72,0x73,0x73,0x74,0x75,
0x76,0x78,0x79,0x7a,0x7c,0x7d,0x7f,0x80,0x81,0x83,0x84,0x85,0x86,0x87,0x87,0x88,
0x89,0x89,0x8a,0x8b,0x8c,0x8b,0x8c,0x8d,0x8d,0x8c,0x8c,0x8c,0x8a,0x8a,0x89,0x89,
0x87,0x86,0x85,0x85,0x84,0x83,0x83,0x82,0x82,0x81,0x81,0x81,0x81,0x81,0x80,0x80,
0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x79,0x78,0x77,0x76,
0x75,0x75,0x74,0x73,0x72,0x72,0x71,0x72,0x71,0x72,0x72,0x73,0x74,0x75,0x76,0x77,
0x78,0x7a,0x7b,0x7d,0x7e,0x7f,0x80,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,
0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8d,0x8d,0x8c,0x8b,0x8b,0x8b,0x8a,0x8a,0x87,0x88,
0x86,0x86,0x85,0x84,0x83,0x83,0x83,0x82,0x82,0x81,0x81,0x81,0x81,0x80,0x80,0x80,
0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7b,0x7a,0x7a,0x79,0x78,0x77,0x76,0x75,0x75,
0x74,0x73,0x72,0x72,0x71,0x71,0x71,0x72,0x72,0x72,0x73,0x74,0x75,0x76,0x77,0x79,
0x7a,0x7b,0x7d,0x7e,0x7f,0x81,0x82,0x83,0x84,0x85,0x86,0x86,0x87,0x88,0x88,0x89,
0x8a,0x8b,0x8b,0x8b,0x8c,0x8c,0x8d,0x8d,0x8c,0x8b,0x8b,0x8b,0x8a,0x89,0x88,0x87,
0x87,0x86,0x85,0x84,0x83,0x83,0x82,0x82,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x78,0x78,0x77,0x76,0x75,0x75,0x74,
0x73,0x73,0x72,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x7a,
0x7b,0x7d,0x7e,0x7f,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x87,0x88,0x89,0x89,0x8a,
0x8a,0x8b,0x8c,0x8c,0x8d,0x8d,0x8d,0x8c,0x8c,0x8c,0x8b,0x8a,0x8a,0x89,0x88,0x87,
0x86,0x86,0x85,0x84,0x83,0x83,0x82,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7e,0x7e,
0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x78,0x78,0x77,0x76,0x76,0x75,0x74,0x74,
0x73,0x73,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7b,
0x7c,0x7d,0x7f,0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8b,
0x8b,0x8c,0x8c,0x8d,0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8a,0x8a,0x89,0x88,0x87,
0x86,0x85,0x84,0x84,0x83,0x82,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,
0x7d,0x7c,0x7c,0x7b,0x7b,0x7a,0x79,0x79,0x78,0x78,0x77,0x76,0x75,0x75,0x74,0x73,
0x73,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,0x74,0x75,0x76,0x77,0x79,0x7a,0x7c,
0x7d,0x7e,0x7f,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x89,0x8a,0x8b,
0x8b,0x8c,0x8c,0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x88,0x87,
0x86,0x85,0x84,0x83,0x83,0x82,0x81,0x80,0x80,0x80,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,
0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x78,0x78,0x77,0x76,0x75,0x75,0x74,0x73,0x73,
0x72,0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,
0x7d,0x7f,0x80,0x81,0x82,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8e,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x87,0x86,
0x85,0x85,0x84,0x83,0x82,0x82,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,
0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x77,0x76,0x76,0x75,0x74,0x74,0x73,0x73,
0x72,0x72,0x72,0x72,0x72,0x72,0x73,0x73,0x74,0x75,0x76,0x78,0x79,0x7a,0x7c,0x7d,
0x7e,0x80,0x81,0x82,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8a,0x8a,0x89,0x88,0x87,0x86,
0x85,0x84,0x83,0x83,0x82,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,
0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x73,0x73,0x73,
0x72,0x72,0x72,0x72,0x72,0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x7a,0x7b,0x7c,0x7e,
0x7f,0x80,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8d,0x8d,0x8d,0x8d,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x88,0x87,0x86,
0x85,0x84,0x83,0x82,0x81,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,
0x7b,0x7b,0x7a,0x7a,0x79,0x78,0x78,0x77,0x76,0x76,0x75,0x75,0x74,0x73,0x73,0x72,
0x72,0x72,0x72,0x72,0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7d,0x7e,
0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x86,0x85,
0x84,0x83,0x82,0x82,0x81,0x80,0x80,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,
0x7a,0x7a,0x79,0x79,0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x73,0x73,0x72,
0x72,0x72,0x72,0x72,0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7d,0x7e,
0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8b,0x8b,0x8b,0x8c,
0x8c,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x8a,0x89,0x88,0x87,0x86,0x85,0x84,
0x83,0x82,0x82,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7b,0x7b,0x7b,
0x7a,0x7a,0x79,0x79,0x78,0x78,0x77,0x76,0x76,0x75,0x75,0x74,0x73,0x73,0x73,0x72,
0x72,0x72,0x73,0x73,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7d,0x7e,0x7f,
0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8b,0x8b,0x8c,0x8c,0x8d,
0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x87,0x87,0x86,0x85,0x84,
0x83,0x82,0x81,0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,
0x7b,0x7a,0x7a,0x79,0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x73,0x73,0x73,
0x73,0x73,0x74,0x74,0x75,0x75,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7d,0x7f,0x80,0x81,
0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x89,0x8a,0x8b,0x8b,0x8c,0x8c,0x8d,0x8d,
0x8d,0x8d,0x8d,0x8d,0x8c,0x8c,0x8b,0x8a,0x8a,0x89,0x88,0x87,0x86,0x85,0x84,0x83,
0x82,0x81,0x81,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,
0x7a,0x7a,0x79,0x79,0x78,0x77,0x77,0x76,0x76,0x75,0x74,0x74,0x74,0x73,0x73,0x73,
0x73,0x73,0x74,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7b,0x7d,0x7e,0x7f,0x81,0x82,
0x83,0x84,0x85,0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8d,0x8d,
0x8d,0x8c,0x8c,0x8b,0x8b,0x8a,0x89,0x88,0x88,0x87,0x86,0x85,0x84,0x83,0x82,0x81,
0x81,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,
0x79,0x79,0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x74,0x73,0x73,0x73,0x73,
0x73,0x74,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7c,0x7d,0x7e,0x7f,0x81,0x82,0x83,
0x84,0x85,0x86,0x87,0x88,0x89,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8c,0x8c,
0x8c,0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x86,0x85,0x84,0x84,0x83,0x82,0x81,0x81,
0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,
0x79,0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x74,0x73,0x73,0x73,0x73,0x74,
0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x7b,0x7c,0x7e,0x7f,0x80,0x82,0x83,0x84,0x85,
0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8c,0x8c,0x8c,0x8b,
0x8b,0x8a,0x8a,0x89,0x88,0x87,0x86,0x86,0x85,0x84,0x83,0x82,0x82,0x81,0x80,0x80,
0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,
0x78,0x78,0x77,0x77,0x76,0x75,0x75,0x74,0x74,0x74,0x74,0x74,0x74,0x74,0x74,0x75,
0x76,0x76,0x77,0x78,0x7a,0x7b,0x7c,0x7d,0x7f,0x80,0x81,0x82,0x83,0x84,0x85,0x86,
0x87,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8c,0x8c,0x8b,0x8b,0x8a,0x8a,
0x89,0x88,0x88,0x87,0x86,0x85,0x84,0x83,0x82,0x82,0x81,0x81,0x80,0x7f,0x7f,0x7e,
0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,
0x77,0x77,0x76,0x76,0x75,0x75,0x74,0x74,0x74,0x74,0x74,0x75,0x75,0x76,0x76,0x77,
0x78,0x79,0x7a,0x7b,0x7d,0x7e,0x7f,0x80,0x81,0x83,0x84,0x85,0x86,0x87,0x87,0x88,
0x89,0x8a,0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8c,0x8c,0x8b,0x8b,0x8a,0x8a,0x89,0x88,
0x87,0x86,0x86,0x85,0x84,0x83,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,
0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x78,0x78,0x77,0x77,
0x76,0x76,0x75,0x75,0x74,0x74,0x74,0x74,0x74,0x75,0x75,0x76,0x77,0x77,0x78,0x79,
0x7b,0x7c,0x7d,0x7e,0x7f,0x80,0x81,0x83,0x84,0x85,0x86,0x87,0x87,0x88,0x89,0x8a,
0x8a,0x8b,0x8b,0x8c,0x8c,0x8c,0x8b,0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x86,0x86,
0x85,0x84,0x83,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,
0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x79,0x78,0x78,0x77,0x77,0x76,
0x76,0x75,0x75,0x75,0x75,0x75,0x75,0x76,0x76,0x77,0x78,0x78,0x79,0x7a,0x7c,0x7d,
0x7e,0x7f,0x80,0x81,0x82,0x84,0x85,0x86,0x87,0x87,0x88,0x89,0x8a,0x8a,0x8b,0x8c,
0x8c,0x8c,0x8c,0x8b,0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x86,0x85,0x84,0x84,0x83,
0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,
0x7c,0x7b,0x7b,0x7a,0x7a,0x79,0x79,0x79,0x78,0x78,0x77,0x77,0x76,0x76,0x76,0x75,
0x75,0x75,0x75,0x76,0x76,0x76,0x77,0x78,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x80,
0x81,0x82,0x83,0x84,0x85,0x86,0x87,0x88,0x89,0x89,0x8a,0x8b,0x8b,0x8b,0x8b,0x8b,
0x8b,0x8b,0x8a,0x89,0x89,0x88,0x87,0x87,0x86,0x85,0x84,0x83,0x82,0x82,0x81,0x81,
0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,
0x7a,0x7a,0x79,0x79,0x79,0x78,0x78,0x77,0x77,0x76,0x76,0x76,0x76,0x76,0x76,0x76,
0x76,0x76,0x77,0x78,0x78,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x80,0x81,0x82,0x83,0x84,
0x85,0x86,0x87,0x87,0x88,0x89,0x8a,0x8a,0x8b,0x8b,0x8b,0x8b,0x8b,0x8a,0x8a,0x89,
0x89,0x88,0x87,0x87,0x86,0x85,0x84,0x83,0x83,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,
0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,
0x79,0x78,0x78,0x77,0x77,0x77,0x76,0x76,0x76,0x76,0x76,0x76,0x76,0x77,0x77,0x78,
0x79,0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x7f,0x80,0x81,0x82,0x83,0x84,0x85,0x86,0x87,
0x88,0x88,0x89,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,0x8a,0x89,0x89,0x88,0x88,0x87,0x86,
0x86,0x85,0x84,0x83,0x82,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,
0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,0x79,0x78,0x78,0x78,
0x77,0x77,0x77,0x77,0x76,0x76,0x76,0x77,0x77,0x77,0x78,0x79,0x79,0x7a,0x7b,0x7c,
0x7d,0x7e,0x7f,0x80,0x81,0x82,0x83,0x84,0x84,0x85,0x86,0x87,0x87,0x88,0x89,0x89,
0x89,0x89,0x89,0x89,0x89,0x89,0x88,0x88,0x88,0x87,0x86,0x86,0x85,0x84,0x84,0x83,
0x82,0x82,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,
0x7c,0x7b,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,0x79,0x79,0x78,0x78,0x78,0x77,0x77,0x77,
0x77,0x77,0x78,0x78,0x78,0x79,0x79,0x7a,0x7b,0x7c,0x7c,0x7d,0x7e,0x7f,0x80,0x81,
0x82,0x83,0x83,0x84,0x85,0x86,0x86,0x87,0x87,0x88,0x88,0x89,0x89,0x89,0x89,0x89,
0x88,0x88,0x88,0x87,0x87,0x86,0x85,0x85,0x84,0x83,0x83,0x82,0x82,0x81,0x81,0x80,
0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7a,
0x7a,0x7a,0x79,0x79,0x79,0x79,0x78,0x78,0x78,0x78,0x78,0x78,0x78,0x78,0x78,0x79,
0x79,0x7a,0x7a,0x7b,0x7c,0x7d,0x7d,0x7e,0x7f,0x80,0x81,0x82,0x82,0x83,0x84,0x84,
0x85,0x86,0x86,0x87,0x87,0x88,0x88,0x88,0x88,0x88,0x88,0x88,0x88,0x87,0x87,0x86,
0x86,0x85,0x85,0x84,0x84,0x83,0x82,0x82,0x81,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7a,0x7a,0x7a,0x79,
0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x79,0x7a,0x7a,0x7b,0x7b,0x7c,0x7d,
0x7d,0x7e,0x7f,0x7f,0x80,0x81,0x82,0x82,0x83,0x84,0x84,0x85,0x86,0x86,0x86,0x87,
0x87,0x87,0x87,0x87,0x87,0x87,0x87,0x86,0x86,0x85,0x85,0x85,0x84,0x83,0x83,0x82,
0x82,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,
0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,
0x7a,0x7a,0x7a,0x7b,0x7b,0x7b,0x7c,0x7c,0x7d,0x7d,0x7e,0x7f,0x7f,0x80,0x80,0x81,
0x82,0x82,0x83,0x84,0x84,0x85,0x85,0x86,0x86,0x86,0x86,0x86,0x86,0x86,0x86,0x86,
0x85,0x85,0x85,0x84,0x84,0x83,0x83,0x83,0x82,0x82,0x81,0x81,0x81,0x80,0x80,0x7f,
0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,
0x7b,0x7b,0x7b,0x7b,0x7b,0x7a,0x7a,0x7b,0x7b,0x7b,0x7b,0x7b,0x7c,0x7c,0x7c,0x7d,
0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x80,0x80,0x81,0x81,0x82,0x82,0x83,0x83,0x84,0x84,
0x85,0x85,0x85,0x85,0x85,0x85,0x85,0x85,0x85,0x85,0x84,0x84,0x84,0x83,0x83,0x83,
0x82,0x82,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,
0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7b,0x7b,0x7b,0x7b,0x7b,0x7b,0x7b,
0x7c,0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7f,0x7f,0x7f,0x80,0x80,
0x81,0x81,0x82,0x82,0x82,0x83,0x83,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,0x84,
0x84,0x84,0x83,0x83,0x83,0x82,0x82,0x82,0x81,0x81,0x81,0x80,0x80,0x80,0x7f,0x7f,
0x7f,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,0x7c,
0x7c,0x7c,0x7c,0x7c,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7f,
0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x81,0x81,0x81,0x82,0x82,0x82,0x83,0x83,0x83,
0x83,0x83,0x83,0x83,0x83,0x83,0x83,0x83,0x83,0x83,0x82,0x82,0x82,0x81,0x81,0x81,
0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,
0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x81,0x81,0x81,0x81,
0x81,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x81,
0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,
0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x81,
0x81,0x81,0x81,0x81,0x81,0x81,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x81,
0x81,0x81,0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,0x7d,
0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,
0x80,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,
0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x7f,
0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7d,0x7d,
0x7d,0x7d,0x7d,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,
0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x81,0x81,0x81,0x81,0x81,0x82,0x82,0x82,
0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x82,0x81,0x81,0x81,0x81,0x81,0x81,
0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,
0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x81,
0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,0x81,
0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x81,0x81,0x81,0x81,0x81,
0x81,0x81,0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x7e,0x7f,0x7f,0x7f,0x7e,0x7e,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x80,0x81,0x7a,0x7b,0x7a,0x7c,0x7c,0x7d,0x7e,0x7d,0x81,0x7f,0x81,
0x81,0x82,0x83,0x82,0x86,0x84,0x84,0x83,0x81,0x82,0x82,0x82,0x80,0x80,0x80,0x7e,
0x80,0x80,0x7e,0x7e,0x7d,0x7e,0x7c,0x7f,0x7f,0x7e,0x7f,0x7f,0x80,0x80,0x81,0x80,
0x7f,0x82,0x81,0x81,0x81,0x81,0x80,0x80,0x81,0x80,0x80,0x81,0x80,0x7b,0x7c,0x7c,
0x7c,0x7b,0x7b,0x7b,0x7a,0x7f,0x7d,0x7e,0x7f,0x7f,0x80,0x80,0x83,0x81,0x82,0x82,
0x80,0x82,0x82,0x82,0x7f,0x80,0x81,0x7f,0x81,0x80,0x7e,0x7e,0x7f,0x7e,0x7d,0x7f,
0x7e,0x7d,0x7e,0x7e,0x7f,0x7f,0x80,0x7f,0x80,0x82,0x82,0x82,0x84,0x84,0x85,0x86,
0x86,0x86,0x86,0x87,0x86,0x86,0x87,0x87,0x87,0x87,0x86,0x86,0x87,0x87,0x86,0x85,
0x84,0x83,0x82,0x82,0x80,0x7e,0x7d,0x7b,0x79,0x78,0x77,0x75,0x74,0x73,0x74,0x73,
0x73,0x72,0x73,0x74,0x75,0x76,0x76,0x77,0x78,0x79,0x7b,0x7c,0x7c,0x7d,0x7e,0x7f,
0x81,0x81,0x82,0x83,0x84,0x84,0x85,0x86,0x86,0x87,0x88,0x88,0x89,0x8a,0x8a,0x8a,
0x8a,0x8c,0x8d,0x8e,0x8e,0x8f,0x8f,0x8c,0x8b,0x8b,0x8b,0x89,0x85,0x81,0x7f,0x7e,
0x7b,0x77,0x74,0x72,0x71,0x6f,0x6e,0x6e,0x6d,0x6e,0x6e,0x6f,0x71,0x74,0x75,0x76,
0x79,0x7c,0x7f,0x80,0x81,0x83,0x85,0x86,0x86,0x86,0x86,0x85,0x83,0x81,0x81,0x80,
0x7e,0x7b,0x79,0x78,0x78,0x77,0x76,0x76,0x77,0x78,0x7a,0x7c,0x7f,0x82,0x83,0x86,
0x89,0x8e,0x91,0x94,0x94,0x9a,0x9d,0x94,0x98,0x94,0x96,0x92,0x8c,0x87,0x81,0x82,
0x79,0x75,0x71,0x6d,0x6c,0x67,0x65,0x66,0x67,0x67,0x67,0x6a,0x6e,0x71,0x75,0x76,
0x7c,0x81,0x83,0x86,0x87,0x8b,0x8d,0x8d,0x8d,0x8c,0x8c,0x89,0x85,0x83,0x81,0x7f,
0x7a,0x76,0x74,0x73,0x72,0x70,0x70,0x72,0x73,0x77,0x79,0x7d,0x80,0x85,0x8a,0x8e,
0x92,0x98,0x9b,0x9d,0xa1,0x9b,0x9b,0x9b,0x9a,0x96,0x8e,0x89,0x81,0x80,0x78,0x71,
0x6d,0x68,0x65,0x62,0x60,0x60,0x61,0x62,0x63,0x68,0x6d,0x71,0x76,0x79,0x7f,0x85,
0x89,0x8c,0x8f,0x91,0x93,0x94,0x93,0x92,0x90,0x8d,0x89,0x86,0x82,0x7f,0x7b,0x75,
0x72,0x70,0x6e,0x6b,0x69,0x69,0x6a,0x6c,0x6d,0x71,0x75,0x79,0x7d,0x82,0x86,0x8c,
0x90,0x94,0x97,0x9c,0x9d,0xa0,0xa1,0xa5,0xa6,0x97,0x98,0x92,0x93,0x8d,0x82,0x79,
0x72,0x73,0x69,0x65,0x61,0x5e,0x60,0x5e,0x5e,0x63,0x67,0x69,0x6d,0x73,0x7a,0x81,
0x85,0x86,0x8c,0x92,0x93,0x93,0x92,0x93,0x93,0x91,0x8c,0x88,0x85,0x80,0x7a,0x75,
0x72,0x6f,0x6b,0x67,0x67,0x68,0x6b,0x6c,0x6f,0x74,0x7a,0x80,0x85,0x8a,0x90,0x96,
0x9a,0x9e,0xa2,0xa6,0xa7,0xaa,0xa5,0x9b,0x9d,0x99,0x93,0x8a,0x80,0x78,0x73,0x6d,
0x64,0x5f,0x5c,0x59,0x59,0x59,0x5a,0x5f,0x63,0x67,0x6e,0x77,0x7d,0x83,0x87,0x8d,
0x94,0x97,0x97,0x98,0x98,0x98,0x96,0x92,0x8d,0x88,0x83,0x7e,0x7a,0x75,0x70,0x6b,
0x68,0x67,0x67,0x67,0x67,0x69,0x6d,0x71,0x75,0x7a,0x80,0x86,0x8b,0x8f,0x95,0x99,
0x9d,0x9e,0xa0,0xa2,0xa4,0xa4,0xa5,0xa3,0x93,0x94,0x8d,0x89,0x84,0x78,0x70,0x69,
0x67,0x60,0x5d,0x5b,0x58,0x5c,0x5e,0x61,0x67,0x6c,0x71,0x78,0x80,0x86,0x8c,0x8f,
0x91,0x96,0x98,0x98,0x96,0x93,0x90,0x8d,0x89,0x83,0x7f,0x7a,0x72,0x6e,0x6a,0x68,
0x67,0x64,0x63,0x65,0x69,0x6d,0x71,0x76,0x7c,0x83,0x8b,0x8f,0x96,0x9a,0x9f,0xa1,
0xa3,0xa5,0xa7,0xa8,0xa6,0xa6,0x99,0x92,0x90,0x89,0x83,0x77,0x6d,0x66,0x63,0x5e,
0x58,0x57,0x56,0x58,0x5d,0x5f,0x65,0x6c,0x72,0x78,0x81,0x88,0x8e,0x92,0x94,0x97,
0x9b,0x9a,0x97,0x94,0x90,0x8c,0x87,0x81,0x7b,0x76,0x71,0x6c,0x69,0x65,0x63,0x63,
0x63,0x66,0x69,0x6c,0x70,0x76,0x7d,0x84,0x8a,0x8f,0x94,0x99,0x9e,0xa0,0xa2,0xa2,
0xa4,0xa3,0xa3,0xa2,0xa5,0x98,0x8b,0x8a,0x85,0x83,0x77,0x6b,0x63,0x63,0x60,0x5a,
0x59,0x59,0x5b,0x60,0x63,0x68,0x72,0x76,0x7b,0x82,0x8a,0x90,0x94,0x94,0x95,0x98,
0x98,0x94,0x8f,0x8b,0x88,0x83,0x7c,0x77,0x73,0x6e,0x68,0x66,0x65,0x66,0x65,0x64,
0x68,0x6e,0x73,0x76,0x7b,0x81,0x8a,0x8f,0x93,0x97,0x9c,0x9e,0xa1,0xa1,0xa1,0xa1,
0xa1,0xa1,0xa0,0xa0,0x90,0x88,0x87,0x81,0x7d,0x73,0x68,0x63,0x61,0x5e,0x5a,0x5c,
0x5c,0x5f,0x64,0x67,0x70,0x77,0x7b,0x80,0x88,0x8e,0x93,0x94,0x93,0x95,0x97,0x93,
0x8f,0x8a,0x86,0x82,0x7c,0x77,0x72,0x6f,0x6a,0x68,0x67,0x66,0x67,0x68,0x6b,0x6f,
0x73,0x78,0x7c,0x81,0x87,0x8c,0x91,0x94,0x98,0x9a,0x9d,0x9e,0x9e,0x9e,0x9d,0x9d,
0x9e,0x9f,0x9b,0x8a,0x88,0x85,0x81,0x7c,0x6f,0x68,0x64,0x64,0x5e,0x5d,0x5e,0x5f,
0x63,0x66,0x6b,0x74,0x7a,0x7c,0x83,0x8a,0x90,0x93,0x92,0x91,0x94,0x94,0x90,0x8b,
0x87,0x83,0x80,0x7a,0x75,0x72,0x6f,0x6a,0x68,0x68,0x69,0x6a,0x6a,0x6c,0x71,0x77,
0x7b,0x7f,0x83,0x8a,0x8f,0x93,0x96,0x99,0x9b,0x9e,0x9e,0x9e,0x9e,0x9e,0x9e,0xa0,
0xa0,0x90,0x86,0x82,0x84,0x7e,0x75,0x66,0x62,0x63,0x60,0x5c,0x5b,0x5e,0x61,0x67,
0x69,0x73,0x7a,0x7e,0x81,0x89,0x90,0x95,0x95,0x91,0x92,0x95,0x92,0x8c,0x86,0x81,
0x7f,0x79,0x74,0x6f,0x6d,0x6a,0x66,0x65,0x68,0x6a,0x6b,0x6b,0x71,0x78,0x7c,0x7f,
0x83,0x89,0x8f,0x93,0x95,0x98,0x9b,0x9c,0x9d,0x9c,0x9d,0x9b,0x9c,0x9d,0xa0,0x99,
0x87,0x84,0x82,0x80,0x7b,0x6d,0x63,0x62,0x61,0x5f,0x5d,0x5f,0x5f,0x65,0x69,0x6f,
0x79,0x7d,0x80,0x86,0x8d,0x92,0x96,0x93,0x91,0x93,0x91,0x8c,0x87,0x81,0x7d,0x79,
0x73,0x6f,0x6d,0x6a,0x66,0x66,0x67,0x69,0x6c,0x6e,0x71,0x76,0x7c,0x81,0x85,0x88,
0x8e,0x92,0x96,0x98,0x9a,0x9b,0x9b,0x9a,0x9b,0x9d,0x9e,0x9c,0x9f,0x99,0x86,0x86,
0x81,0x81,0x7a,0x6c,0x63,0x61,0x61,0x5c,0x5d,0x5d,0x5f,0x65,0x6a,0x6f,0x7a,0x7f,
0x82,0x88,0x8e,0x94,0x96,0x94,0x91,0x93,0x91,0x8c,0x86,0x80,0x7b,0x77,0x72,0x6e,
0x6c,0x69,0x66,0x64,0x66,0x6b,0x6e,0x6e,0x70,0x77,0x7e,0x83,0x85,0x89,0x8e,0x93,
0x97,0x98,0x9a,0x9b,0x9b,0x9b,0x9c,0x9e,0x9e,0x9c,0xa0,0x95,0x88,0x86,0x80,0x7f,
0x77,0x6c,0x62,0x61,0x5f,0x5c,0x5e,0x5e,0x61,0x67,0x6b,0x72,0x7d,0x81,0x85,0x8b,
0x90,0x94,0x97,0x94,0x92,0x92,0x8e,0x8a,0x84,0x7e,0x79,0x75,0x70,0x6c,0x6b,0x69,
0x67,0x66,0x67,0x6c,0x70,0x72,0x75,0x79,0x7f,0x85,0x89,0x89,0x8d,0x90,0x94,0x96,
0x97,0x96,0x97,0x97,0x97,0x99,0x99,0x9a,0x9a,0x9f,0x8b,0x89,0x84,0x7f,0x80,0x73,
0x6c,0x62,0x66,0x5e,0x61,0x60,0x60,0x65,0x6a,0x6d,0x77,0x7f,0x80,0x87,0x8b,0x91,
0x93,0x96,0x90,0x91,0x8f,0x8b,0x87,0x81,0x7c,0x78,0x74,0x70,0x6d,0x6b,0x69,0x67,
0x69,0x6a,0x6e,0x70,0x72,0x77,0x7d,0x81,0x85,0x88,0x8d,0x91,0x95,0x96,0x98,0x9a,
0x9c,0x9c,0x9b,0x9a,0x9d,0x9e,0xa2,0x9c,0x85,0x86,0x82,0x81,0x7a,0x6b,0x61,0x60,
0x61,0x5b,0x5e,0x5d,0x5f,0x66,0x6c,0x71,0x7e,0x82,0x85,0x8b,0x92,0x97,0x99,0x95,
0x91,0x92,0x90,0x8a,0x83,0x7c,0x77,0x73,0x6f,0x6c,0x69,0x67,0x62,0x64,0x68,0x6d,
0x6f,0x70,0x74,0x7c,0x83,0x87,0x8a,0x8e,0x91,0x96,0x98,0x99,0x9a,0x99,0x99,0x9a,
0x9b,0x9b,0x9d,0x9c,0x9f,0x8b,0x83,0x81,0x7f,0x7f,0x70,0x65,0x5c,0x62,0x5f,0x5e,
0x5e,0x5f,0x65,0x6d,0x70,0x79,0x83,0x85,0x8a,0x8e,0x95,0x98,0x97,0x91,0x90,0x8f,
0x8b,0x84,0x7d,0x76,0x73,0x6f,0x6b,0x69,0x68,0x67,0x66,0x68,0x6a,0x70,0x72,0x76,
0x7a,0x80,0x84,0x89,0x8a,0x8f,0x91,0x94,0x94,0x96,0x97,0x97,0x97,0x98,0x98,0x9a,
0x9c,0x9c,0xa0,0x87,0x88,0x82,0x80,0x7d,0x71,0x67,0x5f,0x64,0x5a,0x60,0x5f,0x61,
0x64,0x6c,0x6f,0x7c,0x82,0x83,0x8a,0x8f,0x95,0x95,0x96,0x8f,0x91,0x8e,0x88,0x83,
0x7f,0x78,0x73,0x6e,0x6c,0x6a,0x69,0x65,0x63,0x67,0x6c,0x72,0x73,0x74,0x79,0x81,
0x87,0x8b,0x8c,0x8f,0x91,0x95,0x96,0x98,0x97,0x96,0x95,0x97,0x97,0x9b,0x9a,0x9c,
0x9b,0x85,0x87,0x81,0x81,0x7c,0x70,0x64,0x61,0x64,0x5d,0x60,0x60,0x61,0x67,0x6e,
0x71,0x7e,0x82,0x85,0x8a,0x90,0x94,0x96,0x94,0x8f,0x8f,0x8d,0x87,0x81,0x7b,0x76,
0x73,0x6f,0x6c,0x69,0x68,0x66,0x67,0x69,0x6d,0x71,0x73,0x75,0x7c,0x81,0x86,0x89,
0x8c,0x90,0x93,0x95,0x96,0x97,0x96,0x98,0x99,0x9b,0x99,0x9c,0x9a,0xa2,0x93,0x85,
0x85,0x7f,0x80,0x75,0x6a,0x60,0x63,0x5f,0x5d,0x5f,0x60,0x64,0x6c,0x6e,0x77,0x82,
0x85,0x89,0x8d,0x93,0x96,0x98,0x92,0x8f,0x8f,0x8b,0x84,0x7e,0x78,0x74,0x70,0x6b,
0x69,0x69,0x68,0x67,0x68,0x6a,0x6f,0x74,0x77,0x7a,0x80,0x83,0x88,0x8b,0x8e,0x91,
0x93,0x93,0x95,0x96,0x96,0x96,0x95,0x97,0x98,0x9b,0x9b,0xa3,0x8c,0x85,0x84,0x82,
0x82,0x75,0x69,0x60,0x65,0x5e,0x60,0x61,0x60,0x65,0x6b,0x6f,0x7a,0x83,0x83,0x88,
0x8d,0x93,0x96,0x96,0x90,0x8f,0x8e,0x89,0x84,0x7e,0x78,0x74,0x70,0x6c,0x6b,0x6a,
0x68,0x66,0x68,0x6c,0x71,0x74,0x76,0x7a,0x7f,0x84,0x89,0x8b,0x8e,0x91,0x94,0x96,
0x98,0x97,0x98,0x98,0x99,0x99,0x9c,0x9a,0x9f,0x9b,0x84,0x85,0x80,0x81,0x79,0x6d,
0x61,0x60,0x62,0x5b,0x60,0x60,0x63,0x69,0x6e,0x74,0x81,0x84,0x87,0x8c,0x92,0x96,
0x97,0x94,0x8e,0x8f,0x8c,0x85,0x7f,0x79,0x75,0x71,0x6c,0x69,0x68,0x68,0x66,0x67,
0x69,0x6f,0x74,0x76,0x79,0x7f,0x84,0x88,0x8b,0x8d,0x90,0x92,0x94,0x94,0x96,0x95,
0x97,0x94,0x96,0x96,0x9a,0x99,0xa2,0x90,0x83,0x87,0x80,0x82,0x73,0x6b,0x61,0x67,
0x5f,0x5c,0x60,0x60,0x66,0x6b,0x6f,0x77,0x84,0x83,0x88,0x8c,0x94,0x95,0x96,0x90,
0x8e,0x8f,0x89,0x83,0x7d,0x78,0x73,0x70,0x6b,0x6a,0x69,0x67,0x67,0x6b,0x6e,0x71,
0x73,0x77,0x7c,0x82,0x84,0x88,0x8a,0x8d,0x8f,0x91,0x92,0x93,0x94,0x92,0x94,0x95,
0x97,0x97,0x99,0x9a,0xa2,0x8e,0x86,0x86,0x80,0x83,0x75,0x6a,0x61,0x65,0x5f,0x5f,
0x61,0x60,0x66,0x6b,0x6e,0x79,0x82,0x83,0x88,0x8d,0x93,0x96,0x96,0x90,0x8e,0x8d,
0x89,0x83,0x7d,0x77,0x74,0x70,0x6c,0x6a,0x69,0x67,0x68,0x6a,0x6d,0x72,0x75,0x77,
0x7b,0x81,0x85,0x8a,0x8b,0x8d,0x90,0x94,0x93,0x95,0x94,0x96,0x96,0x97,0x97,0x9a,
0x9b,0x9f,0x9b,0x84,0x87,0x83,0x82,0x7c,0x6e,0x64,0x61,0x63,0x5c,0x60,0x60,0x62,
0x68,0x6e,0x74,0x81,0x84,0x86,0x8b,0x92,0x96,0x97,0x94,0x8e,0x8e,0x8b,0x85,0x7f,
0x7a,0x74,0x71,0x6c,0x6a,0x69,0x68,0x68,0x69,0x6c,0x71,0x73,0x76,0x7b,0x80,0x84,
0x87,0x8a,0x8c,0x8f,0x90,0x91,0x92,0x94,0x92,0x93,0x92,0x95,0x95,0x99,0x98,0x9e,
0x9a,0x85,0x88,0x81,0x84,0x7c,0x6f,0x64,0x65,0x65,0x5e,0x62,0x61,0x64,0x6a,0x6f,
0x74,0x81,0x84,0x86,0x8a,0x90,0x94,0x96,0x92,0x8d,0x8e,0x8b,0x85,0x7f,0x79,0x74,
0x73,0x6e,0x6b,0x6a,0x69,0x67,0x68,0x6c,0x71,0x75,0x76,0x79,0x7f,0x85,0x89,0x8c,
0x8d,0x90,0x93,0x94,0x96,0x95,0x95,0x96,0x96,0x97,0x98,0x9a,0x9b,0x9e,0x87,0x83,
0x85,0x7f,0x7f,0x71,0x66,0x61,0x65,0x5f,0x60,0x63,0x62,0x69,0x6f,0x73,0x7f,0x86,
0x86,0x8b,0x8f,0x94,0x96,0x94,0x8e,0x8d,0x8c,0x85,0x80,0x7a,0x74,0x71,0x6e,0x6b,
0x6a,0x69,0x68,0x6a,0x6e,0x72,0x75,0x76,0x79,0x7f,0x85,0x86,0x88,0x89,0x8c,0x8e,
0x8f,0x8f,0x91,0x90,0x91,0x92,0x94,0x95,0x96,0x97,0x9c,0xa3,0x8c,0x89,0x83,0x81,
0x83,0x77,0x69,0x62,0x65,0x5f,0x62,0x60,0x61,0x67,0x6c,0x6f,0x7b,0x83,0x85,0x88,
0x8c,0x92,0x96,0x96,0x8e,0x8d,0x8c,0x88,0x83,0x7d,0x76,0x74,0x70,0x6d,0x6a,0x6a,
0x67,0x67,0x69,0x6e,0x73,0x75,0x76,0x7b,0x81,0x86,0x8a,0x8c,0x8e,0x91,0x94,0x94,
0x95,0x95,0x96,0x94,0x96,0x97,0x9c,0x98,0x9e,0x93,0x81,0x88,0x82,0x81,0x76,0x6b,
0x61,0x65,0x63,0x5c,0x62,0x62,0x66,0x6c,0x71,0x78,0x84,0x85,0x87,0x8d,0x93,0x95,
0x95,0x90,0x8c,0x8d,0x88,0x81,0x7c,0x77,0x73,0x70,0x6b,0x6a,0x6a,0x69,0x69,0x6c,
0x6f,0x73,0x75,0x78,0x7c,0x82,0x86,0x88,0x8a,0x8b,0x8e,0x8f,0x91,0x91,0x92,0x90,
0x91,0x92,0x95,0x95,0x98,0x97,0xa0,0x9a,0x85,0x88,0x81,0x84,0x7c,0x70,0x64,0x65,
0x64,0x5d,0x62,0x62,0x66,0x6b,0x6e,0x74,0x81,0x84,0x86,0x8b,0x90,0x94,0x96,0x92,
0x8c,0x8d,0x89,0x83,0x7e,0x78,0x75,0x72,0x6d,0x6a,0x6b,0x6a,0x69,0x6a,0x6d,0x71,
0x74,0x77,0x7b,0x81,0x84,0x88,0x8a,0x8d,0x90,0x92,0x92,0x94,0x94,0x93,0x93,0x95,
0x96,0x99,0x9a,0x9b,0xa0,0x8a,0x86,0x84,0x83,0x81,0x74,0x66,0x60,0x66,0x5f,0x60,
0x61,0x61,0x68,0x6e,0x73,0x7e,0x85,0x85,0x8a,0x8f,0x94,0x96,0x94,0x8e,0x8d,0x8b,
0x86,0x80,0x7a,0x75,0x72,0x6f,0x6b,0x6a,0x6a,0x68,0x69,0x6b,0x70,0x74,0x76,0x79,
0x7e,0x84,0x87,0x8a,0x8b,0x8e,0x90,0x92,0x91,0x94,0x93,0x93,0x91,0x94,0x97,0x99,
0x97,0x9b,0x9d,0x88,0x88,0x81,0x81,0x7f,0x73,0x67,0x62,0x67,0x60,0x63,0x61,0x63,
0x6b,0x70,0x73,0x7e,0x84,0x86,0x8a,0x8e,0x92,0x95,0x93,0x8c,0x8b,0x89,0x85,0x7f,
0x7a,0x75,0x73,0x6f,0x6c,0x6a,0x6a,0x69,0x6a,0x6e,0x71,0x75,0x77,0x79,0x7f,0x84,
0x87,0x8a,0x8a,0x8d,0x8f,0x91,0x91,0x92,0x91,0x92,0x92,0x94,0x96,0x99,0x97,0x9b,
0x9b,0x8a,0x89,0x82,0x81,0x7d,0x72,0x67,0x63,0x64,0x5f,0x62,0x62,0x64,0x6a,0x6f,
0x74,0x7e,0x84,0x86,0x8b,0x8e,0x92,0x94,0x92,0x8d,0x8c,0x89,0x84,0x7f,0x7a,0x75,
0x72,0x6f,0x6c,0x6b,0x6b,0x6a,0x6c,0x6e,0x72,0x76,0x77,0x7a,0x7f,0x83,0x85,0x87,
0x87,0x8b,0x8d,0x8d,0x8d,0x8e,0x8f,0x8f,0x90,0x90,0x94,0x98,0x9b,0x9a,0xa1,0x94,
0x89,0x8a,0x83,0x83,0x79,0x6f,0x63,0x65,0x61,0x5e,0x62,0x60,0x65,0x6b,0x6f,0x76,
0x81,0x83,0x87,0x8c,0x90,0x93,0x95,0x91,0x8d,0x8c,0x88,0x83,0x7f,0x79,0x75,0x72,
0x6d,0x6c,0x6b,0x6b,0x6a,0x6b,0x6d,0x71,0x75,0x77,0x7a,0x7f,0x84,0x87,0x88,0x89,
0x8d,0x8f,0x90,0x90,0x91,0x92,0x93,0x93,0x95,0x97,0x9b,0x99,0xa0,0x96,0x86,0x89,
0x80,0x82,0x79,0x6e,0x63,0x64,0x62,0x5e,0x64,0x61,0x66,0x6c,0x70,0x77,0x82,0x85,
0x87,0x8d,0x90,0x93,0x95,0x90,0x8c,0x8b,0x87,0x82,0x7e,0x77,0x73,0x71,0x6d,0x6c,
0x6b,0x69,0x69,0x6c,0x6f,0x74,0x76,0x78,0x7b,0x81,0x86,0x89,0x8a,0x8b,0x8e,0x91,
0x91,0x92,0x91,0x92,0x93,0x93,0x94,0x99,0x9a,0x9c,0x9f,0x8d,0x86,0x87,0x82,0x81,
0x76,0x69,0x62,0x65,0x60,0x60,0x64,0x61,0x67,0x6d,0x72,0x7c,0x84,0x85,0x89,0x8f,
0x92,0x95,0x94,0x8e,0x8b,0x8a,0x85,0x80,0x7b,0x74,0x72,0x6e,0x6b,0x6a,0x6a,0x6a,
0x6a,0x6e,0x72,0x76,0x78,0x7a,0x7f,0x85,0x89,0x8a,0x8b,0x8d,0x8f,0x91,0x91,0x91,
0x91,0x92,0x93,0x94,0x96,0x9c,0x9a,0x9e,0x96,0x87,0x8a,0x84,0x81,0x79,0x6e,0x65,
0x64,0x63,0x5d,0x62,0x62,0x65,0x6b,0x70,0x77,0x81,0x85,0x87,0x8d,0x91,0x94,0x94,
0x91,0x8d,0x8c,0x88,0x81,0x7d,0x78,0x74,0x70,0x6c,0x6a,0x6a,0x69,0x68,0x6a,0x6f,
0x74,0x76,0x78,0x7c,0x82,0x87,0x8a,0x8b,0x8d,0x8f,0x91,0x91,0x92,0x92,0x93,0x93,
0x94,0x95,0x98,0x99,0x9b,0x9e,0x89,0x86,0x83,0x80,0x80,0x73,0x68,0x61,0x64,0x60,
0x61,0x64,0x62,0x69,0x6f,0x74,0x7e,0x85,0x86,0x89,0x8e,0x92,0x95,0x94,0x8d,0x8a,
0x89,0x84,0x7f,0x7a,0x74,0x71,0x6d,0x6b,0x6a,0x6b,0x69,0x6a,0x6d,0x72,0x75,0x79,
0x7b,0x7f,0x84,0x88,0x8a,0x8c,0x8d,0x8f,0x91,0x90,0x91,0x92,0x94,0x92,0x94,0x95,
0x9a,0x9b,0xa2,0x93,0x83,0x88,0x81,0x84,0x79,0x6c,0x61,0x64,0x63,0x5e,0x63,0x61,
0x65,0x6c,0x70,0x78,0x84,0x86,0x87,0x8c,0x91,0x95,0x96,0x90,0x8a,0x8a,0x87,0x81,
0x7d,0x76,0x73,0x70,0x6c,0x6a,0x6a,0x6a,0x69,0x6b,0x6f,0x74,0x77,0x78,0x7b,0x81,
0x86,0x89,0x8b,0x8c,0x8e,0x91,0x91,0x92,0x91,0x93,0x92,0x93,0x95,0x98,0x9b,0x9d,
0x9e,0x88,0x86,0x86,0x83,0x80,0x71,0x66,0x62,0x66,0x60,0x60,0x62,0x62,0x69,0x6e,
0x73,0x7e,0x85,0x86,0x89,0x8f,0x94,0x96,0x93,0x8d,0x8b,0x8a,0x85,0x7f,0x79,0x74,
0x72,0x6e,0x6b,0x6b,0x6b,0x6a,0x6b,0x6e,0x72,0x77,0x79,0x7b,0x7f,0x85,0x87,0x8a,
0x89,0x8a,0x8c,0x8d,0x8d,0x8d,0x8d,0x8e,0x90,0x90,0x91,0x95,0x9a,0x9b,0xa5,0x91,
0x89,0x8a,0x84,0x87,0x7b,0x6e,0x63,0x67,0x61,0x5f,0x63,0x61,0x65,0x6b,0x6e,0x78,
0x83,0x84,0x86,0x8b,0x90,0x95,0x96,0x90,0x8c,0x8c,0x88,0x82,0x7e,0x78,0x74,0x71,
0x6d,0x6b,0x6c,0x6b,0x69,0x6a,0x6f,0x74,0x77,0x78,0x7b,0x82,0x86,0x89,0x8a,0x8c,
0x8e,0x91,0x91,0x93,0x92,0x95,0x94,0x94,0x96,0x9c,0x9b,0xa1,0x98,0x84,0x88,0x81,
0x82,0x7c,0x6e,0x63,0x61,0x62,0x5d,0x63,0x62,0x63,0x6c,0x70,0x78,0x84,0x87,0x88,
0x8d,0x92,0x95,0x97,0x93,0x8c,0x8a,0x87,0x81,0x7e,0x77,0x71,0x6f,0x6c,0x6b,0x6a,
0x6b,0x6a,0x6c,0x71,0x75,0x79,0x7b,0x7d,0x83,0x87,0x89,0x8a,0x8b,0x8c,0x8c,0x8d,
0x8d,0x8e,0x8d,0x8d,0x8f,0x92,0x94,0x98,0x99,0xa1,0x99,0x89,0x8a,0x84,0x86,0x7e,
0x71,0x65,0x64,0x64,0x5f,0x62,0x61,0x64,0x6a,0x6e,0x75,0x80,0x85,0x86,0x8a,0x8f,
0x93,0x95,0x92,0x8c,0x8b,0x88,0x83,0x7f,0x79,0x74,0x71,0x6d,0x6c,0x6c,0x6b,0x69,
0x6b,0x6f,0x74,0x77,0x79,0x7b,0x81,0x85,0x87,0x89,0x8a,0x8b,0x8d,0x8e,0x8f,0x8f,
0x8f,0x91,0x91,0x93,0x96,0x9a,0x9b,0xa2,0x92,0x86,0x87,0x82,0x84,0x79,0x6c,0x61,
0x64,0x61,0x5f,0x64,0x62,0x66,0x6c,0x71,0x7a,0x85,0x87,0x88,0x8c,0x92,0x95,0x96,
0x90,0x8a,0x89,0x86,0x80,0x7b,0x75,0x71,0x6f,0x6c,0x6a,0x6b,0x6b,0x6b,0x6e,0x72,
0x76,0x7a,0x7d,0x7f,0x84,0x86,0x89,0x8a,0x8b,0x8b,0x8b,0x8b,0x8c,0x8d,0x8d,0x8d,
0x8f,0x91,0x94,0x99,0x9b,0xa2,0x91,0x87,0x87,0x84,0x87,0x7a,0x6e,0x62,0x66,0x63,
0x61,0x64,0x61,0x66,0x6b,0x71,0x79,0x82,0x85,0x87,0x8c,0x90,0x94,0x95,0x90,0x8b,
0x8a,0x86,0x82,0x7d,0x76,0x73,0x70,0x6d,0x6c,0x6c,0x6a,0x6a,0x6d,0x72,0x75,0x78,
0x79,0x7e,0x82,0x86,0x89,0x8a,0x8b,0x8d,0x8f,0x90,0x92,0x91,0x93,0x93,0x93,0x95,
0x9b,0x9a,0xa3,0x91,0x83,0x85,0x81,0x82,0x77,0x6c,0x60,0x64,0x62,0x5f,0x64,0x64,
0x67,0x6d,0x73,0x7c,0x86,0x88,0x89,0x8d,0x93,0x96,0x95,0x90,0x8a,0x89,0x85,0x7f,
0x7b,0x75,0x71,0x6d,0x6b,0x6a,0x6b,0x6c,0x6b,0x6d,0x73,0x77,0x7b,0x7c,0x7f,0x84,
0x88,0x8a,0x8b,0x8c,0x8c,0x8d,0x8d,0x8e,0x8d,0x8f,0x8f,0x91,0x92,0x97,0x98,0xa0,
0x9d,0x87,0x87,0x82,0x86,0x80,0x74,0x66,0x63,0x66,0x60,0x64,0x63,0x64,0x6a,0x6f,
0x75,0x81,0x87,0x87,0x8a,0x8e,0x93,0x96,0x93,0x8c,0x8a,0x89,0x83,0x7f,0x78,0x73,
0x71,0x6e,0x6c,0x6c,0x6c,0x6c,0x6c,0x6f,0x74,0x78,0x7b,0x7b,0x80,0x85,0x88,0x89,
0x8a,0x8a,0x8e,0x8e,0x90,0x8f,0x90,0x90,0x91,0x93,0x96,0x9a,0x9b,0xa3,0x8d,0x87,
0x84,0x81,0x84,0x78,0x6c,0x61,0x65,0x60,0x61,0x64,0x63,0x68,0x6e,0x73,0x7c,0x86,
0x88,0x8a,0x8e,0x92,0x95,0x96,0x90,0x8a,0x89,0x84,0x7f,0x7a,0x74,0x71,0x6e,0x6b,
0x6b,0x6c,0x6c,0x6c,0x6f,0x73,0x76,0x7a,0x7c,0x7f,0x84,0x87,0x88,0x8b,0x8b,0x8d,
0x8e,0x8f,0x8f,0x90,0x91,0x90,0x93,0x95,0x9a,0x9c,0xa3,0x8f,0x86,0x86,0x82,0x85,
0x77,0x6b,0x60,0x64,0x60,0x60,0x64,0x62,0x67,0x6c,0x72,0x7c,0x86,0x88,0x89,0x8d,
0x92,0x97,0x97,0x90,0x8a,0x89,0x85,0x80,0x7a,0x74,0x70,0x6e,0x6a,0x6a,0x6a,0x6a,
0x6a,0x6b,0x71,0x76,0x7a,0x7c,0x7f,0x84,0x8a,0x8b,0x8d,0x8d,0x91,0x91,0x92,0x91,
0x92,0x91,0x93,0x92,0x96,0x99,0x9c,0xa0,0x83,0x84,0x80,0x83,0x81,0x72,0x66,0x5e,
0x66,0x5f,0x64,0x65,0x65,0x6a,0x70,0x76,0x81,0x8a,0x88,0x8a,0x8f,0x94,0x96,0x94,
0x8c,0x88,0x87,0x82,0x7d,0x78,0x73,0x6f,0x6c,0x69,0x6b,0x6d,0x6c,0x6d,0x70,0x74,
0x78,0x7c,0x7e,0x82,0x85,0x88,0x89,0x8b,0x8a,0x8c,0x8d,0x8d,0x8e,0x8f,0x8f,0x8e,
0x91,0x94,0x9a,0x99,0xa4,0x91,0x85,0x86,0x82,0x86,0x7b,0x6f,0x60,0x65,0x63,0x61,
0x66,0x62,0x66,0x6d,0x72,0x7a,0x85,0x87,0x88,0x8c,0x91,0x94,0x96,0x90,0x89,0x88,
0x85,0x80,0x7c,0x75,0x71,0x6f,0x6d,0x6b,0x6d,0x6c,0x6b,0x6d,0x71,0x76,0x7a,0x7b,
0x7d,0x82,0x87,0x89,0x8c,0x8c,0x8e,0x90,0x91,0x91,0x92,0x94,0x92,0x93,0x94,0x99,
0x9a,0xa2,0x8e,0x81,0x85,0x80,0x83,0x77,0x6c,0x60,0x66,0x63,0x61,0x66,0x65,0x68,
0x6f,0x74,0x7c,0x88,0x89,0x88,0x8d,0x92,0x95,0x95,0x8e,0x88,0x87,0x84,0x7d,0x7a,
0x75,0x70,0x6e,0x6b,0x6b,0x6e,0x6e,0x6d,0x6e,0x73,0x78,0x7c,0x7d,0x7f,0x84,0x87,
0x89,0x8a,0x8b,0x8c,0x8e,0x8d,0x8f,0x8f,0x91,0x8f,0x92,0x92,0x98,0x98,0xa0,0x97,
0x85,0x88,0x81,0x85,0x7d,0x72,0x65,0x64,0x65,0x60,0x66,0x65,0x66,0x6c,0x71,0x77,
0x83,0x87,0x88,0x8b,0x8f,0x93,0x95,0x92,0x8a,0x88,0x85,0x80,0x7c,0x77,0x72,0x6f,
0x6d,0x6c,0x6d,0x6d,0x6c,0x6c,0x70,0x75,0x79,0x7c,0x7e,0x81,0x86,0x88,0x8b,0x8d,
0x8e,0x90,0x90,0x91,0x92,0x94,0x92,0x93,0x93,0x97,0x98,0xa0,0x96,0x81,0x83,0x80,
0x81,0x7c,0x6f,0x63,0x64,0x65,0x60,0x66,0x68,0x68,0x6e,0x73,0x79,0x85,0x8a,0x88,
0x8a,0x8f,0x92,0x94,0x90,0x88,0x85,0x84,0x7e,0x7a,0x76,0x71,0x6f,0x6d,0x6c,0x6e,
0x70,0x6e,0x6e,0x72,0x77,0x7b,0x7d,0x7e,0x82,0x86,0x88,0x88,0x89,0x8a,0x8c,0x8c,
0x8d,0x8d,0x90,0x8f,0x90,0x90,0x96,0x98,0x9d,0xa2,0x89,0x87,0x84,0x83,0x83,0x79,
0x6b,0x62,0x67,0x60,0x63,0x67,0x65,0x69,0x6f,0x72,0x7c,0x87,0x87,0x88,0x8c,0x8f,
0x93,0x94,0x8d,0x87,0x87,0x83,0x7f,0x7c,0x75,0x72,0x70,0x6d,0x6e,0x70,0x6f,0x6e,
0x70,0x74,0x78,0x7b,0x7c,0x7d,0x82,0x84,0x86,0x87,0x87,0x88,0x89,0x8a,0x8a,0x8c,
0x8c,0x8c,0x8d,0x90,0x90,0x92,0x93,0x98,0x97,0x8d,0x85,0x81,0x82,0x80,0x79,0x6e,
0x69,0x69,0x68,0x68,0x68,0x6b,0x6f,0x72,0x75,0x7b,0x83,0x86,0x88,0x89,0x8a,0x8d,
0x8d,0x89,0x85,0x83,0x81,0x7d,0x79,0x75,0x74,0x72,0x6f,0x6e,0x6f,0x70,0x71,0x73,
0x76,0x7a,0x7d,0x7f,0x81,0x86,0x89,0x8d,0x8e,0x8f,0x8f,0x92,0x92,0x93,0x92,0x93,
0x93,0x93,0x96,0x98,0xa0,0x8c,0x80,0x7d,0x7c,0x80,0x78,0x6a,0x5f,0x63,0x62,0x64,
0x68,0x69,0x6c,0x72,0x75,0x7e,0x8a,0x8c,0x8a,0x8c,0x8f,0x93,0x93,0x8b,0x84,0x83,
0x80,0x7b,0x77,0x73,0x70,0x6e,0x6c,0x6d,0x72,0x73,0x71,0x72,0x76,0x7d,0x80,0x80,
0x80,0x84,0x86,0x88,0x87,0x86,0x87,0x88,0x87,0x88,0x89,0x89,0x8a,0x8b,0x8c,0x8f,
0x94,0x95,0x99,0x96,0x8d,0x89,0x86,0x85,0x81,0x7a,0x70,0x6b,0x6b,0x68,0x68,0x69,
0x6a,0x6d,0x70,0x75,0x7b,0x81,0x84,0x86,0x89,0x8b,0x8e,0x8d,0x8a,0x86,0x85,0x82,
0x7f,0x7b,0x78,0x75,0x71,0x70,0x6f,0x70,0x70,0x70,0x71,0x75,0x79,0x7b,0x7e,0x81,
0x85,0x88,0x8c,0x8e,0x90,0x91,0x92,0x93,0x95,0x93,0x93,0x92,0x93,0x95,0x95,0x9a,
0x8c,0x83,0x7c,0x79,0x7b,0x77,0x6e,0x63,0x63,0x63,0x66,0x6b,0x6c,0x6e,0x74,0x78,
0x7f,0x88,0x8b,0x8b,0x8b,0x8d,0x8f,0x8f,0x8b,0x84,0x80,0x7d,0x7a,0x77,0x73,0x70,
0x6e,0x6d,0x6e,0x70,0x72,0x73,0x73,0x77,0x7b,0x80,0x82,0x83,0x84,0x87,0x88,0x8a,
0x8b,0x8b,0x8a,0x8a,0x8b,0x8e,0x8f,0x8d,0x8d,0x8e,0x93,0x96,0x9f,0x93,0x86,0x82,
0x7f,0x83,0x7f,0x75,0x68,0x66,0x64,0x65,0x6a,0x6a,0x6a,0x6e,0x71,0x78,0x83,0x87,
0x87,0x88,0x8a,0x8e,0x91,0x8e,0x88,0x84,0x82,0x7f,0x7c,0x78,0x73,0x70,0x6e,0x6f,
0x71,0x70,0x6f,0x6f,0x72,0x77,0x7c,0x7d,0x7e,0x81,0x84,0x88,0x8b,0x8c,0x8d,0x8e,
0x8d,0x8e,0x91,0x92,0x90,0x8f,0x8e,0x94,0x94,0x9b,0x97,0x85,0x80,0x7c,0x80,0x7d,
0x76,0x68,0x63,0x66,0x65,0x69,0x6b,0x6b,0x6f,0x74,0x79,0x82,0x89,0x89,0x89,0x8b,
0x8e,0x90,0x8f,0x88,0x82,0x81,0x7d,0x7a,0x76,0x72,0x70,0x6f,0x6d,0x6e,0x70,0x72,
0x72,0x74,0x77,0x7c,0x80,0x81,0x82,0x85,0x88,0x8b,0x8c,0x8c,0x8d,0x8d,0x8e,0x8e,
0x91,0x90,0x90,0x8e,0x92,0x93,0x9d,0x98,0x83,0x81,0x7d,0x82,0x7e,0x75,0x68,0x66,
0x68,0x64,0x69,0x6b,0x6c,0x70,0x72,0x77,0x82,0x89,0x88,0x87,0x8a,0x8e,0x91,0x8f,
0x88,0x83,0x82,0x7e,0x7b,0x78,0x74,0x71,0x6f,0x6e,0x70,0x73,0x72,0x71,0x73,0x77,
0x7c,0x80,0x81,0x82,0x84,0x87,0x89,0x8b,0x8c,0x8c,0x8b,0x8c,0x8d,0x8f,0x8f,0x8f,
0x8f,0x91,0x93,0x96,0x9f,0x8c,0x84,0x7f,0x7f,0x83,0x7c,0x70,0x64,0x68,0x65,0x68,
0x6b,0x6a,0x6d,0x71,0x73,0x7b,0x86,0x88,0x87,0x88,0x8a,0x8f,0x91,0x8b,0x85,0x83,
0x81,0x7e,0x7a,0x76,0x73,0x71,0x6e,0x6e,0x71,0x71,0x71,0x71,0x74,0x7a,0x7e,0x80,
0x81,0x84,0x87,0x8a,0x8c,0x8e,0x8f,0x8f,0x8f,0x90,0x93,0x91,0x92,0x90,0x93,0x91,
0x9b,0x97,0x83,0x82,0x7c,0x7f,0x7d,0x76,0x69,0x66,0x68,0x64,0x6a,0x6c,0x6d,0x71,
0x73,0x77,0x82,0x89,0x88,0x88,0x8a,0x8c,0x90,0x8e,0x88,0x83,0x81,0x7d,0x7b,0x78,
0x74,0x71,0x6e,0x6d,0x70,0x73,0x72,0x71,0x73,0x77,0x7d,0x80,0x80,0x82,0x85,0x87,
0x89,0x8c,0x8c,0x8e,0x8c,0x8d,0x8e,0x91,0x90,0x8f,0x8e,0x92,0x93,0x9a,0x99,0x83,
0x82,0x7e,0x82,0x80,0x77,0x6a,0x65,0x69,0x65,0x6a,0x6c,0x6b,0x6e,0x72,0x75,0x80,
0x88,0x86,0x86,0x89,0x8c,0x90,0x8f,0x88,0x84,0x83,0x7f,0x7c,0x79,0x75,0x72,0x6f,
0x6d,0x6f,0x71,0x71,0x6f,0x71,0x75,0x7b,0x7e,0x80,0x81,0x85,0x88,0x8b,0x8d,0x8e,
0x8f,0x8e,0x8f,0x90,0x93,0x91,0x91,0x90,0x93,0x93,0x9b,0x8e,0x80,0x80,0x7e,0x81,
0x7a,0x71,0x66,0x68,0x68,0x67,0x6b,0x6c,0x6e,0x71,0x74,0x7a,0x85,0x89,0x87,0x87,
0x8b,0x8e,0x91,0x8b,0x85,0x83,0x82,0x7d,0x7a,0x77,0x73,0x71,0x6f,0x6f,0x71,0x73,
0x72,0x72,0x74,0x79,0x7c,0x7f,0x7f,0x82,0x84,0x86,0x87,0x88,0x89,0x8a,0x8a,0x8a,
0x8b,0x8c,0x8e,0x8d,0x8e,0x8f,0x94,0x95,0x9c,0x90,0x84,0x84,0x83,0x85,0x7d,0x75,
0x68,0x6b,0x69,0x67,0x6a,0x6a,0x6b,0x6f,0x72,0x77,0x82,0x85,0x84,0x86,0x8a,0x8d,
0x90,0x8c,0x87,0x85,0x84,0x80,0x7d,0x79,0x76,0x74,0x71,0x70,0x70,0x71,0x70,0x70,
0x73,0x76,0x7a,0x7c,0x7e,0x81,0x86,0x88,0x8b,0x8b,0x8e,0x8f,0x90,0x8f,0x91,0x92,
0x91,0x90,0x90,0x94,0x94,0x9c,0x8a,0x80,0x81,0x7f,0x80,0x7a,0x71,0x66,0x6a,0x67,
0x67,0x6c,0x6d,0x6e,0x72,0x75,0x7b,0x86,0x88,0x87,0x89,0x8c,0x8e,0x8f,0x8b,0x85,
0x84,0x82,0x7d,0x7b,0x77,0x73,0x71,0x70,0x70,0x72,0x73,0x72,0x73,0x76,0x7b,0x7e,
0x7f,0x80,0x83,0x85,0x87,0x88,0x88,0x88,0x88,0x88,0x89,0x8c,0x8b,0x8c,0x8b,0x8e,
0x8d,0x94,0x93,0x9c,0x95,0x86,0x85,0x82,0x86,0x81,0x7a,0x6b,0x6a,0x6a,0x68,0x6b,
0x6b,0x6b,0x6d,0x71,0x75,0x7e,0x84,0x84,0x84,0x88,0x8b,0x8f,0x8e,0x88,0x85,0x85,
0x82,0x7f,0x7c,0x78,0x76,0x74,0x71,0x71,0x72,0x71,0x71,0x72,0x75,0x78,0x7b,0x7c,
0x7e,0x82,0x85,0x87,0x8a,0x8b,0x8d,0x8e,0x8f,0x8f,0x92,0x91,0x91,0x90,0x92,0x93,
0x98,0x96,0x84,0x81,0x7f,0x82,0x7e,0x76,0x6a,0x67,0x6a,0x67,0x69,0x6b,0x6d,0x6f,
0x73,0x77,0x80,0x87,0x87,0x86,0x89,0x8c,0x8f,0x8e,0x88,0x84,0x83,0x80,0x7c,0x79,
0x76,0x74,0x71,0x70,0x71,0x73,0x71,0x71,0x73,0x77,0x7b,0x7d,0x7d,0x80,0x83,0x85,
0x87,0x88,0x8a,0x8a,0x8a,0x8a,0x8c,0x8d,0x8f,0x8d,0x8e,0x8d,0x93,0x93,0x9a,0x93,
0x84,0x84,0x81,0x83,0x7e,0x78,0x6a,0x6a,0x6a,0x67,0x6b,0x6c,0x6b,0x6e,0x72,0x76,
0x80,0x85,0x84,0x85,0x89,0x8c,0x8f,0x8d,0x88,0x85,0x84,0x81,0x7e,0x7b,0x77,0x75,
0x72,0x71,0x72,0x73,0x72,0x70,0x72,0x76,0x79,0x7c,0x7c,0x7f,0x81,0x85,0x87,0x89,
0x8a,0x8b,0x8b,0x8c,0x8e,0x90,0x8f,0x8d,0x8e,0x91,0x93,0x96,0x9a,0x88,0x83,0x80,
0x81,0x81,0x7b,0x70,0x68,0x6b,0x67,0x6a,0x6c,0x6c,0x6d,0x71,0x74,0x7c,0x84,0x85,
0x85,0x87,0x8a,0x8e,0x8f,0x8a,0x85,0x84,0x82,0x80,0x7d,0x78,0x75,0x74,0x72,0x72,
0x73,0x73,0x73,0x72,0x75,0x78,0x7c,0x7d,0x7e,0x80,0x82,0x86,0x88,0x89,0x89,0x8a,
0x8a,0x8c,0x8d,0x8f,0x8d,0x8e,0x8d,0x91,0x93,0x98,0x99,0x87,0x84,0x81,0x84,0x81,
0x7b,0x6f,0x69,0x6c,0x69,0x6b,0x6c,0x6c,0x6e,0x72,0x74,0x7c,0x83,0x84,0x84,0x86,
0x8a,0x8e,0x8e,0x89,0x85,0x84,0x83,0x80,0x7d,0x79,0x76,0x74,0x72,0x71,0x72,0x72,
0x71,0x71,0x74,0x78,0x7c,0x7d,0x7e,0x81,0x85,0x89,0x8b,0x8b,0x8d,0x8d,0x8e,0x8f,
0x91,0x90,0x90,0x8f,0x90,0x91,0x95,0x99,0x88,0x82,0x7e,0x81,0x81,0x7b,0x70,0x67,
0x6b,0x69,0x6c,0x6d,0x6d,0x6f,0x72,0x75,0x7d,0x85,0x86,0x84,0x86,0x89,0x8e,0x8e,
0x8a,0x84,0x83,0x82,0x7f,0x7c,0x78,0x75,0x73,0x71,0x71,0x74,0x74,0x73,0x72,0x74,
0x7a,0x7f,0x7f,0x7f,0x81,0x84,0x88,0x89,0x89,0x8a,0x8b,0x8b,0x8c,0x8d,0x8f,0x8e,
0x8d,0x8c,0x91,0x93,0x99,0x8f,0x83,0x81,0x81,0x84,0x7d,0x77,0x6c,0x6c,0x6b,0x6a,
0x6d,0x6e,0x6e,0x6f,0x72,0x78,0x80,0x84,0x82,0x83,0x87,0x8b,0x8d,0x8a,0x86,0x84,
0x84,0x81,0x7e,0x7b,0x78,0x75,0x72,0x71,0x72,0x73,0x71,0x71,0x73,0x78,0x7b,0x7d,
0x7e,0x80,0x84,0x88,0x8b,0x8c,0x8d,0x8d,0x8f,0x8f,0x92,0x91,0x91,0x90,0x90,0x90,
0x96,0x94,0x84,0x81,0x7e,0x80,0x7d,0x77,0x6b,0x69,0x6b,0x68,0x6b,0x6d,0x6e,0x70,
0x73,0x76,0x7e,0x85,0x85,0x84,0x87,0x8a,0x8d,0x8d,0x87,0x84,0x83,0x82,0x7e,0x7b,
0x78,0x75,0x73,0x71,0x71,0x73,0x73,0x71,0x72,0x75,0x7b,0x7d,0x7e,0x7f,0x83,0x87,
0x89,0x8a,0x8a,0x8d,0x8e,0x8d,0x8e,0x90,0x8f,0x8f,0x8c,0x8e,0x90,0x97,0x93,0x84,
0x80,0x7f,0x83,0x80,0x7a,0x6e,0x6b,0x6d,0x6a,0x6c,0x6e,0x6e,0x6f,0x71,0x74,0x7c,
0x83,0x83,0x82,0x84,0x88,0x8c,0x8b,0x87,0x84,0x84,0x82,0x7f,0x7d,0x7a,0x77,0x74,
0x71,0x71,0x73,0x73,0x71,0x72,0x75,0x79,0x7c,0x7e,0x7f,0x84,0x87,0x8a,0x8b,0x8e,
0x8f,0x91,0x90,0x91,0x92,0x93,0x92,0x91,0x90,0x93,0x92,0x86,0x80,0x7e,0x7f,0x7d,
0x77,0x6e,0x6a,0x6c,0x6a,0x6b,0x6d,0x6f,0x71,0x73,0x75,0x7c,0x83,0x85,0x85,0x86,
0x88,0x8c,0x8c,0x88,0x85,0x84,0x82,0x7e,0x7b,0x78,0x76,0x74,0x71,0x71,0x72,0x73,
0x72,0x73,0x75,0x79,0x7d,0x7f,0x82,0x84,0x87,0x8a,0x8c,0x8e,0x8f,0x90,0x90,0x92,
0x92,0x92,0x91,0x91,0x8f,0x94,0x92,0x86,0x81,0x7e,0x7f,0x7d,0x78,0x6e,0x6b,0x6c,
0x6a,0x6c,0x6e,0x6f,0x70,0x73,0x74,0x7b,0x82,0x84,0x85,0x85,0x87,0x8a,0x8c,0x89,
0x86,0x84,0x81,0x7f,0x7c,0x79,0x77,0x74,0x71,0x70,0x72,0x73,0x74,0x73,0x75,0x79,
0x7d,0x81,0x82,0x85,0x88,0x8b,0x8e,0x90,0x91,0x92,0x93,0x93,0x93,0x93,0x94,0x93,
0x93,0x92,0x8a,0x83,0x7f,0x7d,0x7b,0x79,0x71,0x6a,0x6a,0x69,0x6a,0x6d,0x6e,0x6e,
0x71,0x74,0x79,0x7f,0x83,0x85,0x86,0x87,0x88,0x8b,0x8b,0x88,0x84,0x81,0x7e,0x7d,
0x7b,0x78,0x74,0x71,0x70,0x71,0x73,0x74,0x75,0x75,0x78,0x7c,0x80,0x82,0x84,0x86,
0x89,0x8c,0x8e,0x8f,0x91,0x91,0x90,0x91,0x92,0x93,0x92,0x90,0x91,0x90,0x88,0x83,
0x7f,0x7d,0x7b,0x78,0x6f,0x6c,0x6c,0x6a,0x6b,0x6c,0x6e,0x70,0x73,0x74,0x79,0x7f,
0x83,0x84,0x84,0x85,0x87,0x89,0x87,0x84,0x82,0x7f,0x7c,0x7a,0x78,0x77,0x75,0x73,
0x72,0x74,0x76,0x78,0x79,0x7a,0x7d,0x80,0x83,0x86,0x88,0x8a,0x8c,0x8d,0x8f,0x91,
0x92,0x92,0x91,0x91,0x91,0x93,0x94,0x91,0x89,0x83,0x80,0x7f,0x7d,0x78,0x71,0x6b,
0x6a,0x69,0x6b,0x6c,0x6d,0x6e,0x6f,0x73,0x78,0x7f,0x81,0x82,0x83,0x85,0x87,0x89,
0x88,0x85,0x82,0x7f,0x7e,0x7c,0x7a,0x78,0x75,0x73,0x72,0x74,0x76,0x77,0x77,0x79,
0x7c,0x7f,0x82,0x85,0x88,0x8a,0x8c,0x8e,0x90,0x92,0x93,0x92,0x91,0x92,0x92,0x93,
0x93,0x91,0x8b,0x84,0x81,0x7f,0x7e,0x79,0x73,0x6d,0x6a,0x69,0x6a,0x6c,0x6d,0x6d,
0x6e,0x72,0x76,0x7c,0x80,0x82,0x82,0x83,0x85,0x88,0x88,0x86,0x83,0x80,0x7e,0x7d,
0x7c,0x7a,0x77,0x75,0x74,0x76,0x77,0x79,0x79,0x7b,0x7c,0x7f,0x83,0x86,0x89,0x8a,
0x8b,0x8c,0x90,0x92,0x92,0x90,0x90,0x90,0x91,0x92,0x91,0x90,0x8a,0x84,0x7f,0x7f,
0x7d,0x7b,0x75,0x6f,0x6b,0x6b,0x6c,0x6d,0x6e,0x6e,0x6f,0x71,0x75,0x7a,0x7e,0x80,
0x80,0x81,0x83,0x86,0x86,0x85,0x83,0x80,0x7f,0x7e,0x7d,0x7c,0x7a,0x78,0x77,0x78,
0x7a,0x7b,0x7c,0x7c,0x7e,0x82,0x85,0x87,0x89,0x8a,0x8c,0x8e,0x90,0x91,0x91,0x90,
0x90,0x8f,0x8f,0x90,0x8f,0x8c,0x88,0x82,0x7f,0x7d,0x7b,0x78,0x74,0x6f,0x6d,0x6d,
0x6d,0x6f,0x6f,0x70,0x71,0x73,0x76,0x7a,0x7e,0x7f,0x7f,0x80,0x82,0x83,0x84,0x83,
0x81,0x7f,0x7e,0x7d,0x7d,0x7c,0x7c,0x7a,0x79,0x7a,0x7c,0x7e,0x7f,0x80,0x81,0x83,
0x85,0x89,0x8a,0x8b,0x8b,0x8c,0x8d,0x8e,0x8f,0x8f,0x8e,0x8d,0x8c,0x8b,0x89,0x88,
0x85,0x81,0x7e,0x7a,0x78,0x76,0x74,0x70,0x6f,0x6e,0x6f,0x70,0x71,0x72,0x73,0x76,
0x78,0x7b,0x7d,0x7f,0x7f,0x80,0x80,0x81,0x82,0x81,0x80,0x7f,0x7e,0x7d,0x7d,0x7e,
0x7e,0x7d,0x7d,0x7d,0x7f,0x81,0x83,0x84,0x84,0x86,0x87,0x89,0x8a,0x8b,0x8a,0x8b,
0x8b,0x8b,0x8b,0x8b,0x89,0x89,0x88,0x86,0x84,0x82,0x7f,0x7d,0x7b,0x78,0x77,0x75,
0x74,0x73,0x72,0x73,0x74,0x75,0x75,0x77,0x79,0x7b,0x7c,0x7d,0x7e,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7e,0x7e,0x7d,0x7d,0x7d,0x7d,0x7c,0x7d,0x7d,0x7e,0x7f,0x80,0x81,0x82,
0x83,0x83,0x85,0x86,0x88,0x88,0x89,0x89,0x89,0x89,0x89,0x89,0x89,0x87,0x87,0x86,
0x84,0x83,0x81,0x80,0x7e,0x7c,0x7a,0x79,0x78,0x78,0x77,0x76,0x75,0x76,0x77,0x78,
0x79,0x7a,0x7b,0x7c,0x7d,0x7e,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,
0x7d,0x7d,0x7d,0x7e,0x7f,0x7f,0x7f,0x80,0x81,0x83,0x84,0x85,0x85,0x86,0x85,0x86,
0x86,0x86,0x86,0x86,0x85,0x84,0x84,0x83,0x83,0x82,0x81,0x7f,0x7f,0x7e,0x7e,0x7d,
0x7b,0x7a,0x7a,0x7a,0x7a,0x7a,0x7a,0x7b,0x7a,0x7a,0x7b,0x7d,0x7e,0x7f,0x7f,0x7f,
0x7f,0x80,0x80,0x81,0x80,0x7f,0x7e,0x7e,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7f,0x7f,
0x80,0x81,0x81,0x82,0x82,0x83,0x84,0x85,0x84,0x84,0x84,0x85,0x84,0x84,0x84,0x83,
0x83,0x81,0x81,0x81,0x80,0x7f,0x7e,0x7d,0x7d,0x7d,0x7c,0x7c,0x7c,0x7c,0x7b,0x7c,
0x7c,0x7e,0x7e,0x7e,0x7e,0x7e,0x7f,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x80,
0x80,0x7f,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x81,0x81,0x81,0x81,
0x81,0x82,0x83,0x83,0x83,0x83,0x82,0x82,0x82,0x82,0x82,0x81,0x81,0x7f,0x7f,0x7e,
0x7e,0x7e,0x7e,0x7e,0x7d,0x7c,0x7d,0x7d,0x7e,0x7f,0x7e,0x7e,0x7e,0x7f,0x7f,0x80,
0x80,0x80,0x80,0x7f,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x7f,
0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x81,0x81,0x81,0x81,0x81,0x81,
0x81,0x81,0x81,0x81,0x81,0x80,0x80,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,
0x7e,0x7e,0x7e,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x81,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,
0x7f,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7e,0x7d,0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,
0x80,0x80,0x81,0x81,0x81,0x81,0x81,0x81,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,
0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,
0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7e,0x7e,0x7e,0x7d,
0x7e,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x80,0x81,0x81,0x80,0x80,0x80,0x80,
0x80,0x7f,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7e,0x80,
0x7f,0x7f,0x7f,0x7e,0x7f,0x7e,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,
0x80,0x80,0x81,0x81,0x80,0x81,0x81,0x80,0x80,0x80,0x7f,0x80,0x80,0x81,0x80,0x80,
0x80,0x7f,0x80,0x80,0x81,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x81,0x7f,0x80,0x7e,0x7e,
0x7f,0x7e,0x81,0x7f,0x80,0x7e,0x7e,0x80,0x7e,0x81,0x7f,0x80,0x7e,0x7f,0x7f,0x7e,
0x80,0x7f,0x80,0x7f,0x7e,0x7f,0x7f,0x80,0x81,0x81,0x81,0x81,0x80,0x7f,0x80,0x80,
0x82,0x80,0x81,0x80,0x80,0x80,0x7f,0x81,0x80,0x81,0x7f,0x7f,0x7f,0x7f,0x7f,0x81,
0x80,0x81,0x80,0x7f,0x7e,0x7f,0x7f,0x80,0x81,0x7f,0x81,0x7e,0x7f,0x80,0x7f,0x81,
0x80,0x80,0x7f,0x7f,0x7e,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x80,
0x80,0x7e,0x80,0x7f,0x80,0x80,0x80,0x81,0x7f,0x81,0x80,0x80,0x80,0x80,0x81,0x81,
0x7e,0x80,0x7e,0x7f,0x81,0x7f,0x82,0x7e,0x80,0x7e,0x7e,0x82,0x7e,0x82,0x7f,0x7e,
0x80,0x7c,0x81,0x7f,0x7f,0x80,0x7d,0x80,0x7c,0x81,0x7e,0x7f,0x80,0x7d,0x81,0x7d,
0x7f,0x81,0x7d,0x81,0x7e,0x80,0x80,0x7f,0x81,0x7e,0x81,0x7f,0x80,0x81,0x80,0x80,
0x7f,0x7f,0x80,0x7f,0x82,0x7e,0x82,0x7e,0x7f,0x80,0x7d,0x82,0x7e,0x82,0x7f,0x7f,
0x80,0x7e,0x80,0x7f,0x81,0x7f,0x7f,0x80,0x7c,0x80,0x7e,0x80,0x7f,0x80,0x7e,0x7d,
0x80,0x7e,0x80,0x80,0x7f,0x80,0x7d,0x80,0x7e,0x80,0x81,0x7f,0x82,0x7d,0x81,0x7c,
0x80,0x81,0x80,0x83,0x7e,0x7e,0x7d,0x7f,0x80,0x80,0x83,0x7f,0x7e,0x7f,0x7d,0x80,
0x81,0x81,0x81,0x7f,0x7d,0x7f,0x7e,0x81,0x84,0x80,0x81,0x7e,0x7c,0x7f,0x7e,0x83,
0x7f,0x82,0x7e,0x7e,0x7e,0x7d,0x82,0x80,0x82,0x7f,0x7f,0x7d,0x7e,0x7f,0x80,0x81,
0x82,0x7c,0x7f,0x7d,0x7f,0x80,0x7f,0x83,0x7e,0x81,0x7e,0x7f,0x80,0x82,0x80,0x81,
0x7f,0x7e,0x7e,0x7c,0x82,0x7e,0x81,0x81,0x7d,0x81,0x7e,0x7f,0x81,0x80,0x82,0x7d,
0x81,0x7e,0x7f,0x80,0x80,0x81,0x7f,0x82,0x7d,0x80,0x80,0x7f,0x82,0x7f,0x81,0x7e,
0x7e,0x82,0x7d,0x83,0x7d,0x80,0x7f,0x7e,0x80,0x7f,0x81,0x7e,0x7f,0x7e,0x7f,0x7e,
0x83,0x7f,0x82,0x7f,0x80,0x7e,0x80,0x82,0x7f,0x82,0x7e,0x81,0x7e,0x80,0x7f,0x81,
0x7f,0x81,0x80,0x7e,0x82,0x7d,0x81,0x7f,0x7f,0x81,0x7e,0x81,0x7f,0x7f,0x81,0x7e,
0x7f,0x80,0x7f,0x82,0x7e,0x81,0x80,0x7c,0x83,0x7d,0x81,0x7f,0x81,0x7f,0x7e,0x80,
0x7e,0x81,0x7e,0x83,0x7e,0x7e,0x81,0x7e,0x80,0x7e,0x82,0x80,0x7f,0x82,0x7e,0x81,
0x80,0x7f,0x80,0x7f,0x80,0x81,0x7f,0x80,0x7f,0x7f,0x80,0x81,0x7f,0x7f,0x7f,0x7f,
0x80,0x80,0x7f,0x7f,0x83,0x7d,0x82,0x7e,0x80,0x7f,0x81,0x80,0x7f,0x82,0x7e,0x82,
0x7e,0x81,0x7e,0x84,0x7e,0x81,0x80,0x7d,0x81,0x7c,0x83,0x7e,0x81,0x80,0x7d,0x80,
0x7f,0x81,0x80,0x82,0x7e,0x80,0x80,0x7d,0x81,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x80,
0x81,0x7c,0x84,0x7d,0x7f,0x81,0x7c,0x84,0x7a,0x84,0x7c,0x82,0x80,0x7e,0x82,0x7c,
0x82,0x7e,0x7f,0x82,0x7e,0x7f,0x80,0x7d,0x81,0x7e,0x82,0x7d,0x81,0x7f,0x7e,0x82,
0x7c,0x82,0x7d,0x82,0x7d,0x81,0x7f,0x7e,0x82,0x7c,0x83,0x7c,0x83,0x7d,0x7f,0x7f,
0x7d,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7d,0x81,0x7e,0x81,0x7f,0x81,0x7c,0x81,
0x7f,0x80,0x80,0x7f,0x81,0x7d,0x81,0x7c,0x81,0x7f,0x80,0x80,0x81,0x7d,0x80,0x7f,
0x7e,0x82,0x7d,0x83,0x7c,0x81,0x7e,0x7e,0x82,0x7d,0x84,0x7c,0x82,0x7d,0x7f,0x80,
0x7d,0x83,0x7d,0x81,0x7e,0x7e,0x7f,0x7e,0x80,0x7f,0x80,0x80,0x7e,0x80,0x7f,0x80,
0x80,0x7f,0x81,0x7e,0x80,0x80,0x7f,0x81,0x7e,0x82,0x7f,0x80,0x7e,0x7f,0x81,0x7d,
0x82,0x7c,0x82,0x7d,0x80,0x80,0x7d,0x82,0x7c,0x82,0x7d,0x81,0x7e,0x80,0x80,0x7f,
0x82,0x7d,0x81,0x7e,0x81,0x7d,0x82,0x7e,0x80,0x7f,0x7e,0x80,0x7e,0x80,0x80,0x7f,
0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x82,0x7e,0x80,0x7e,0x80,0x81,0x80,0x80,0x7f,
0x80,0x7f,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x80,0x7e,0x81,0x7e,0x80,0x80,
0x7e,0x81,0x7e,0x80,0x7f,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x81,0x80,0x80,0x7f,
0x7f,0x80,0x7d,0x81,0x7f,0x80,0x80,0x7e,0x81,0x7e,0x81,0x7f,0x80,0x80,0x7f,0x81,
0x7f,0x7f,0x81,0x7f,0x7f,0x80,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x81,0x80,0x80,
0x81,0x7e,0x81,0x7e,0x81,0x80,0x80,0x80,0x7f,0x81,0x7e,0x81,0x7d,0x82,0x7e,0x7f,
0x81,0x7d,0x81,0x7f,0x81,0x80,0x7f,0x82,0x7e,0x81,0x7e,0x80,0x80,0x7f,0x81,0x7e,
0x82,0x7c,0x81,0x7e,0x81,0x7f,0x81,0x80,0x7e,0x80,0x7e,0x82,0x7e,0x80,0x7f,0x80,
0x80,0x80,0x81,0x7e,0x81,0x7e,0x80,0x80,0x7e,0x82,0x7d,0x81,0x7f,0x80,0x7f,0x80,
0x7f,0x7f,0x80,0x7e,0x81,0x7e,0x80,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x81,0x7d,0x82,
0x7d,0x82,0x7f,0x80,0x81,0x7c,0x82,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7e,0x81,
0x7f,0x81,0x7f,0x81,0x7e,0x80,0x7f,0x7f,0x81,0x80,0x81,0x7f,0x80,0x7f,0x7e,0x82,
0x7e,0x80,0x80,0x7e,0x81,0x7d,0x81,0x7e,0x81,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x80,
0x80,0x80,0x80,0x7f,0x7f,0x80,0x7e,0x81,0x7e,0x81,0x7e,0x7e,0x80,0x7e,0x7e,0x81,
0x7f,0x80,0x80,0x7f,0x80,0x7e,0x82,0x7f,0x80,0x80,0x7e,0x80,0x7e,0x80,0x7f,0x80,
0x81,0x7e,0x7f,0x7e,0x80,0x7f,0x82,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x82,0x7e,0x82,
0x7d,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x81,0x7e,0x81,0x7f,
0x80,0x7f,0x7e,0x80,0x7f,0x80,0x80,0x80,0x7e,0x80,0x7e,0x81,0x7e,0x80,0x80,0x7e,
0x80,0x7d,0x82,0x7d,0x81,0x80,0x80,0x81,0x7d,0x83,0x7d,0x81,0x7f,0x7f,0x80,0x7e,
0x81,0x7f,0x80,0x80,0x7f,0x81,0x7e,0x80,0x81,0x7e,0x82,0x7d,0x80,0x7f,0x7f,0x80,
0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x81,0x80,0x7e,0x82,0x7c,0x82,0x7d,0x81,
0x81,0x7f,0x81,0x7d,0x81,0x7d,0x81,0x7f,0x81,0x7f,0x80,0x7f,0x7e,0x80,0x7e,0x82,
0x7f,0x81,0x7f,0x80,0x7f,0x7e,0x81,0x7f,0x7f,0x81,0x7f,0x80,0x80,0x7f,0x82,0x7f,
0x80,0x81,0x7e,0x81,0x7e,0x81,0x7e,0x82,0x7e,0x80,0x80,0x7e,0x82,0x7c,0x84,0x7d,
0x81,0x80,0x80,0x80,0x7f,0x81,0x7e,0x81,0x80,0x7f,0x80,0x7e,0x81,0x7e,0x80,0x80,
0x7e,0x80,0x7f,0x7f,0x81,0x7f,0x80,0x80,0x7e,0x82,0x7c,0x83,0x7e,0x81,0x80,0x7f,
0x81,0x7e,0x82,0x7e,0x81,0x7e,0x82,0x7d,0x81,0x7e,0x80,0x81,0x7e,0x83,0x7e,0x81,
0x7e,0x80,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x81,0x7f,0x81,0x7f,
0x81,0x7e,0x81,0x80,0x7e,0x82,0x7d,0x82,0x7e,0x81,0x80,0x7d,0x81,0x7d,0x80,0x7f,
0x80,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x81,0x7f,0x81,0x7f,0x7f,0x80,0x7f,0x81,0x7f,
0x81,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x7f,0x81,0x80,0x7f,0x7f,0x80,0x80,0x7e,0x81,
0x80,0x7e,0x7f,0x7f,0x80,0x7e,0x82,0x7e,0x81,0x7f,0x7f,0x80,0x7d,0x82,0x7d,0x82,
0x7f,0x7f,0x80,0x7d,0x81,0x7e,0x81,0x7f,0x7f,0x80,0x7d,0x80,0x7f,0x81,0x7e,0x81,
0x80,0x7e,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7e,0x81,0x7d,0x81,0x7d,0x81,0x7f,
0x7f,0x81,0x7d,0x80,0x7e,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,
0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x81,0x7e,0x80,0x7e,0x81,0x7f,
0x7f,0x81,0x7d,0x81,0x7d,0x81,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x81,0x7f,0x80,0x7f,
0x80,0x80,0x7f,0x81,0x7f,0x80,0x7e,0x80,0x7e,0x80,0x80,0x7e,0x80,0x7f,0x80,0x7e,
0x81,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7e,0x81,0x7e,0x80,0x7f,0x80,
0x7e,0x80,0x7f,0x7e,0x81,0x7f,0x80,0x7e,0x80,0x7e,0x7f,0x80,0x7e,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x80,0x80,
0x7e,0x81,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x81,0x7f,0x7f,0x81,0x7e,0x80,0x7f,0x7f,
0x80,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7e,0x81,0x7e,0x80,0x7f,0x81,0x7f,0x80,0x81,
0x7e,0x81,0x7e,0x81,0x7e,0x81,0x80,0x7f,0x80,0x7f,0x7f,0x81,0x7f,0x81,0x7f,0x80,
0x80,0x7e,0x81,0x7e,0x80,0x80,0x80,0x7f,0x7f,0x81,0x7f,0x7f,0x82,0x7e,0x81,0x7f,
0x80,0x7f,0x80,0x81,0x7e,0x82,0x7e,0x81,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,
0x80,0x80,0x7f,0x80,0x80,0x80,0x80,0x80,0x81,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x80,0x7f,0x81,0x7f,0x80,0x80,0x7f,0x80,0x7e,0x80,0x80,0x7f,0x81,0x7f,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,
0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x81,0x7f,0x80,0x7f,
0x81,0x7f,0x80,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7e,0x80,
0x7f,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x7f,0x80,0x7f,0x81,0x7e,0x7f,0x80,0x7f,
0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x7e,0x7f,0x7f,
0x7f,0x80,0x80,0x80,0x7e,0x80,0x7e,0x80,0x80,0x80,0x80,0x7e,0x80,0x7e,0x7f,0x80,
0x7f,0x80,0x80,0x7e,0x80,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x81,0x7f,0x7f,0x80,0x7e,0x80,
0x7f,0x80,0x7f,0x7e,0x80,0x7d,0x81,0x7e,0x7f,0x81,0x7e,0x80,0x7f,0x80,0x80,0x7e,
0x81,0x7d,0x81,0x7f,0x7f,0x80,0x7e,0x81,0x7d,0x81,0x7e,0x80,0x80,0x7f,0x80,0x7f,
0x81,0x7e,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,
0x7f,0x81,0x7f,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x81,0x7f,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,0x81,0x7f,0x80,0x80,0x7f,0x80,0x7f,
0x81,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,0x7f,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7e,0x81,0x7f,0x82,0x7e,0x80,0x7f,
0x7f,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x7e,0x81,0x7f,0x80,0x80,0x7f,0x80,0x7e,
0x81,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,
0x80,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x80,
0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x81,
0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7e,0x81,0x7e,0x81,0x7e,0x80,0x7e,0x80,0x80,
0x7f,0x81,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7e,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x7f,0x81,0x7e,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x7e,0x81,0x7e,0x81,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x7f,0x7f,0x80,0x80,0x7f,0x80,0x7e,0x80,0x7e,0x80,0x7e,0x80,0x7f,0x7f,
0x7f,0x7f,0x7f,0x7f,0x80,0x7e,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x81,
0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x81,0x7e,0x80,0x7e,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x7f,0x81,
0x7e,0x81,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x81,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x81,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,
0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,
0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x80,0x7f,0x7f,0x80,
0x7f,0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,
0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x7f,
0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,
0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,
0x7f,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x80,
0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x80,
0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,
0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x7f,0x80,0x7f,0x80,0x7f,
0x80,0x7f,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80,0x80,0x7f,0x80,0x80,0x80,0x80,0x80,
0x80,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x7f,0x80,0x80,0x80
};
const byte soundWow[] ={
0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x80,
0x80,0x80,0x80,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x81,0x81,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,
0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x81,0x80,0x81,0x80,0x80,0x80,0x7f,
0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x80,
0x80,0x7e,0x80,0x7e,0x81,0x78,0x79,0x82,0x7b,0x83,0x82,0x84,0x80,0x82,0x7f,0x80,
0x7e,0x80,0x7e,0x7f,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x7f,0x80,0x80,0x80,0x7f,0x7f,0x7f,0x7f,0x7e,0x7f,0x7f,
0x7f,0x7f,0x7f,0x7f,0x7f,0x7a,0x76,0x7e,0x7a,0x80,0x81,0x86,0x83,0x84,0x81,0x80,
0x7d,0x7f,0x7f,0x80,0x7e,0x7d,0x80,0x80,0x83,0x83,0x85,0x83,0x82,0x81,0x75,0x7e,
0x79,0x7d,0x7f,0x83,0x82,0x84,0x82,0x80,0x80,0x7d,0x80,0x7c,0x80,0x7f,0x80,0x80,
0x81,0x7f,0x7f,0x7e,0x7e,0x80,0x7f,0x81,0x7f,0x81,0x7f,0x80,0x7f,0x81,0x7f,0x81,
0x80,0x81,0x80,0x81,0x80,0x81,0x81,0x80,0x7e,0x7f,0x7e,0x7f,0x81,0x80,0x81,0x7f,
0x80,0x7e,0x7f,0x7e,0x80,0x7e,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,
0x7f,0x81,0x7f,0x7f,0x80,0x7f,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x7f,0x7f,0x81,
0x7f,0x80,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,0x81,0x80,
0x80,0x7f,0x7f,0x80,0x80,0x7f,0x82,0x7f,0x81,0x7f,0x80,0x7f,0x7f,0x7f,0x80,0x7f,
0x7f,0x80,0x7e,0x80,0x7e,0x81,0x7f,0x81,0x7f,0x81,0x80,0x7f,0x80,0x7e,0x7f,0x7f,
0x7f,0x7e,0x7e,0x7f,0x7f,0x80,0x7e,0x7f,0x7f,0x7f,0x7f,0x80,0x80,0x81,0x80,0x81,
0x7f,0x80,0x7f,0x7e,0x7f,0x81,0x7f,0x80,0x80,0x7f,0x7f,0x7f,0x80,0x80,0x80,0x80,
0x7f,0x7f,0x7f,0x7e,0x80,0x7f,0x80,0x80,0x7e,0x7f,0x7f,0x7e,0x7f,0x7f,0x7f,0x80,
0x80,0x81,0x80,0x81,0x80,0x80,0x80,0x7f,0x7f,0x80,0x7f,0x7e,0x80,0x7e,0x80,0x80,
0x7f,0x81,0x80,0x81,0x81,0x81,0x80,0x81,0x7e,0x80,0x7f,0x7d,0x7f,0x7d,0x7e,0x7e,
0x7e,0x7f,0x7e,0x7f,0x80,0x81,0x81,0x82,0x83,0x81,0x81,0x81,0x7e,0x7f,0x7e,0x7d,
0x7d,0x7d,0x7b,0x7d,0x7b,0x7e,0x7e,0x81,0x82,0x84,0x88,0x89,0x8a,0x88,0x86,0x81,
0x7c,0x7a,0x75,0x75,0x75,0x74,0x76,0x77,0x78,0x7a,0x7c,0x82,0x88,0x8f,0x97,0x9b,
0x9d,0x98,0x8d,0x83,0x77,0x6e,0x63,0x60,0x61,0x5e,0x68,0x6f,0x79,0x85,0x8e,0x96,
0x9d,0xa2,0xa5,0xa8,0x9c,0x8f,0x7f,0x6a,0x4e,0x4e,0x46,0x4e,0x68,0x77,0x8c,0x99,
0x99,0x97,0x90,0x8f,0x91,0x99,0x9c,0x97,0x8c,0x7e,0x71,0x59,0x58,0x58,0x5b,0x6f,
0x7c,0x87,0x8f,0x8e,0x8c,0x8d,0x8f,0x96,0xa0,0xa5,0x98,0x8a,0x76,0x64,0x55,0x52,
0x5b,0x65,0x74,0x84,0x8c,0x8e,0x8c,0x8a,0x8a,0x8f,0x99,0xa4,0xa5,0x98,0x82,0x71,
0x5a,0x4c,0x52,0x5c,0x6c,0x7f,0x8c,0x90,0x8d,0x88,0x85,0x8a,0x94,0xa2,0xaa,0xa4,
0x8d,0x75,0x60,0x46,0x49,0x53,0x63,0x7e,0x8e,0x95,0x95,0x8a,0x83,0x84,0x8d,0x9b,
0xad,0xa9,0x95,0x7e,0x61,0x4b,0x44,0x4d,0x64,0x7a,0x8f,0x98,0x92,0x89,0x83,0x82,
0x8c,0x9f,0xad,0xaa,0x95,0x7a,0x5e,0x46,0x43,0x55,0x68,0x82,0x95,0x96,0x8f,0x84,
0x7d,0x83,0x91,0xa2,0xb0,0xa5,0x90,0x70,0x59,0x43,0x4a,0x5e,0x74,0x8c,0x96,0x95,
0x87,0x7e,0x7d,0x86,0x9a,0xad,0xaa,0x98,0x7c,0x5b,0x4c,0x44,0x5a,0x75,0x8b,0x9a,
0x99,0x89,0x79,0x78,0x7e,0x91,0xaa,0xad,0x9c,0x80,0x5f,0x47,0x41,0x56,0x74,0x90,
0xa2,0xa1,0x8f,0x7b,0x74,0x7c,0x8e,0xaa,0xaa,0x99,0x7f,0x56,0x43,0x3f,0x58,0x79,
0x97,0xa7,0xa2,0x8f,0x76,0x74,0x7d,0x95,0xaf,0xa6,0x95,0x71,0x47,0x3b,0x40,0x5f,
0x86,0xa3,0xa9,0x9f,0x89,0x76,0x7b,0x8c,0xa3,0xb1,0x9e,0x80,0x59,0x35,0x38,0x4e,
0x73,0x99,0xab,0xa2,0x8f,0x7b,0x76,0x89,0xa5,0xbb,0xb2,0x90,0x67,0x37,0x23,0x3a,
0x60,0x8d,0xad,0xaf,0x96,0x7c,0x6f,0x7a,0x9a,0xbc,0xc5,0xa1,0x7f,0x4d,0x1f,0x30,
0x58,0x7c,0xa2,0xb3,0x94,0x78,0x6c,0x73,0x91,0xb7,0xcd,0xad,0x87,0x5a,0x29,0x2a,
0x54,0x7c,0x9d,0xb0,0x9a,0x75,0x66,0x6f,0x8b,0xb1,0xcb,0xb1,0x84,0x5d,0x2e,0x31,
0x57,0x87,0xa2,0xad,0x98,0x75,0x61,0x6e,0x8c,0xac,0xc3,0xb1,0x7d,0x55,0x35,0x31,
0x57,0x8e,0xa9,0xaa,0x9f,0x7b,0x63,0x71,0x90,0xa5,0xbd,0xaa,0x73,0x50,0x36,0x35,
0x5a,0x94,0xa9,0xa7,0x9c,0x7b,0x67,0x76,0x99,0xad,0xb9,0xa1,0x6b,0x48,0x2f,0x3a,
0x65,0x96,0xa9,0xa2,0x93,0x79,0x6d,0x82,0xa3,0xb2,0xba,0x8e,0x5e,0x3e,0x2d,0x44,
0x74,0x9e,0xa5,0x9c,0x89,0x76,0x73,0x8e,0xae,0xb6,0xae,0x7b,0x53,0x39,0x36,0x56,
0x82,0x9d,0x9c,0x90,0x80,0x79,0x81,0xa1,0xb2,0xb7,0x9f,0x66,0x45,0x37,0x47,0x67,
0x8d,0x9c,0x90,0x7f,0x7c,0x80,0x8d,0xaa,0xb7,0xb1,0x8a,0x57,0x47,0x3d,0x51,0x73,
0x95,0x96,0x84,0x7f,0x7e,0x80,0x95,0xb6,0xb7,0xae,0x79,0x50,0x3b,0x3e,0x60,0x80,
0x9e,0x95,0x81,0x77,0x7d,0x83,0xa4,0xb8,0xb9,0xa4,0x64,0x47,0x39,0x46,0x6a,0x8b,
0x9a,0x89,0x7a,0x7a,0x83,0x8c,0xac,0xb7,0xb9,0x97,0x57,0x4c,0x3c,0x48,0x72,0x91,
0x90,0x82,0x7e,0x7e,0x82,0x95,0xb2,0xb3,0xb4,0x8d,0x57,0x45,0x41,0x51,0x70,0x8f,
0x8e,0x7d,0x7d,0x89,0x87,0x97,0xb3,0xb7,0xaa,0x77,0x53,0x4b,0x45,0x5e,0x82,0x8f,
0x7f,0x78,0x7e,0x83,0x8b,0xa7,0xb6,0xb5,0xa1,0x5f,0x4f,0x4c,0x4d,0x6d,0x8d,0x8e,
0x73,0x73,0x7e,0x82,0x91,0xb4,0xb4,0xb3,0x90,0x55,0x4b,0x49,0x57,0x74,0x8f,0x88,
0x74,0x7a,0x88,0x87,0x98,0xb5,0xb7,0xa8,0x72,0x53,0x4b,0x4b,0x67,0x85,0x91,0x7f,
0x72,0x78,0x84,0x8b,0xa6,0xb6,0xba,0x97,0x5b,0x54,0x48,0x55,0x76,0x91,0x86,0x70,
0x78,0x81,0x84,0x95,0xb2,0xad,0xad,0x7f,0x54,0x4c,0x53,0x64,0x7c,0x8e,0x83,0x75,
0x7b,0x8e,0x8d,0x9d,0xac,0xb2,0x97,0x5d,0x50,0x52,0x5a,0x71,0x8d,0x8d,0x72,0x70,
0x86,0x8c,0x91,0xae,0xb9,0xac,0x74,0x50,0x51,0x4a,0x63,0x83,0x95,0x7f,0x6e,0x7e,
0x8c,0x88,0x9f,0xb6,0xb2,0x97,0x5b,0x51,0x4a,0x5a,0x74,0x8d,0x8a,0x74,0x72,0x88,
0x8f,0x90,0xac,0xb5,0xac,0x70,0x50,0x57,0x4d,0x63,0x84,0x92,0x7a,0x6f,0x80,0x8d,
0x88,0xa0,0xb8,0xae,0x92,0x65,0x56,0x4d,0x53,0x74,0x88,0x84,0x76,0x79,0x86,0x8c,
0x90,0xab,0xb5,0xad,0x81,0x56,0x52,0x4f,0x5b,0x7a,0x8c,0x7d,0x74,0x84,0x90,0x8a,
0x98,0xb3,0xb3,0x97,0x60,0x55,0x55,0x58,0x71,0x8c,0x85,0x6b,0x75,0x89,0x8e,0x8f,
0xad,0xb3,0xa7,0x77,0x5a,0x57,0x50,0x65,0x7f,0x8b,0x7d,0x73,0x81,0x8d,0x86,0x99,
0xb1,0xb5,0x8e,0x5d,0x59,0x54,0x58,0x74,0x8d,0x85,0x70,0x7b,0x91,0x8c,0x8f,0xa7,
0xb0,0x9c,0x6c,0x56,0x5c,0x5e,0x6b,0x81,0x8a,0x73,0x6d,0x8b,0x96,0x8f,0x9e,0xaf,
0xac,0x82,0x53,0x58,0x5a,0x5e,0x73,0x90,0x84,0x6d,0x7e,0x99,0x90,0x92,0xab,0xae,
0x93,0x5e,0x58,0x5d,0x5a,0x6a,0x85,0x86,0x71,0x74,0x92,0x99,0x8d,0xa2,0xb1,0xa6,
0x72,0x54,0x5c,0x5c,0x62,0x7b,0x88,0x77,0x6d,0x87,0x9d,0x94,0x9a,0xac,0xab,0x8a,
0x5a,0x57,0x5d,0x5d,0x70,0x89,0x83,0x6e,0x75,0x95,0x98,0x94,0xa7,0xb1,0xa0,0x63,
0x4f,0x60,0x60,0x65,0x7f,0x8a,0x73,0x68,0x8a,0xa1,0x94,0x9b,0xad,0xa9,0x78,0x55,
0x60,0x63,0x5f,0x73,0x88,0x79,0x6a,0x7d,0x9e,0x98,0x98,0xa9,0xb1,0x91,0x5c,0x54,
0x61,0x5f,0x69,0x85,0x87,0x6d,0x6d,0x90,0x9d,0x95,0xa3,0xaf,0xa2,0x6d,0x51,0x61,
0x63,0x65,0x79,0x8a,0x77,0x66,0x7d,0x9e,0x99,0x9c,0xab,0xad,0x88,0x55,0x57,0x67,
0x65,0x6b,0x85,0x83,0x69,0x6b,0x94,0x9f,0x94,0xa4,0xb2,0x9f,0x65,0x54,0x65,0x63,
0x64,0x7e,0x89,0x74,0x64,0x81,0x9c,0x97,0x9e,0xaf,0xad,0x83,0x55,0x54,0x61,0x64,
0x74,0x86,0x83,0x6b,0x73,0x94,0x9d,0x98,0xa6,0xad,0x99,0x64,0x51,0x60,0x64,0x69,
0x7c,0x88,0x75,0x69,0x85,0x9d,0x97,0x9c,0xaf,0xab,0x79,0x4f,0x59,0x66,0x65,0x74,
0x8b,0x7f,0x65,0x74,0x9a,0x9c,0x97,0xa9,0xaf,0x90,0x5f,0x54,0x63,0x66,0x6c,0x7f,
0x84,0x70,0x6a,0x8a,0x9f,0x98,0x9e,0xaf,0xa5,0x75,0x50,0x5a,0x62,0x6a,0x7a,0x88,
0x7a,0x68,0x78,0x99,0x9e,0x9d,0xa7,0xab,0x8f,0x5a,0x4f,0x62,0x68,0x6f,0x7f,0x85,
0x70,0x6c,0x8c,0xa0,0x9c,0xa2,0xac,0xa0,0x6c,0x50,0x5c,0x66,0x6a,0x7a,0x85,0x77,
0x67,0x7f,0x9c,0x9c,0x9d,0xad,0xae,0x85,0x56,0x55,0x60,0x62,0x70,0x84,0x83,0x6d,
0x71,0x91,0x9d,0x97,0xa2,0xb2,0x9e,0x6a,0x50,0x5e,0x63,0x68,0x7a,0x88,0x76,0x67,
0x7f,0x9e,0x9b,0x9c,0xaa,0xa9,0x83,0x55,0x58,0x69,0x6b,0x6f,0x80,0x80,0x6b,0x6f,
0x92,0x9f,0x99,0xa3,0xae,0x9a,0x66,0x51,0x5f,0x6c,0x6f,0x7a,0x82,0x73,0x69,0x82,
0x9c,0x9a,0x9c,0xab,0xa5,0x7e,0x59,0x57,0x66,0x6c,0x7a,0x82,0x7a,0x6b,0x74,0x91,
0x9b,0x99,0xa3,0xaa,0x98,0x6b,0x54,0x60,0x69,0x6c,0x77,0x81,0x77,0x70,0x84,0x9a,
0x98,0x99,0xa9,0xa6,0x83,0x5b,0x58,0x64,0x67,0x71,0x81,0x7f,0x6e,0x75,0x90,0x9b,
0x97,0xa2,0xae,0x9c,0x6b,0x56,0x5e,0x66,0x69,0x79,0x83,0x76,0x6d,0x84,0x99,0x98,
0x99,0xa8,0xaa,0x88,0x5f,0x58,0x65,0x63,0x6b,0x7c,0x82,0x72,0x76,0x8e,0x9b,0x94,
0x9e,0xad,0xa0,0x74,0x57,0x61,0x66,0x66,0x73,0x82,0x78,0x6d,0x80,0x98,0x97,0x95,
0xa6,0xaa,0x8f,0x66,0x59,0x63,0x66,0x6b,0x78,0x80,0x75,0x73,0x89,0x99,0x96,0x9a,
0xa8,0xa1,0x81,0x5f,0x5e,0x65,0x67,0x6e,0x78,0x7b,0x77,0x7e,0x91,0x96,0x95,0xa1,
0xa6,0x99,0x76,0x5b,0x5b,0x65,0x6e,0x74,0x7b,0x7b,0x77,0x82,0x93,0x99,0x9c,0xa4,
0xa6,0x8b,0x62,0x58,0x62,0x67,0x6d,0x76,0x7d,0x7a,0x7d,0x8d,0x96,0x96,0x9d,0xa6,
0x9f,0x7b,0x5a,0x59,0x64,0x68,0x70,0x7b,0x7f,0x7a,0x82,0x92,0x99,0x99,0xa1,0xa0,
0x90,0x69,0x5b,0x60,0x68,0x6e,0x72,0x7a,0x7d,0x7d,0x88,0x93,0x99,0x9f,0xa2,0xa0,
0x7f,0x5e,0x58,0x64,0x6c,0x6e,0x77,0x7e,0x79,0x7f,0x8f,0x9a,0x9b,0x9f,0xa2,0x97,
0x72,0x59,0x5c,0x67,0x6b,0x70,0x7e,0x80,0x79,0x83,0x94,0x99,0x99,0x9e,0xa3,0x88,
0x61,0x5b,0x68,0x6e,0x6c,0x73,0x7c,0x79,0x79,0x8a,0x99,0x9c,0x9f,0xa2,0x9b,0x7a,
0x60,0x5e,0x63,0x6b,0x6f,0x79,0x7d,0x7c,0x81,0x8d,0x95,0x9b,0xa0,0xa2,0x93,0x72,
0x5b,0x5f,0x66,0x6a,0x70,0x7b,0x7f,0x7b,0x82,0x91,0x99,0x9d,0x9f,0xa1,0x88,0x64,
0x5a,0x65,0x6c,0x6c,0x75,0x7d,0x79,0x79,0x8a,0x97,0x9c,0x9e,0xa6,0x9c,0x79,0x5d,
0x5d,0x66,0x6a,0x6f,0x79,0x7f,0x79,0x7e,0x8e,0x98,0x97,0x9b,0xa1,0x98,0x74,0x5c,
0x60,0x68,0x6a,0x6d,0x7a,0x7f,0x7b,0x82,0x92,0x9a,0x9d,0x9e,0xa2,0x8d,0x6b,0x5d,
0x61,0x69,0x6c,0x72,0x7b,0x7c,0x7c,0x87,0x94,0x98,0x99,0xa0,0xa1,0x84,0x63,0x5b,
0x66,0x6a,0x6e,0x76,0x7d,0x7a,0x7b,0x8a,0x97,0x9a,0x9c,0xa0,0x9a,0x7b,0x60,0x5f,
0x68,0x6c,0x6c,0x75,0x7e,0x7d,0x7f,0x8c,0x98,0x9a,0x9c,0xa0,0x98,0x75,0x5b,0x5f,
0x69,0x6c,0x6f,0x7a,0x7e,0x79,0x7e,0x91,0x9b,0x9e,0x9d,0xa0,0x8f,0x6b,0x5c,0x62,
0x6b,0x6d,0x70,0x7a,0x7d,0x7b,0x85,0x92,0x9a,0x9a,0x9d,0x9e,0x8c,0x68,0x5e,0x67,
0x68,0x66,0x70,0x7f,0x7f,0x7c,0x89,0x96,0x99,0x9d,0xa0,0x9d,0x7d,0x60,0x61,0x69,
0x6a,0x6b,0x75,0x7d,0x7b,0x7e,0x8b,0x94,0x99,0x9c,0xa2,0x9c,0x7b,0x5f,0x5c,0x66,
0x6b,0x70,0x79,0x7d,0x79,0x80,0x8f,0x97,0x99,0x9e,0xa0,0x92,0x72,0x64,0x66,0x67,
0x67,0x6d,0x7a,0x7d,0x7b,0x83,0x90,0x96,0x9b,0xa1,0xa2,0x90,0x6f,0x5f,0x63,0x67,
0x6c,0x73,0x7b,0x79,0x78,0x85,0x92,0x96,0x9a,0xa2,0xa4,0x8b,0x6c,0x5f,0x63,0x65,
0x6b,0x76,0x7b,0x77,0x7b,0x88,0x93,0x95,0x9a,0xa2,0xa3,0x89,0x69,0x5f,0x62,0x66,
0x6e,0x77,0x7b,0x77,0x7a,0x86,0x92,0x98,0x9d,0xa4,0xa2,0x87,0x66,0x5d,0x61,0x65,
0x6f,0x78,0x7c,0x77,0x7a,0x89,0x92,0x94,0x9b,0xa6,0xa2,0x86,0x68,0x5e,0x5f,0x65,
0x70,0x79,0x7a,0x78,0x7c,0x89,0x90,0x95,0x9f,0xa5,0x9f,0x85,0x65,0x5f,0x63,0x65,
0x6c,0x79,0x7c,0x77,0x7b,0x8c,0x92,0x95,0x9b,0xa8,0xa2,0x82,0x65,0x61,0x62,0x65,
0x6e,0x79,0x7a,0x77,0x7d,0x8b,0x91,0x94,0x9c,0xa7,0xa7,0x87,0x64,0x59,0x5e,0x66,
0x6e,0x7a,0x7f,0x78,0x79,0x88,0x91,0x93,0x99,0xa6,0xa8,0x89,0x66,0x5f,0x61,0x61,
0x68,0x78,0x7f,0x7a,0x7b,0x88,0x8f,0x92,0x99,0xa7,0xa7,0x8f,0x6b,0x5d,0x5d,0x61,
0x69,0x75,0x7e,0x7b,0x7a,0x86,0x91,0x93,0x98,0xa4,0xad,0x97,0x6d,0x5a,0x57,0x5d,
0x66,0x77,0x84,0x80,0x79,0x82,0x8c,0x90,0x95,0xa4,0xac,0x9d,0x72,0x5a,0x58,0x5b,
0x63,0x75,0x83,0x82,0x79,0x82,0x8d,0x8f,0x92,0xa2,0xb1,0xa6,0x7a,0x58,0x53,0x56,
0x60,0x74,0x87,0x86,0x7b,0x7c,0x89,0x8d,0x8f,0x9d,0xb0,0xae,0x89,0x5c,0x52,0x53,
0x5b,0x6c,0x83,0x8a,0x80,0x7c,0x87,0x8a,0x8b,0x98,0xaf,0xb6,0x93,0x62,0x51,0x52,
0x56,0x66,0x83,0x8f,0x81,0x76,0x81,0x8a,0x89,0x92,0xad,0xb9,0xa0,0x71,0x55,0x50,
0x4f,0x5e,0x7b,0x90,0x88,0x7a,0x7a,0x83,0x83,0x8c,0xa6,0xb8,0xb6,0x89,0x59,0x4d,
0x4f,0x57,0x6d,0x89,0x93,0x82,0x78,0x7c,0x84,0x85,0x95,0xaf,0xbf,0xa8,0x71,0x50,
0x4d,0x52,0x5e,0x7a,0x91,0x8c,0x79,0x77,0x80,0x83,0x83,0x9d,0xba,0xc1,0x99,0x5b,
0x47,0x4e,0x57,0x6c,0x8b,0x92,0x7f,0x73,0x7b,0x81,0x82,0x89,0xa3,0xbb,0xbf,0x93,
0x55,0x45,0x4b,0x5c,0x7d,0x98,0x8b,0x6d,0x68,0x7d,0x85,0x85,0x88,0x9f,0xb6,0xc0,
0x9b,0x5c,0x42,0x49,0x5b,0x7a,0x9b,0x98,0x6f,0x5e,0x73,0x85,0x81,0x7e,0x97,0xb4,
0xc7,0xb4,0x74,0x45,0x3f,0x4d,0x70,0x9a,0xa5,0x7d,0x5f,0x69,0x7d,0x7e,0x7a,0x86,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,
0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80,0x80
};
void setup() {
attachInterrupt(INTIR, irInt, CHANGE);
analogWriteFrequency(16000);
pinMode(LED1_M1F, OUTPUT);
pinMode(LED2_M0F, OUTPUT);
pinMode(LED3_M0B, OUTPUT);
pinMode(LED4_M1B, OUTPUT);
pinMode(LED5, OUTPUT);
pinMode(LED6, OUTPUT);
pinMode(LED_R, OUTPUT);
pinMode(LED_G, OUTPUT);
pinMode(LED_B, OUTPUT);
pinMode(4, OUTPUT);
pinMode(SW1, INPUT_PULLUP);
pinMode(SW2, INPUT_PULLUP);
digitalWrite(LED1_M1F, LED_OFF);
digitalWrite(LED2_M0F, LED_OFF);
digitalWrite(LED3_M0B, LED_OFF);
digitalWrite(LED4_M1B, LED_OFF);
digitalWrite(LED5, LED_OFF);
digitalWrite(LED6, LED_OFF);
randomSeed((unsigned int)analogRead(BATT));
Serial.begin(115200);
Wire.begin();
Wire.beginTransmission(0x68); //Gyro sensor
Wire.write(0x6B); // Power management register
Wire.write(0); // wake up MPU-6050
Wire.endTransmission(true);
SD2.begin(27);
checkVoltage();
selectMode();
pinMode(SOUTPIN, OUTPUT);
analogWrite(SOUTPIN, 0);
delay(100); //allow pullup and gyro to stabilize
readEEPROMbal();
readEEPROMadhoc();
resetPara();
resetVar();
digitalWrite(LED6, LED_ON);
calibGyro();
digitalWrite(LED6, LED_OFF);
soundStart(soundGreet, sizeof(soundGreet), 70);
openFiles();
while (soundBusy);
if (demoMode==2) soundStartSD(fDemo, 70);
if (debug) soundStartSD(fDebug, 70);
}
void loop(){
time0=micros();
getIR();
getGyro();
pendulum();
servoHead();
randomPlay();
if (pendPhase!=-1) monitorVoltage();
counter += 1;
if (counter >= 100) {
counter = 0;
counterSec++;
if (debug) digitalWrite(LED6, LED_ON);
if (serialMonitor) sendSerial();
digitalWrite(LED6, LED_OFF);
}
while (micros() - time0 < pendInterval);
}
void pendulum() {
switch (pendPhase) {
case -1: //wait until upright
calcTarget();
if (upright()) pendPhase =0;
break;
case 0: //calib Acc
resetVar();
demoDelayCounter=0;
demoPhase=0;
delay(1300);
digitalWrite(LED6, LED_ON);
calibAcc();
digitalWrite(LED6, LED_OFF);
pendPhase=1;
break;
case 1: //run
if (demoMode==2) demo8();
calcTarget();
drive();
if (!standing()) {
if (musicPlaying) soundStop=true;
soundStart(soundWow, sizeof(soundWow), 70);
pendPhase=6;
}
else if (counterOverSpd > maxOverSpd) {
if (musicPlaying) soundStop=true;
delay(1000);
pendPhase=2;
}
break;
case 2: //wait until upright
if (upright()) pendPhase=0;
break;
case 6: //fell
if (laid() && !soundBusy) pendPhase=8;
break;
case 8:
if (soundSD) soundStartSD(fTipover, 70);
pendPhase=2;
break;
}
}
void openFiles() {
fGreet=SD2.open("kon168m.wav");
if (!fGreet) {
soundSD=false;
return;
}
soundSD=true;
fStop=SD2.open("tom168m.wav");
fRight=SD2.open("mig168m.wav");
fLeft=SD2.open("hid168m.wav");
fForward=SD2.open("sus168m.wav");
fBack=SD2.open("bac168m.wav");
fSpin=SD2.open("maw168m.wav");
fAccel=SD2.open("kaso168m.wav");
fTipover=SD2.open("koro168m.wav");
fDemo=SD2.open("demo168m.wav");
fDebug=SD2.open("debu168m.wav");
fBattery=SD2.open("denc168m.wav");
fReplace=SD2.open("kouk168m.wav");
voiceFile[0]=SD2.open(soundVoice[0]);
if (voiceFile[0]) {
if (serialMonitor) Serial.println(soundVoice[0]);
minVoiceFile=0;
}
for (int i=1; i<sizeof(soundVoice)/2; i++) {
voiceFile[i]=SD2.open(soundVoice[i]);
if (voiceFile[i]) {
if (serialMonitor) Serial.println(soundVoice[i]);
maxVoiceFile=i;
}
}
if (minVoiceFile==-1 && maxVoiceFile>=1) minVoiceFile=1;
for (int i=0; i<sizeof(soundMusic)/2; i++) {
musicFile[i]=SD2.open(soundMusic[i]);
if (musicFile[i]) {
if (serialMonitor) Serial.println(soundMusic[i]);
minMusicFile=0;
maxMusicFile=i;
}
}
}
void randomPlay() {
if (!randomSoundOn || minVoiceFile==-1) return;
// if (abs(moveRate)<10.0 && abs(spinStep)<1.5) {
switch (soundPhase) {
case 1:
if (!soundBusy) {
counterSec0=counterSec;
soundInterval=(int)random(MINSINTERVAL, MAXSINTERVAL+1);
soundPhase=2;
}
break;
case 2:
if (counterSec-counterSec0>soundInterval) {
soundId=random(minVoiceFile, maxVoiceFile+1);
soundStartSD(voiceFile[soundId], 10);
if (soundId==0) {
if (minMusicFile!=-1 && demoMode==0) soundPhase=3;
else soundPhase=1;
}
else soundPhase=1;
}
break;
case 3:
if (!soundBusy) {
musicPlaying=true;
soundStartSD(musicFile[random(minMusicFile, maxMusicFile+1)], 10);
soundPhase=1;
}
break;
}
// }
}
void servoHead() {
switch(servoPhase) {
case 1:
servoDrive();
if (servoComplete) {
servoComplete=false;
servoPhase=2;
}
break;
case 2:
servoContinue(90.0, 1.0);
servoPhase=3;
break;
case 3:
servoDrive();
if (servoComplete) {
servoComplete=false;
servoPhase=4;
}
break;
case 4:
break;
}
}
void servoStart(double ang, double stp) {
servoPhase=1;
servoContinue(ang, stp);
}
void servoContinue(double ang, double stp) {
if (ang<servoAngTarget) stp=-stp;
servoAngDestination=ang;
servoAngStep=stp;
}
void servoDrive() {
if (servoAngStep>=0) {
if (servoAngDestination-servoAngStep>servoAngTarget) servoAngTarget+=servoAngStep;
else {
servoAngTarget=servoAngDestination;
servoComplete=true;
}
}
else {
if (servoAngDestination-servoAngStep<servoAngTarget) servoAngTarget+=servoAngStep;
else {
servoAngTarget=servoAngDestination;
servoComplete=true;
}
}
servoPulseWidth=600+(int)(servoAngTarget*10.0);
digitalWrite(4, HIGH);
delayMicroseconds(servoPulseWidth);
digitalWrite(4, LOW);
}
void calcTarget() {
if (spinContinuous) spinTarget += spinStep;
else {
if (spinTarget < spinDestination) spinTarget += spinStep;
if (spinTarget > spinDestination) spinTarget -= spinStep;
}
moveTarget -= moveStep * moveRate;
}
void drive() {
varSpd += power * pendClk;
varDst += Kdst * (varSpd * pendClk - moveTarget);
varIang += KIang * varAng * pendClk;
varIdst += KIdst * varDst * pendClk;
power = varIang + varIdst + varDst + (Kspd * varSpd) + (Kang * varAng) + (Komg * varOmg);
if (abs(power) > 5000.0) counterOverSpd +=1;
else counterOverSpd=0;
if (counterOverSpd > maxOverSpd) {
resetMotor();
return;
}
spinPower = (spinAngle - spinTarget) * Kspin;
powerR = power - spinPower;
powerL = power + spinPower;
motor();
}
void motor() {
ipowerR = (int) (constrain(powerR * mechFactorR * battFactor, -maxSpd, maxSpd));
if (ipowerR > 0) {
if (motorRdir == 1) drvMotorL(ipowerR);
else drvMotorL(ipowerR + backlashSpd); //compensate backlash
motorRdir = 1;
}
else if (ipowerR < 0) {
if (motorRdir == -1) drvMotorL(ipowerR);
else drvMotorL(ipowerR - backlashSpd);
motorRdir = -1;
}
else {
drvMotorL(0);
motorRdir = 0;
}
ipowerL = (int) (constrain(powerL * mechFactorL * battFactor, -maxSpd, maxSpd));
if (ipowerL > 0) {
if (motorLdir == 1) drvMotorR(ipowerL);
else drvMotorR(ipowerL + backlashSpd); //compensate backlash
motorLdir = 1;
}
else if (ipowerL < 0) {
if (motorLdir == -1) drvMotorR(ipowerL);
else drvMotorR(ipowerL - backlashSpd);
motorLdir = -1;
}
else {
drvMotorR(0);
motorLdir = 0;
}
}
void drvMotor0(int pwm) {
if (pwm >0) {
digitalWrite(M0B,LOW);
analogWrite(M0F,constrain(pwm+drvHLbalance, 0,PWMMAX));
}
else if (pwm < 0) {
digitalWrite(M0B,HIGH);
analogWrite(M0F,constrain(PWMMAX+pwm, 0,PWMMAX));
}
else {
digitalWrite(M0B,LOW);
pinMode(M0F, OUTPUT);
digitalWrite(M0F,LOW);
}
}
void drvMotor1(int pwm) {
if (pwm >0) {
digitalWrite(M1B,LOW);
analogWrite(M1F,constrain(pwm+drvHLbalance, 0,PWMMAX));
}
else if (pwm < 0) {
digitalWrite(M1B,HIGH);
analogWrite(M1F,constrain(PWMMAX+pwm, 0,PWMMAX));
}
else {
digitalWrite(M1B,LOW);
pinMode(M1F, OUTPUT);
digitalWrite(M1F,LOW);
}
}
void drvMotorL(int pwm) {
switch (MotorConfig) {
case 0: drvMotor1(pwm);
break;
case 1: drvMotor1(-pwm);
break;
case 2: drvMotor1(pwm);
break;
case 3: drvMotor1(-pwm);
break;
}
}
void drvMotorR(int pwm) {
switch (MotorConfig) {
case 0: drvMotor0(pwm);
break;
case 1: drvMotor0(-pwm);
break;
case 2: drvMotor0(-pwm);
break;
case 3: drvMotor0(pwm);
break;
}
}
void getGyro() {
readGyro();
snsGyroY = (gyroDataY - gyroOffsetY) * gyroLSB;
varOmg = (gyroDataZ - gyroOffsetZ) * gyroLSB; // unit:deg/sec
snsAccX = (accDataX - accOffsetX) * accLSB; //unit:g
spinAngle += snsGyroY * pendClk;
varAng += (varOmg + (snsAccX * 57.3 - varAng) * cutoff ) * pendClk;
//angle filter accX=g*sin(ang) -> accX/g=sin(ang)=ang [rad] (if ang is small) -> ang=accX*57.3[deg]
// varAng += varOmg * pendClk;
}
void readGyro() {
Wire.beginTransmission(0x68);
Wire.write(0x3B);
Wire.endTransmission(false); //enable incremental read
Wire.requestFrom(0x68, 14, (int)true);
accX=Wire.read()<<8|Wire.read(); //0x3B
accY=Wire.read()<<8|Wire.read(); //0x3D
accZ=Wire.read()<<8|Wire.read(); //0x3F
temp=Wire.read()<<8|Wire.read(); //0x41
gyroX=Wire.read()<<8|Wire.read(); //0x43
gyroY=Wire.read()<<8|Wire.read(); //0x45
gyroZ=Wire.read()<<8|Wire.read(); //0x47
gyroDataY = (double) gyroY;
gyroDataZ = -(double) gyroX;
accDataX = -(double) accZ;
aveAccX = aveAccX * 0.9 + accDataX * 0.1;
accDataY = -(double) accY;
aveAccY = aveAccY * 0.9 + accDataY * 0.1;
}
boolean laid() {
if (abs(aveAccX) >13000.0) return true;
else return false;
}
boolean upright() {
if (abs(aveAccY) >13000.0) return true;
else return false;
}
boolean standing() {
if (abs(aveAccY) >8000.0 && abs(varAng) < 40.0) return true;
else {
resetMotor();
return false;
}
}
void calibAcc() {
accOffsetX=0.0;
for (int i=1; i <= 30; i++) {
readGyro();
accOffsetX += accDataX;
delay(20);
}
accOffsetX /= 30.0;
}
void calibGyro() {
gyroOffsetZ=gyroOffsetY=0.0;
for (int i=1; i <= 30; i++) {
readGyro();
gyroOffsetZ += gyroDataZ;
gyroOffsetY += gyroDataY;
delay(20);
}
gyroOffsetY /= 30.0;
gyroOffsetZ /= 30.0;
}
void resetPara() {
Kang=150.0;
Komg=3.0;
KIang=1200.0;
Kspin=15.0;
Kdst=80.0;
Kspd=3.5;
KIdst=0.0;
mechFactorR=0.4;
mechFactorL=0.4;
backlashSpd=30;
}
void resetVar() {
power=0.0;
moveTarget=0.0;
spinDestination=0.0;
spinTarget=0.0;
spinAngle=0.0;
varAng=0.0;
varOmg=0.0;
varDst=0.0;
varSpd=0.0;
varIang=0.0;
varIdst=0.0;
counterOverSpd=0;
spinContinuous=false;
moveRate=0.0;
}
void resetMotor() {
digitalWrite(M0B,LOW);
pinMode(M0F, OUTPUT);
digitalWrite(M0F,LOW);
digitalWrite(M1B,LOW);
pinMode(M1F, OUTPUT);
digitalWrite(M1F,LOW);
}
void checkVoltage() {
monitorVoltage();
if (serialMonitor) {Serial.print("Batt=");Serial.println(bVolt);}
if (bVolt>=0.5 && bVolt<3.8) {
if (soundSD) soundStartSD(fBattery, 70);
blinkLED(5); //Batt Low
if (soundSD) soundStartSD(fReplace, 70);
blinkLED(45);
}
}
void blinkLED(int n) {
for (int i=0; i<n; i++) {
digitalWrite(LED6, LED_ON);
delay(10);
digitalWrite(LED6, LED_OFF);
delay(200);
}
}
void monitorVoltage() {
bVolt=getBattVolt();
aveVolt = aveVolt * 0.98 + bVolt * 0.02;
if (bVolt<0.5) { //USB POWER
battFactor=1.3;
setColor(0,0,1);
}
else {
battFactor = 18.0 / aveVolt / aveVolt;
// battFactor = 4.5 / aveVolt;
// battFactor = 4.5 / bVolt;
if (bVolt<3.6) setColor(0,0,0);
else if (bVolt<4.0) setColor(1,0,0);
else if (bVolt<4.4) setColor(1,1,0);
else setColor(0,1,0);
}
}
double getBattVolt() {
return ((double) analogRead(BATT)) / 1023.0 * 6.6;
}
void selectMode() {
if (digitalRead(SW1) == LOW) { //debug
debug=true;
serialMonitor=true;
spinStep=0.0;
blinkLED(1);
}
else if (digitalRead(SW2) == LOW) { //demo
demoMode=2;
blinkLED(2);
}
else spinStep=0.0;
}
void demo8() {
switch (demoPhase) {
case 0:
demoDelayCounter=200;
demoPhase=1;
break;
case 1:
if (demoDelayCounter>1) demoDelayCounter--;
else {
moveRate=3.0;
spinStep=0.5;
spinDestination += 270.0;
demoPhase=2;
}
break;
case 2:
if (abs(spinTarget-spinDestination)<5.0) {
demoDelayCounter=100;
moveRate=5.0;
demoPhase=3;
}
break;
case 3:
if (demoDelayCounter>1) demoDelayCounter--;
else {
moveRate=3.0;
spinDestination -= 270.0;
demoPhase=4;
}
break;
case 4:
if (abs(spinTarget-spinDestination)<5.0) {
demoDelayCounter=100;
moveRate=5.0;
demoPhase=1;
}
break;
}
}
void setColor(int r, int g, int b) {
digitalWrite(LED_R, r);
digitalWrite(LED_G, g);
digitalWrite(LED_B, b);
}
void readEEPROMbal() {
if (EEPROM.read(0)==HCODE) {
drvHLbalance=EEPROM.read(1);
if (serialMonitor) {Serial.print("drvHLbal=");Serial.println(drvHLbalance);}
}
else {
drvHLbalance=30;
noInterrupts();
EEPROM.write(0, HCODE);
EEPROM.write(1, drvHLbalance);
interrupts();
}
}
void writeEEPROMbal() {
noInterrupts();
EEPROM.write(1, drvHLbalance);
interrupts();
}
void readEEPROMadhoc() {
if (EEPROM.read(2)==HCODE) {
for (int i=0; i<ADHOC_IR_MAX; i++) {
ADHOC_CUSTOMER[i]=EEPROM.read(3+i*4)<<8|EEPROM.read(4+i*4);
ADHOC_IR[i]=EEPROM.read(5+i*4)<<8|EEPROM.read(6+i*4);
if (serialMonitor) {
Serial.print("CUST=");Serial.print(ADHOC_CUSTOMER[i],HEX);Serial.print(" CODE=");Serial.println(ADHOC_IR[i],HEX);
}
}
}
}
void writeEEPROMadhoc() {
noInterrupts();
EEPROM.write(2, HCODE);
for (int i=0; i<ADHOC_IR_MAX; i++) {
EEPROM.write(3+i*4, (byte)((ADHOC_CUSTOMER[i]>>8)&0xFF));
EEPROM.write(4+i*4, (byte)(ADHOC_CUSTOMER[i]&0xFF));
EEPROM.write(5+i*4, (byte)((ADHOC_IR[i]>>8)&0xFF));
EEPROM.write(6+i*4, (byte)(ADHOC_IR[i]&0xFF));
}
interrupts();
}
void sendSerial () {
Serial.print(micros()-time0);
Serial.print(" phase=");Serial.print(pendPhase);
Serial.print(" accX="); Serial.print(aveAccX);
Serial.print(" accY="); Serial.print(aveAccY);
Serial.print(" ang=");Serial.print(varAng);
// Serial.print(" temp = "); Serial.print(temp/340.0+36.53);
Serial.print(" drvBal="); Serial.print(drvHLbalance);
Serial.print(F(" apinA=")); Serial.print(spinAngle);
Serial.print(F(" batt=")); Serial.print(aveVolt);
Serial.print(", ");
Serial.print(micros()-time0);
Serial.println();
}
void getIR() {
if (!(irStarted && (micros()-irMicroOff>10000))) return;
if ((irDataOn[0]>1800) && musicPlaying) soundStop=true;
irStarted=false;
irDecoding=true;
if (irDataOn[0]>7000) { //NEC
if (irOffIndex >=33) {
decodeNECAEHA();
printIrData("NEC");
}
}
else if (irDataOn[0]>2600) { //AEHA
if (irOffIndex >=41) {
decodeNECAEHA();
printIrData("AEHA");
}
}
else if (irDataOn[0]>1800) { //SONY
if (irOnIndex >=12) {
decodeSONY();
printIrData("SONY");
}
}
if (irReady) {
irReady=false;
lastIrTime=millis();
if (serialMonitor) {
Serial.print("IR code=");Serial.println(ircode, HEX);
Serial.print("Cust Code=");Serial.println(customer_code, HEX);
}
if (adhoc_ir_num>=0 && adhoc_ir_num<ADHOC_IR_MAX) regIR();
else irCommand();
}
irDecoding=false;
}
void irCommand() {
if (
((ircode==AKI_REMO_CENTER)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_CENTER])&&(customer_code==ADHOC_CUSTOMER[IR_CENTER])) ) {
if (pendPhase!=-1) {
if (abs(moveRate)>1.0 || abs(spinStep)>0.1) {
if (soundSD) soundStartSD(fStop, 10);
else tone(TONE_PIN, 500, 100);
}
button=5;
demoMode=0;
spinContinuous=false;
spinStep=0.0;
moveRate=0.0;
spinDestination = spinTarget;
}
}
else if (
((ircode==AKI_REMO_RIGHT)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_RIGHT])&&(customer_code==ADHOC_CUSTOMER[IR_RIGHT])) ) {
if (pendPhase==-1) {
servoStart(60.0, 0.5);
drvMotorR(-80);
delay(1000);
drvMotorR(0);
}
else if (demoMode==0) {
servoStart(headRight, 3.0);
if (button!=6) {
if (soundSD) soundStartSD(fRight, 10);
else tone(TONE_PIN, 2000, 100);
}
button=6;
if (spinContinuous) spinDestination=spinTarget;
spinContinuous=false;
spinStep=0.6;
spinDestination -= 30.0;
}
}
else if (
((ircode==AKI_REMO_LEFT)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_LEFT])&&(customer_code==ADHOC_CUSTOMER[IR_LEFT])) ) {
if (pendPhase==-1) {
servoStart(120.0, 0.5);
drvMotorL(-80);
delay(1000);
drvMotorL(0);
}
else if (demoMode==0) {
servoStart(headLeft, 3.0);
if (button!=4) {
if (soundSD) soundStartSD(fLeft, 10);
else tone(TONE_PIN, 2000, 100);
}
button=4;
if (spinContinuous) spinDestination=spinTarget;
spinContinuous=false;
spinStep=0.6;
spinDestination += 30.0;
}
}
else if (
((ircode==AKI_REMO_UP)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_UP])&&(customer_code==ADHOC_CUSTOMER[IR_UP])) ) {
if (pendPhase!=-1 && demoMode==0) {
button=2;
if (abs(moveRate)<1.0) {
if (soundSD) soundStartSD(fForward, 10);
else tone(TONE_PIN, 1000, 100);
}
if (moveRate>10.0) {
if (soundSD) soundStartSD(fAccel, 70);
else soundStart(soundWow, sizeof(soundWow), 10);
}
moveRate+=4.0;
}
}
else if (
((ircode==AKI_REMO_DOWN)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_DOWN])&&(customer_code==ADHOC_CUSTOMER[IR_DOWN])) ) {
if (pendPhase!=-1 && demoMode==0) {
button=8;
if (abs(moveRate)<1.0) {
if (soundSD) soundStartSD(fBack, 10);
else tone(TONE_PIN, 1000, 100);
}
moveRate-=4.0;
}
}
else if (
((ircode==AKI_REMO_UL)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_CIRL])&&(customer_code==ADHOC_CUSTOMER[IR_CIRL])) ) {
if (pendPhase!=-1 && demoMode==0) {
button=1;
if (abs(spinStep)<0.1) {
if (soundSD) soundStartSD(fSpin, 10);
else tone(TONE_PIN, 2000, 20);
}
if (!spinContinuous) spinStep=0.0;
spinContinuous=true;
spinStep+=0.3;
}
}
else if (
((ircode==AKI_REMO_UR)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_CIRR])&&(customer_code==ADHOC_CUSTOMER[IR_CIRR])) ) {
if (pendPhase!=-1 && demoMode==0) {
button=3;
if (abs(spinStep)<0.1) {
if (soundSD) soundStartSD(fSpin, 10);
else tone(TONE_PIN, 2000, 20);
}
if (!spinContinuous) spinStep=0.0;
spinContinuous=true;
spinStep-=0.3;
}
}
else if (
((ircode==AKI_REMO_DL)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_BALF])&&(customer_code==ADHOC_CUSTOMER[IR_BALF])) ) {
if (demoMode==0) {
if (moveRate==0.0 && spinTarget==spinDestination) {
if (drvHLbalance<100) {
drvHLbalance-=5;
setColor(1,0,1);
digitalWrite(LED5,LED_ON);
writeEEPROMbal();
digitalWrite(LED5,LED_OFF);
}
}
}
}
else if (
((ircode==AKI_REMO_DR)&&(customer_code==AKI_REMO_CUSTOMER))||
((ircode==ADHOC_IR[IR_BALB])&&(customer_code==ADHOC_CUSTOMER[IR_BALB])) ) {
if (demoMode==0) {
if (moveRate==0.0 && spinTarget==spinDestination) {
if (drvHLbalance>-100) {
drvHLbalance+=5;
setColor(1,0,1);
digitalWrite(LED5,LED_ON);
writeEEPROMbal();
digitalWrite(LED5,LED_OFF);
}
}
}
}
else {
if (pendPhase == -1 && debug && adhoc_ir_num==-1) {
setColor(1,0,1);
digitalWrite(LED5, LED_ON);
randomSoundOn=false;
adhoc_ir_num=0;
}
}
}
void regIR() {
// Ad hoc IR code registration
if (adhoc_ir_num<ADHOC_IR_MAX) {
ADHOC_IR[adhoc_ir_num]=ircode;
ADHOC_CUSTOMER[adhoc_ir_num]=customer_code;
if (serialMonitor) {
Serial.print("set ADHOC_IR[");
Serial.print(adhoc_ir_num);
Serial.print("] = ");
Serial.println(ircode, HEX);
Serial.print("set ADHOC_CUSTOMER[");
Serial.print(adhoc_ir_num);
Serial.print("] = ");
Serial.println(customer_code, HEX);
}
if (adhoc_ir_num==0) adhoc_ir_num++;
else if (ADHOC_IR[adhoc_ir_num-1]!=ircode) adhoc_ir_num++;
for (int i=1; i<=adhoc_ir_num; i++) {
digitalWrite(LED5, LED_OFF);
delay(200);
digitalWrite(LED5, LED_ON);
delay(100);
}
if (adhoc_ir_num==ADHOC_IR_MAX) {
writeEEPROMadhoc();
digitalWrite(LED5, LED_OFF);
randomSoundOn=true;
}
}
}
void irInt() {
if (millis()-lastIrTime<250) return;
if (irDecoding) return;
if (digitalRead(IRIN) == IRON) {
irMicroOn=micros();
if (irStarted) {
irDataOff[irOffIndex]=irMicroOn-irMicroOff;
irOffIndex++;
if (irOffIndex>=IRBUFFLEN) irStarted=false;
}
else {
irStarted=true;
irOnIndex=0;
irOffIndex=0;
irMicroOff=irMicroOn;
}
}
else {
irMicroOff=micros();
irDataOn[irOnIndex]=irMicroOff-irMicroOn;
irOnIndex++;
if (irOnIndex>=IRBUFFLEN) irStarted=false;
}
}
void decodeNECAEHA() {
int len=irOffIndex/8;
int idx=1;
for (int i=0; i<len; i++) {
irData[i]=0;
for (int j=0; j<8; j++) {
irData[i]>>=1;
if (irDataOff[idx]>1000) irData[i]|=0x80;
idx++;
}
}
customer_code=irData[0]<<8|irData[1];
ircode=irData[len-2]<<8|irData[len-1];
irReady=true;
}
void decodeSONY() {
byte data=0;
for (int i=1; i<=7; i++) {
if (irDataOn[i]>900) data|=0x80;
data>>=1;
}
unsigned int addr=0;
int idx=8;
for (int i=0; i<16; i++) {
addr>>=1;
if (idx<irOnIndex && irDataOn[idx]<1800) {
if (irDataOn[idx]>900) addr|=0x8000;
idx++;
}
}
customer_code=addr;
ircode=(unsigned int)data;
irReady=true;
}
void printIrData(String s) {
if (!serialMonitor) return;
Serial.println(s);
Serial.print("Customer=");Serial.println(customer_code, HEX);
Serial.print("Code=");Serial.println(ircode, HEX);
/*
for (int i=0; i<irOffIndex; i++) {
Serial.print(irDataOn[i]);Serial.print(" ");Serial.println(irDataOff[i]);
}
Serial.println("");
*/
}
void soundIntSD() {
if (sdfile.available() && !soundStop) {
byte d=sdfile.read();
if (soundGain!=10) {
int di=(int)d-128;
di=(di*soundGain)/10;
d=(byte)constrain((di+128), 10, 250);
}
else d=constrain(d, 10, 250);
analogWrite(SOUTPIN, d);
}
else {
detachInterrupt(INTSOUND);
analogWrite(SOUTPIN, 0);
musicPlaying=false;
soundBusy=false;
}
}
void soundStartSD(File s, int gain) {
if (soundBusy || !soundSD || !soundOn) return;
sdfile=s;
soundBusy=true;
soundStop=false;
if (sdfile.seek(44)) {
soundGain=gain;
attachInterrupt(INTSOUND, soundIntSD, RISING);
analogWrite(SOUTPIN, 128);
}
}
void soundStart(const byte* ptr, unsigned long sz, int gain) {
if (soundBusy || !soundOn) return;
counterSec0=counterSec;
soundBusy=true;
soundIndex=0;
soundPtr=ptr;
soundSize=sz;
soundGain=gain;
attachInterrupt(INTSOUND, soundInt, RISING);
analogWrite(SOUTPIN, 128);
}
void soundInt() {
byte d=soundPtr[soundIndex];
if (soundGain!=10) {
int di=(int)d-128;
di=(di*soundGain)/10;
d=(byte)constrain((di+128), 10, 250);
}
else d=constrain(d, 10, 250);
analogWrite(SOUTPIN, d);
soundIndex++;
if (soundIndex>=soundSize) {
detachInterrupt(INTSOUND);
analogWrite(SOUTPIN, 0);
soundBusy=false;
}
}

2017年5月18日木曜日

Processingでm2xのデータをダウンロード

import java.io.InputStreamReader;
import java.io.BufferedInputStream;
import java.net.HttpURLConnection;
import java.net.URL;
Table dataTable;
String filePath;
final String dataFile="dataFile.csv";
final String[] stream={"Temp1", "Temp2", "Temp3", "Temp4", "Humid1", "Humid2", "Humid3", "Humid4"};
final String apiKey="xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
final String deviceId="yyyyyyyyyyyyyyyyyyyyyyyyyyyyyyyy";
void setup() {
tableSetup();
getData();
exit();
}
void draw() {
}
void getData() {
String request;
String startTime="";
for (int i=0; i<stream.length; i++) {
int lastIdx=dataTable.getInt(0, stream[i]);
if (lastIdx==0) {
request="?sort=timestamp&dir=desc&limit=1";
}
else {
startTime=dataTable.getString(lastIdx, "time"+stream[i]);
request="?sort=timestamp&dir=asc&limit=1000&start="+startTime;
}
try {
String s="http://api-m2x.att.com/v2/devices/"+deviceId+"/streams/"+stream[i]+"/values.csv"+request;
println(s);
URL url = new URL(s);
HttpURLConnection con = (HttpURLConnection) url.openConnection();
con.setRequestMethod("GET");
con.setRequestProperty("X-M2X-KEY", apiKey);
con.connect();
int res=con.getResponseCode();
if (res==200) {
InputStream inputStr = new BufferedInputStream(con.getInputStream());
BufferedReader rd= new BufferedReader(new InputStreamReader(inputStr));
String line=rd.readLine();
while (line!=null) {
String[] csvData = split(line, ',');
String time=csvData[0];
float data=float(csvData[1]);
println(time+", "+data);
if (!time.equals(startTime)) {
int idx=dataTable.getInt(0, stream[i]);
idx++;
if (dataTable.getRowCount()<=idx) dataTable.addRow();
dataTable.setString(idx, "time"+stream[i], time);
dataTable.setFloat(idx, stream[i], data);
dataTable.setInt(0, stream[i], idx);
}
line=rd.readLine();
}
}
else println("Http Error "+con.getErrorStream());
}
catch(IOException e) {
println("EXCEPTION "+e);
}
}
saveTable(dataTable, filePath+dataFile);
println("File saved: "+filePath+dataFile);
}
void tableSetup() {
filePath=sketchPath("");
File f=new File(filePath+dataFile);
if (f.exists()) {
dataTable=loadTable(filePath+dataFile, "header");
println("File loaded: "+filePath+dataFile);
}
else {
dataTable = new Table();
for (int i=0; i<stream.length; i++) {
dataTable.addColumn("time"+stream[i]);
dataTable.addColumn(stream[i]);
}
dataTable.addRow();
for (int i=0; i<stream.length; i++) {
dataTable.setInt(0, stream[i], 0);
}
saveTable(dataTable, filePath+dataFile);
println("File created: "+filePath+dataFile);
}
}
view raw m2x0561c.pde hosted with ❤ by GitHub

2017年5月2日火曜日

COTTON虫Ver2

<script src="https://gist.github.com/kirakulabo/c615397ce78a164231648f80f736849e.js"></script>

GR-ADZUKIで倒立振子

/*GR-ADZUKI Sketch Template Version: V1.02*/
//wheele dia ~= 50mm
//Gear ratio ~= 114 (TAMIYA Double Gear Box)
//Battery: Alkaline x 3
//MPU/Driver: GR-ADZUKI
//Gyro: MPU6050 (I2C)
//SW1: Circle
#include "Arduino.h"
#include <Wire.h>
#define LED5 13
#define leftFwd 6
#define leftRvs 11
#define rightFwd 5
#define rightRvs 10
#define ON LOW //LOW active LED
#define OFF HIGH
#define SW1 2
#define SW2 3
#define BATT A3
void resetPara();
void resetVar();
void getGyro();
void readGyro();
void calcTarget();
void motor();
void selectMode();
void calibrate();
bool laid();
bool upright();
bool standing();
void getBaseline();
void drive();
void resetMotor();
void adaptCalibAccX();
void sendSerial();
void drvMotorR(int pwm);
void drvMotorL(int pwm);
int state=-1;
int cycleCount=0;
unsigned long time1=0;
unsigned long time0=0;
float power, powerR, powerL, yawPower;
int ipowerR, ipowerL;
float Kang, Komg, Kdst, Kspd, Kyaw, KIang, KIdst;
float gyroZdps, accXg;
float varAng, varOmg, varSpd, varDst, varIang, varIdst;
float aveDst, aveDst0;
int accX, accY, accZ, temp, gyroX, gyroY, gyroZ;
float gyroZoffset, gyroYoffset, accXoffset;
float gyroZdata, gyroYdata, accXdata, accZdata;
float aveAccX=0.0;
float aveAccZ=0.0;
float moveStep, moveTarget;
float spinStep, spinTarget;
float orientation;
int motorRdir=0; //0:stop 1:+ -1:-
int motorLdir=0;
int overSpdCount;
float battFactor=1.3; // 2016.07.14
float bVolt;
float aveVolt=4.5;
bool usbPower=false;
bool serialMonitor=false;
const float gyroLSB=1.0/131.0; // deg/sec
const float accLSB=1.0/16384.0; // g
const float clk = 0.01; // in sec,
const unsigned long interval = (unsigned long) (clk*1000.0); // in msec
const float filterConst = 0.1;
const float maxSpd=250.0;
const float battConst=6.6/1023.0;
const int driverHLoffset=27; //bigger : backword
const float mechFactorR=0.55;
const float mechFactorL=0.55;
const int backlashSpd=30;
void setup() {
analogWriteFrequency(25000);
pinMode(leftFwd,OUTPUT);
pinMode(leftRvs,OUTPUT);
pinMode(rightFwd,OUTPUT);
pinMode(rightRvs,OUTPUT);
pinMode(LED5, OUTPUT);
pinMode(SW1, INPUT_PULLUP);
pinMode(SW2, INPUT_PULLUP);
digitalWrite(LED5, OFF);
Serial.begin(115200);
Wire.begin();
Wire.beginTransmission(0x68); //Gyro sensor
Wire.write(0x6B); // Power management register
Wire.write(0); // wake up MPU-6050
Wire.endTransmission(true);
delay(500);
checkVoltage();
resetPara();
resetVar();
selectMode();
delay(1000);
}
void loop(){
monitorVoltage();
getGyro();
switch (state) {
case -1:
calcTarget();
if (upright()) state =0;
break;
case 0: //baseline
calibrate();
state=1;
break;
case 1: //run
if (standing() && overSpdCount <= 20) {
calcTarget();
drive();
}
else {
resetMotor();
resetVar();
if (upright()) state=0;
else state=9;
}
break;
case 2: //wait until upright
if (upright()) state=0;
break;
case 9: //fell
if (laid()) state=2;
break;
}
cycleCount += 1;
if (cycleCount >= 100) {
cycleCount = 0;
adaptCalibAccX();
if (serialMonitor) sendSerial();
}
do time1 = millis();
while (time1 - time0 < interval);
time0 = time1;
}
void resetPara() {
Kang=150.0;//150
Komg=3.0;//3.0
KIang=1500.0;//1200
Kyaw=15.0;//15
Kdst=80.0;//80
Kspd=3.5;//3.5
KIdst=0.0;
}
void calcTarget() {
spinTarget += spinStep;
moveTarget += moveStep;
}
void drive() {
varSpd += power * clk;
varDst += Kdst * (varSpd * clk - moveTarget);
aveDst = aveDst * 0.99 + varDst * 0.01;
varIang += KIang * varAng * clk;
varIdst += KIdst * varDst * clk;
power = varIang + varIdst + varDst + (Kspd * varSpd) + (Kang * varAng) + (Komg * varOmg);
if (abs(power) > 300.0) overSpdCount += 1;
else overSpdCount =0;
if (overSpdCount > 20) return;
yawPower = (orientation - spinTarget) * Kyaw;
powerR = power + yawPower;
powerL = power - yawPower;
motor();
}
void motor() {
ipowerR = (int) (constrain(powerR * mechFactorR * battFactor, -maxSpd, maxSpd));
if (ipowerR > 0) {
if (motorRdir == 1) drvMotorR(ipowerR);
else drvMotorR(ipowerR + backlashSpd);
motorRdir = 1;
}
else if (ipowerR < 0) {
if (motorRdir == -1) drvMotorR(ipowerR);
else drvMotorR(ipowerR - backlashSpd);
motorRdir = -1;
}
else {
drvMotorR(0);
motorRdir = 0;
}
ipowerL = (int) (constrain(powerL * mechFactorL * battFactor, -maxSpd, maxSpd));
if (ipowerL > 0) {
if (motorLdir == 1) drvMotorL(ipowerL);
else drvMotorL(ipowerL + backlashSpd);
motorLdir = 1;
}
else if (ipowerL < 0) {
if (motorLdir == -1) drvMotorL(ipowerL);
else drvMotorL(ipowerL - backlashSpd);
motorLdir = -1;
}
else {
drvMotorL(0);
motorLdir = 0;
}
}
void getGyro() {
readGyro();
gyroZdps = (gyroZdata - gyroZoffset) * gyroLSB;
varOmg = (gyroYdata - gyroYoffset) * gyroLSB; // unit:deg/sec
accXg = (accXdata - accXoffset) * accLSB; //unit:g
orientation += gyroZdps * clk;
varAng += (varOmg + (accXg * 57.3 - varAng) * filterConst ) * clk;
// varAng += varOmg * clk;
}
void readGyro() {
Wire.beginTransmission(0x68);
Wire.write(0x3B);
Wire.endTransmission(false); //enable incremental read
Wire.requestFrom(0x68, 14, (int)true); //used to be requestFrom(0x68, 14, true) but got warning.
accX=Wire.read()<<8|Wire.read(); //0x3B
accY=Wire.read()<<8|Wire.read(); //0x3D
accZ=Wire.read()<<8|Wire.read(); //0x3F
temp=Wire.read()<<8|Wire.read(); //0x41
gyroX=Wire.read()<<8|Wire.read(); //0x43
gyroY=Wire.read()<<8|Wire.read(); //0x45
gyroZ=Wire.read()<<8|Wire.read(); //0x47
gyroZdata = -(float) gyroX;
gyroYdata = (float) gyroY;
accXdata = -(float) accZ;
aveAccX = aveAccX * 0.9 + accXdata * 0.1;
accZdata = -(float) accX;
aveAccZ = aveAccZ * 0.9 + accZdata * 0.1;
}
bool laid() {
if (abs(aveAccX) >13000.0) return true;
else return false;
}
bool upright() {
if (abs(aveAccZ) >13000.0) return true;
else return false;
}
bool standing() {
if (abs(aveAccZ) > 10000.0 && abs(varAng) < 40.0) return true;
else return false;
}
void calibrate() {
resetVar();
resetMotor();
delay(2000);
blinkLED(2);
delay(500);
getBaseline();
delay(500);
blinkLED(2);
}
void getBaseline() {
gyroYoffset=gyroZoffset=0.0;
accXoffset=0.0;
for (int i=1; i <= 30; i++){
readGyro();
gyroYoffset += gyroYdata;
gyroZoffset += gyroZdata;
accXoffset += accXdata;
delay(10);
}
gyroZoffset /= 30.0;
gyroYoffset /= 30.0;
accXoffset /= 30.0;
}
void adaptCalibAccX() {
if (aveDst > 100.0 && aveDst > aveDst0) accXoffset -= 20.0;
if (aveDst < -100.0 && aveDst < aveDst0) accXoffset += 20.0;
aveDst0=aveDst;
}
void resetVar() {
power=0.0;
moveTarget=0.0;
spinTarget=0.0;
orientation=0.0;
varAng=0.0;
varOmg=0.0;
varDst=0.0;
varSpd=0.0;
varIang=0.0;
varIdst=0.0;
aveDst=0.0;
aveDst0=0.0;
}
void resetMotor() {
drvMotorR(0);
drvMotorL(0);
overSpdCount=0;
}
void checkVoltage() {
usbPower=false;
bVolt = ((float) analogRead(BATT)) * battConst;
if (serialMonitor) Serial.println(bVolt);
if (bVolt > 4.4) blinkLED(3);
else if (bVolt > 4.1) blinkLED(2);
else if (bVolt > 3.8) blinkLED(1);
else if (bVolt > 0.5) blinkLED(200);
else usbPower=true;
}
void blinkLED(int n) {
for (int i=0; i<n; i++) {
digitalWrite(LED5,ON);
delay(10);
digitalWrite(LED5,OFF);
delay(200);
}
}
void monitorVoltage() {
digitalWrite(LED5, OFF);
bVolt = ((float) analogRead(BATT)) * battConst;
if (bVolt<3.4) {
digitalWrite(LED5, ON);
if (serialMonitor) {
Serial.print("Batt=");
Serial.println(bVolt);
}
}
aveVolt = aveVolt * 0.99 + bVolt * 0.01;
if (usbPower) battFactor = 1.3;
else battFactor = 5.0 / aveVolt;
}
void drvMotorR(int pwm) {
if (pwm >0) {
digitalWrite(rightRvs, HIGH);
analogWrite(rightFwd, constrain(256-pwm, -255, 255));
}
else if (pwm < 0) {
digitalWrite(rightRvs, LOW);
analogWrite(rightFwd, constrain(-pwm+driverHLoffset, -255, 255));
}
else {
digitalWrite(rightRvs, LOW);
analogWrite(rightFwd, constrain(pwm, -255, 255));
}
}
void drvMotorL(int pwm) {
if (pwm >0) {
digitalWrite(leftRvs, HIGH);
analogWrite(leftFwd, constrain(256-pwm, -255, 255));
}
else if (pwm < 0) {
digitalWrite(leftRvs, LOW);
analogWrite(leftFwd, constrain(-pwm+driverHLoffset, -255, 255));
}
else {
digitalWrite(leftRvs, LOW);
analogWrite(leftFwd, constrain(pwm, -255, 255));
}
}
void selectMode() {
if (digitalRead(SW1) == LOW) { //circle
moveStep=0.003;
spinStep=0.2;
blinkLED(1);
}
}
void sendSerial () {
Serial.print(millis()-time0);
Serial.print(" state=");Serial.print(state);
Serial.print(" accX="); Serial.print(aveAccX);
Serial.print(" Xoffset=");Serial.print(accXoffset);
Serial.print(" accZ="); Serial.print(aveAccZ);
Serial.print(" ang=");Serial.print(varAng);
// Serial.print(" Omg="); Serial.print(varOmg);
// Serial.print(" temp="); Serial.print(temp/340.0+36.53);
Serial.print(" Dst="); Serial.print(varDst);
Serial.print(" aveDst=");Serial.print(aveDst);
Serial.print(" power="); Serial.print(power);
// Serial.print(" ori="); Serial.print(orientation);
Serial.print(" batt="); Serial.print(aveVolt);
Serial.print(" bFactor=");Serial.print(battFactor);
Serial.print(" ");
Serial.print(millis()-time0);
Serial.println();
}

棒テンプ時計精度アップ

//DRV8835 connected to D2,3,4,5,6,9
//MBM1422 mag sensor with 3.3V power
//Touch sens antenna connected to A0
//LED connected to D13
//1H = 64 escapment wheel turn
//1 escapment turn = 15 tic
//tact time 100ms
//folio calc every 4 min
//#define NOMOTOR
#include <ST7032.h>
#include <RTC.h>
#include <Wire.h>
#define DRVPWR 9
#define DRVMODE 2
#define DRVAIN1 3
#define DRVAIN2 4
#define DRVBIN1 5
#define DRVBIN2 6
#define NHISTORY 64
#define BM14 0x0E
ST7032 lcd;
volatile long rtcTic=1;
long rtcLastLoop=1;
int dataX, dataY, dataZ;
int angle, angLast; //1deg=10
int angMax, angMin;
int angThresh;
int angHyst=50; //5deg
int folioDir, folioDirLast;
unsigned long loopTime;
long rtcLastFolioMove;
long tFolio, tFolioCumulativeError;
long cFolio=-3;
int stepNumber=0;
int stepNumberTarget=0;
long rtcEscWheelHistory[NHISTORY];
long nEscapeTurn, thresh;
long tFolioRateError;
long nCumulativeStep=0;
long tFolioErrorMax=0;
long tFolioErrorMin=0;
boolean lcdEnabled=true;
int lcdTimerCount=900; //90 sec
int lcdTimer;
void setup() {
pinMode(DRVPWR, OUTPUT);
pinMode(DRVMODE, OUTPUT);
pinMode(DRVAIN1, OUTPUT);
pinMode(DRVAIN2, OUTPUT);
pinMode(DRVBIN1, OUTPUT);
pinMode(DRVBIN2, OUTPUT);
pinMode(13, OUTPUT);
digitalWrite(13, HIGH);
digitalWrite(DRVPWR, LOW);
digitalWrite(DRVMODE, LOW);
Serial.begin(115200);
setPowerManagementMode(PM_STOP_MODE);
rtc_init();
rtc_attach_constant_period_interrupt_handler(rtcIntHandler);
rtc_set_constant_period_interrupt_time(RTC_CONSTANT_PERIOD_TIME_1SECOND);
rtc_constant_period_interrupt_on();
delay(100);
initMag();
lcd.begin(8,2); //(c,r)
delay(1000);
startup();
Serial.println("Ready");
}
void loop() {
loopTime=millis();
getAngle();
if (angle>angThresh+angHyst) folioDir=1;
if (angle<angThresh-angHyst) folioDir=-1;
if (folioDir==1 && folioDirLast==-1) folioCycle();
folioDirLast=folioDir;
if (rtcTic != rtcLastLoop && cFolio>0) { //executed very 1 sec
rtcLastLoop=rtcTic;
lcdDispStatus();
}
delay(50);
touchSens();
while(millis()-loopTime<100) delay(2);
}
void rtcIntHandler() {
rtcTic++;
}
void startup() {
lcd.setContrast(25);
lcdOn();
lcdDispText(0,0, "STEPPER");
lcdDispText(0,1, "TRAINING");
delay(1000);
for (int i=0; i<20; i++) {
stepNumberTarget+=10;
motorStep();
delay(200);
}
stepNumber=190;
stepNumberTarget=0;
motorStep();
nCumulativeStep=0;
lcdDispText(0,0, "WAIT FOR");
lcdDispText(0,1, "FOLIO MV");
waitFolioMotion();
lcdDispText(0,0, "CALC ANG");
lcdDispText(0,1, "THRESHLD");
getThresh();
lcdDispText(0,0, "OK 000");
lcdDispText(0,1, "0000 000");
}
void folioCycle() {
digitalWrite(13, LOW);
delay(1);
digitalWrite(13, HIGH);
rtcLastFolioMove=rtcTic;
cFolio++;
if (cFolio==0) {
rtcTic=0;
cFolio=0;
stepNumber=stepNumberTarget=0;
tFolioErrorMax=tFolioErrorMin=0;
nCumulativeStep=0;
}
else if (cFolio<=0 || rtcTic<=0) return;
tFolio=cFolio*15/4; //escapement 1tic=3.75sec
tFolioCumulativeError=tFolio-rtcTic;
lcdDispFolioTic(4,1);
lcdDispNum34(4,0, tFolioCumulativeError);
if (tFolioCumulativeError>tFolioErrorMax) tFolioErrorMax=tFolioCumulativeError;
if (tFolioCumulativeError<tFolioErrorMin) tFolioErrorMin=tFolioCumulativeError;
if (cFolio%60==0) { //every 60 turn =~4min
nEscapeTurn=cFolio/15;
rtcEscWheelHistory[nEscapeTurn%NHISTORY]=rtcTic;
if (nEscapeTurn>=4) tFolioRateError=225-(rtcTic-rtcEscWheelHistory[(nEscapeTurn+NHISTORY-4)%NHISTORY]); //gain against 4 turns ago
else tFolioRateError=0;
lcdDispNum3(5,1, tFolioRateError);
if (tFolioRateError*tFolioCumulativeError >=0) stepNumberTarget += (int) tFolioRateError/3 + (int) tFolioCumulativeError/4;
if (stepNumberTarget != stepNumber) {
motorStep();
lcdDispNum4(0,0, nCumulativeStep);
}
}
}
void touchSens() {
int adata1=analogRead(A0); //touch sensor
delay(1);
int adata2=analogRead(A0);
if (abs(adata1-adata2) > 18 || adata1+adata2 < 800) { //touch detect threshold
if (!lcdEnabled) lcdOn();
lcdTimer=lcdTimerCount;
}
else {
if (lcdEnabled) lcdTimer--;
if (lcdTimer<=0) lcdOff();
}
}
void lcdOn() {
lcdTimer=lcdTimerCount;
lcd.display();
lcdEnabled=true;
lcdDispNum4(0,0, nCumulativeStep);
lcdDispNum4(0,1, tFolioErrorMax);
lcdDispNum34(4,0, tFolioCumulativeError);
lcdDispNum3(5,1, tFolioRateError);
}
void lcdOff() {
lcd.noDisplay();
lcdEnabled=false;
}
void lcdDispText(int col, int row, String s) {
if (!lcdEnabled) return;
lcd.setCursor(col,row);
lcd.print(s);
}
void lcdDispStatus() {
if (rtcTic-rtcLastFolioMove > 6) { //disp LCD even if folio not moving
tFolioCumulativeError=tFolio-rtcTic;
lcdDispNum34(4,0, tFolioCumulativeError);
}
if (rtcTic%8==0) {
lcdDispNum4(0,0, nCumulativeStep);
lcdDispNum4(0,1, tFolioErrorMax);
}
else if (rtcTic%8==4) {
if (rtcTic<43200) {
lcdDispNum3(0,0, rtcTic/60);
lcdDispText(3,0, "M");
}
else if (rtcTic<3600000) {
lcdDispNum3(0,0, rtcTic/3600);
lcdDispText(3,0, "H");
}
else {
lcdDispNum3(0,0, rtcTic/86400);
lcdDispText(3,0, "D");
}
lcdDispNum4(0,1, tFolioErrorMin);
}
}
void lcdDispNum4(int col, int row, long n) {
if (!lcdEnabled) return;
char pNum[6];
if (n>999999) sprintf(pNum, "%s", ">1+6");
else if (n>99999) sprintf(pNum, "%02dE4", n/10000);
else if (n>9999) sprintf(pNum, "%02dE3", n/1000);
else if (n>=0) sprintf(pNum, "%04d", n);
else if (n>=-999) sprintf(pNum, "%04d", n);
else if (n>=-9999) sprintf(pNum, "%02d-2", -n/100);
else if (n>=-99999) sprintf(pNum, "%02d-3", -n/1000);
else if (n>=-999999) sprintf(pNum, "%02d-4", -n/10000);
else sprintf(pNum, "%s", "<1-6");
lcd.setCursor(col,row);
lcd.print(pNum);
}
void lcdDispNum3(int col, int row, long n) {
if (!lcdEnabled) return;
char pNum[6];
if (n>999) sprintf(pNum, "%s", ">k+");
else if (n>=-99) sprintf(pNum, "%03d", n);
else if (n>=-999) sprintf(pNum, "%02d-", -n/10);
else sprintf(pNum, "%s", "<k-");
lcd.setCursor(col,row);
lcd.print(pNum);
}
void lcdDispNum34(int col, int row, long n) {
if (!lcdEnabled) return;
char pNum[6];
if (n>999) sprintf(pNum, "%s", " >k+");
else if (n>=-99) sprintf(pNum, " %03d", n);
else if (n>=-999) sprintf(pNum, "%04d", n);
else sprintf(pNum, "%s", " <k-");
lcd.setCursor(col,row);
lcd.print(pNum);
}
void lcdDispFolioTic(int col, int row) {
if (!lcdEnabled) return;
lcd.setCursor(col, row);
char n=cFolio%15+0xb1; //"ア"=0,... "ソ"=14
lcd.print(n);
}
void motorStep() {
digitalWrite(DRVPWR, HIGH);
delay(5);
while (stepNumberTarget-stepNumber != 0) {
if (stepNumberTarget>stepNumber) stepNumber++;
else stepNumber--;
nCumulativeStep++;
#ifdef NOMOTOR
Serial.print("Motor setp=");Serial.println(stepNumber);
#else
motorDrive();
#endif
delay(10); //motor freq=100Hz
}
motorOut(LOW, LOW, LOW, LOW);
digitalWrite(DRVPWR, LOW);
}
void motorDrive() {
int phase=stepNumber%4;
if (phase<0) phase=4+phase;
if (phase==0) motorOut(HIGH, LOW, HIGH, LOW);
if (phase==1) motorOut(LOW, HIGH, HIGH, LOW);
if (phase==2) motorOut(LOW, HIGH, LOW, HIGH);
if (phase==3) motorOut(HIGH, LOW, LOW, HIGH);
}
void motorOut(byte out1, byte out2, byte out3, byte out4) {
digitalWrite(DRVAIN1, out1);
digitalWrite(DRVAIN2, out2);
digitalWrite(DRVBIN1, out3);
digitalWrite(DRVBIN2, out4);
}
void getMag() {
magWrite(0x1D, 0x40); //Start ADC
delay(1);
dataX=magRead(0x10);
dataY=magRead(0x12);
dataY+=160;
dataZ=magRead(0x14);
dataZ+=50;
}
void initMag() {
// AVE_A defaul=0 -> 4times averate
magWrite(0x1B, 0x82); //CNTL1
delay(2);
magWrite(0x5C, 0); //CNTL4 LSB
magWrite(0x5D, 0); //CNTL4 MSB
magWrite(0x1C, 0x08); //CNTL2 DRDY enable with low active
getMag();
}
void waitFolioMotion() {
angMax=-3600;
angMin=3600;
do {
getAngle();
if (angle > angMax) angMax=angle;
if (angle < angMin) angMin=angle;
delay(100);
} while (angMax-angMin<300);
}
void getThresh() {
unsigned long msec=millis();
angMax=-3600;
angMin=3600;
do {
getAngle();
if (angle > angMax) angMax=angle;
if (angle < angMin) angMin=angle;
delay(100);
} while (millis()-msec<15000); //15second
angThresh=(angMax+angMin)/2;
}
void getAngle() {
getMag();
angle= (int) (atan2((double)dataZ, (double)dataY)*572.9579); //1800.0/3.141592=572.9579
int diff=angle - angLast;
if (diff > 1800) angle-=3600;
if (diff < -1800) angle+=3600;
angLast=angle;
/*
Serial.print(dataZ);
Serial.print(" ");
Serial.print(dataY);
Serial.print(" ");
Serial.print(angle);
*/
}
void magWrite (unsigned char adr, unsigned char data) {
Wire.beginTransmission(BM14);
Wire.write(adr);
Wire.write(data);
Wire.endTransmission(true);
}
int magRead(unsigned char adr) {
Wire.beginTransmission(BM14);
Wire.write(adr);
Wire.endTransmission(false);
Wire.requestFrom(BM14, 2, (int)true);
return Wire.read()|Wire.read()<<8;
}