Initial update nach Github crash

This commit is contained in:
Norbert Walter 2021-12-16 09:37:54 +01:00
parent d3e1e9b3e8
commit c14ef2d886
31 changed files with 31623 additions and 0 deletions

7
.vscode/extensions.json vendored Normal file
View File

@ -0,0 +1,7 @@
{
// See http://go.microsoft.com/fwlink/?LinkId=827846
// for the documentation about the extensions.json format
"recommendations": [
"platformio.platformio-ide"
]
}

Binary file not shown.

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,324 @@
//we only compile for some boards
#ifdef BOARD_NODEMCU32S_OBP60
#include "GwOBP60Task.h"
#include "GwApi.h"
#include "OBP60Hardware.h" // PIN definitions
#include <Ticker.h> // Timer Lib for timer interrupts
#include <Wire.h> // I2C connections
#include <MCP23017.h> // MCP23017 extension Port
#include <NMEA0183.h>
#include <NMEA0183Msg.h>
#include <NMEA0183Messages.h>
#include <GxEPD.h> // GxEPD lib for E-Ink displays
#include <GxGDEW042T2/GxGDEW042T2.h> // 4.2" Waveshare S/W 300 x 400 pixel
#include <GxIO/GxIO_SPI/GxIO_SPI.h> // GxEPD lip for SPI display communikation
#include <GxIO/GxIO.h> // GxEPD lip for SPI
#include "OBP60ExtensionPort.h" // Functions lib for extension board
#include "OBP60Keypad.h" // Functions lib for keypad
// True type character sets
#include "Ubuntu_Bold6pt7b.h"
#include "Ubuntu_Bold8pt7b.h"
#include "Ubuntu_Bold10pt7b.h"
#include "Ubuntu_Bold32pt7b.h"
#include "Seven_Segment32pt7b.h"
#include "DSEG7Classic-BoldItalic60pt7b.h"
#include <Fonts/FreeMonoBold9pt7b.h>
#include <Fonts/FreeMonoBold12pt7b.h>
#include <Fonts/FreeMonoBold24pt7b.h>
// Pictures
//#include GxEPD_BitmapExamples // Example picture
#include "MFD_OBP60_400x300_sw.h" // MFD with logo
#include "Logo_OBP_400x300_sw.h" // OBP Logo
#include "OBP60QRWiFi.h" // Functions lib for WiFi QR code
#include "Page_0.h" // Page 0
#include "Page_1.h" // Page 1
#include "Page_2.h" // Page 2
#include "OBP60Pages.h" // Functions lib for show pages
tNMEA0183Msg NMEA0183Msg;
tNMEA0183 NMEA0183;
// Timer Interrupts for hardware functions
Ticker Timer1; // Under voltage detection
Ticker Timer2; // Keypad
Ticker Timer3; // Binking flash LED
// Global vars
bool initComplete = false; // Initialization complete
int taskRunCounter = 0; // Task couter for loop section
bool gps_ready = false; // GPS initialized and ready to use
#define INVALID_COORD -99999
class GetBoatDataRequest: public GwMessage{
private:
GwApi *api;
public:
double latitude;
double longitude;
GetBoatDataRequest(GwApi *api):GwMessage(F("boat data")){
this->api=api;
}
virtual ~GetBoatDataRequest(){}
protected:
/**
* this methos will be executed within the main thread
* be sure not to make any time consuming or blocking operation
*/
virtual void processImpl(){
//api->getLogger()->logDebug(GwLog::DEBUG,"boatData request from example task");
/*access the values from boatData (see GwBoatData.h)
by using getDataWithDefault it will return the given default value
if there is no valid data available
so be sure to use a value that never will be a valid one
alternatively you can check using the isValid() method at each boatData item
*/
latitude=api->getBoatData()->Latitude->getDataWithDefault(INVALID_COORD);
longitude=api->getBoatData()->Longitude->getDataWithDefault(INVALID_COORD);
};
};
// Hardware initialisation before start all services
//##################################################
void OBP60Init(GwApi *api){
GwLog *logger=api->getLogger();
// Define timer interrupts
// Timer1.attach_ms(1, underVoltageDetection); // Maximum speed with 1ms
Timer2.attach_ms(40, readKeypad); // Timer value nust grater than 30ms
Timer3.attach_ms(500, blinkingFlashLED);
// Extension port MCP23017
// Check I2C devices MCP23017
Wire.begin(OBP_I2C_SDA, OBP_I2C_SCL);
Wire.beginTransmission(MCP23017_I2C_ADDR);
if (Wire.endTransmission() != 0) {
LOG_DEBUG(GwLog::ERROR,"MCP23017 not found, check wiring");
initComplete = false;
}
else{
// Start communication
mcp.init();
mcp.portMode(MCP23017Port::A, 0b00110000); //Port A, 0 = out, 1 = in
mcp.portMode(MCP23017Port::B, 0b11110000); //Port B, 0 = out, 1 = in
// Extension Port A set defaults
setPortPin(OBP_DIGITAL_OUT1, false); // PA0
setPortPin(OBP_DIGITAL_OUT2, false); // PA1
setPortPin(OBP_FLASH_LED, false); // PA2
setPortPin(OBP_BACKLIGHT_LED, false); // PA3
setPortPin(OBP_POWER_50, true); // PA6
setPortPin(OBP_POWER_33, true); // PA7
// Extension Port B set defaults
setPortPin(PB0, false); // PB0
setPortPin(PB1, false); // PB1
setPortPin(PB2, false); // PB2
setPortPin(PB3, false); // PB3
// Settings for 1Wire
bool enable1Wire = api->getConfig()->getConfigItem(api->getConfig()->use1Wire,true)->asBoolean();
if(enable1Wire == true){
LOG_DEBUG(GwLog::DEBUG,"1Wire Mode is On");
}
else{
LOG_DEBUG(GwLog::DEBUG,"1Wire Mode is Off");
}
// Settings for backlight
String backlightMode = api->getConfig()->getConfigItem(api->getConfig()->backlight,true)->asString();
LOG_DEBUG(GwLog::DEBUG,"Backlight Mode is: %s", backlightMode);
if(String(backlightMode) == "On"){
setPortPin(OBP_BACKLIGHT_LED, true);
}
if(String(backlightMode) == "Off"){
setPortPin(OBP_BACKLIGHT_LED, false);
}
if(String(backlightMode) == "Control by Key"){
setPortPin(OBP_BACKLIGHT_LED, false);
}
// Settings flash LED mode
String ledMode = api->getConfig()->getConfigItem(api->getConfig()->flashLED,true)->asString();
LOG_DEBUG(GwLog::DEBUG,"Backlight Mode is: %s", ledMode);
if(String(ledMode) == "Off"){
blinkingLED = false;
}
if(String(ledMode) == "Limits Overrun"){
blinkingLED = true;
}
// Start serial stream and take over GPS data stream form internal GPS
bool gpsOn=api->getConfig()->getConfigItem(api->getConfig()->useGPS,true)->asBoolean();
if(gpsOn == true){
Serial2.begin(9600, SERIAL_8N1, OBP_GPS_TX, -1); // GPS RX unused in hardware (-1)
if (!Serial2) {
LOG_DEBUG(GwLog::ERROR,"GPS modul NEO-6M not found, check wiring");
gps_ready = false;
}
else{
LOG_DEBUG(GwLog::DEBUG,"GPS modul NEO-M6 found");
NMEA0183.SetMessageStream(&Serial2);
NMEA0183.Open();
gps_ready = true;
}
}
// Marker for init complete
// Used in OBP60Task()
initComplete = true;
// Buzzer tone for initialization finish
buzPower = uint(api->getConfig()->getConfigItem(api->getConfig()->buzzerPower,true)->asInt());
buzzer(TONE4, buzPower, 500);
}
}
// OBP60 Task
//#######################################
void OBP60Task(void *param){
GwApi *api=(GwApi*)param;
GwLog *logger=api->getLogger();
bool hasPosition = false;
// Get some configuration data from webside
bool exampleSwitch=api->getConfig()->getConfigItem(api->getConfig()->obp60Config,true)->asBoolean();
LOG_DEBUG(GwLog::DEBUG,"example switch ist %s",exampleSwitch?"true":"false");
bool gpsOn=api->getConfig()->getConfigItem(api->getConfig()->useGPS,true)->asBoolean();
bool bme280On=api->getConfig()->getConfigItem(api->getConfig()->useBME280,true)->asBoolean();
bool onewireOn=api->getConfig()->getConfigItem(api->getConfig()->use1Wire,true)->asBoolean();
String powerMode=api->getConfig()->getConfigItem(api->getConfig()->powerMode,true)->asString();
String displayMode=api->getConfig()->getConfigItem(api->getConfig()->display,true)->asString();
String backlightMode=api->getConfig()->getConfigItem(api->getConfig()->backlight,true)->asString();
// Initializing all necessary boat data
double lastWaterDepth=0;
bool lastWaterDepthValid=false;
GwApi::BoatValue *longitude=new GwApi::BoatValue(F("Longitude"));
GwApi::BoatValue *latitude=new GwApi::BoatValue(F("Latitude"));
GwApi::BoatValue *waterdepth=new GwApi::BoatValue(F("WaterDepth"));
GwApi::BoatValue *valueList[]={longitude, latitude, waterdepth};
//Init E-Ink display
display.init(); // Initialize and clear display
display.setTextColor(GxEPD_BLACK); // Set display color
display.setRotation(0); // Set display orientation (horizontal)
display.fillRect(0, 0, GxEPD_WIDTH, GxEPD_HEIGHT, GxEPD_WHITE); // Draw white sreen
display.update(); // Full update (slow)
if(displayMode == "Logo + QR Code" || displayMode == "Logo"){
display.drawExampleBitmap(gImage_Logo_OBP_400x300_sw, 0, 0, GxEPD_WIDTH, GxEPD_HEIGHT, GxEPD_WHITE); // Draw start logo
// display.drawExampleBitmap(gImage_MFD_OBP60_400x300_sw, 0, 0, GxEPD_WIDTH, GxEPD_HEIGHT, GxEPD_WHITE); // Draw start logo
display.updateWindow(0, 0, GxEPD_WIDTH, GxEPD_HEIGHT, true); // Partial update (fast)
delay(SHOW_TIME); // Logo show time
display.fillRect(0, 0, GxEPD_WIDTH, GxEPD_HEIGHT, GxEPD_WHITE); // Draw white sreen
display.update(); // Full update (slow)
if(displayMode == "Logo + QR Code"){
qrWiFi(); // Show QR code for WiFi connection
delay(SHOW_TIME); // Logo show time
}
}
// Task Loop
//###############################
while(true){
// Task cycle time
delay(10); // 10ms
// Backlight On/Off Subtask 100ms
if((taskRunCounter % 10) == 0){
// If key controled
if(backlightMode == "Control by Key"){
if(keystatus == "6s"){
LOG_DEBUG(GwLog::DEBUG,"Toggle Backlight LED");
togglePortPin(OBP_BACKLIGHT_LED);
keystatus = "0";
}
}
if(keystatus == "5s"){
pageNumber ++;
if(pageNumber > MAX_PAGE_NUMBER - 1){
pageNumber = 0;
}
first_view = true;
keystatus = "0";
}
if(keystatus == "1s"){
pageNumber --;
if(pageNumber < 0){
pageNumber = MAX_PAGE_NUMBER - 1;
}
first_view = true;
keystatus = "0";
}
}
// Subtask all 1000ms
if((taskRunCounter % 100) == 0 || first_view == true){
// LOG_DEBUG(GwLog::DEBUG,"Subtask 1");
LOG_DEBUG(GwLog::DEBUG,"Keystatus: %s", keystatus);
LOG_DEBUG(GwLog::DEBUG,"Pagenumber: %d", pageNumber);
if(displayMode == "Logo + QR Code" || displayMode == "Logo" || displayMode == "White Screen"){
showPage();
}
}
// Subtask all 3000ms
if((taskRunCounter % 300) == 0){
// LOG_DEBUG(GwLog::DEBUG,"Subtask 2");
//Clear swipe code
if(keystatus == "left" || keystatus == "right"){
keystatus = "0";
}
}
// Subtask E-Ink full refresh
if((taskRunCounter % (FULL_REFRESH_TIME * 100)) == 0){
LOG_DEBUG(GwLog::DEBUG,"E-Ink full refresh");
display.update();
}
// Send NMEA0183 GPS data on several bus systems
if(gpsOn == true){ // If config enabled
if(gps_ready = true){
tNMEA0183Msg NMEA0183Msg;
while(NMEA0183.GetMessage(NMEA0183Msg)){
api->sendNMEA0183Message(NMEA0183Msg);
}
}
}
//fetch the current values of the items that we have in itemNames
api->getBoatDataValues(3,valueList);
//check if the values are valid (i.e. the values we requested have been found in boatData)
if (waterdepth->valid){
//both values are there - so we have a valid position
if (! lastWaterDepthValid){
//access to the values via iterator->second (iterator->first would be the name)
LOG_DEBUG(GwLog::LOG,"%s new value %f",waterdepth->getName().c_str(),waterdepth->value);
lastWaterDepthValid=true;
lastWaterDepth=waterdepth->value;
}
}
else{
if (lastWaterDepthValid){
if (exampleSwitch) LOG_DEBUG(GwLog::LOG,"Water depth lost");
lastWaterDepthValid=false;
}
}
taskRunCounter++;
}
vTaskDelete(NULL);
}
#endif

View File

@ -0,0 +1,23 @@
#ifndef _GWOBP60TASK_H
#define _GWOBP60TASK_H
#include "GwApi.h"
//we only compile for some boards
#ifdef BOARD_NODEMCU32S_OBP60
//CAN NMEA2000
#define ESP32_CAN_TX_PIN GPIO_NUM_13
#define ESP32_CAN_RX_PIN GPIO_NUM_12
//RS485 NMEA0183
#define GWSERIAL_TX 26
#define GWSERIAL_RX 14
#define GWSERIAL_MODE "UNI"
// Init OBP60 Task
void OBP60Init(GwApi *param);
DECLARE_INITFUNCTION(OBP60Init);
// OBP60 Task
void OBP60Task(void *param);
DECLARE_USERTASK_PARAM(OBP60Task, 25000) // Need 25k RAM as stack size
DECLARE_CAPABILITY(obp60,true);
#endif
#endif

View File

@ -0,0 +1,939 @@
const unsigned char gImage_Logo_OBP_400x300_sw[15000] = { /* 0X00,0X01,0X90,0X01,0X2C,0X01, */
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X40,
0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X01,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X01,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X03,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0X80,0X00,0X03,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0X80,0X00,0X03,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0X80,
0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X3F,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X3F,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X7F,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XFF,0XFF,0X00,0X03,0XFF,0XFF,0XF8,0X00,0X00,0X0F,0XFF,0XFF,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X3F,0XFF,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XFF,0XE0,0X00,0X00,0X1F,0XFF,0XF8,0X00,0X00,0X00,0X07,0XFF,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0X80,0X00,0X00,0X07,0XFF,0XF8,0X00,0X00,0X00,
0X03,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X0F,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0X00,0X00,0X00,0X03,0XFF,0XF8,0X00,
0X00,0X00,0X01,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X1F,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFE,0X00,0X00,0X00,0X00,0XFF,
0XF8,0X00,0X00,0X00,0X00,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFC,0X00,0X00,0X00,
0X00,0X7F,0XF8,0X00,0X00,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XF8,0X00,
0X00,0X00,0X00,0X7F,0XF8,0X00,0X00,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XF0,0X00,0X00,0X00,0X00,0X3F,0XF8,0X00,0X00,0X00,0X00,0X3F,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XE0,0X00,0X00,0X00,0X00,0X1F,0XF8,0X00,0X1E,0X00,0X00,0X3F,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XE0,0X00,0X0F,0XC0,0X00,0X1F,0XF8,0X00,0X1F,0XE0,0X00,0X3F,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X3F,0XF0,0X00,0X0F,0XF8,0X00,0X1F,0XF0,
0X00,0X3F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X01,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X7F,0XF8,0X00,0X0F,0XF8,0X00,
0X1F,0XF8,0X00,0X3F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X03,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0XFF,0XFC,0X00,0X07,
0XF8,0X00,0X1F,0XF8,0X00,0X3F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0X80,0X01,0XFF,0XFE,
0X00,0X07,0XF8,0X00,0X1F,0XF8,0X00,0X3F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0X80,0X01,
0XFF,0XFE,0X00,0X07,0XF8,0X00,0X1F,0XF8,0X00,0X3F,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0X80,0X01,0XFF,0XFF,0X00,0X07,0XF8,0X00,0X1F,0XF8,0X00,0X3F,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0X80,0X03,0XFF,0XFF,0X00,0X03,0XF8,0X00,0X1F,0XF0,0X00,0X3F,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0X80,0X03,0XFF,0XFF,0X00,0X03,0XF8,0X00,0X1F,0XE0,0X00,0X3F,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0X00,0X03,0XFF,0XFF,0X00,0X03,0XF8,0X00,0X00,0X00,
0X00,0X3F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X7F,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0X00,0X03,0XFF,0XFF,0X00,0X03,0XF8,0X00,
0X00,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0X00,0X03,0XFF,0XFF,0X00,0X03,
0XF8,0X00,0X00,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0X00,0X03,0XFF,0XFF,
0X00,0X03,0XF8,0X00,0X00,0X00,0X00,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X01,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0X00,0X03,
0XFF,0XFF,0X00,0X03,0XF8,0X00,0X00,0X00,0X01,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0X00,0X03,0XFF,0XFF,0X00,0X03,0XF8,0X00,0X00,0X00,0X03,0XFF,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0X00,0X03,0XFF,0XFF,0X00,0X03,0XF8,0X00,0X00,0X00,0X07,0XFF,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0X00,0X03,0XFF,0XFF,0X00,0X03,0XF8,0X00,0X00,0X00,0X0F,0XFF,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0X80,0X03,0XFF,0XFF,0X00,0X03,0XF8,0X00,0X00,0X00,
0X7F,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,
0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0X80,0X03,0XFF,0XFF,0X00,0X07,0XF8,0X00,
0X1F,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X1F,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0X80,0X01,0XFF,0XFE,0X00,0X07,
0XF8,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X3F,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0X80,0X01,0XFF,0XFE,
0X00,0X07,0XF8,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0X80,0X00,
0XFF,0XFC,0X00,0X07,0XF8,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XC0,0X00,0XFF,0XFC,0X00,0X0F,0XF8,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XC0,0X00,0X3F,0XF8,0X00,0X0F,0XF8,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XFF,0XFF,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XE0,0X00,0X1F,0XE0,0X00,0X1F,0XF8,0X00,0X1F,0XFF,0XFF,0XFF,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0XE0,0X00,0X00,0X00,0X00,0X1F,0XF8,0X00,0X1F,0XFF,
0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,
0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X3F,0XF8,0X00,
0X1F,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X07,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X3F,
0XF8,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X0F,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XF8,0X00,0X00,0X00,
0X00,0X7F,0XF8,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X0F,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFC,0X00,
0X00,0X00,0X00,0XFF,0XF8,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XFE,0X00,0X00,0X00,0X01,0XFF,0XF8,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XFF,0X80,0X00,0X00,0X03,0XFF,0XF8,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,0XFF,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XFF,0XC0,0X00,0X00,0X0F,0XFF,0XF8,0X00,0X1F,0XFF,0XFF,0XFF,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0XFF,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X3F,0XFF,0XF8,0X00,0X1F,0XFF,
0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,
0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFE,0X00,0X01,0XFF,0XFF,0XF8,0X00,
0X3F,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,
0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X01,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,0XFF,
0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,
0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X7F,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X03,0XFE,0X00,0X1F,0XFF,0XF8,
0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X03,0XFE,0X00,0X0F,
0XFF,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X03,0XFE,
0X00,0X07,0XFF,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X1F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,
0X03,0XFE,0X00,0X03,0XFF,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,
0X00,0X00,0X03,0XFE,0X00,0X03,0XFF,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X3F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XC0,0X00,0X00,0X00,0X03,0XFE,0X00,0X01,0XFF,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XC0,0X00,0X00,0X00,0X03,0XFE,0X00,0X00,0XFF,0XF0,0X00,0X7F,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X03,0XFE,0X00,0X00,0XFF,0XF0,0X00,0X7F,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X03,0XFE,0X00,0X00,0X7F,0XF0,
0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X03,0XFE,0X00,0X00,
0X3F,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X01,0XFF,0XFF,0XFF,0XFE,
0X00,0X00,0X3F,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X01,0XFF,0XFF,
0XFF,0XFE,0X00,0X00,0X1F,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X01,
0XFF,0XFF,0XFF,0XFE,0X00,0X00,0X0F,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XC0,0X01,0XFF,0XFF,0XFF,0XFE,0X00,0X00,0X0F,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XC0,0X01,0XFF,0XFF,0XFF,0XFE,0X00,0X00,0X07,0XF0,0X00,0X7F,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XC0,0X01,0XFF,0XFF,0XFF,0XFE,0X00,0X00,0X03,0XF0,0X00,0X7F,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X01,0XFF,0XFF,0XFF,0XFE,0X00,0X00,0X03,0XF0,
0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X07,0XFE,0X00,0X00,
0X01,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X07,0XFE,
0X00,0X00,0X00,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,
0X07,0XFE,0X00,0X00,0X00,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,
0X00,0X00,0X07,0XFE,0X00,0X00,0X00,0X70,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X01,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XC0,0X00,0X00,0X00,0X07,0XFE,0X00,0X00,0X00,0X30,0X00,0X7F,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XC0,0X00,0X00,0X00,0X07,0XFE,0X00,0X08,0X00,0X30,0X00,0X7F,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X07,0XFE,0X00,0X0C,0X00,0X10,0X00,0X7F,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X07,0XFE,0X00,0X0C,0X00,0X00,
0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X07,0XFE,0X00,0X0E,
0X00,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X01,0XFF,0XFF,0XFF,0XFE,
0X00,0X0F,0X00,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X01,0XFF,0XFF,
0XFF,0XFE,0X00,0X0F,0X00,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X3F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X01,
0XFF,0XFF,0XFF,0XFE,0X00,0X0F,0X80,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X7F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XC0,0X01,0XFF,0XFF,0XFF,0XFE,0X00,0X0F,0XC0,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X7F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XC0,0X01,0XFF,0XFF,0XFF,0XFE,0X00,0X0F,0XC0,0X00,0X00,0X7F,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XC0,0X01,0XFF,0XFF,0XFF,0XFE,0X00,0X0F,0XE0,0X00,0X00,0X7F,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X01,0XFF,0XFF,0XFF,0XFE,0X00,0X0F,0XF0,0X00,
0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X01,0XFF,0XFF,0XFF,0XFE,0X00,0X0F,
0XF8,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0XFF,0XFF,0XFF,0XFE,
0X00,0X0F,0XF8,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,
0X01,0XFE,0X00,0X0F,0XFC,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X0F,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,
0X00,0X00,0X01,0XFE,0X00,0X0F,0XFE,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X0F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XC0,0X00,0X00,0X00,0X01,0XFE,0X00,0X0F,0XFE,0X00,0X00,0X7F,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XC0,0X00,0X00,0X00,0X01,0XFE,0X00,0X0F,0XFF,0X00,0X00,0X7F,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X01,0XFE,0X00,0X0F,0XFF,0X80,0X00,0X7F,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X01,0XFE,0X00,0X0F,0XFF,0X80,
0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X01,0XFE,0X00,0X0F,
0XFF,0XC0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X01,0XFE,
0X00,0X0F,0XFF,0XE0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,
0X01,0XFE,0X00,0X0F,0XFF,0XE0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XC0,0X00,
0X00,0X00,0X01,0XFE,0X00,0X1F,0XFF,0XF0,0X00,0X7F,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X7F,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,0X00,0X03,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X01,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0X80,
0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0X80,0X00,0X01,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XC0,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,
0XFF,0XFE,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X40,0X00,0X0F,0XFF,0XE0,0X00,0X00,
0X00,0X00,0X00,0X7E,0X00,0X00,0X00,0X00,0X00,0X00,0X02,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X03,0XFF,0XFF,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XC0,0X00,0X0F,0XFF,0XF8,
0X00,0X00,0X00,0X00,0X00,0X7E,0X00,0X00,0X00,0X00,0X00,0X00,0X0E,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X00,0X00,0X07,0XC0,0X00,0X0F,
0XFF,0XFC,0X00,0X00,0X00,0X00,0X00,0X7E,0X00,0X00,0X00,0X00,0X00,0X00,0X3E,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XC0,0X00,0X00,0X00,0X00,0X00,0X0F,0XC0,
0X00,0X0F,0XFF,0XFE,0X00,0X00,0X00,0X00,0X00,0X7E,0X00,0X00,0X00,0X00,0X00,0X00,
0X7E,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XE0,0X00,0X00,0X00,0X00,0X00,
0X0F,0XC0,0X00,0X0F,0XFF,0XFE,0X00,0X00,0X00,0X00,0X00,0X7E,0X00,0X00,0X00,0X00,
0X00,0X00,0XFE,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XF8,0X1F,0XE0,0X00,0X00,0X00,
0X00,0X00,0X0F,0XC0,0X00,0X0F,0XE0,0XFF,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0XFE,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XF8,0X0F,0XE0,0X03,
0XE0,0X00,0X3F,0XE0,0X1F,0XC0,0X00,0X0F,0XE0,0X7F,0X00,0X0E,0X00,0X7E,0X00,0X00,
0X00,0X3F,0X00,0X01,0XFC,0X00,0XFE,0X00,0X3F,0XC0,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XF8,0X0F,
0XC0,0X1F,0XFC,0X00,0XFF,0XF8,0X7F,0XFC,0X00,0X0F,0XE0,0X7F,0X1F,0X9F,0X83,0XFF,
0X80,0X7E,0X01,0XFF,0XE0,0X07,0XFF,0X03,0XFF,0XE0,0XFF,0XF0,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,
0XF8,0X1F,0XC0,0X3F,0XFE,0X03,0XFF,0XFC,0X7F,0XFC,0X00,0X0F,0XE0,0X7F,0X1F,0XFF,
0X07,0XFF,0XE0,0X7E,0X03,0XFF,0XF0,0X1F,0XFF,0XC3,0XFF,0XE1,0XFF,0XF8,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X03,0XFF,0XFF,0X80,0X7F,0XFF,0X83,0XFF,0XFE,0X7F,0XFC,0X00,0X0F,0XE0,0XFF,
0X1F,0XFF,0X0F,0XFF,0XF0,0X7E,0X07,0XFF,0XF8,0X3F,0XFF,0XE3,0XFF,0XE3,0XFF,0XFC,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X03,0XFF,0XFF,0X00,0XFF,0XFF,0X87,0XF8,0XFE,0X7F,0XFC,0X00,0X0F,
0XFF,0XFE,0X1F,0XFE,0X1F,0XFF,0XF0,0X7E,0X0F,0XE3,0XF8,0X3F,0XFF,0XE3,0XFF,0XE3,
0XE1,0XFC,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0X01,0XFE,0X3F,0XC7,0XF0,0X7E,0X1F,0XC0,
0X00,0X0F,0XFF,0XFE,0X1F,0XF2,0X1F,0XC3,0XF8,0X7E,0X0F,0XC1,0XFC,0X7F,0X87,0XF0,
0XFE,0X07,0XE0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XC1,0XFC,0X1F,0XC0,0X00,0XFE,
0X0F,0XC0,0X00,0X0F,0XFF,0XFC,0X1F,0XE0,0X3F,0X83,0XF8,0X7E,0X1F,0XC0,0XFC,0X7F,
0X03,0X80,0XFE,0X03,0XFC,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XE1,0XFC,0X0F,0XC0,
0X07,0XFE,0X0F,0XC0,0X00,0X0F,0XFF,0XF8,0X1F,0XC0,0X3F,0X81,0XF8,0X7E,0X1F,0XC0,
0XFC,0X7E,0X00,0X00,0XFE,0X03,0XFF,0XE0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XF8,0X0F,0XE1,0XF8,
0X0F,0XC0,0XFF,0XFE,0X0F,0XC0,0X00,0X0F,0XFF,0XE0,0X1F,0XC0,0X3F,0X81,0XF8,0X7E,
0X1F,0XFF,0XFE,0X7E,0X00,0X00,0XFE,0X01,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XF8,0X0F,
0XF1,0XF8,0X0F,0XC3,0XFF,0XFE,0X0F,0XC0,0X00,0X0F,0XE0,0X00,0X1F,0XC0,0X3F,0X01,
0XFC,0X7E,0X1F,0XFF,0XFE,0X7E,0X00,0X00,0XFE,0X00,0XFF,0XFC,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,
0XF8,0X0F,0XF1,0XF8,0X0F,0XC7,0XFC,0X7E,0X0F,0XC0,0X00,0X0F,0XE0,0X00,0X1F,0XC0,
0X3F,0X81,0XF8,0X7E,0X1F,0XFF,0XFE,0X7E,0X00,0X00,0XFE,0X00,0X3F,0XFC,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X03,0XF8,0X0F,0XF1,0XFC,0X1F,0XC7,0XF0,0X7E,0X0F,0XC0,0X00,0X0F,0XE0,0X00,
0X1F,0XC0,0X3F,0X81,0XF8,0X7E,0X1F,0XC0,0X00,0X7F,0X03,0XC0,0XFE,0X00,0X01,0XFE,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X03,0XFC,0X3F,0XF1,0XFC,0X1F,0XC7,0XE0,0X7E,0X0F,0XC0,0X00,0X0F,
0XE0,0X00,0X1F,0XC0,0X1F,0X83,0XF8,0X7E,0X1F,0XC0,0X00,0X7F,0X07,0XF0,0XFE,0X00,
0X60,0X7E,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XE0,0XFF,0X3F,0X87,0XE0,0XFE,0X0F,0XFC,
0X00,0X0F,0XE0,0X00,0X1F,0XC0,0X1F,0XE7,0XF0,0X7E,0X0F,0XE1,0XFC,0X7F,0XCF,0XF0,
0X7F,0XC7,0XF0,0X7E,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XE0,0XFF,0XFF,0X87,0XFF,0XFE,
0X0F,0XFC,0X00,0X0F,0XE0,0X00,0X1F,0XC0,0X0F,0XFF,0XF0,0X7E,0X0F,0XFF,0XF8,0X3F,
0XFF,0XE0,0X7F,0XC7,0XFF,0XFC,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XC0,0X7F,0XFF,0X07,
0XFF,0XFE,0X0F,0XFC,0X00,0X0F,0XE0,0X00,0X1F,0XC0,0X07,0XFF,0XE0,0X7E,0X07,0XFF,
0XF0,0X1F,0XFF,0XC0,0X7F,0XE3,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0X80,0X1F,
0XFE,0X03,0XFF,0X3F,0X07,0XFC,0X00,0X0F,0XE0,0X00,0X1F,0XC0,0X03,0XFF,0XC0,0X7E,
0X03,0XFF,0XE0,0X0F,0XFF,0X80,0X3F,0XE1,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XF8,
0X00,0X07,0XF8,0X00,0XFC,0X3F,0X03,0XFC,0X00,0X0F,0XE0,0X00,0X1F,0XC0,0X00,0XFF,
0X00,0X7E,0X00,0XFF,0X80,0X03,0XFE,0X00,0X1F,0XE0,0X7F,0XC0,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0XFE,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X03,0XFE,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFE,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFE,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFC,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFC,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XE0,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,};

View File

@ -0,0 +1,939 @@
const unsigned char gImage_MFD_OBP60_400x300_sw[15000] = { /* 0X00,0X01,0X90,0X01,0X2C,0X01, */
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XE0,0X3F,
0XC0,0X00,0X00,0X7E,0X00,0X40,0XFC,0X07,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X08,0X1F,0X80,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XE0,0X0F,0XC0,0X00,0X00,0X00,
0X00,0X1F,0X80,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,
0XF0,0X3F,0XC0,0X00,0X00,0X7E,0X01,0XC0,0XFC,0X1F,0XF0,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X38,0X1F,0X80,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XF8,0X0F,0XC0,0X00,
0X00,0X00,0X00,0X1F,0X80,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X1F,0XF0,0X7F,0XC0,0X00,0X00,0X7E,0X07,0XC0,0XFC,0X1F,0XF0,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0XF8,0X1F,0X80,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XFC,0X0F,
0XC0,0X00,0X00,0X00,0X00,0X1F,0X80,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X1F,0XF0,0X7F,0XC0,0X00,0X00,0X7E,0X0F,0XC0,0XFC,0X3F,0XE0,0X00,
0X00,0X00,0X00,0X00,0X00,0X01,0XF8,0X1F,0X80,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,
0XFE,0X0F,0XC0,0X00,0X00,0X00,0X00,0X1F,0X80,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X1F,0XF0,0X7F,0XC0,0X00,0X00,0X7E,0X0F,0XC0,0X00,0X3F,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X07,0XFF,0XFE,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0X80,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XF8,0X7F,0XC0,0X00,0X00,0X7E,0X0F,0XC0,
0X00,0X3F,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XF8,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X07,0XF0,0XFF,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0X80,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XF8,0XFF,0XC3,0XE0,0XF8,0X7E,
0X3F,0XF8,0XFC,0XFF,0XE7,0XC1,0XF0,0XF8,0XF8,0X01,0XFC,0X07,0XFF,0X1F,0X80,0X7F,
0X00,0XF8,0XF8,0X00,0X07,0XF0,0X7F,0X0F,0XC0,0X7F,0X80,0XF9,0XF0,0X1F,0X80,0XFF,
0X83,0XF0,0X3F,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0X78,0XF7,0XC3,0XE0,
0XF8,0X7E,0X3F,0XF8,0XFC,0XFF,0XE7,0XC1,0XF0,0XFB,0XFC,0X07,0XFF,0X07,0XFF,0X1F,
0X81,0XFF,0XC0,0XFB,0XFC,0X00,0X07,0XF0,0X3F,0X0F,0XC1,0XFF,0XE0,0XFB,0XFC,0X1F,
0X83,0XFF,0XE1,0XF8,0X3E,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0X78,0XF7,
0XC3,0XE0,0XF8,0X7E,0X3F,0XF8,0XFC,0XFF,0XE7,0XC1,0XF0,0XFF,0XFE,0X0F,0XFF,0XC7,
0XFF,0X1F,0X83,0XFF,0XE0,0XFF,0XFE,0X00,0X07,0XF0,0X3F,0X0F,0XC3,0XFF,0XF0,0XFF,
0XFE,0X1F,0X87,0XFF,0XF1,0XF8,0X3E,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,
0X7C,0XF7,0XC3,0XE0,0XF8,0X7E,0X3F,0XF8,0XFC,0XFF,0XE7,0XC1,0XF0,0XFF,0XFE,0X1F,
0XFF,0XC7,0XFF,0X1F,0X87,0XFF,0XF0,0XFF,0XFE,0X00,0X07,0XF0,0X3F,0X8F,0XC3,0XE3,
0XF0,0XFF,0XFE,0X1F,0X87,0XFF,0XF0,0XF8,0X7E,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X1F,0X3D,0XE7,0XC3,0XE0,0XF8,0X7E,0X0F,0XC0,0XFC,0X3F,0X07,0XC1,0XF0,0XFF,
0XFE,0X1F,0X87,0XE1,0XF8,0X1F,0X87,0XE3,0XF0,0XFF,0XFE,0X00,0X07,0XF0,0X3F,0X8F,
0XC3,0XE1,0X80,0XFC,0X7F,0X1F,0X87,0XC1,0XF0,0XFC,0X7C,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X1F,0X3D,0XE7,0XC3,0XE0,0XF8,0X7E,0X0F,0XC0,0XFC,0X3F,0X07,0XC1,
0XF0,0XFC,0X7E,0X3F,0X07,0X01,0XF8,0X1F,0X8F,0XC1,0XF8,0XFC,0X7E,0X00,0X07,0XF0,
0X3F,0X8F,0XC3,0XFC,0X00,0XFC,0X3F,0X1F,0X80,0X07,0XF0,0X7C,0X7C,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X1F,0X3F,0XE7,0XC3,0XE0,0XF8,0X7E,0X0F,0XC0,0XFC,0X3F,
0X07,0XC1,0XF0,0XFC,0X3E,0X3F,0X00,0X01,0XF8,0X1F,0X8F,0XC1,0XF8,0XFC,0X3E,0X00,
0X07,0XF0,0X3F,0X0F,0XC3,0XFF,0XE0,0XF8,0X3F,0X1F,0X80,0X7F,0XF0,0X7C,0XF8,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0X3F,0XE7,0XC3,0XE0,0XF8,0X7E,0X0F,0XC0,
0XFC,0X3F,0X07,0XC1,0XF0,0XF8,0X3E,0X3F,0X00,0X01,0XF8,0X1F,0X8F,0XC1,0XF8,0XF8,
0X3E,0X00,0X07,0XF0,0X3F,0X0F,0XC1,0XFF,0XF0,0XF8,0X3F,0X1F,0X83,0XFF,0XF0,0X7C,
0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0X1F,0XC7,0XC3,0XE1,0XF8,0X7E,
0X0F,0XC0,0XFC,0X3F,0X07,0XC3,0XF0,0XF8,0X3E,0X3F,0X00,0X01,0XF8,0X1F,0X8F,0XC1,
0XF8,0XF8,0X3E,0X00,0X07,0XF0,0X3F,0X0F,0XC0,0X7F,0XF8,0XF8,0X3F,0X1F,0X87,0XF1,
0XF0,0X3E,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0X1F,0XC7,0XC3,0XF1,
0XF8,0X7E,0X0F,0XC0,0XFC,0X3F,0X07,0XE3,0XF0,0XF8,0X3E,0X3F,0X03,0X01,0XF8,0X1F,
0X8F,0XC1,0XF8,0XF8,0X3E,0X00,0X07,0XF0,0X7F,0X0F,0XC0,0X03,0XF8,0XFC,0X3F,0X1F,
0X8F,0XC1,0XF0,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0X1F,0XC7,
0XC3,0XFF,0XF8,0X7E,0X0F,0XC0,0XFC,0X3F,0X07,0XFF,0XF0,0XF8,0X3E,0X1F,0X87,0XE1,
0XF8,0X1F,0X87,0XE3,0XF0,0XF8,0X3E,0X00,0X07,0XFF,0XFE,0X0F,0XC0,0XE0,0XF8,0XFC,
0X7F,0X1F,0X8F,0XC3,0XF0,0X1F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,
0X1F,0XC7,0XC3,0XFF,0XF8,0X7E,0X0F,0XF8,0XFC,0X3F,0X07,0XFF,0XF0,0XF8,0X3E,0X1F,
0XFF,0XC1,0XFF,0X1F,0X87,0XFF,0XF0,0XF8,0X3E,0X00,0X07,0XFF,0XFE,0X0F,0XC7,0XE1,
0XF8,0XFF,0XFE,0X1F,0X8F,0XFF,0XF0,0X1F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X1F,0X0F,0X87,0XC3,0XFF,0XF8,0X7E,0X0F,0XF8,0XFC,0X3F,0X07,0XFF,0XF0,0XF8,
0X3E,0X0F,0XFF,0XC1,0XFF,0X1F,0X83,0XFF,0XE0,0XF8,0X3E,0X00,0X07,0XFF,0XFC,0X0F,
0XC3,0XFF,0XF0,0XFF,0XFE,0X1F,0X8F,0XFF,0XF0,0X1F,0XE0,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X1F,0X0F,0X87,0XC1,0XFE,0XF8,0X7E,0X07,0XF8,0XFC,0X3F,0X03,0XFD,
0XF0,0XF8,0X3E,0X07,0XFF,0X80,0XFF,0X1F,0X81,0XFF,0XC0,0XF8,0X3E,0X00,0X07,0XFF,
0XF8,0X0F,0XC3,0XFF,0XE0,0XFF,0XFC,0X1F,0X87,0XFD,0XF0,0X0F,0XE0,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X1F,0X0F,0X87,0XC0,0XF8,0XF8,0X7E,0X03,0XF8,0XFC,0X3F,
0X01,0XF1,0XF0,0XF8,0X3E,0X01,0XFE,0X00,0X7F,0X1F,0X80,0X7F,0X00,0XF8,0X3E,0X00,
0X07,0XFF,0XC0,0X0F,0XC0,0X7F,0X80,0XF9,0XF0,0X1F,0X81,0XF0,0XF8,0X0F,0XC0,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XF8,0X00,0X00,0X00,0X00,0X00,0X0F,
0XC0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XF8,0X00,0X00,0X00,0X00,
0X00,0X0F,0XC0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XF8,0X00,0X00,
0X00,0X00,0X01,0XFF,0X80,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XF8,
0X00,0X00,0X00,0X00,0X01,0XFF,0X80,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0XF8,0X00,0X00,0X00,0X00,0X01,0XFF,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0XF8,0X00,0X00,0X00,0X00,0X00,0XFC,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XF8,0X01,0XFF,0XFC,0X03,0XFF,0XF0,0X00,0XFC,
0X00,0X3F,0X80,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFE,0X01,0XFF,0XFF,0X03,0XFF,0XFC,
0X03,0XFF,0X00,0XFF,0XE0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0X81,0XFF,0XFF,0X83,
0XFF,0XFE,0X07,0XFF,0X81,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0XC1,0XFF,
0XFF,0X83,0XFF,0XFE,0X0F,0XFF,0XC3,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,
0XC1,0XFF,0XFF,0XC3,0XFF,0XFE,0X1F,0X8F,0XC3,0XF1,0XF8,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,
0XFE,0X1F,0XE1,0XFC,0X1F,0XC3,0XF0,0X7F,0X1F,0X87,0X83,0XE0,0XF8,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X01,0XFC,0X0F,0XE1,0XFC,0X1F,0X83,0XF0,0X3F,0X1F,0X00,0X07,0XE0,0XF8,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X01,0XF8,0X07,0XE1,0XFC,0X1F,0X83,0XF0,0X3F,0X3F,0X3E,0X07,0XE0,
0XFC,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X03,0XF8,0X07,0XF1,0XFF,0XFF,0X03,0XF0,0X7F,0X3F,0X7F,
0X87,0XE0,0XFC,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XF8,0X07,0XF1,0XFF,0XFE,0X03,0XFF,0XFE,
0X3F,0XFF,0XC7,0XE0,0XFC,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XF8,0X07,0XF1,0XFF,0XFF,0X03,
0XFF,0XFE,0X3F,0XFF,0XC7,0XE0,0XFC,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XF8,0X07,0XF1,0XFF,
0XFF,0X83,0XFF,0XFC,0X3F,0X87,0XE7,0XE0,0XFC,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XF8,0X07,
0XF1,0XFF,0XFF,0XC3,0XFF,0XF8,0X3F,0X07,0XE7,0XE0,0XFC,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,
0XF8,0X07,0XE1,0XFC,0X0F,0XC3,0XFF,0XE0,0X3F,0X03,0XE7,0XE0,0XFC,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X01,0XFC,0X0F,0XE1,0XFC,0X0F,0XE3,0XF0,0X00,0X1F,0X03,0XE3,0XE0,0XFC,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X01,0XFE,0X1F,0XE1,0XFC,0X0F,0XE3,0XF0,0X00,0X1F,0X07,0XE3,0XE0,
0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,0XC1,0XFF,0XFF,0XC3,0XF0,0X00,0X1F,0X87,
0XE3,0XF1,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0XC1,0XFF,0XFF,0XC3,0XF0,0X00,
0X0F,0XFF,0XC1,0XFF,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0X81,0XFF,0XFF,0X83,
0XF0,0X00,0X07,0XFF,0X81,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFE,0X01,0XFF,
0XFF,0X83,0XF0,0X00,0X03,0XFF,0X00,0XFF,0XE0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XF8,
0X01,0XFF,0XFC,0X03,0XF0,0X00,0X00,0XFC,0X00,0X3F,0X80,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X40,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0XC0,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XC0,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XC0,0X07,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XC0,0X07,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XC0,0X07,
0XFF,0XFC,0X07,0XFF,0X00,0X07,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,
0XC0,0X07,0XFF,0XE0,0X00,0XFF,0X00,0X00,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X0F,0XC0,0X07,0XFF,0XC0,0X00,0X7F,0X00,0X00,0X7F,0XF0,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X1F,0XC0,0X07,0XFF,0X80,0X00,0X3F,0X00,0X00,0X3F,0XF0,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X1F,0XC0,0X07,0XFF,0X00,0X00,0X1F,0X00,0X00,0X1F,0XF0,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XC0,0X07,0XFE,0X00,0XC0,0X0F,0X01,0XE0,
0X1F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XC0,0X07,0XFE,0X03,0XF0,0X0F,
0X01,0XF0,0X1F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XC0,0X07,0XFC,0X03,
0XF8,0X0F,0X01,0XF0,0X1F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XC0,0X07,
0XFC,0X07,0XF8,0X07,0X01,0XF0,0X1F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XFF,
0XC0,0X07,0XFC,0X07,0XFC,0X07,0X01,0XE0,0X1F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X03,0XFF,0XC0,0X07,0XFC,0X07,0XFC,0X07,0X00,0X00,0X3F,0XF0,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X03,0XFF,0XC0,0X07,0XFC,0X07,0XFC,0X07,0X00,0X00,0X3F,0XF0,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X07,0XFF,0XC0,0X07,0XFC,0X07,0XFC,0X07,0X00,0X00,0X7F,0XF0,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,0XC0,0X07,0XFC,0X07,0XFC,0X07,0X00,0X00,
0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,0XC0,0X07,0XFC,0X07,0XF8,0X07,
0X01,0XDF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,0XC0,0X07,0XFC,0X07,
0XF8,0X0F,0X01,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,0XC0,0X07,
0XFE,0X03,0XF8,0X0F,0X01,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,
0XC0,0X07,0XFE,0X00,0XE0,0X0F,0X01,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X7F,0XFF,0XC0,0X07,0XFF,0X00,0X00,0X1F,0X01,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0XFF,0XFF,0XC0,0X07,0XFF,0X00,0X00,0X3F,0X01,0XFF,0XFF,0XF0,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X01,0XFF,0XFF,0XC0,0X07,0XFF,0X80,0X00,0X7F,0X01,0XFF,0XFF,0XF0,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X01,0XFF,0XFF,0XC0,0X07,0XFF,0XE0,0X00,0XFF,0X01,0XFF,
0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XC0,0X07,0XFF,0XF8,0X03,0XFF,
0X01,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,0XC0,0X07,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,0XC0,0X07,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,0XFF,
0XC0,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,
0XFF,0XFF,0XC0,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X3F,0XFF,0XFF,0XC0,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X3F,0XFF,0XFF,0XC0,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0XFF,0XC0,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X00,0X00,0X78,
0X0F,0XF0,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X00,
0X00,0X78,0X07,0XF0,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XFF,0XFF,0XFF,0XC0,0X07,
0XFE,0X00,0X00,0X78,0X07,0XF0,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,
0XC0,0X07,0XFE,0X00,0X00,0X78,0X03,0XF0,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,
0XFF,0XFF,0XC0,0X07,0XFE,0X00,0X00,0X78,0X01,0XF0,0X3F,0XF0,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X07,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X03,0XFF,0XF8,0X01,0XF0,0X3F,0XF0,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X0F,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X03,0XFF,0XF8,0X00,0XF0,0X3F,0XF0,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X1F,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X03,0XFF,0XF8,0X00,0X70,
0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X00,0X00,0XF8,
0X00,0X70,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X00,
0X00,0XF8,0X00,0X30,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0XFF,0XFF,0XC0,0X07,
0XFE,0X00,0X00,0XF8,0X00,0X10,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X7F,0XFF,0XFF,0XFF,
0XC0,0X07,0XFE,0X00,0X00,0XF8,0X00,0X10,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,
0XFF,0XFF,0XC0,0X07,0XFE,0X00,0X00,0XF8,0X08,0X00,0X3F,0XF0,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X01,
0XFF,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X03,0XFF,0XF8,0X0C,0X00,0X3F,0XF0,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X01,0XFF,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X03,0XFF,0XF8,0X0E,0X00,0X3F,0XF0,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X03,0XFF,0XF8,0X0E,0X00,
0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X03,0XFF,0XF8,
0X0F,0X00,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X00,
0X00,0X78,0X0F,0X80,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X0F,0XFF,0XFF,0XFF,0XFF,0XC0,0X07,
0XFE,0X00,0X00,0X78,0X0F,0X80,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X1F,0XFF,0XFF,0XFF,0XFF,
0XC0,0X07,0XFE,0X00,0X00,0X78,0X0F,0XC0,0X3F,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,0XFF,0XFF,
0XFF,0XFF,0XC0,0X07,0XFE,0X00,0X00,0X78,0X0F,0XE0,0X3F,0XF0,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X3F,
0XFF,0XFF,0XFF,0XFF,0XC0,0X07,0XFE,0X00,0X00,0X78,0X0F,0XE0,0X3F,0XF0,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X7F,0XFF,0XFF,0XFF,0XFF,0XC0,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0XFF,0XFF,0XFF,0XFF,0XFF,0XC0,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,
0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0XFF,0XFF,0XFF,0XFF,0XFF,0XC0,0X07,0XFF,0XFF,0XFF,0XFF,
0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X01,0XFF,0XFF,0XFF,0XFF,0XFF,0XC0,0X07,0XFF,0XFF,
0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X03,0XFF,0XFF,0XFF,0XFF,0XFF,0XC0,0X07,
0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,
0XC0,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFF,0XFF,0XFF,
0XFF,0XFF,0XC0,0X07,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XFF,0XF0,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XF8,0X00,0X00,0X00,0X20,0X0F,0XE0,
0X00,0X00,0X38,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFC,0X00,0X00,0X00,0X60,
0X0F,0XF8,0X00,0X00,0X38,0X00,0X00,0X01,0X80,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFE,0X00,0X00,
0X00,0XE0,0X0F,0XF8,0X00,0X00,0X00,0X00,0X00,0X03,0X80,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0X0E,
0X06,0X00,0XC0,0XE0,0X0E,0X3C,0X08,0X38,0X00,0X18,0X03,0X03,0X81,0XC0,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X07,0X1E,0X1F,0X87,0XFB,0XF8,0X0E,0X3C,0XDC,0XFE,0X38,0X7F,0X0F,0XE7,0XE7,0XF0,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X07,0XFC,0X3F,0XCF,0X3B,0XF8,0X0F,0XF8,0XF9,0XFF,0X38,0XE7,0X1F,0XE7,
0XE6,0X38,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X07,0XFE,0X78,0XE0,0X38,0XE0,0X0F,0XF8,0XE1,0XC7,0X39,0XE3,
0XBC,0X03,0X87,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X07,0X0E,0X70,0XE3,0XF8,0XE0,0X0F,0XE0,0XE1,0XC7,
0X39,0XFF,0XB8,0X03,0X87,0XF0,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0X0F,0X70,0XEF,0X38,0XE0,0X0E,0X00,
0XE1,0XC7,0X39,0XFF,0XB8,0X03,0X81,0XF8,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0X1E,0X39,0XEE,0X38,0XE0,
0X0E,0X00,0XE1,0XC7,0X38,0XE0,0X3C,0XF3,0X80,0X38,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFE,0X3F,0XCF,
0XF8,0XF0,0X0E,0X00,0XE0,0XFF,0X38,0XFF,0X1F,0XE3,0XEF,0X78,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X07,0XFC,
0X1F,0X87,0XD8,0XF8,0X0E,0X00,0XE0,0X7C,0X38,0X7E,0X0F,0XC1,0XE7,0XF0,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X38,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X78,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0XF8,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X20,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,
0X00,0X00,0X00,0X00,0X00,0X00,0X00,0X00,};

View File

@ -0,0 +1,106 @@
#ifndef _OBP60EXTENSIONPORT_H
#define _OBP60EXTENSIONPORT_H
#include <Arduino.h>
#include "OBP60Hardware.h"
MCP23017 mcp = MCP23017(MCP23017_I2C_ADDR);
// SPI pin definitions for E-Ink display
GxIO_Class io(SPI, OBP_SPI_CS, OBP_SPI_DC, OBP_SPI_RST); // SPI, CS, DC, RST
GxEPD_Class display(io, OBP_SPI_RST, OBP_SPI_BUSY); // io, RST, BUSY
// Global vars
int outA = 0; // Outport Byte A
int outB = 0; // Outport Byte B
bool blinkingLED = false; // Enable / disable blinking flash LED
int uvDuration = 0; // Under voltage duration in n x 100ms
uint buzPower = 50; // Buzzer loudness in [%]
void setPortPin(uint pin, bool value){
if(pin <=7){
outA &= ~(1 << pin); // Clear bit
outA |= (value << pin); // Set bit
mcp.writeRegister(MCP23017Register::GPIO_A, outA);
}
else{
pin = pin - 8;
outB &= ~(1 << pin); // Clear bit
outB |= (value << pin); // Set bit
mcp.writeRegister(MCP23017Register::GPIO_B, outB);
}
}
void togglePortPin(uint pin){
if(pin <=7){
outA ^= (1 << pin); // Set bit
mcp.writeRegister(MCP23017Register::GPIO_A, outA);
}
else{
pin = pin - 8;
outB ^= (1 << pin); // Set bit
mcp.writeRegister(MCP23017Register::GPIO_B, outB);
}
}
void blinkingFlashLED(){
noInterrupts();
if(blinkingLED == true){
togglePortPin(OBP_FLASH_LED);
}
else{
setPortPin(OBP_FLASH_LED, false);
}
interrupts();
}
void buzzer(uint frequency, uint power, uint duration){
if(frequency > 8000){ // Max 8000Hz
frequency = 8000;
}
if(power > 100){ // Max 100%
power = 100;
}
if(duration > 1000){ // Max 1000ms
duration = 1000;
}
pinMode(OBP_BUZZER, OUTPUT);
ledcSetup(0, frequency, 8); // Ch 0, ferquency in Hz, 8 Bit resolution of PWM
ledcAttachPin(OBP_BUZZER, 0);
ledcWrite(0, int(power * 1.28)); // 50% duty cycle are 100%
delay(duration);
ledcWrite(0, 0); // 0% duty cycle are 0%
}
void underVoltageDetection(){
noInterrupts();
float actVoltage = (float(analogRead(OBP_ANALOG0)) * 3.3 / 4096 + 0.17) * 20; // Vin = 1/20
if(actVoltage < MIN_VOLTAGE){
uvDuration ++;
}
else{
uvDuration = 0;
}
if(uvDuration > POWER_FAIL_TIME){
setPortPin(OBP_BACKLIGHT_LED, false); // Backlight Off
setPortPin(OBP_FLASH_LED, false); // Flash LED Off
buzzer(TONE4, buzPower, 20); // Buzzer tone 4kHz 20% 20ms
setPortPin(OBP_POWER_50, false); // Power rail 5.0V Off
setPortPin(OBP_POWER_33, false); // Power rail 3.3V Off
// Shutdown EInk display
display.fillRect(0, 0, GxEPD_WIDTH, GxEPD_HEIGHT, GxEPD_WHITE); // Draw white sreen
display.updateWindow(0, 0, GxEPD_WIDTH, GxEPD_HEIGHT, false); // Partial update
// display._sleep(); // Display shut dow
// Stop system
while(true){
esp_deep_sleep_start(); // Deep Sleep without weakup. Weakup only after power cycle (restart).
}
}
interrupts();
}
#endif

View File

@ -0,0 +1,80 @@
// Other pin definititins see GwOBP60Task.h
// Direction pin for RS485 NMEA0183
#define OBP_DIRECTION_PIN 27
// SeaTalk
#define OBP_SEATALK_TX 2
#define OBP_SEATALK_RX 15
// I2C (MCP23017)
#define OBP_I2C_SDA 21
#define OBP_I2C_SCL 22
// SPI (E-Ink display, Extern Bus)
#define OBP_SPI_CS 5
#define OBP_SPI_DC 17
#define OBP_SPI_RST 16
#define OBP_SPI_BUSY 4
#define OBP_SPI_CLK 18
#define OBP_SPI_DIN 23
#define X_PIX 400 // X display dimension in pix
#define Y_PIX 300 // Y display dimension in pix
#define SHOW_TIME 6000 // Show time for logo and WiFi QR code
#define FULL_REFRESH_TIME 600 // Refresh cycle time in [s][600...3600] for full display update (very important healcy function)
#define MAX_PAGE_NUMBER 3 // Max number of pages for show data
#define FONT_MIN_SIZE "AA"
#define FONT_MIDDLE_SIZE "Ubuntu_Bold32pt7b"
#define FONT_MAX_SIZE "DSEG7Classic_BoldItalic80pt7b"
// GPS (NEO-6M)
#define OBP_GPS_TX 35 // Read only GPS data
// TTP229 Touch Pad Controller (!!No I2C!!)
#define TTP_SDO 25
#define TTP_SCL 33
// 1Wire (DS18B20)
#define OBP_1WIRE 32 // External 1Wire
// Buzzer
#define OBP_BUZZER 19
#define TONE1 1500 // 1500Hz
#define TONE2 2000 // 200Hz
#define TONE3 3000 // 3000Hz
#define TONE4 4000 // 4000Hz
// Analog Input
#define OBP_ANALOG0 34 // Voltage power supplay
#define OBP_ANALOG1 36 // Analog In 1
#define OBP_ANALOG2 39 // Analog In 2
#define MIN_VOLTAGE 9.0 // Min voltage for under voltage detection (then goto deep sleep)
#define POWER_FAIL_TIME 2 // Accept min voltage until 2 x 1ms (for under voltage gaps by engine start)
// Extension Port MCP23017
#define MCP23017_I2C_ADDR 0x20 // Addr. 0 is 0x20
// Extension Port PA
#define PA0 0 // Digital Out 1
#define PA1 1 // Digital Out 2
#define PA2 2 // Flash LED
#define PA3 3 // Backlight LEDs
#define PA4 4 // Digital In 1
#define PA5 5 // Digital In 2
#define PA6 6 // Power Rail 5.0V
#define PA7 7 // Power Rail 3.3V
// Extension Port PB
#define PB0 8 // Extension Connector
#define PB1 9 // Extension Connector
#define PB2 10 // Extension Connector
#define PB3 11 // Extension Connector
#define PB4 12 // Extension Connector
#define PB5 13 // Extension Connector
#define PB6 14 // Extension Connector
#define PB7 15 // Extension Connector
// Extension Port Digital Out
#define OBP_DIGITAL_OUT1 PA0
#define OBP_DIGITAL_OUT2 PA1
// Extension Port LED
#define OBP_FLASH_LED PA2
// Extension Port Backlight LEDs
#define OBP_BACKLIGHT_LED PA3
// Extension Port Digital In
#define OBP_DIGITAL_IN1 PA4
#define OBP_DIGITAL_IN2 PA5
// Extension Port Power Rails
#define OBP_POWER_50 PA6
#define OBP_POWER_33 PA7

103
lib/obp60task/OBP60Keypad.h Normal file
View File

@ -0,0 +1,103 @@
#ifndef _OBP60FUNCTIONS_H
#define _OBP60FUNCTIONS_H
#include <Arduino.h>
#include "OBP60Hardware.h"
// Global vars
// Routine for TTP229-BSF (!!! IC use not a I2C bus !!!)
//
// 8 Key Mode
//
// Key number {0, 1, 2, 3, 4, 5, 6, 7, 8}
// Scan code {0, 8, 7, 1, 6, 2, 5, 3, 4}
int keyposition[9] = {0, 3, 5, 7, 8, 6, 4, 2, 1}; // Position of key in raw data, 0 = nothing touched
int keypad[9]; // Raw data array from TTP229
int key; // Value of key [0|1], 0 = touched, 1 = not touched
int keycode = 0; // Keycode of pressed key [0...8], 0 = nothing touched
String keystatus = "0"; // Status of key (0 = processed, 1s...8s, 1l...8l, left, right unprocessed)
int keycodeold;
int swipedelay = 500; // Delay after swipe in [ms]
int keydelay = 500; // Delay after key pressed in [ms]
bool keylock = 0; // Key lock after pressed key is valid (repeat protection by conginous pressing)
int repeatnum; // Actual number of key detections for a pressed key
int shortpress = 5; // number of key detections after that the key is valid (n * 40ms) for short pessing
int longpress = 25; // number of key detections after that the key is valid (n * 40ms) for long pessing
int swipedir = 0; // Swipe direction 0 = nothing, -1 = left, +1 = right
void readKeypad() {
noInterrupts();
pinMode(TTP_SDO, INPUT);
pinMode(TTP_SCL, OUTPUT);
keycode = 0;
// Read key code from raw data
for (int i = 0; i < 9; i++) {
digitalWrite(TTP_SCL, LOW);
delay(1); // 2ms clock
keypad[i] = digitalRead(TTP_SDO);
if(i > 0){
// Invert keypad
if(keypad[i] == 1){
key = 0;
}
else{
key = 1;
}
keycode += key * i;
}
digitalWrite(TTP_SCL, HIGH);
delay(1);
}
// Remapping keycode
keycode = keyposition[keycode];
// Read repeat number
if(keycode == keycodeold){
repeatnum ++;
}
/*
// Detect swipe right
if (keycode > 0 && keycodeold > 0 && keycode > keycodeold && keycode != keycodeold && keylock == false){
keylock = true;
swipedir = 1;
keystatus = "right";
buzzer(TONE3 buzPower, 100);
delay(swipedelay);
}
// Detect swipe left
if (keycode > 0 && keycodeold > 0 && keycode < keycodeold && keycode != keycodeold && keylock == false){
keylock = true;
swipedir = -1;
keystatus = "left";
buzzer(TONE3, buzPower, 100);
delay(swipedelay);
}
*/
// Detect short perssed keynumber
if (keycode > 0 && repeatnum >= shortpress && repeatnum < longpress && keycode == keycodeold && keylock == false){
keylock = true;
keystatus = String(keycode) + "s";
buzzer(TONE4, buzPower, 100);
delay(keydelay);
}
/*
// Detect long perssed keynumber
if (keycode > 0 && repeatnum >= longpress && keylock == false){
keystatus = String(keycode) + "l";
buzzer(4000, 20, 200);
keylock = true;
}
*/
// Reset keylock after release
if (keycode == 0 && keycodeold == 0){
keylock = false;
repeatnum = 0;
}
// Copy keycode
keycodeold = keycode;
interrupts();
}
#endif

View File

@ -0,0 +1,66 @@
#ifndef _OBP60PAGES_H
#define _OBP60PAGES_H
#include <Arduino.h>
// Global vars
uint pageNumber = 0; // Page number for actual page
String key_label[6] = {" ", " ", " ", " ", " ", " "};
bool first_view = true;
void showPage(){
// Clear display
display.fillRect(0, 0, GxEPD_WIDTH, GxEPD_HEIGHT, GxEPD_WHITE); // Draw white sreen
/*
// If new first page the init the display for reducing ghost picture
if(first_view == true){
display.init();
display.fillRect(0, 0, GxEPD_WIDTH, GxEPD_HEIGHT, GxEPD_WHITE); // Draw white sreen
display.update();
}
*/
// Draw status heder
// display.fillRect(0, 0, GxEPD_WIDTH, 20, GxEPD_BLACK); // Draw black box
display.setFont(&Ubuntu_Bold8pt7b);
display.setTextColor(GxEPD_BLACK);
display.setCursor(0, 15);
display.print(" WiFi AP TCP N2K 183 GPS");
display.setCursor(230, 15);
display.print("14.12.2021 17:50 UTC");
// Read page number
switch (pageNumber) {
case 0:
page_0();
break;
case 1:
page_1();
break;
case 2:
page_2();
break;
case 3:
// Statement(s)
break;
case 4:
// Statement(s)
break;
case 5:
// Statement(s)
break;
default:
page_0();
break;
}
// Partial update display
display.updateWindow(0, 0, GxEPD_WIDTH, GxEPD_HEIGHT, false); // Partial update (fast)
first_view = false;
}
#endif

View File

@ -0,0 +1,41 @@
#ifndef _OBP60QRWIFI_H
#define _OBP60QRWIFI_H
#include <Arduino.h>
#include "qrcode.h"
void qrWiFi(){
// Set start point and pixel size
int16_t box_x = 100; // X offset
int16_t box_y = 30; // Y offset
int16_t box_s = 6; // Pixel size
int16_t init_x = box_x;
// Create the QR code
QRCode qrcode;
uint8_t qrcodeData[qrcode_getBufferSize(4)];
qrcode_initText(&qrcode, qrcodeData, 4, 0, "WIFI:S:OBP60;T:WPA;P:esp32nmea2k;;");
// Top quiet zone
for (uint8_t y = 0; y < qrcode.size; y++) {
// Each horizontal module
for (uint8_t x = 0; x < qrcode.size; x++) {
if(qrcode_getModule(&qrcode, x, y)){
display.fillRect(box_x, box_y, box_s, box_s, GxEPD_BLACK);
} else {
display.fillRect(box_x, box_y, box_s, box_s, GxEPD_WHITE);
}
box_x = box_x + box_s;
}
box_y = box_y + box_s;
box_x = init_x;
}
display.setFont(&Ubuntu_Bold32pt7b);
display.setTextColor(GxEPD_BLACK);
display.setCursor(140, 285);
display.print("WiFi");
display.update(); // Full update (slow)
}
#endif

32
lib/obp60task/Page_0.h Normal file
View File

@ -0,0 +1,32 @@
#ifndef _PAGE_0_H
#define _PAGE_0_H
#include <Arduino.h>
#include "OBP60Hardware.h"
void page_0(){
// Measuring Values
display.setFont(&Ubuntu_Bold32pt7b);
display.setTextColor(GxEPD_BLACK);
display.setCursor(20, 100);
display.print("Depth:");
display.setCursor(310, 240);
display.print("m");
display.setFont(&DSEG7Classic_BoldItalic60pt7b);
display.setCursor(20, 240);
float deep = 84;
deep += float(random(0, 13)) / 10;
display.print(deep,1);
// Key Layout
display.setFont(&Ubuntu_Bold8pt7b);
display.setTextColor(GxEPD_BLACK);
display.setCursor(0, 290);
display.print(" [ < ]");
display.setCursor(290, 290);
display.print("[ > ]");
display.setCursor(343, 290);
display.print("[ILUM]");
}
#endif

32
lib/obp60task/Page_1.h Normal file
View File

@ -0,0 +1,32 @@
#ifndef _PAGE_1_H
#define _PAGE_1_H
#include <Arduino.h>
#include "OBP60Hardware.h"
void page_1(){
// Measuring Values
display.setFont(&Ubuntu_Bold32pt7b);
display.setTextColor(GxEPD_BLACK);
display.setCursor(20, 100);
display.print("Speed:");
display.setCursor(310, 240);
display.print("kn");
display.setFont(&DSEG7Classic_BoldItalic60pt7b);
display.setCursor(20, 240);
float speed = 5;
speed += float(random(0, 13)) / 10;
display.print(speed,1);
// Key Layout
display.setFont(&Ubuntu_Bold8pt7b);
display.setTextColor(GxEPD_BLACK);
display.setCursor(0, 290);
display.print(" [ < ]");
display.setCursor(290, 290);
display.print("[ > ]");
display.setCursor(343, 290);
display.print("[ILUM]");
}
#endif

31
lib/obp60task/Page_2.h Normal file
View File

@ -0,0 +1,31 @@
#ifndef _PAGE_2_H
#define _PAGE_2_H
#include <Arduino.h>
#include "OBP60Hardware.h"
void page_2(){
// Measuring Values
display.setFont(&Ubuntu_Bold32pt7b);
display.setTextColor(GxEPD_BLACK);
display.setCursor(20, 100);
display.print("VBat:");
display.setCursor(310, 240);
display.print("V");
display.setFont(&DSEG7Classic_BoldItalic60pt7b);
display.setCursor(20, 240);
float actVoltage = (float(analogRead(OBP_ANALOG0)) * 3.3 / 4096 + 0.17) * 20; // Vin = 1/20
display.print(actVoltage,1);
// Key Layout
display.setFont(&Ubuntu_Bold8pt7b);
display.setTextColor(GxEPD_BLACK);
display.setCursor(0, 290);
display.print(" [ < ]");
display.setCursor(290, 290);
display.print("[ > ]");
display.setCursor(343, 290);
display.print("[ILUM]");
}
#endif

51
lib/obp60task/Readme.md Normal file
View File

@ -0,0 +1,51 @@
Extending the Core
==================
This directory contains an example on how you can extend the base functionality of the gateway.
Maybe you have another interesting hardware or need some additional functions but would like to use the base functionality of the gateway.
You can define own hardware configurations (environments) here and can add one or more tasks that will be started by the core.
You can also add additional libraries that will be used to build your task.
In this example we define an addtional board (environment) with the name "testboard".
When building for this board we add the -DTEST_BOARD to the compilation - see [platformio.ini](platformio.ini).
The additional task that we defined will only be compiled and started for this environment (see the #ifdef TEST_BOARD in the code).
You can add your own directory below "lib". The name of the directory must contain "task".
Files
-----
* [platformio.ini](platformio.ini)<br>
This file is completely optional.
You only need this if you want to
extend the base configuration - we add a dummy library here and define one additional build environment (board)
* [GwExampleTask.h](GwExampleTask.h) the name of this include must match the name of the directory (ignoring case) with a "gw" in front. This file includes our special hardware definitions and registers our task at the core (DECLARE_USERTASK in the code). Optionally it can define some capabilities (using DECLARE_CAPABILITY) that can be used in the config UI (see below).
Avoid including headers from other libraries in this file as this could interfere with the main code. Just only include them in your .cpp files (or in other headers).
* [GwExampleTaks.cpp](GwExampleTask.cpp) includes the implementation of our task. This tasks runs in an own thread - see the comments in the code.
We can have as many cpp (and header files) as we need to structure our code.
* [GwExampleHardware.h](GwExampleHardware.h) includes our pin definitions for the board.
* [config.json](config.json)<br>
This file allows to add some config definitions that are needed for our task. For the possible options have a look at the global [config.json](../../web/config.json). Be careful not to overwrite config defitions from the global file. A good practice wood be to prefix the names of definitions with parts of the library name. Always put them in a separate category so that they do not interfere with the system ones.
The defined config items can later be accessed in the code (see the example in [GwExampleTask.cpp](GwExampleTask.cpp)).
Hints
-----
Just be careful not to interfere with C symbols from the core - so it is a good practice to prefix your files and class like in the example.
Developing
----------
To develop I recommend forking the gateway repository and adding your own directory below lib (with the string task in it's name).
As your code goes into a separate directory it should be very easy to fetch upstream changes without the need to adapt your code.
Typically after forking the repo on github (https://github.com/wellenvogel/esp32-nmea2000) and initially cloning it you will add my repository as an "upstream repo":
```
git remote add upstream https://github.com/wellenvogel/esp32-nmea2000.git
```
To merge in a new version use:
```
git fetch upstream
git merge upstream/master
```
Refer to https://docs.github.com/en/pull-requests/collaborating-with-pull-requests/working-with-forks/syncing-a-fork
By following the hints in this doc the merge should always succeed without conflicts.
Future Plans
------------
If there will be a need we can extend this extension API by means of adding specific java script code and css for the UI.

Binary file not shown.

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

Binary file not shown.

View File

@ -0,0 +1,232 @@
const uint8_t Ubuntu_Bold10pt7bBitmaps[] PROGMEM = {
0xFF, 0xFF, 0xFF, 0xE3, 0xFF, 0xC0, 0xEF, 0xDF, 0xBF, 0x7E, 0xFD, 0xC0,
0x0E, 0xE0, 0xEE, 0x1D, 0xCF, 0xFF, 0xFF, 0xF1, 0xDC, 0x1D, 0xC3, 0xB8,
0xFF, 0xFF, 0xFF, 0x3B, 0x83, 0xB8, 0x77, 0x07, 0x70, 0x1C, 0x0E, 0x0F,
0xCF, 0xEE, 0x07, 0x03, 0x81, 0xFC, 0x7F, 0x0F, 0xC0, 0xE0, 0x74, 0x3F,
0xF9, 0xF8, 0x38, 0x1C, 0x00, 0x38, 0x38, 0x7C, 0x70, 0xC6, 0x70, 0xC6,
0xE0, 0xC6, 0xE0, 0xC7, 0xC0, 0x7D, 0xDC, 0x3B, 0xBE, 0x03, 0xE3, 0x07,
0x63, 0x07, 0x63, 0x0E, 0x63, 0x0E, 0x3E, 0x1C, 0x1C, 0x1E, 0x01, 0xF8,
0x1F, 0xE0, 0xE7, 0x07, 0x38, 0x1F, 0x80, 0xF8, 0x0F, 0xCE, 0xEF, 0x77,
0x3F, 0x38, 0xF9, 0xFF, 0xC7, 0xFF, 0x1F, 0xBC, 0xFF, 0xFF, 0xC0, 0x08,
0x73, 0x8E, 0x71, 0xCE, 0x38, 0xE3, 0x8E, 0x38, 0xE3, 0x87, 0x1C, 0x38,
0xE1, 0xC2, 0x43, 0x87, 0x1C, 0x38, 0xE1, 0xC7, 0x1C, 0x71, 0xC7, 0x1C,
0x73, 0x8E, 0x71, 0xCE, 0x10, 0x1C, 0x0E, 0x17, 0x5F, 0xFF, 0xF9, 0xB1,
0xDC, 0x6C, 0x0E, 0x01, 0xC0, 0x38, 0x07, 0x0F, 0xFF, 0xFF, 0xFF, 0xF8,
0x70, 0x0E, 0x01, 0xC0, 0x38, 0x00, 0x77, 0x77, 0xEE, 0xFF, 0xFF, 0xC0,
0x6F, 0xF6, 0x01, 0xC0, 0xE0, 0x38, 0x0E, 0x07, 0x01, 0xC0, 0x70, 0x38,
0x0E, 0x03, 0x81, 0xC0, 0x70, 0x1C, 0x0E, 0x03, 0x80, 0xE0, 0x70, 0x1C,
0x07, 0x03, 0x80, 0x1C, 0x3F, 0x9F, 0xDE, 0xFE, 0x3F, 0x1F, 0x8F, 0xC7,
0xE3, 0xF1, 0xFD, 0xEF, 0xE7, 0xF0, 0xE0, 0x0E, 0x3D, 0xFF, 0xF6, 0xE1,
0xC3, 0x87, 0x0E, 0x1C, 0x38, 0x70, 0xE1, 0xC0, 0x3E, 0x7F, 0xBF, 0xEC,
0x70, 0x38, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1C, 0x1F, 0xFF, 0xFF, 0xFC,
0x3C, 0x7F, 0x3F, 0xC8, 0xE0, 0x70, 0x30, 0xF0, 0x7E, 0x07, 0x81, 0xE0,
0xFF, 0xFF, 0xF3, 0xF0, 0x07, 0x07, 0x87, 0xC3, 0xE3, 0xF3, 0xB9, 0x9D,
0xCE, 0xFF, 0xFF, 0xFF, 0xE0, 0xE0, 0x70, 0x38, 0x3F, 0x1F, 0x8F, 0xC7,
0x03, 0x83, 0xF1, 0xFC, 0xFF, 0x07, 0x81, 0xC0, 0xFF, 0xFF, 0xF3, 0xE0,
0x07, 0x0F, 0x8F, 0xCF, 0x07, 0x07, 0xF3, 0xFD, 0xFF, 0xE3, 0xF1, 0xF8,
0xEF, 0xF7, 0xF1, 0xF0, 0xFF, 0xFF, 0xFF, 0xE0, 0xE0, 0xE0, 0x70, 0x70,
0x38, 0x38, 0x1C, 0x0E, 0x0E, 0x07, 0x03, 0x80, 0x3E, 0x3F, 0xBF, 0xFC,
0x7E, 0x3F, 0xB9, 0xF8, 0xFE, 0xE7, 0xF1, 0xF8, 0xFF, 0xF7, 0xF1, 0xF0,
0x3E, 0x3F, 0xBF, 0xDC, 0x7E, 0x3F, 0x1F, 0xFE, 0xFF, 0x3F, 0x83, 0xC3,
0xCF, 0xC7, 0xC3, 0x80, 0x6F, 0xF6, 0x00, 0x06, 0xFF, 0x60, 0x33, 0xDE,
0x60, 0x00, 0x00, 0x73, 0x9C, 0xEE, 0x70, 0x01, 0x87, 0xEF, 0xFF, 0xF8,
0xE0, 0x3F, 0x8F, 0xFC, 0x7E, 0x01, 0x80, 0xFF, 0xFF, 0xFF, 0xE0, 0x00,
0x07, 0xFF, 0xFF, 0xFF, 0x60, 0x3E, 0x3F, 0xE3, 0xF0, 0x38, 0xFF, 0xFE,
0xF8, 0x60, 0x00, 0x7C, 0xFE, 0xFF, 0x07, 0x07, 0x07, 0x0E, 0x1E, 0x3C,
0x38, 0x38, 0x00, 0x30, 0x78, 0x78, 0x30, 0x03, 0xF0, 0x07, 0xFE, 0x0F,
0x03, 0x86, 0x00, 0xE6, 0x1F, 0xB7, 0x3F, 0xCF, 0x3C, 0xE7, 0x9C, 0x73,
0xCE, 0x39, 0xE7, 0x1C, 0xF3, 0xCE, 0x5C, 0xFF, 0xE6, 0x3F, 0xE3, 0x80,
0x00, 0xF0, 0x00, 0x3F, 0xE0, 0x07, 0xF8, 0x00, 0x03, 0x80, 0x0F, 0x80,
0x1F, 0x00, 0x77, 0x00, 0xEE, 0x03, 0xDE, 0x07, 0x1C, 0x1E, 0x3C, 0x3F,
0xF8, 0x7F, 0xF1, 0xFF, 0xF3, 0x80, 0xE7, 0x01, 0xDC, 0x01, 0xC0, 0xFE,
0x3F, 0xCF, 0xFB, 0x8E, 0xE3, 0xBF, 0xCF, 0xF3, 0xFE, 0xE1, 0xF8, 0x7E,
0x1F, 0xFF, 0xFF, 0xBF, 0x80, 0x0F, 0xC7, 0xFD, 0xFF, 0xBC, 0x2F, 0x01,
0xC0, 0x38, 0x07, 0x00, 0xE0, 0x1E, 0x01, 0xE0, 0x3F, 0xF3, 0xFE, 0x1F,
0x80, 0xFF, 0x0F, 0xFC, 0xFF, 0xEE, 0x1E, 0xE0, 0xFE, 0x07, 0xE0, 0x7E,
0x07, 0xE0, 0x7E, 0x0F, 0xE1, 0xEF, 0xFE, 0xFF, 0xCF, 0xF0, 0xFF, 0xFF,
0xFF, 0xFC, 0x0E, 0x07, 0xFB, 0xFD, 0xFE, 0xE0, 0x70, 0x38, 0x1F, 0xFF,
0xFF, 0xFC, 0xFF, 0xFF, 0xFF, 0xE0, 0xE0, 0xFE, 0xFE, 0xFE, 0xE0, 0xE0,
0xE0, 0xE0, 0xE0, 0xE0, 0x0F, 0xC7, 0xFD, 0xFF, 0xBC, 0x2F, 0x01, 0xC0,
0x38, 0x07, 0x07, 0xE0, 0xFE, 0x1D, 0xE3, 0xBF, 0xF3, 0xFE, 0x1F, 0x80,
0xE0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xFF, 0xFF, 0xFF, 0xFF, 0xE0,
0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F, 0xC1, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xC0, 0x03, 0x81, 0xC0, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03,
0x81, 0xD1, 0xEF, 0xFF, 0xF3, 0xF0, 0xE0, 0xFE, 0x1E, 0xE3, 0xCE, 0x78,
0xEF, 0x0F, 0xE0, 0xFC, 0x0F, 0xC0, 0xEE, 0x0E, 0x70, 0xE7, 0x8E, 0x3C,
0xE1, 0xEE, 0x0F, 0xE0, 0x70, 0x38, 0x1C, 0x0E, 0x07, 0x03, 0x81, 0xC0,
0xE0, 0x70, 0x38, 0x1F, 0xFF, 0xFF, 0xFC, 0x70, 0x1C, 0xF0, 0x79, 0xE0,
0xF3, 0xE3, 0xE7, 0xC7, 0xDD, 0x8D, 0xFB, 0xBB, 0xF3, 0x67, 0xE7, 0xCF,
0xCF, 0x9F, 0x8E, 0x3F, 0x1C, 0x7E, 0x00, 0xFC, 0x01, 0xC0, 0xE0, 0xFE,
0x1F, 0xC3, 0xFC, 0x7F, 0xCF, 0xD9, 0xFB, 0xBF, 0x3F, 0xE7, 0xFC, 0x7F,
0x87, 0xF0, 0xFE, 0x0F, 0xC1, 0xC0, 0x0F, 0xC0, 0xFF, 0xC7, 0xFF, 0x9E,
0x1E, 0xF0, 0x3F, 0x80, 0x7E, 0x01, 0xF8, 0x07, 0xE0, 0x1F, 0xC0, 0xF7,
0x87, 0x9F, 0xFE, 0x3F, 0xF0, 0x3F, 0x00, 0xFE, 0x3F, 0xEF, 0xFF, 0x87,
0xE1, 0xF8, 0x7F, 0xFF, 0xFE, 0xFE, 0x38, 0x0E, 0x03, 0x80, 0xE0, 0x38,
0x00, 0x0F, 0xC0, 0xFF, 0xC7, 0xFF, 0x9E, 0x1E, 0xF0, 0x3F, 0x80, 0x7E,
0x01, 0xF8, 0x07, 0xE0, 0x1F, 0xC0, 0xF7, 0x87, 0x9F, 0xFE, 0x3F, 0xF0,
0x3F, 0x00, 0x3C, 0x00, 0x7E, 0x00, 0x78, 0xFE, 0x1F, 0xF3, 0xFF, 0x70,
0xEE, 0x1D, 0xC3, 0xBF, 0xF7, 0xFC, 0xFF, 0x1C, 0xF3, 0x8E, 0x70, 0xEE,
0x1D, 0xC1, 0xC0, 0x3F, 0x1F, 0xEF, 0xFB, 0x80, 0xE0, 0x3E, 0x07, 0xF0,
0x7E, 0x03, 0xC0, 0x74, 0x1F, 0xFF, 0xFF, 0x9F, 0xC0, 0xFF, 0xFF, 0xFF,
0xFF, 0x87, 0x00, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC0, 0x38,
0x07, 0x00, 0xE0, 0x1C, 0x00, 0xE0, 0xFC, 0x1F, 0x83, 0xF0, 0x7E, 0x0F,
0xC1, 0xF8, 0x3F, 0x07, 0xE0, 0xFC, 0x1F, 0xC7, 0xBF, 0xE7, 0xFC, 0x3E,
0x00, 0xE0, 0x0E, 0xE0, 0x39, 0xC0, 0x71, 0xC1, 0xC3, 0x83, 0x87, 0x07,
0x07, 0x1C, 0x0E, 0x38, 0x0E, 0xE0, 0x1D, 0xC0, 0x1F, 0x00, 0x3E, 0x00,
0x7C, 0x00, 0x70, 0x00, 0xE0, 0x00, 0xFC, 0x1C, 0x1D, 0xC3, 0x87, 0x38,
0x78, 0xE7, 0x1F, 0x1C, 0xE3, 0x63, 0x8E, 0x6C, 0xE1, 0xDD, 0xDC, 0x3B,
0xBB, 0x83, 0x63, 0x60, 0x7C, 0x7C, 0x0F, 0x8F, 0x81, 0xE0, 0xF0, 0x1C,
0x1C, 0x00, 0xF0, 0x3D, 0xE1, 0xE3, 0x87, 0x07, 0x38, 0x1F, 0xE0, 0x3F,
0x00, 0x78, 0x01, 0xE0, 0x0F, 0xC0, 0x7F, 0x81, 0xCE, 0x0E, 0x1C, 0x78,
0x7B, 0xC0, 0xF0, 0xE0, 0x3B, 0x83, 0x9C, 0x1C, 0x71, 0xC3, 0xDE, 0x0E,
0xE0, 0x3E, 0x01, 0xF0, 0x07, 0x00, 0x38, 0x01, 0xC0, 0x0E, 0x00, 0x70,
0x03, 0x80, 0xFF, 0xFF, 0xFF, 0xFC, 0x0E, 0x07, 0x03, 0x80, 0xE0, 0x70,
0x38, 0x1E, 0x07, 0x03, 0xFF, 0xFF, 0xFF, 0xF0, 0xFF, 0xFF, 0xCE, 0x73,
0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9C, 0xE7, 0xFF, 0xF0, 0xE0, 0x1C, 0x07,
0x01, 0xC0, 0x38, 0x0E, 0x03, 0x80, 0x70, 0x1C, 0x07, 0x00, 0xE0, 0x38,
0x0E, 0x01, 0xC0, 0x70, 0x1C, 0x03, 0x80, 0xE0, 0x38, 0x07, 0xFF, 0xFE,
0x73, 0x9C, 0xE7, 0x39, 0xCE, 0x73, 0x9C, 0xE7, 0x3F, 0xFF, 0xF0, 0x0E,
0x03, 0xE0, 0x7C, 0x1D, 0xC7, 0xBC, 0xE3, 0xB8, 0x3B, 0x06, 0xFF, 0xFF,
0xF0, 0x47, 0x1E, 0x20, 0x7E, 0x3F, 0x9F, 0xE0, 0x73, 0xFB, 0xFF, 0x8F,
0xC7, 0xFF, 0xBF, 0xCF, 0xE0, 0xE0, 0x38, 0x0E, 0x03, 0x80, 0xE0, 0x3F,
0xCF, 0xFB, 0xFE, 0xE3, 0xF8, 0x7E, 0x1F, 0x87, 0xE3, 0xFF, 0xEF, 0xFB,
0xF8, 0x1F, 0x3F, 0x7F, 0xF0, 0xE0, 0xE0, 0xE0, 0xF0, 0x7F, 0x7F, 0x1F,
0x01, 0xC0, 0x70, 0x1C, 0x07, 0x01, 0xC7, 0xF7, 0xFD, 0xFF, 0xF1, 0xF8,
0x7E, 0x1F, 0x87, 0xF1, 0xDF, 0xF7, 0xFC, 0x7F, 0x1F, 0x1F, 0xE7, 0xFF,
0x87, 0xFF, 0xFF, 0xFE, 0x03, 0xC0, 0x7F, 0x9F, 0xE1, 0xF8, 0x3F, 0x7E,
0xFE, 0xE0, 0xE0, 0xFE, 0xFE, 0xFE, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0, 0xE0,
0xE0, 0xE0, 0x1F, 0xDF, 0xF7, 0xFF, 0xC7, 0xE1, 0xF8, 0x7F, 0x1F, 0xFF,
0x7F, 0xCF, 0xF0, 0x1C, 0x0F, 0x7F, 0x9F, 0xE7, 0xE0, 0xE0, 0x38, 0x0E,
0x03, 0x80, 0xE0, 0x3F, 0xCF, 0xFB, 0xFF, 0xE3, 0xF8, 0x7E, 0x1F, 0x87,
0xE1, 0xF8, 0x7E, 0x1F, 0x87, 0xFF, 0xF1, 0xFF, 0xFF, 0xFF, 0xFF, 0x1C,
0x71, 0xC7, 0x00, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1C, 0x71, 0xC7, 0x1F,
0xFF, 0xBC, 0xE0, 0x1C, 0x03, 0x80, 0x70, 0x0E, 0x01, 0xC3, 0xB8, 0xE7,
0x38, 0xEE, 0x1F, 0x83, 0xF8, 0x77, 0x8E, 0x79, 0xC7, 0x38, 0x77, 0x07,
0xE7, 0x39, 0xCE, 0x73, 0x9C, 0xE7, 0x39, 0xCE, 0x7F, 0xE7, 0xFE, 0xF9,
0xFF, 0xFB, 0xFF, 0xFF, 0x1C, 0x7E, 0x38, 0xFC, 0x71, 0xF8, 0xE3, 0xF1,
0xC7, 0xE3, 0x8F, 0xC7, 0x1F, 0x8E, 0x38, 0xFF, 0x3F, 0xEF, 0xFF, 0x8F,
0xE1, 0xF8, 0x7E, 0x1F, 0x87, 0xE1, 0xF8, 0x7E, 0x1C, 0x1E, 0x1F, 0xE7,
0xFB, 0xCF, 0xE1, 0xF8, 0x7E, 0x1F, 0xCF, 0x7F, 0x9F, 0xE1, 0xE0, 0xFE,
0x3F, 0xEF, 0xFB, 0x8F, 0xE1, 0xF8, 0x7E, 0x1F, 0x8F, 0xFF, 0xBF, 0xEF,
0xF3, 0x80, 0xE0, 0x38, 0x0E, 0x00, 0x1F, 0xDF, 0xF7, 0xFF, 0xC7, 0xE1,
0xF8, 0x7E, 0x1F, 0xC7, 0x7F, 0xDF, 0xF3, 0xFC, 0x07, 0x01, 0xC0, 0x70,
0x1C, 0x7F, 0xFF, 0xFF, 0x0E, 0x1C, 0x38, 0x70, 0xE1, 0xC3, 0x80, 0x3E,
0xFE, 0xE0, 0xE0, 0xF8, 0x7E, 0x1F, 0x07, 0x87, 0xFF, 0xFC, 0xE1, 0xC3,
0x87, 0xFF, 0xFF, 0xF8, 0x70, 0xE1, 0xC3, 0x87, 0xF7, 0xE7, 0xC0, 0xE1,
0xF8, 0x7E, 0x1F, 0x87, 0xE1, 0xF8, 0x7E, 0x1F, 0xC7, 0xFF, 0xDF, 0xF3,
0xFC, 0xE0, 0xFE, 0x1D, 0xC7, 0x38, 0xE7, 0xBC, 0x77, 0x0E, 0xE1, 0xFC,
0x1F, 0x03, 0xE0, 0x38, 0x00, 0xE3, 0x8F, 0xC7, 0x1D, 0x8E, 0x33, 0x9E,
0xE7, 0x7D, 0xCE, 0xDB, 0x8D, 0xB6, 0x1F, 0x7C, 0x3C, 0x78, 0x38, 0xE0,
0x71, 0xC0, 0xF1, 0xEF, 0x78, 0xEE, 0x1F, 0xC1, 0xF0, 0x1C, 0x07, 0xC1,
0xFC, 0x3B, 0x8F, 0x7B, 0xC7, 0x80, 0xE0, 0xFC, 0x1D, 0xC7, 0x38, 0xE7,
0x1C, 0x77, 0x0E, 0xE1, 0xFC, 0x1F, 0x03, 0xE0, 0x7C, 0x0F, 0x0F, 0xE1,
0xF8, 0x3E, 0x00, 0xFF, 0xFF, 0xFF, 0x0E, 0x1C, 0x38, 0x38, 0x70, 0xFF,
0xFF, 0xFF, 0x0E, 0x3C, 0xF9, 0xC3, 0x87, 0x0E, 0x1C, 0x79, 0xE3, 0xC7,
0xC3, 0x87, 0x0E, 0x1C, 0x38, 0x7C, 0xF8, 0x70, 0xFF, 0xFF, 0xFF, 0xFF,
0xFF, 0xFF, 0xFF, 0xF0, 0xE1, 0xE3, 0xE1, 0xC3, 0x87, 0x0E, 0x1C, 0x3C,
0x3C, 0x79, 0xF3, 0x87, 0x0E, 0x1C, 0x39, 0xF3, 0xE7, 0x00, 0x30, 0x9F,
0x3F, 0xFF, 0x3E, 0x43, 0x00 };
const GFXglyph Ubuntu_Bold10pt7bGlyphs[] PROGMEM = {
{ 0, 0, 0, 5, 0, 1 }, // 0x20 ' '
{ 0, 3, 14, 5, 1, -13 }, // 0x21 '!'
{ 6, 7, 6, 9, 1, -14 }, // 0x22 '"'
{ 12, 12, 14, 14, 1, -13 }, // 0x23 '#'
{ 33, 9, 17, 11, 1, -14 }, // 0x24 '$'
{ 53, 16, 14, 18, 1, -13 }, // 0x25 '%'
{ 81, 13, 14, 14, 1, -13 }, // 0x26 '&'
{ 104, 3, 6, 5, 1, -14 }, // 0x27 '''
{ 107, 6, 20, 7, 1, -15 }, // 0x28 '('
{ 122, 6, 20, 7, 0, -15 }, // 0x29 ')'
{ 137, 9, 8, 10, 1, -13 }, // 0x2A '*'
{ 146, 11, 11, 13, 1, -11 }, // 0x2B '+'
{ 162, 4, 6, 5, 0, -2 }, // 0x2C ','
{ 165, 6, 3, 8, 1, -7 }, // 0x2D '-'
{ 168, 4, 4, 6, 1, -3 }, // 0x2E '.'
{ 170, 10, 20, 9, -1, -15 }, // 0x2F '/'
{ 195, 9, 14, 11, 1, -13 }, // 0x30 '0'
{ 211, 7, 14, 11, 1, -13 }, // 0x31 '1'
{ 224, 9, 14, 11, 1, -13 }, // 0x32 '2'
{ 240, 9, 14, 11, 1, -13 }, // 0x33 '3'
{ 256, 9, 14, 11, 1, -13 }, // 0x34 '4'
{ 272, 9, 14, 11, 1, -13 }, // 0x35 '5'
{ 288, 9, 14, 11, 1, -13 }, // 0x36 '6'
{ 304, 9, 14, 11, 1, -13 }, // 0x37 '7'
{ 320, 9, 14, 11, 1, -13 }, // 0x38 '8'
{ 336, 9, 14, 11, 1, -13 }, // 0x39 '9'
{ 352, 4, 11, 6, 1, -10 }, // 0x3A ':'
{ 358, 5, 14, 6, 0, -10 }, // 0x3B ';'
{ 367, 10, 9, 11, 1, -9 }, // 0x3C '<'
{ 379, 9, 8, 11, 1, -9 }, // 0x3D '='
{ 388, 9, 9, 11, 1, -9 }, // 0x3E '>'
{ 399, 8, 16, 9, 0, -15 }, // 0x3F '?'
{ 415, 17, 17, 19, 1, -13 }, // 0x40 '@'
{ 452, 15, 14, 15, 0, -13 }, // 0x41 'A'
{ 479, 10, 14, 13, 2, -13 }, // 0x42 'B'
{ 497, 11, 14, 13, 1, -13 }, // 0x43 'C'
{ 517, 12, 14, 15, 2, -13 }, // 0x44 'D'
{ 538, 9, 14, 12, 2, -13 }, // 0x45 'E'
{ 554, 8, 14, 11, 2, -13 }, // 0x46 'F'
{ 568, 11, 14, 14, 1, -13 }, // 0x47 'G'
{ 588, 11, 14, 15, 2, -13 }, // 0x48 'H'
{ 608, 3, 14, 7, 2, -13 }, // 0x49 'I'
{ 614, 9, 14, 11, 0, -13 }, // 0x4A 'J'
{ 630, 12, 14, 14, 2, -13 }, // 0x4B 'K'
{ 651, 9, 14, 11, 2, -13 }, // 0x4C 'L'
{ 667, 15, 14, 17, 1, -13 }, // 0x4D 'M'
{ 694, 11, 14, 15, 2, -13 }, // 0x4E 'N'
{ 714, 14, 14, 16, 1, -13 }, // 0x4F 'O'
{ 739, 10, 14, 13, 2, -13 }, // 0x50 'P'
{ 757, 14, 17, 16, 1, -13 }, // 0x51 'Q'
{ 787, 11, 14, 13, 2, -13 }, // 0x52 'R'
{ 807, 10, 14, 12, 1, -13 }, // 0x53 'S'
{ 825, 11, 14, 11, 0, -13 }, // 0x54 'T'
{ 845, 11, 14, 15, 2, -13 }, // 0x55 'U'
{ 865, 15, 14, 15, 0, -13 }, // 0x56 'V'
{ 892, 19, 14, 19, 0, -13 }, // 0x57 'W'
{ 926, 14, 14, 14, 0, -13 }, // 0x58 'X'
{ 951, 13, 14, 13, 0, -13 }, // 0x59 'Y'
{ 974, 10, 14, 12, 1, -13 }, // 0x5A 'Z'
{ 992, 5, 20, 7, 2, -15 }, // 0x5B '['
{ 1005, 10, 20, 9, -1, -15 }, // 0x5C '\'
{ 1030, 5, 20, 7, 0, -15 }, // 0x5D ']'
{ 1043, 11, 8, 11, 0, -13 }, // 0x5E '^'
{ 1054, 10, 2, 10, 0, 3 }, // 0x5F '_'
{ 1057, 5, 4, 6, 1, -15 }, // 0x60 '`'
{ 1060, 9, 11, 11, 1, -10 }, // 0x61 'a'
{ 1073, 10, 16, 12, 1, -15 }, // 0x62 'b'
{ 1093, 8, 11, 10, 1, -10 }, // 0x63 'c'
{ 1104, 10, 16, 12, 1, -15 }, // 0x64 'd'
{ 1124, 10, 11, 12, 1, -10 }, // 0x65 'e'
{ 1138, 8, 16, 8, 1, -15 }, // 0x66 'f'
{ 1154, 10, 15, 12, 1, -10 }, // 0x67 'g'
{ 1173, 10, 16, 12, 1, -15 }, // 0x68 'h'
{ 1193, 3, 16, 5, 1, -15 }, // 0x69 'i'
{ 1199, 6, 20, 5, -2, -15 }, // 0x6A 'j'
{ 1214, 11, 16, 12, 1, -15 }, // 0x6B 'k'
{ 1236, 5, 16, 6, 1, -15 }, // 0x6C 'l'
{ 1246, 15, 11, 17, 1, -10 }, // 0x6D 'm'
{ 1267, 10, 11, 12, 1, -10 }, // 0x6E 'n'
{ 1281, 10, 11, 12, 1, -10 }, // 0x6F 'o'
{ 1295, 10, 15, 12, 1, -10 }, // 0x70 'p'
{ 1314, 10, 15, 12, 1, -10 }, // 0x71 'q'
{ 1333, 7, 11, 8, 1, -10 }, // 0x72 'r'
{ 1343, 8, 11, 10, 1, -10 }, // 0x73 's'
{ 1354, 7, 14, 9, 1, -13 }, // 0x74 't'
{ 1367, 10, 11, 12, 1, -10 }, // 0x75 'u'
{ 1381, 11, 11, 11, 0, -10 }, // 0x76 'v'
{ 1397, 15, 11, 15, 0, -10 }, // 0x77 'w'
{ 1418, 11, 11, 11, 0, -10 }, // 0x78 'x'
{ 1434, 11, 15, 11, 0, -10 }, // 0x79 'y'
{ 1455, 8, 11, 10, 1, -10 }, // 0x7A 'z'
{ 1466, 7, 20, 8, 1, -15 }, // 0x7B '{'
{ 1484, 3, 20, 7, 2, -15 }, // 0x7C '|'
{ 1492, 7, 20, 8, 0, -15 }, // 0x7D '}'
{ 1510, 10, 5, 11, 1, -8 } }; // 0x7E '~'
const GFXfont Ubuntu_Bold10pt7b PROGMEM = {
(uint8_t *)Ubuntu_Bold10pt7bBitmaps,
(GFXglyph *)Ubuntu_Bold10pt7bGlyphs,
0x20, 0x7E, 23 };
// Approx. 2189 bytes

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,149 @@
const uint8_t Ubuntu_Bold6pt7bBitmaps[] PROGMEM = {
0xFF, 0xCF, 0xDE, 0xF7, 0xB0, 0x36, 0x6F, 0xFB, 0x66, 0xDF, 0xF6, 0x6C,
0x31, 0x9F, 0xFC, 0x79, 0xE3, 0xFF, 0xCC, 0x60, 0x71, 0x9B, 0x63, 0x78,
0x3B, 0x00, 0xDC, 0x1E, 0xC6, 0xD9, 0x8E, 0x38, 0x6C, 0x7C, 0x70, 0xDE,
0xCC, 0xFE, 0x77, 0xFF, 0x36, 0x6C, 0xCC, 0xCC, 0x66, 0x30, 0xC6, 0x63,
0x33, 0x33, 0x66, 0xC0, 0x25, 0x7E, 0xAD, 0x80, 0x30, 0xCF, 0xFF, 0x30,
0xC0, 0x6D, 0xE0, 0xFC, 0xF0, 0x0C, 0x61, 0x86, 0x30, 0xC3, 0x18, 0x61,
0x8C, 0x00, 0x77, 0xF7, 0xBD, 0xEF, 0xEE, 0x3F, 0xB3, 0x33, 0x33, 0x77,
0xC6, 0x23, 0x33, 0xFF, 0x77, 0xC6, 0xE1, 0x8F, 0xFE, 0x18, 0xE7, 0xB6,
0xFF, 0xF1, 0x86, 0x7B, 0xD9, 0xEF, 0x8F, 0xFE, 0x33, 0xB9, 0xEF, 0xEF,
0xEE, 0xFF, 0xCC, 0xC6, 0x73, 0x18, 0x77, 0xF6, 0xED, 0xEF, 0xEE, 0x77,
0xF7, 0xF7, 0x8D, 0xCC, 0xF0, 0xF0, 0x6C, 0x06, 0xDE, 0x04, 0xFF, 0xB0,
0xF8, 0xF0, 0x40, 0xFF, 0xF0, 0x3F, 0xFC, 0x83, 0xC7, 0xC3, 0x7F, 0xC8,
0x00, 0xF7, 0xC6, 0x77, 0x30, 0x0C, 0x60, 0x0F, 0x83, 0xFE, 0x70, 0xEE,
0xFB, 0xDF, 0xBD, 0x9B, 0xD9, 0xBD, 0xFE, 0xEF, 0xE7, 0x00, 0x3F, 0x00,
0xF0, 0x1C, 0x0E, 0x0D, 0x86, 0xC7, 0xF3, 0xF9, 0x8D, 0x83, 0xFB, 0xFC,
0xFE, 0xFF, 0x3F, 0xFE, 0x3D, 0xFE, 0x30, 0xC3, 0x07, 0xCF, 0xF9, 0xFB,
0x3E, 0x3C, 0x79, 0xFF, 0x7C, 0xFF, 0xF1, 0xEF, 0x63, 0xFF, 0xFF, 0xFC,
0x3F, 0xFF, 0x0C, 0x30, 0x3D, 0xFC, 0x30, 0xCF, 0x37, 0xCF, 0xC7, 0x8F,
0x1F, 0xFF, 0xF8, 0xF1, 0xE3, 0xFF, 0xFF, 0x18, 0xC6, 0x31, 0x8F, 0xFE,
0xC7, 0x9B, 0x67, 0x8D, 0x9B, 0x33, 0x63, 0xC3, 0x0C, 0x30, 0xC3, 0x0F,
0xFF, 0x63, 0x31, 0x9D, 0xDA, 0xBD, 0x5E, 0xEF, 0x27, 0x83, 0xC7, 0xCF,
0xDF, 0xBD, 0xF9, 0xF3, 0xE3, 0x38, 0xFB, 0x1E, 0x3C, 0x78, 0xDF, 0x1C,
0xFB, 0xFC, 0xFF, 0xFB, 0x0C, 0x30, 0x38, 0xFB, 0x1E, 0x3C, 0x78, 0xDF,
0x9E, 0x18, 0x18, 0xF9, 0xFB, 0x37, 0xEF, 0x9B, 0x33, 0x63, 0x7F, 0xF1,
0xE7, 0x8F, 0xFE, 0xFF, 0xFF, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0xC7,
0x8F, 0x1E, 0x3C, 0x78, 0xFF, 0xBE, 0xC1, 0xB1, 0x98, 0xCE, 0xE3, 0x61,
0xB0, 0x70, 0x38, 0xC0, 0x78, 0x8D, 0xBB, 0x35, 0x66, 0xAC, 0xF7, 0x8E,
0xE1, 0x8C, 0xC3, 0x66, 0x3C, 0x18, 0x18, 0x3C, 0x66, 0xC3, 0xC3, 0x66,
0x66, 0x3C, 0x18, 0x18, 0x18, 0x18, 0xFF, 0xCC, 0x66, 0x33, 0xFF, 0xFF,
0x6D, 0xB6, 0xDF, 0x80, 0xC1, 0x86, 0x18, 0x30, 0xC3, 0x06, 0x18, 0x60,
0xC0, 0xFD, 0xB6, 0xDB, 0x7F, 0x80, 0x10, 0x71, 0xB3, 0x2C, 0x60, 0xFF,
0xF0, 0x5C, 0x80, 0xF7, 0xC7, 0xFD, 0xFC, 0xC6, 0x31, 0xEF, 0xEF, 0x7F,
0xF0, 0x7F, 0xCC, 0xF7, 0x18, 0xC6, 0xFF, 0xEF, 0x7F, 0x78, 0x76, 0xFF,
0x8F, 0xBC, 0x7F, 0xCF, 0xFC, 0xCC, 0xC0, 0x7F, 0xF7, 0xF7, 0x8F, 0xFE,
0xC6, 0x31, 0xEF, 0xEF, 0x7B, 0xD8, 0xF3, 0xFF, 0xC0, 0x33, 0x03, 0x33,
0x33, 0x3F, 0xE0, 0xC3, 0x0C, 0x33, 0xDB, 0xCD, 0xB6, 0xCC, 0xDB, 0x6D,
0xB7, 0x60, 0xFE, 0xFF, 0xDB, 0xDB, 0xDB, 0xDB, 0xF7, 0xF7, 0xBD, 0xEC,
0x77, 0xF7, 0xBF, 0xB8, 0xF7, 0xF7, 0xBF, 0xFB, 0x18, 0x7F, 0xF7, 0xBF,
0xBC, 0x63, 0xFF, 0xCC, 0xCC, 0x7C, 0xE7, 0x3E, 0xCC, 0xFF, 0xCC, 0xF7,
0xDE, 0xF7, 0xBF, 0xBC, 0xC7, 0xDD, 0xB3, 0x63, 0x87, 0x00, 0xCD, 0xEE,
0xD7, 0x4A, 0xA7, 0x71, 0x10, 0xC6, 0xD8, 0xE1, 0xC6, 0xD8, 0xC0, 0xC7,
0xDD, 0xB3, 0x63, 0x87, 0x3C, 0x78, 0xFF, 0x66, 0xFF, 0x37, 0x66, 0xEE,
0x66, 0x73, 0xFF, 0xFF, 0xFC, 0xCE, 0x66, 0x77, 0x66, 0xEC, 0x67, 0xF9,
0x80 };
const GFXglyph Ubuntu_Bold6pt7bGlyphs[] PROGMEM = {
{ 0, 0, 0, 3, 0, 1 }, // 0x20 ' '
{ 0, 2, 8, 4, 1, -7 }, // 0x21 '!'
{ 2, 5, 4, 6, 1, -8 }, // 0x22 '"'
{ 5, 7, 8, 9, 1, -7 }, // 0x23 '#'
{ 12, 5, 12, 7, 1, -9 }, // 0x24 '$'
{ 20, 11, 8, 11, 0, -7 }, // 0x25 '%'
{ 31, 8, 8, 9, 1, -7 }, // 0x26 '&'
{ 39, 2, 4, 4, 1, -8 }, // 0x27 '''
{ 40, 4, 11, 4, 1, -8 }, // 0x28 '('
{ 46, 4, 11, 4, -1, -8 }, // 0x29 ')'
{ 52, 5, 5, 6, 1, -7 }, // 0x2A '*'
{ 56, 6, 6, 8, 1, -6 }, // 0x2B '+'
{ 61, 3, 4, 4, 0, -1 }, // 0x2C ','
{ 63, 3, 2, 5, 1, -3 }, // 0x2D '-'
{ 64, 2, 2, 4, 1, -1 }, // 0x2E '.'
{ 65, 6, 11, 5, 0, -8 }, // 0x2F '/'
{ 74, 5, 8, 7, 1, -7 }, // 0x30 '0'
{ 79, 4, 8, 7, 1, -7 }, // 0x31 '1'
{ 83, 5, 8, 7, 1, -7 }, // 0x32 '2'
{ 88, 5, 8, 7, 1, -7 }, // 0x33 '3'
{ 93, 6, 8, 7, 1, -7 }, // 0x34 '4'
{ 99, 5, 8, 7, 1, -7 }, // 0x35 '5'
{ 104, 5, 8, 7, 1, -7 }, // 0x36 '6'
{ 109, 5, 8, 7, 1, -7 }, // 0x37 '7'
{ 114, 5, 8, 7, 1, -7 }, // 0x38 '8'
{ 119, 5, 8, 7, 1, -7 }, // 0x39 '9'
{ 124, 2, 6, 4, 1, -5 }, // 0x3A ':'
{ 126, 3, 8, 4, 0, -5 }, // 0x3B ';'
{ 129, 6, 7, 7, 0, -6 }, // 0x3C '<'
{ 135, 6, 5, 8, 1, -5 }, // 0x3D '='
{ 139, 6, 7, 7, 1, -6 }, // 0x3E '>'
{ 145, 5, 9, 5, 0, -8 }, // 0x3F '?'
{ 151, 12, 12, 12, 0, -8 }, // 0x40 '@'
{ 169, 9, 8, 9, 0, -7 }, // 0x41 'A'
{ 178, 6, 8, 8, 1, -7 }, // 0x42 'B'
{ 184, 6, 8, 8, 1, -7 }, // 0x43 'C'
{ 190, 7, 8, 9, 1, -7 }, // 0x44 'D'
{ 197, 5, 8, 7, 1, -7 }, // 0x45 'E'
{ 202, 6, 8, 7, 1, -7 }, // 0x46 'F'
{ 208, 6, 8, 8, 1, -7 }, // 0x47 'G'
{ 214, 7, 8, 9, 1, -7 }, // 0x48 'H'
{ 221, 2, 8, 4, 1, -7 }, // 0x49 'I'
{ 223, 5, 8, 6, 0, -7 }, // 0x4A 'J'
{ 228, 7, 8, 8, 1, -7 }, // 0x4B 'K'
{ 235, 6, 8, 7, 1, -7 }, // 0x4C 'L'
{ 241, 9, 8, 11, 1, -7 }, // 0x4D 'M'
{ 250, 7, 8, 9, 1, -7 }, // 0x4E 'N'
{ 257, 7, 8, 9, 1, -7 }, // 0x4F 'O'
{ 264, 6, 8, 8, 1, -7 }, // 0x50 'P'
{ 270, 7, 10, 9, 1, -7 }, // 0x51 'Q'
{ 279, 7, 8, 8, 1, -7 }, // 0x52 'R'
{ 286, 5, 8, 7, 1, -7 }, // 0x53 'S'
{ 291, 8, 8, 8, 0, -7 }, // 0x54 'T'
{ 299, 7, 8, 9, 1, -7 }, // 0x55 'U'
{ 306, 9, 8, 9, 0, -7 }, // 0x56 'V'
{ 315, 11, 8, 11, 0, -7 }, // 0x57 'W'
{ 326, 8, 8, 8, 0, -7 }, // 0x58 'X'
{ 334, 8, 8, 8, 0, -7 }, // 0x59 'Y'
{ 342, 5, 8, 7, 1, -7 }, // 0x5A 'Z'
{ 347, 3, 11, 4, 1, -8 }, // 0x5B '['
{ 352, 6, 11, 5, 0, -8 }, // 0x5C '\'
{ 361, 3, 11, 4, 0, -8 }, // 0x5D ']'
{ 366, 7, 5, 7, 0, -7 }, // 0x5E '^'
{ 371, 6, 2, 6, 0, 2 }, // 0x5F '_'
{ 373, 3, 3, 3, 1, -9 }, // 0x60 '`'
{ 375, 5, 6, 7, 1, -5 }, // 0x61 'a'
{ 379, 5, 9, 7, 1, -8 }, // 0x62 'b'
{ 385, 4, 6, 6, 1, -5 }, // 0x63 'c'
{ 388, 5, 9, 7, 1, -8 }, // 0x64 'd'
{ 394, 5, 6, 7, 1, -5 }, // 0x65 'e'
{ 398, 4, 9, 5, 1, -8 }, // 0x66 'f'
{ 403, 5, 8, 7, 1, -5 }, // 0x67 'g'
{ 408, 5, 9, 7, 1, -8 }, // 0x68 'h'
{ 414, 2, 9, 4, 1, -8 }, // 0x69 'i'
{ 417, 4, 11, 4, -1, -8 }, // 0x6A 'j'
{ 423, 6, 9, 7, 1, -8 }, // 0x6B 'k'
{ 430, 3, 9, 4, 1, -8 }, // 0x6C 'l'
{ 434, 8, 6, 10, 1, -5 }, // 0x6D 'm'
{ 440, 5, 6, 7, 1, -5 }, // 0x6E 'n'
{ 444, 5, 6, 7, 1, -5 }, // 0x6F 'o'
{ 448, 5, 8, 7, 1, -5 }, // 0x70 'p'
{ 453, 5, 8, 7, 1, -5 }, // 0x71 'q'
{ 458, 4, 6, 5, 1, -5 }, // 0x72 'r'
{ 461, 4, 6, 6, 1, -5 }, // 0x73 's'
{ 464, 4, 8, 6, 1, -7 }, // 0x74 't'
{ 468, 5, 6, 7, 1, -5 }, // 0x75 'u'
{ 472, 7, 6, 7, 0, -5 }, // 0x76 'v'
{ 478, 9, 6, 9, 0, -5 }, // 0x77 'w'
{ 485, 7, 6, 7, 0, -5 }, // 0x78 'x'
{ 491, 7, 8, 7, 0, -5 }, // 0x79 'y'
{ 498, 4, 6, 6, 1, -5 }, // 0x7A 'z'
{ 501, 4, 10, 4, 0, -7 }, // 0x7B '{'
{ 506, 2, 11, 4, 1, -8 }, // 0x7C '|'
{ 509, 4, 10, 4, 0, -7 }, // 0x7D '}'
{ 514, 6, 3, 7, 1, -4 } }; // 0x7E '~'
const GFXfont Ubuntu_Bold6pt7b PROGMEM = {
(uint8_t *)Ubuntu_Bold6pt7bBitmaps,
(GFXglyph *)Ubuntu_Bold6pt7bGlyphs,
0x20, 0x7E, 14 };
// Approx. 1189 bytes

View File

@ -0,0 +1,182 @@
const uint8_t Ubuntu_Bold8pt7bBitmaps[] PROGMEM = {
0xFF, 0xFC, 0xFC, 0xDE, 0xF7, 0xBD, 0x80, 0x1B, 0x0D, 0x87, 0xDF, 0xFF,
0xF9, 0xB3, 0xFF, 0xFF, 0x6C, 0x36, 0x1B, 0x00, 0x18, 0x30, 0xFF, 0xFC,
0x38, 0x1C, 0x1E, 0x0E, 0x0C, 0x1F, 0xF7, 0xC3, 0x06, 0x00, 0x78, 0x63,
0xF3, 0x0C, 0xCC, 0x33, 0x60, 0xCF, 0xFB, 0xFF, 0xF7, 0xFC, 0xC1, 0xB3,
0x0C, 0xCC, 0x33, 0xF1, 0x87, 0x80, 0x3C, 0x1F, 0x86, 0x61, 0x98, 0x3C,
0x1E, 0x6C, 0xDB, 0x1C, 0xC7, 0x3F, 0xE7, 0xDC, 0xFF, 0xC0, 0x13, 0x66,
0xCC, 0xCC, 0xCC, 0xCC, 0x66, 0x31, 0x8C, 0x66, 0x33, 0x33, 0x33, 0x33,
0x66, 0xC8, 0x39, 0xFF, 0xF8, 0x86, 0xDD, 0xD1, 0x00, 0x18, 0x18, 0x18,
0xFF, 0xFF, 0x18, 0x18, 0x18, 0x6D, 0xEC, 0xFF, 0xC0, 0xFF, 0x80, 0x06,
0x1C, 0x30, 0x60, 0xC3, 0x06, 0x0C, 0x30, 0x60, 0xC3, 0x06, 0x0C, 0x38,
0x60, 0x38, 0xFB, 0xBE, 0x3C, 0x78, 0xF1, 0xE3, 0xEE, 0xF8, 0xE0, 0x1B,
0xFE, 0xB1, 0x8C, 0x63, 0x18, 0xC6, 0x7D, 0xFD, 0x18, 0x30, 0xE3, 0x8E,
0x38, 0xE1, 0xFF, 0xF8, 0x7D, 0xFC, 0x18, 0x33, 0xE7, 0x81, 0x83, 0x87,
0xFF, 0xE0, 0x06, 0x0E, 0x1E, 0x3E, 0x36, 0x66, 0xE6, 0xFF, 0xFF, 0x06,
0x06, 0x7E, 0xFD, 0x83, 0x0F, 0x9F, 0x83, 0x83, 0x07, 0xFB, 0xE0, 0x1C,
0x79, 0xC7, 0x0F, 0xDF, 0xF1, 0xE3, 0xC6, 0xF8, 0xE0, 0xFF, 0xFC, 0x30,
0xE1, 0x87, 0x0C, 0x18, 0x60, 0xC1, 0x80, 0x3C, 0xFF, 0x1E, 0x3E, 0xEF,
0xBF, 0xE3, 0xC7, 0xFD, 0xF0, 0x38, 0xFB, 0x1E, 0x3C, 0x7F, 0xDF, 0x87,
0x1C, 0xF1, 0xC0, 0xFF, 0x80, 0x3F, 0xE0, 0x77, 0x70, 0x00, 0x06, 0x66,
0xCC, 0x06, 0x3E, 0xF8, 0xC0, 0xF8, 0x3F, 0x06, 0xFF, 0xFF, 0x00, 0x00,
0xFF, 0xFF, 0x60, 0x7C, 0x1F, 0x03, 0x1F, 0xFC, 0x60, 0x7D, 0xFC, 0x18,
0x30, 0xC3, 0x0C, 0x18, 0x00, 0x70, 0xE1, 0xC0, 0x0F, 0xC0, 0x7F, 0xC3,
0x83, 0x98, 0x06, 0xE7, 0xCF, 0x3F, 0x3D, 0x8C, 0xF6, 0x33, 0xD8, 0xCF,
0xBF, 0xE6, 0x7F, 0x1E, 0x00, 0x3F, 0xC0, 0x3F, 0x00, 0x0E, 0x01, 0xC0,
0x7C, 0x0D, 0x83, 0xB8, 0x63, 0x0C, 0x63, 0xFE, 0x7F, 0xCC, 0x1B, 0x01,
0x80, 0xFC, 0x7F, 0xB0, 0xD8, 0x6F, 0xE7, 0xFB, 0x07, 0x83, 0xC3, 0xFF,
0xBF, 0x80, 0x1F, 0x1F, 0xD8, 0x18, 0x0C, 0x06, 0x03, 0x01, 0x80, 0x60,
0x3F, 0xC7, 0xC0, 0xFE, 0x3F, 0xCC, 0x3B, 0x07, 0xC0, 0xF0, 0x3C, 0x0F,
0x07, 0xC3, 0xBF, 0xCF, 0xE0, 0xFF, 0xFF, 0xC0, 0xC0, 0xFE, 0xFE, 0xC0,
0xC0, 0xC0, 0xFF, 0xFF, 0xFF, 0xFF, 0xC0, 0xC0, 0xFE, 0xFE, 0xC0, 0xC0,
0xC0, 0xC0, 0xC0, 0x1F, 0x1F, 0xD8, 0x18, 0x0C, 0x06, 0x0F, 0x07, 0x83,
0x71, 0xBF, 0xC7, 0xE0, 0xC1, 0xE0, 0xF0, 0x78, 0x3F, 0xFF, 0xFF, 0x07,
0x83, 0xC1, 0xE0, 0xF0, 0x60, 0xFF, 0xFF, 0xFC, 0x06, 0x0C, 0x18, 0x30,
0x60, 0xC1, 0x83, 0x07, 0xF9, 0xE0, 0xC1, 0xB0, 0xCC, 0x63, 0x30, 0xF8,
0x3C, 0x0D, 0x83, 0x30, 0xC6, 0x30, 0xCC, 0x18, 0xC0, 0xC0, 0xC0, 0xC0,
0xC0, 0xC0, 0xC0, 0xC0, 0xC0, 0xFF, 0xFF, 0x60, 0x33, 0x83, 0x9C, 0x1C,
0xF1, 0xED, 0x8D, 0xEE, 0xEF, 0x36, 0x79, 0xF3, 0xC7, 0x1E, 0x38, 0xF0,
0x06, 0xC0, 0xF8, 0x3F, 0x0F, 0xE3, 0xDC, 0xF3, 0xBC, 0x7F, 0x0F, 0xC1,
0xF0, 0x7C, 0x0C, 0x1F, 0x07, 0xF1, 0xC7, 0x70, 0x7C, 0x07, 0x80, 0xF0,
0x1F, 0x07, 0x71, 0xCF, 0xF8, 0x7C, 0x00, 0xFC, 0xFE, 0xC3, 0xC3, 0xC3,
0xFE, 0xFC, 0xC0, 0xC0, 0xC0, 0xC0, 0x1F, 0x07, 0xF1, 0xC7, 0x70, 0x7C,
0x07, 0x80, 0xF0, 0x1F, 0x07, 0x71, 0xCF, 0xF0, 0xF8, 0x07, 0x00, 0x7C,
0x07, 0x80, 0xFC, 0x7F, 0x30, 0xD8, 0x6C, 0x37, 0xF3, 0xE1, 0x98, 0xC6,
0x63, 0xB0, 0xE0, 0x3D, 0xFF, 0x06, 0x0F, 0x0F, 0x87, 0x83, 0x07, 0xFD,
0xF0, 0xFF, 0xFF, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18, 0x18,
0xC1, 0xE0, 0xF0, 0x78, 0x3C, 0x1E, 0x0F, 0x07, 0x83, 0xE3, 0xBF, 0x8F,
0x80, 0xC0, 0x6C, 0x19, 0x83, 0x38, 0xE3, 0x18, 0x63, 0x06, 0xC0, 0xD8,
0x0E, 0x01, 0xC0, 0x38, 0x00, 0xC0, 0x07, 0x87, 0x0D, 0x8E, 0x33, 0x1C,
0x66, 0x6C, 0xC6, 0xDB, 0x0D, 0xB6, 0x1B, 0x6C, 0x1C, 0x70, 0x38, 0xE0,
0x71, 0xC0, 0xE0, 0xEC, 0x18, 0xC6, 0x0D, 0x80, 0xE0, 0x1C, 0x03, 0x80,
0xD8, 0x31, 0x8C, 0x1B, 0x83, 0x80, 0xC0, 0xD8, 0x67, 0x38, 0xCC, 0x1E,
0x07, 0x80, 0xC0, 0x30, 0x0C, 0x03, 0x00, 0xC0, 0xFF, 0xFF, 0x06, 0x0C,
0x1C, 0x18, 0x30, 0x70, 0x60, 0xFF, 0xFF, 0xFF, 0xF1, 0x8C, 0x63, 0x18,
0xC6, 0x31, 0x8C, 0x63, 0xFF, 0xC1, 0xC1, 0x83, 0x06, 0x06, 0x0C, 0x18,
0x18, 0x30, 0x60, 0x60, 0xC1, 0x83, 0x83, 0xFF, 0xC6, 0x31, 0x8C, 0x63,
0x18, 0xC6, 0x31, 0x8F, 0xFF, 0x08, 0x0E, 0x0F, 0x86, 0xC7, 0x77, 0x1D,
0x04, 0xFF, 0xFF, 0x4E, 0x72, 0x7C, 0xFC, 0x1B, 0xFF, 0xF8, 0xFF, 0xBF,
0xC1, 0x83, 0x06, 0x0F, 0x9F, 0xB3, 0xE3, 0xC7, 0x9F, 0xF7, 0xC0, 0x3D,
0xFE, 0x30, 0xC3, 0x87, 0xCF, 0x06, 0x0C, 0x18, 0x33, 0xEF, 0xF9, 0xE3,
0xC7, 0xCD, 0xF9, 0xF0, 0x38, 0xFB, 0x1F, 0xFF, 0xF8, 0x1F, 0x1E, 0x7F,
0xF1, 0x8F, 0xFF, 0x18, 0xC6, 0x31, 0x80, 0x3E, 0xFF, 0x9E, 0x3C, 0x7C,
0xDF, 0x9F, 0x06, 0xFB, 0xE0, 0xC1, 0x83, 0x06, 0x0F, 0xDF, 0xF1, 0xE3,
0xC7, 0x8F, 0x1E, 0x30, 0xFC, 0xFF, 0xFF, 0x33, 0x30, 0x33, 0x33, 0x33,
0x33, 0x3F, 0xE0, 0xC0, 0xC0, 0xC0, 0xC0, 0xC6, 0xCC, 0xD8, 0xF0, 0xD8,
0xCC, 0xC6, 0xC7, 0xDB, 0x6D, 0xB6, 0xDB, 0xB0, 0xFD, 0xEF, 0xFF, 0xC6,
0x3C, 0x63, 0xC6, 0x3C, 0x63, 0xC6, 0x3C, 0x63, 0xFD, 0xFF, 0x1E, 0x3C,
0x78, 0xF1, 0xE3, 0x3C, 0x7E, 0xE7, 0xC3, 0xC3, 0xE7, 0x7E, 0x3C, 0xF9,
0xFB, 0x3E, 0x3C, 0x79, 0xFF, 0x7C, 0xC1, 0x83, 0x00, 0x3E, 0xFF, 0x9E,
0x3C, 0x7C, 0xDF, 0xBF, 0x06, 0x0C, 0x18, 0xFF, 0xF1, 0x8C, 0x63, 0x18,
0x7F, 0xEC, 0x3E, 0x7C, 0x3F, 0xFE, 0xC6, 0x3F, 0xFC, 0x63, 0x18, 0xFB,
0xC0, 0xC7, 0x8F, 0x1E, 0x3C, 0x78, 0xFF, 0xBF, 0xC1, 0xB1, 0x98, 0xCE,
0xE3, 0x61, 0xF0, 0x70, 0x38, 0xC6, 0x79, 0xCD, 0xBB, 0x35, 0x66, 0xAC,
0x77, 0x0E, 0xE1, 0x8C, 0xE3, 0xBB, 0x8D, 0x83, 0x81, 0xC1, 0xB1, 0xDD,
0xC7, 0xE3, 0xB1, 0x98, 0xCE, 0xE3, 0x61, 0xF0, 0x70, 0x38, 0x18, 0x7C,
0x3C, 0x00, 0xFF, 0xF1, 0x8E, 0x71, 0x8F, 0xFF, 0x3B, 0xD8, 0xC6, 0x31,
0x98, 0xC3, 0x18, 0xC6, 0x31, 0xE7, 0xFF, 0xFF, 0xFF, 0xFF, 0xE7, 0x8C,
0x63, 0x18, 0xC3, 0x19, 0x8C, 0x63, 0x1B, 0xDC, 0x73, 0xFF, 0xCE };
const GFXglyph Ubuntu_Bold8pt7bGlyphs[] PROGMEM = {
{ 0, 0, 0, 4, 0, 1 }, // 0x20 ' '
{ 0, 2, 11, 4, 1, -10 }, // 0x21 '!'
{ 3, 5, 5, 7, 1, -11 }, // 0x22 '"'
{ 7, 9, 11, 11, 1, -10 }, // 0x23 '#'
{ 20, 7, 15, 9, 1, -12 }, // 0x24 '$'
{ 34, 14, 11, 16, 1, -10 }, // 0x25 '%'
{ 54, 10, 11, 11, 1, -10 }, // 0x26 '&'
{ 68, 2, 5, 4, 1, -11 }, // 0x27 '''
{ 70, 4, 16, 6, 1, -12 }, // 0x28 '('
{ 78, 4, 16, 6, 1, -12 }, // 0x29 ')'
{ 86, 7, 7, 8, 1, -10 }, // 0x2A '*'
{ 93, 8, 8, 10, 1, -8 }, // 0x2B '+'
{ 101, 3, 5, 4, 0, -1 }, // 0x2C ','
{ 103, 5, 2, 7, 1, -5 }, // 0x2D '-'
{ 105, 3, 3, 5, 1, -2 }, // 0x2E '.'
{ 107, 7, 16, 7, 0, -12 }, // 0x2F '/'
{ 121, 7, 11, 9, 1, -10 }, // 0x30 '0'
{ 131, 5, 11, 9, 1, -10 }, // 0x31 '1'
{ 138, 7, 11, 9, 1, -10 }, // 0x32 '2'
{ 148, 7, 11, 9, 1, -10 }, // 0x33 '3'
{ 158, 8, 11, 9, 1, -10 }, // 0x34 '4'
{ 169, 7, 11, 9, 1, -10 }, // 0x35 '5'
{ 179, 7, 11, 9, 1, -10 }, // 0x36 '6'
{ 189, 7, 11, 9, 1, -10 }, // 0x37 '7'
{ 199, 7, 11, 9, 1, -10 }, // 0x38 '8'
{ 209, 7, 11, 9, 1, -10 }, // 0x39 '9'
{ 219, 3, 9, 5, 1, -8 }, // 0x3A ':'
{ 223, 4, 12, 5, 0, -8 }, // 0x3B ';'
{ 229, 8, 7, 9, 1, -7 }, // 0x3C '<'
{ 236, 8, 6, 10, 1, -7 }, // 0x3D '='
{ 242, 8, 7, 9, 0, -7 }, // 0x3E '>'
{ 249, 7, 12, 7, 0, -11 }, // 0x3F '?'
{ 260, 14, 14, 16, 1, -10 }, // 0x40 '@'
{ 285, 11, 11, 11, 0, -10 }, // 0x41 'A'
{ 301, 9, 11, 11, 1, -10 }, // 0x42 'B'
{ 314, 9, 11, 11, 1, -10 }, // 0x43 'C'
{ 327, 10, 11, 12, 1, -10 }, // 0x44 'D'
{ 341, 8, 11, 10, 1, -10 }, // 0x45 'E'
{ 352, 8, 11, 9, 1, -10 }, // 0x46 'F'
{ 363, 9, 11, 11, 1, -10 }, // 0x47 'G'
{ 376, 9, 11, 11, 1, -10 }, // 0x48 'H'
{ 389, 2, 11, 4, 1, -10 }, // 0x49 'I'
{ 392, 7, 11, 8, 0, -10 }, // 0x4A 'J'
{ 402, 10, 11, 11, 1, -10 }, // 0x4B 'K'
{ 416, 8, 11, 9, 1, -10 }, // 0x4C 'L'
{ 427, 13, 11, 15, 1, -10 }, // 0x4D 'M'
{ 445, 10, 11, 12, 1, -10 }, // 0x4E 'N'
{ 459, 11, 11, 13, 1, -10 }, // 0x4F 'O'
{ 475, 8, 11, 10, 1, -10 }, // 0x50 'P'
{ 486, 11, 14, 13, 1, -10 }, // 0x51 'Q'
{ 506, 9, 11, 10, 1, -10 }, // 0x52 'R'
{ 519, 7, 11, 9, 1, -10 }, // 0x53 'S'
{ 529, 8, 11, 8, 0, -10 }, // 0x54 'T'
{ 540, 9, 11, 11, 1, -10 }, // 0x55 'U'
{ 553, 11, 11, 11, 0, -10 }, // 0x56 'V'
{ 569, 15, 11, 15, 0, -10 }, // 0x57 'W'
{ 590, 11, 11, 11, 0, -10 }, // 0x58 'X'
{ 606, 10, 11, 10, 0, -10 }, // 0x59 'Y'
{ 620, 8, 11, 10, 1, -10 }, // 0x5A 'Z'
{ 631, 5, 16, 6, 1, -12 }, // 0x5B '['
{ 641, 7, 16, 7, 0, -12 }, // 0x5C '\'
{ 655, 5, 16, 6, 0, -12 }, // 0x5D ']'
{ 665, 9, 7, 9, 0, -10 }, // 0x5E '^'
{ 673, 8, 2, 8, 0, 2 }, // 0x5F '_'
{ 675, 4, 4, 5, 1, -12 }, // 0x60 '`'
{ 677, 7, 8, 9, 1, -7 }, // 0x61 'a'
{ 684, 7, 12, 9, 1, -11 }, // 0x62 'b'
{ 695, 6, 8, 8, 1, -7 }, // 0x63 'c'
{ 701, 7, 12, 9, 1, -11 }, // 0x64 'd'
{ 712, 7, 8, 9, 1, -7 }, // 0x65 'e'
{ 719, 5, 12, 6, 1, -11 }, // 0x66 'f'
{ 727, 7, 11, 9, 1, -7 }, // 0x67 'g'
{ 737, 7, 12, 9, 1, -11 }, // 0x68 'h'
{ 748, 2, 12, 4, 1, -11 }, // 0x69 'i'
{ 751, 4, 15, 4, -1, -11 }, // 0x6A 'j'
{ 759, 8, 12, 9, 1, -11 }, // 0x6B 'k'
{ 771, 3, 12, 4, 1, -11 }, // 0x6C 'l'
{ 776, 12, 8, 14, 1, -7 }, // 0x6D 'm'
{ 788, 7, 8, 9, 1, -7 }, // 0x6E 'n'
{ 795, 8, 8, 10, 1, -7 }, // 0x6F 'o'
{ 803, 7, 11, 9, 1, -7 }, // 0x70 'p'
{ 813, 7, 11, 9, 1, -7 }, // 0x71 'q'
{ 823, 5, 8, 6, 1, -7 }, // 0x72 'r'
{ 828, 6, 8, 8, 1, -7 }, // 0x73 's'
{ 834, 5, 10, 7, 1, -9 }, // 0x74 't'
{ 841, 7, 8, 9, 1, -7 }, // 0x75 'u'
{ 848, 9, 8, 9, 0, -7 }, // 0x76 'v'
{ 857, 11, 8, 11, 0, -7 }, // 0x77 'w'
{ 868, 9, 8, 9, 0, -7 }, // 0x78 'x'
{ 877, 9, 11, 9, 0, -7 }, // 0x79 'y'
{ 890, 6, 8, 8, 1, -7 }, // 0x7A 'z'
{ 896, 5, 16, 5, 0, -12 }, // 0x7B '{'
{ 906, 2, 16, 4, 1, -12 }, // 0x7C '|'
{ 910, 5, 16, 5, 0, -12 }, // 0x7D '}'
{ 920, 8, 3, 9, 1, -5 } }; // 0x7E '~'
const GFXfont Ubuntu_Bold8pt7b PROGMEM = {
(uint8_t *)Ubuntu_Bold8pt7bBitmaps,
(GFXglyph *)Ubuntu_Bold8pt7bGlyphs,
0x20, 0x7E, 18 };
// Approx. 1595 bytes

180
lib/obp60task/config.json Normal file
View File

@ -0,0 +1,180 @@
[
{
"name": "obp60Config",
"label": "Logging",
"type": "boolean",
"default": "false",
"description": "Switch on logging of position acquired/failed",
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
},
{
"name": "useGPS",
"label": "GPS NEO-6M",
"type": "boolean",
"default": "false",
"description": "Using internal GPS modul NEO-6M",
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
},
{
"name": "useBME280",
"label": "BME280",
"type": "boolean",
"default": "false",
"description": "Using internal BME280 modul",
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
},
{
"name": "use1Wire",
"label": "1Wire",
"type": "boolean",
"default": "false",
"description": "Using external 1Wirew devices (DS18B20)",
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
},
{
"name": "powerMode",
"label": "Power Mode",
"type": "list",
"default": "Max Power",
"description": "Settings for power mode",
"list": [
"Max Power",
"Only 3.3V",
"Only 5.0V",
"Min Power"
],
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
},
{
"name": "display",
"label": "Display Mode",
"type": "list",
"default": "Logo + QR Code",
"description": "Settings for display mode",
"list": [
"White Screen",
"Logo",
"Logo + QR Code",
"Off"
],
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
},
{
"name": "backlight",
"label": "Backlight Mode",
"type": "list",
"default": "Off",
"description": "Settings for display mode",
"list": [
"Off",
"Control by Sun",
"Control by Bus",
"Control by Time",
"Control by Key",
"On"
],
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
},
{
"name": "flashLED",
"label": "Flash LED Mode",
"type": "list",
"default": "Off",
"description": "Settings for flash LED",
"list": [
"Off",
"TCP/UDP Data",
"GPS Fix",
"Limits Overrun"
],
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
},
{
"name": "buzzerError",
"label": "Buzzer Error",
"type": "boolean",
"default": "false",
"description": "Settings for buzzer",
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
},
{
"name": "buzzerGps",
"label": "Buzzer GPS Fix",
"type": "boolean",
"default": "false",
"description": "Settings for buzzer",
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
},
{
"name": "buzzerLim",
"label": "Buzzer by Limits",
"type": "boolean",
"default": "false",
"description": "Tone by limit overrun",
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
},
{
"name": "buzzerMode",
"label": "Buzzer Mode",
"type": "list",
"default": "Off",
"description": "Settings for Buzzer Mode",
"list": [
"Off",
"Short Single Beep",
"Longer Single Beep",
"Beep until Confirmation"
],
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
},
{
"name": "buzzerPower",
"label": "Buzzer Power",
"type": "number",
"default": "50",
"check": "checkMinMax",
"min": 0,
"max": 100,
"description": "Buzzer Loudness 0...100%",
"category": "OBP60",
"capabilities": {
"obp60":"true"
}
}
]

View File

@ -0,0 +1,5 @@
# Name, Type, SubType, Offset, Size, Flags
nvs, data, nvs, 0x9000, 0x4000,
otadata, data, ota, 0xd000, 0x2000,
app0, app, ota_0, 0x10000, 0x1f0000,
app1, app, ota_1, 0x200000,0x1f0000,
1 # Name Type SubType Offset Size Flags
2 nvs data nvs 0x9000 0x4000
3 otadata data ota 0xd000 0x2000
4 app0 app ota_0 0x10000 0x1f0000
5 app1 app ota_1 0x200000 0x1f0000

View File

@ -0,0 +1,20 @@
[platformio]
#if you want a pio run to only build
#your special environments you can set this here
#by uncommenting the next line
default_envs = nodemcu32s_obp60
[env:nodemcu32s_obp60]
board_build.partitions = lib/obp60task/partitions_obp60.csv
board = nodemcu-32s
lib_deps =
${env.lib_deps}
lib_deps =
blemasle/MCP23017 @ 2.0.0
adafruit/Adafruit BusIO @ 1.5.0
zinggjm/GxEPD @ 3.1.0
build_flags=
-D BOARD_NODEMCU32S_OBP60
${env.build_flags}
upload_port = COM6
upload_protocol = esptool
monitor_speed = 115200

876
lib/obp60task/qrcode.c Normal file
View File

@ -0,0 +1,876 @@
/**
* The MIT License (MIT)
*
* This library is written and maintained by Richard Moore.
* Major parts were derived from Project Nayuki's library.
*
* Copyright (c) 2017 Richard Moore (https://github.com/ricmoo/QRCode)
* Copyright (c) 2017 Project Nayuki (https://www.nayuki.io/page/qr-code-generator-library)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
/**
* Special thanks to Nayuki (https://www.nayuki.io/) from which this library was
* heavily inspired and compared against.
*
* See: https://github.com/nayuki/QR-Code-generator/tree/master/cpp
*/
#include "qrcode.h"
#include <stdlib.h>
#include <string.h>
#pragma mark - Error Correction Lookup tables
#if LOCK_VERSION == 0
static const uint16_t NUM_ERROR_CORRECTION_CODEWORDS[4][40] = {
// 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40 Error correction level
{ 10, 16, 26, 36, 48, 64, 72, 88, 110, 130, 150, 176, 198, 216, 240, 280, 308, 338, 364, 416, 442, 476, 504, 560, 588, 644, 700, 728, 784, 812, 868, 924, 980, 1036, 1064, 1120, 1204, 1260, 1316, 1372}, // Medium
{ 7, 10, 15, 20, 26, 36, 40, 48, 60, 72, 80, 96, 104, 120, 132, 144, 168, 180, 196, 224, 224, 252, 270, 300, 312, 336, 360, 390, 420, 450, 480, 510, 540, 570, 570, 600, 630, 660, 720, 750}, // Low
{ 17, 28, 44, 64, 88, 112, 130, 156, 192, 224, 264, 308, 352, 384, 432, 480, 532, 588, 650, 700, 750, 816, 900, 960, 1050, 1110, 1200, 1260, 1350, 1440, 1530, 1620, 1710, 1800, 1890, 1980, 2100, 2220, 2310, 2430}, // High
{ 13, 22, 36, 52, 72, 96, 108, 132, 160, 192, 224, 260, 288, 320, 360, 408, 448, 504, 546, 600, 644, 690, 750, 810, 870, 952, 1020, 1050, 1140, 1200, 1290, 1350, 1440, 1530, 1590, 1680, 1770, 1860, 1950, 2040}, // Quartile
};
static const uint8_t NUM_ERROR_CORRECTION_BLOCKS[4][40] = {
// Version: (note that index 0 is for padding, and is set to an illegal value)
// 1, 2, 3, 4, 5, 6, 7, 8, 9,10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40 Error correction level
{ 1, 1, 1, 2, 2, 4, 4, 4, 5, 5, 5, 8, 9, 9, 10, 10, 11, 13, 14, 16, 17, 17, 18, 20, 21, 23, 25, 26, 28, 29, 31, 33, 35, 37, 38, 40, 43, 45, 47, 49}, // Medium
{ 1, 1, 1, 1, 1, 2, 2, 2, 2, 4, 4, 4, 4, 4, 6, 6, 6, 6, 7, 8, 8, 9, 9, 10, 12, 12, 12, 13, 14, 15, 16, 17, 18, 19, 19, 20, 21, 22, 24, 25}, // Low
{ 1, 1, 2, 4, 4, 4, 5, 6, 8, 8, 11, 11, 16, 16, 18, 16, 19, 21, 25, 25, 25, 34, 30, 32, 35, 37, 40, 42, 45, 48, 51, 54, 57, 60, 63, 66, 70, 74, 77, 81}, // High
{ 1, 1, 2, 2, 4, 4, 6, 6, 8, 8, 8, 10, 12, 16, 12, 17, 16, 18, 21, 20, 23, 23, 25, 27, 29, 34, 34, 35, 38, 40, 43, 45, 48, 51, 53, 56, 59, 62, 65, 68}, // Quartile
};
static const uint16_t NUM_RAW_DATA_MODULES[40] = {
// 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17,
208, 359, 567, 807, 1079, 1383, 1568, 1936, 2336, 2768, 3232, 3728, 4256, 4651, 5243, 5867, 6523,
// 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31,
7211, 7931, 8683, 9252, 10068, 10916, 11796, 12708, 13652, 14628, 15371, 16411, 17483, 18587,
// 32, 33, 34, 35, 36, 37, 38, 39, 40
19723, 20891, 22091, 23008, 24272, 25568, 26896, 28256, 29648
};
// @TODO: Put other LOCK_VERSIONS here
#elif LOCK_VERSION == 3
static const int16_t NUM_ERROR_CORRECTION_CODEWORDS[4] = {
26, 15, 44, 36
};
static const int8_t NUM_ERROR_CORRECTION_BLOCKS[4] = {
1, 1, 2, 2
};
static const uint16_t NUM_RAW_DATA_MODULES = 567;
#else
#error Unsupported LOCK_VERSION (add it...)
#endif
static int max(int a, int b) {
if (a > b) { return a; }
return b;
}
/*
static int abs(int value) {
if (value < 0) { return -value; }
return value;
}
*/
#pragma mark - Mode testing and conversion
static int8_t getAlphanumeric(char c) {
if (c >= '0' && c <= '9') { return (c - '0'); }
if (c >= 'A' && c <= 'Z') { return (c - 'A' + 10); }
switch (c) {
case ' ': return 36;
case '$': return 37;
case '%': return 38;
case '*': return 39;
case '+': return 40;
case '-': return 41;
case '.': return 42;
case '/': return 43;
case ':': return 44;
}
return -1;
}
static bool isAlphanumeric(const char *text, uint16_t length) {
while (length != 0) {
if (getAlphanumeric(text[--length]) == -1) { return false; }
}
return true;
}
static bool isNumeric(const char *text, uint16_t length) {
while (length != 0) {
char c = text[--length];
if (c < '0' || c > '9') { return false; }
}
return true;
}
#pragma mark - Counting
// We store the following tightly packed (less 8) in modeInfo
// <=9 <=26 <= 40
// NUMERIC ( 10, 12, 14);
// ALPHANUMERIC ( 9, 11, 13);
// BYTE ( 8, 16, 16);
static char getModeBits(uint8_t version, uint8_t mode) {
// Note: We use 15 instead of 16; since 15 doesn't exist and we cannot store 16 (8 + 8) in 3 bits
// hex(int("".join(reversed([('00' + bin(x - 8)[2:])[-3:] for x in [10, 9, 8, 12, 11, 15, 14, 13, 15]])), 2))
unsigned int modeInfo = 0x7bbb80a;
#if LOCK_VERSION == 0 || LOCK_VERSION > 9
if (version > 9) { modeInfo >>= 9; }
#endif
#if LOCK_VERSION == 0 || LOCK_VERSION > 26
if (version > 26) { modeInfo >>= 9; }
#endif
char result = 8 + ((modeInfo >> (3 * mode)) & 0x07);
if (result == 15) { result = 16; }
return result;
}
#pragma mark - BitBucket
typedef struct BitBucket {
uint32_t bitOffsetOrWidth;
uint16_t capacityBytes;
uint8_t *data;
} BitBucket;
/*
void bb_dump(BitBucket *bitBuffer) {
printf("Buffer: ");
for (uint32_t i = 0; i < bitBuffer->capacityBytes; i++) {
printf("%02x", bitBuffer->data[i]);
if ((i % 4) == 3) { printf(" "); }
}
printf("\n");
}
*/
static uint16_t bb_getGridSizeBytes(uint8_t size) {
return (((size * size) + 7) / 8);
}
static uint16_t bb_getBufferSizeBytes(uint32_t bits) {
return ((bits + 7) / 8);
}
static void bb_initBuffer(BitBucket *bitBuffer, uint8_t *data, int32_t capacityBytes) {
bitBuffer->bitOffsetOrWidth = 0;
bitBuffer->capacityBytes = capacityBytes;
bitBuffer->data = data;
memset(data, 0, bitBuffer->capacityBytes);
}
static void bb_initGrid(BitBucket *bitGrid, uint8_t *data, uint8_t size) {
bitGrid->bitOffsetOrWidth = size;
bitGrid->capacityBytes = bb_getGridSizeBytes(size);
bitGrid->data = data;
memset(data, 0, bitGrid->capacityBytes);
}
static void bb_appendBits(BitBucket *bitBuffer, uint32_t val, uint8_t length) {
uint32_t offset = bitBuffer->bitOffsetOrWidth;
for (int8_t i = length - 1; i >= 0; i--, offset++) {
bitBuffer->data[offset >> 3] |= ((val >> i) & 1) << (7 - (offset & 7));
}
bitBuffer->bitOffsetOrWidth = offset;
}
/*
void bb_setBits(BitBucket *bitBuffer, uint32_t val, int offset, uint8_t length) {
for (int8_t i = length - 1; i >= 0; i--, offset++) {
bitBuffer->data[offset >> 3] |= ((val >> i) & 1) << (7 - (offset & 7));
}
}
*/
static void bb_setBit(BitBucket *bitGrid, uint8_t x, uint8_t y, bool on) {
uint32_t offset = y * bitGrid->bitOffsetOrWidth + x;
uint8_t mask = 1 << (7 - (offset & 0x07));
if (on) {
bitGrid->data[offset >> 3] |= mask;
} else {
bitGrid->data[offset >> 3] &= ~mask;
}
}
static void bb_invertBit(BitBucket *bitGrid, uint8_t x, uint8_t y, bool invert) {
uint32_t offset = y * bitGrid->bitOffsetOrWidth + x;
uint8_t mask = 1 << (7 - (offset & 0x07));
bool on = ((bitGrid->data[offset >> 3] & (1 << (7 - (offset & 0x07)))) != 0);
if (on ^ invert) {
bitGrid->data[offset >> 3] |= mask;
} else {
bitGrid->data[offset >> 3] &= ~mask;
}
}
static bool bb_getBit(BitBucket *bitGrid, uint8_t x, uint8_t y) {
uint32_t offset = y * bitGrid->bitOffsetOrWidth + x;
return (bitGrid->data[offset >> 3] & (1 << (7 - (offset & 0x07)))) != 0;
}
#pragma mark - Drawing Patterns
// XORs the data modules in this QR Code with the given mask pattern. Due to XOR's mathematical
// properties, calling applyMask(m) twice with the same value is equivalent to no change at all.
// This means it is possible to apply a mask, undo it, and try another mask. Note that a final
// well-formed QR Code symbol needs exactly one mask applied (not zero, not two, etc.).
static void applyMask(BitBucket *modules, BitBucket *isFunction, uint8_t mask) {
uint8_t size = modules->bitOffsetOrWidth;
for (uint8_t y = 0; y < size; y++) {
for (uint8_t x = 0; x < size; x++) {
if (bb_getBit(isFunction, x, y)) { continue; }
bool invert = 0;
switch (mask) {
case 0: invert = (x + y) % 2 == 0; break;
case 1: invert = y % 2 == 0; break;
case 2: invert = x % 3 == 0; break;
case 3: invert = (x + y) % 3 == 0; break;
case 4: invert = (x / 3 + y / 2) % 2 == 0; break;
case 5: invert = x * y % 2 + x * y % 3 == 0; break;
case 6: invert = (x * y % 2 + x * y % 3) % 2 == 0; break;
case 7: invert = ((x + y) % 2 + x * y % 3) % 2 == 0; break;
}
bb_invertBit(modules, x, y, invert);
}
}
}
static void setFunctionModule(BitBucket *modules, BitBucket *isFunction, uint8_t x, uint8_t y, bool on) {
bb_setBit(modules, x, y, on);
bb_setBit(isFunction, x, y, true);
}
// Draws a 9*9 finder pattern including the border separator, with the center module at (x, y).
static void drawFinderPattern(BitBucket *modules, BitBucket *isFunction, uint8_t x, uint8_t y) {
uint8_t size = modules->bitOffsetOrWidth;
for (int8_t i = -4; i <= 4; i++) {
for (int8_t j = -4; j <= 4; j++) {
uint8_t dist = max(abs(i), abs(j)); // Chebyshev/infinity norm
int16_t xx = x + j, yy = y + i;
if (0 <= xx && xx < size && 0 <= yy && yy < size) {
setFunctionModule(modules, isFunction, xx, yy, dist != 2 && dist != 4);
}
}
}
}
// Draws a 5*5 alignment pattern, with the center module at (x, y).
static void drawAlignmentPattern(BitBucket *modules, BitBucket *isFunction, uint8_t x, uint8_t y) {
for (int8_t i = -2; i <= 2; i++) {
for (int8_t j = -2; j <= 2; j++) {
setFunctionModule(modules, isFunction, x + j, y + i, max(abs(i), abs(j)) != 1);
}
}
}
// Draws two copies of the format bits (with its own error correction code)
// based on the given mask and this object's error correction level field.
static void drawFormatBits(BitBucket *modules, BitBucket *isFunction, uint8_t ecc, uint8_t mask) {
uint8_t size = modules->bitOffsetOrWidth;
// Calculate error correction code and pack bits
uint32_t data = ecc << 3 | mask; // errCorrLvl is uint2, mask is uint3
uint32_t rem = data;
for (int i = 0; i < 10; i++) {
rem = (rem << 1) ^ ((rem >> 9) * 0x537);
}
data = data << 10 | rem;
data ^= 0x5412; // uint15
// Draw first copy
for (uint8_t i = 0; i <= 5; i++) {
setFunctionModule(modules, isFunction, 8, i, ((data >> i) & 1) != 0);
}
setFunctionModule(modules, isFunction, 8, 7, ((data >> 6) & 1) != 0);
setFunctionModule(modules, isFunction, 8, 8, ((data >> 7) & 1) != 0);
setFunctionModule(modules, isFunction, 7, 8, ((data >> 8) & 1) != 0);
for (int8_t i = 9; i < 15; i++) {
setFunctionModule(modules, isFunction, 14 - i, 8, ((data >> i) & 1) != 0);
}
// Draw second copy
for (int8_t i = 0; i <= 7; i++) {
setFunctionModule(modules, isFunction, size - 1 - i, 8, ((data >> i) & 1) != 0);
}
for (int8_t i = 8; i < 15; i++) {
setFunctionModule(modules, isFunction, 8, size - 15 + i, ((data >> i) & 1) != 0);
}
setFunctionModule(modules, isFunction, 8, size - 8, true);
}
// Draws two copies of the version bits (with its own error correction code),
// based on this object's version field (which only has an effect for 7 <= version <= 40).
static void drawVersion(BitBucket *modules, BitBucket *isFunction, uint8_t version) {
int8_t size = modules->bitOffsetOrWidth;
#if LOCK_VERSION != 0 && LOCK_VERSION < 7
return;
#else
if (version < 7) { return; }
// Calculate error correction code and pack bits
uint32_t rem = version; // version is uint6, in the range [7, 40]
for (uint8_t i = 0; i < 12; i++) {
rem = (rem << 1) ^ ((rem >> 11) * 0x1F25);
}
uint32_t data = version << 12 | rem; // uint18
// Draw two copies
for (uint8_t i = 0; i < 18; i++) {
bool bit = ((data >> i) & 1) != 0;
uint8_t a = size - 11 + i % 3, b = i / 3;
setFunctionModule(modules, isFunction, a, b, bit);
setFunctionModule(modules, isFunction, b, a, bit);
}
#endif
}
static void drawFunctionPatterns(BitBucket *modules, BitBucket *isFunction, uint8_t version, uint8_t ecc) {
uint8_t size = modules->bitOffsetOrWidth;
// Draw the horizontal and vertical timing patterns
for (uint8_t i = 0; i < size; i++) {
setFunctionModule(modules, isFunction, 6, i, i % 2 == 0);
setFunctionModule(modules, isFunction, i, 6, i % 2 == 0);
}
// Draw 3 finder patterns (all corners except bottom right; overwrites some timing modules)
drawFinderPattern(modules, isFunction, 3, 3);
drawFinderPattern(modules, isFunction, size - 4, 3);
drawFinderPattern(modules, isFunction, 3, size - 4);
#if LOCK_VERSION == 0 || LOCK_VERSION > 1
if (version > 1) {
// Draw the numerous alignment patterns
uint8_t alignCount = version / 7 + 2;
uint8_t step;
if (version != 32) {
step = (version * 4 + alignCount * 2 + 1) / (2 * alignCount - 2) * 2; // ceil((size - 13) / (2*numAlign - 2)) * 2
} else { // C-C-C-Combo breaker!
step = 26;
}
uint8_t alignPositionIndex = alignCount - 1;
uint8_t alignPosition[alignCount];
alignPosition[0] = 6;
uint8_t size = version * 4 + 17;
for (uint8_t i = 0, pos = size - 7; i < alignCount - 1; i++, pos -= step) {
alignPosition[alignPositionIndex--] = pos;
}
for (uint8_t i = 0; i < alignCount; i++) {
for (uint8_t j = 0; j < alignCount; j++) {
if ((i == 0 && j == 0) || (i == 0 && j == alignCount - 1) || (i == alignCount - 1 && j == 0)) {
continue; // Skip the three finder corners
} else {
drawAlignmentPattern(modules, isFunction, alignPosition[i], alignPosition[j]);
}
}
}
}
#endif
// Draw configuration data
drawFormatBits(modules, isFunction, ecc, 0); // Dummy mask value; overwritten later in the constructor
drawVersion(modules, isFunction, version);
}
// Draws the given sequence of 8-bit codewords (data and error correction) onto the entire
// data area of this QR Code symbol. Function modules need to be marked off before this is called.
static void drawCodewords(BitBucket *modules, BitBucket *isFunction, BitBucket *codewords) {
uint32_t bitLength = codewords->bitOffsetOrWidth;
uint8_t *data = codewords->data;
uint8_t size = modules->bitOffsetOrWidth;
// Bit index into the data
uint32_t i = 0;
// Do the funny zigzag scan
for (int16_t right = size - 1; right >= 1; right -= 2) { // Index of right column in each column pair
if (right == 6) { right = 5; }
for (uint8_t vert = 0; vert < size; vert++) { // Vertical counter
for (int j = 0; j < 2; j++) {
uint8_t x = right - j; // Actual x coordinate
bool upwards = ((right & 2) == 0) ^ (x < 6);
uint8_t y = upwards ? size - 1 - vert : vert; // Actual y coordinate
if (!bb_getBit(isFunction, x, y) && i < bitLength) {
bb_setBit(modules, x, y, ((data[i >> 3] >> (7 - (i & 7))) & 1) != 0);
i++;
}
// If there are any remainder bits (0 to 7), they are already
// set to 0/false/white when the grid of modules was initialized
}
}
}
}
#pragma mark - Penalty Calculation
#define PENALTY_N1 3
#define PENALTY_N2 3
#define PENALTY_N3 40
#define PENALTY_N4 10
// Calculates and returns the penalty score based on state of this QR Code's current modules.
// This is used by the automatic mask choice algorithm to find the mask pattern that yields the lowest score.
// @TODO: This can be optimized by working with the bytes instead of bits.
static uint32_t getPenaltyScore(BitBucket *modules) {
uint32_t result = 0;
uint8_t size = modules->bitOffsetOrWidth;
// Adjacent modules in row having same color
for (uint8_t y = 0; y < size; y++) {
bool colorX = bb_getBit(modules, 0, y);
for (uint8_t x = 1, runX = 1; x < size; x++) {
bool cx = bb_getBit(modules, x, y);
if (cx != colorX) {
colorX = cx;
runX = 1;
} else {
runX++;
if (runX == 5) {
result += PENALTY_N1;
} else if (runX > 5) {
result++;
}
}
}
}
// Adjacent modules in column having same color
for (uint8_t x = 0; x < size; x++) {
bool colorY = bb_getBit(modules, x, 0);
for (uint8_t y = 1, runY = 1; y < size; y++) {
bool cy = bb_getBit(modules, x, y);
if (cy != colorY) {
colorY = cy;
runY = 1;
} else {
runY++;
if (runY == 5) {
result += PENALTY_N1;
} else if (runY > 5) {
result++;
}
}
}
}
uint16_t black = 0;
for (uint8_t y = 0; y < size; y++) {
uint16_t bitsRow = 0, bitsCol = 0;
for (uint8_t x = 0; x < size; x++) {
bool color = bb_getBit(modules, x, y);
// 2*2 blocks of modules having same color
if (x > 0 && y > 0) {
bool colorUL = bb_getBit(modules, x - 1, y - 1);
bool colorUR = bb_getBit(modules, x, y - 1);
bool colorL = bb_getBit(modules, x - 1, y);
if (color == colorUL && color == colorUR && color == colorL) {
result += PENALTY_N2;
}
}
// Finder-like pattern in rows and columns
bitsRow = ((bitsRow << 1) & 0x7FF) | color;
bitsCol = ((bitsCol << 1) & 0x7FF) | bb_getBit(modules, y, x);
// Needs 11 bits accumulated
if (x >= 10) {
if (bitsRow == 0x05D || bitsRow == 0x5D0) {
result += PENALTY_N3;
}
if (bitsCol == 0x05D || bitsCol == 0x5D0) {
result += PENALTY_N3;
}
}
// Balance of black and white modules
if (color) { black++; }
}
}
// Find smallest k such that (45-5k)% <= dark/total <= (55+5k)%
uint16_t total = size * size;
for (uint16_t k = 0; black * 20 < (9 - k) * total || black * 20 > (11 + k) * total; k++) {
result += PENALTY_N4;
}
return result;
}
#pragma mark - Reed-Solomon Generator
static uint8_t rs_multiply(uint8_t x, uint8_t y) {
// Russian peasant multiplication
// See: https://en.wikipedia.org/wiki/Ancient_Egyptian_multiplication
uint16_t z = 0;
for (int8_t i = 7; i >= 0; i--) {
z = (z << 1) ^ ((z >> 7) * 0x11D);
z ^= ((y >> i) & 1) * x;
}
return z;
}
static void rs_init(uint8_t degree, uint8_t *coeff) {
memset(coeff, 0, degree);
coeff[degree - 1] = 1;
// Compute the product polynomial (x - r^0) * (x - r^1) * (x - r^2) * ... * (x - r^{degree-1}),
// drop the highest term, and store the rest of the coefficients in order of descending powers.
// Note that r = 0x02, which is a generator element of this field GF(2^8/0x11D).
uint16_t root = 1;
for (uint8_t i = 0; i < degree; i++) {
// Multiply the current product by (x - r^i)
for (uint8_t j = 0; j < degree; j++) {
coeff[j] = rs_multiply(coeff[j], root);
if (j + 1 < degree) {
coeff[j] ^= coeff[j + 1];
}
}
root = (root << 1) ^ ((root >> 7) * 0x11D); // Multiply by 0x02 mod GF(2^8/0x11D)
}
}
static void rs_getRemainder(uint8_t degree, uint8_t *coeff, uint8_t *data, uint8_t length, uint8_t *result, uint8_t stride) {
// Compute the remainder by performing polynomial division
//for (uint8_t i = 0; i < degree; i++) { result[] = 0; }
//memset(result, 0, degree);
for (uint8_t i = 0; i < length; i++) {
uint8_t factor = data[i] ^ result[0];
for (uint8_t j = 1; j < degree; j++) {
result[(j - 1) * stride] = result[j * stride];
}
result[(degree - 1) * stride] = 0;
for (uint8_t j = 0; j < degree; j++) {
result[j * stride] ^= rs_multiply(coeff[j], factor);
}
}
}
#pragma mark - QrCode
static int8_t encodeDataCodewords(BitBucket *dataCodewords, const uint8_t *text, uint16_t length, uint8_t version) {
int8_t mode = MODE_BYTE;
if (isNumeric((char*)text, length)) {
mode = MODE_NUMERIC;
bb_appendBits(dataCodewords, 1 << MODE_NUMERIC, 4);
bb_appendBits(dataCodewords, length, getModeBits(version, MODE_NUMERIC));
uint16_t accumData = 0;
uint8_t accumCount = 0;
for (uint16_t i = 0; i < length; i++) {
accumData = accumData * 10 + ((char)(text[i]) - '0');
accumCount++;
if (accumCount == 3) {
bb_appendBits(dataCodewords, accumData, 10);
accumData = 0;
accumCount = 0;
}
}
// 1 or 2 digits remaining
if (accumCount > 0) {
bb_appendBits(dataCodewords, accumData, accumCount * 3 + 1);
}
} else if (isAlphanumeric((char*)text, length)) {
mode = MODE_ALPHANUMERIC;
bb_appendBits(dataCodewords, 1 << MODE_ALPHANUMERIC, 4);
bb_appendBits(dataCodewords, length, getModeBits(version, MODE_ALPHANUMERIC));
uint16_t accumData = 0;
uint8_t accumCount = 0;
for (uint16_t i = 0; i < length; i++) {
accumData = accumData * 45 + getAlphanumeric((char)(text[i]));
accumCount++;
if (accumCount == 2) {
bb_appendBits(dataCodewords, accumData, 11);
accumData = 0;
accumCount = 0;
}
}
// 1 character remaining
if (accumCount > 0) {
bb_appendBits(dataCodewords, accumData, 6);
}
} else {
bb_appendBits(dataCodewords, 1 << MODE_BYTE, 4);
bb_appendBits(dataCodewords, length, getModeBits(version, MODE_BYTE));
for (uint16_t i = 0; i < length; i++) {
bb_appendBits(dataCodewords, (char)(text[i]), 8);
}
}
//bb_setBits(dataCodewords, length, 4, getModeBits(version, mode));
return mode;
}
static void performErrorCorrection(uint8_t version, uint8_t ecc, BitBucket *data) {
// See: http://www.thonky.com/qr-code-tutorial/structure-final-message
#if LOCK_VERSION == 0
uint8_t numBlocks = NUM_ERROR_CORRECTION_BLOCKS[ecc][version - 1];
uint16_t totalEcc = NUM_ERROR_CORRECTION_CODEWORDS[ecc][version - 1];
uint16_t moduleCount = NUM_RAW_DATA_MODULES[version - 1];
#else
uint8_t numBlocks = NUM_ERROR_CORRECTION_BLOCKS[ecc];
uint16_t totalEcc = NUM_ERROR_CORRECTION_CODEWORDS[ecc];
uint16_t moduleCount = NUM_RAW_DATA_MODULES;
#endif
uint8_t blockEccLen = totalEcc / numBlocks;
uint8_t numShortBlocks = numBlocks - moduleCount / 8 % numBlocks;
uint8_t shortBlockLen = moduleCount / 8 / numBlocks;
uint8_t shortDataBlockLen = shortBlockLen - blockEccLen;
uint8_t result[data->capacityBytes];
memset(result, 0, sizeof(result));
uint8_t coeff[blockEccLen];
rs_init(blockEccLen, coeff);
uint16_t offset = 0;
uint8_t *dataBytes = data->data;
// Interleave all short blocks
for (uint8_t i = 0; i < shortDataBlockLen; i++) {
uint16_t index = i;
uint8_t stride = shortDataBlockLen;
for (uint8_t blockNum = 0; blockNum < numBlocks; blockNum++) {
result[offset++] = dataBytes[index];
#if LOCK_VERSION == 0 || LOCK_VERSION >= 5
if (blockNum == numShortBlocks) { stride++; }
#endif
index += stride;
}
}
// Version less than 5 only have short blocks
#if LOCK_VERSION == 0 || LOCK_VERSION >= 5
{
// Interleave long blocks
uint16_t index = shortDataBlockLen * (numShortBlocks + 1);
uint8_t stride = shortDataBlockLen;
for (uint8_t blockNum = 0; blockNum < numBlocks - numShortBlocks; blockNum++) {
result[offset++] = dataBytes[index];
if (blockNum == 0) { stride++; }
index += stride;
}
}
#endif
// Add all ecc blocks, interleaved
uint8_t blockSize = shortDataBlockLen;
for (uint8_t blockNum = 0; blockNum < numBlocks; blockNum++) {
#if LOCK_VERSION == 0 || LOCK_VERSION >= 5
if (blockNum == numShortBlocks) { blockSize++; }
#endif
rs_getRemainder(blockEccLen, coeff, dataBytes, blockSize, &result[offset + blockNum], numBlocks);
dataBytes += blockSize;
}
memcpy(data->data, result, data->capacityBytes);
data->bitOffsetOrWidth = moduleCount;
}
// We store the Format bits tightly packed into a single byte (each of the 4 modes is 2 bits)
// The format bits can be determined by ECC_FORMAT_BITS >> (2 * ecc)
static const uint8_t ECC_FORMAT_BITS = (0x02 << 6) | (0x03 << 4) | (0x00 << 2) | (0x01 << 0);
#pragma mark - Public QRCode functions
uint16_t qrcode_getBufferSize(uint8_t version) {
return bb_getGridSizeBytes(4 * version + 17);
}
// @TODO: Return error if data is too big.
int8_t qrcode_initBytes(QRCode *qrcode, uint8_t *modules, uint8_t version, uint8_t ecc, uint8_t *data, uint16_t length) {
uint8_t size = version * 4 + 17;
qrcode->version = version;
qrcode->size = size;
qrcode->ecc = ecc;
qrcode->modules = modules;
uint8_t eccFormatBits = (ECC_FORMAT_BITS >> (2 * ecc)) & 0x03;
#if LOCK_VERSION == 0
uint16_t moduleCount = NUM_RAW_DATA_MODULES[version - 1];
uint16_t dataCapacity = moduleCount / 8 - NUM_ERROR_CORRECTION_CODEWORDS[eccFormatBits][version - 1];
#else
version = LOCK_VERSION;
uint16_t moduleCount = NUM_RAW_DATA_MODULES;
uint16_t dataCapacity = moduleCount / 8 - NUM_ERROR_CORRECTION_CODEWORDS[eccFormatBits];
#endif
struct BitBucket codewords;
uint8_t codewordBytes[bb_getBufferSizeBytes(moduleCount)];
bb_initBuffer(&codewords, codewordBytes, (int32_t)sizeof(codewordBytes));
// Place the data code words into the buffer
int8_t mode = encodeDataCodewords(&codewords, data, length, version);
if (mode < 0) { return -1; }
qrcode->mode = mode;
// Add terminator and pad up to a byte if applicable
uint32_t padding = (dataCapacity * 8) - codewords.bitOffsetOrWidth;
if (padding > 4) { padding = 4; }
bb_appendBits(&codewords, 0, padding);
bb_appendBits(&codewords, 0, (8 - codewords.bitOffsetOrWidth % 8) % 8);
// Pad with alternate bytes until data capacity is reached
for (uint8_t padByte = 0xEC; codewords.bitOffsetOrWidth < (dataCapacity * 8); padByte ^= 0xEC ^ 0x11) {
bb_appendBits(&codewords, padByte, 8);
}
BitBucket modulesGrid;
bb_initGrid(&modulesGrid, modules, size);
BitBucket isFunctionGrid;
uint8_t isFunctionGridBytes[bb_getGridSizeBytes(size)];
bb_initGrid(&isFunctionGrid, isFunctionGridBytes, size);
// Draw function patterns, draw all codewords, do masking
drawFunctionPatterns(&modulesGrid, &isFunctionGrid, version, eccFormatBits);
performErrorCorrection(version, eccFormatBits, &codewords);
drawCodewords(&modulesGrid, &isFunctionGrid, &codewords);
// Find the best (lowest penalty) mask
uint8_t mask = 0;
int32_t minPenalty = INT32_MAX;
for (uint8_t i = 0; i < 8; i++) {
drawFormatBits(&modulesGrid, &isFunctionGrid, eccFormatBits, i);
applyMask(&modulesGrid, &isFunctionGrid, i);
int penalty = getPenaltyScore(&modulesGrid);
if (penalty < minPenalty) {
mask = i;
minPenalty = penalty;
}
applyMask(&modulesGrid, &isFunctionGrid, i); // Undoes the mask due to XOR
}
qrcode->mask = mask;
// Overwrite old format bits
drawFormatBits(&modulesGrid, &isFunctionGrid, eccFormatBits, mask);
// Apply the final choice of mask
applyMask(&modulesGrid, &isFunctionGrid, mask);
return 0;
}
int8_t qrcode_initText(QRCode *qrcode, uint8_t *modules, uint8_t version, uint8_t ecc, const char *data) {
return qrcode_initBytes(qrcode, modules, version, ecc, (uint8_t*)data, strlen(data));
}
bool qrcode_getModule(QRCode *qrcode, uint8_t x, uint8_t y) {
if (x < 0 || x >= qrcode->size || y < 0 || y >= qrcode->size) {
return false;
}
uint32_t offset = y * qrcode->size + x;
return (qrcode->modules[offset >> 3] & (1 << (7 - (offset & 0x07)))) != 0;
}
/*
uint8_t qrcode_getHexLength(QRCode *qrcode) {
return ((qrcode->size * qrcode->size) + 7) / 4;
}
void qrcode_getHex(QRCode *qrcode, char *result) {
}
*/

99
lib/obp60task/qrcode.h Normal file
View File

@ -0,0 +1,99 @@
/**
* The MIT License (MIT)
*
* This library is written and maintained by Richard Moore.
* Major parts were derived from Project Nayuki's library.
*
* Copyright (c) 2017 Richard Moore (https://github.com/ricmoo/QRCode)
* Copyright (c) 2017 Project Nayuki (https://www.nayuki.io/page/qr-code-generator-library)
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
/**
* Special thanks to Nayuki (https://www.nayuki.io/) from which this library was
* heavily inspired and compared against.
*
* See: https://github.com/nayuki/QR-Code-generator/tree/master/cpp
*/
#ifndef __QRCODE_H_
#define __QRCODE_H_
#ifndef __cplusplus
typedef unsigned char bool;
static const bool false = 0;
static const bool true = 1;
#endif
#include <stdint.h>
// QR Code Format Encoding
#define MODE_NUMERIC 0
#define MODE_ALPHANUMERIC 1
#define MODE_BYTE 2
// Error Correction Code Levels
#define ECC_LOW 0
#define ECC_MEDIUM 1
#define ECC_QUARTILE 2
#define ECC_HIGH 3
// If set to non-zero, this library can ONLY produce QR codes at that version
// This saves a lot of dynamic memory, as the codeword tables are skipped
#ifndef LOCK_VERSION
#define LOCK_VERSION 0
#endif
typedef struct QRCode {
uint8_t version;
uint8_t size;
uint8_t ecc;
uint8_t mode;
uint8_t mask;
uint8_t *modules;
} QRCode;
#ifdef __cplusplus
extern "C"{
#endif /* __cplusplus */
uint16_t qrcode_getBufferSize(uint8_t version);
int8_t qrcode_initText(QRCode *qrcode, uint8_t *modules, uint8_t version, uint8_t ecc, const char *data);
int8_t qrcode_initBytes(QRCode *qrcode, uint8_t *modules, uint8_t version, uint8_t ecc, uint8_t *data, uint16_t length);
bool qrcode_getModule(QRCode *qrcode, uint8_t x, uint8_t y);
#ifdef __cplusplus
}
#endif /* __cplusplus */
#endif /* __QRCODE_H_ */