From c1d82a43c5f2b604be2ba274c6c67d355088169c Mon Sep 17 00:00:00 2001 From: Alexander Malishev Date: Sat, 23 Jun 2018 17:11:05 +1000 Subject: [PATCH] AP_OSD: initial version --- libraries/AP_OSD/AP_OSD.cpp | 272 + libraries/AP_OSD/AP_OSD.h | 67 + libraries/AP_OSD/AP_OSD_Backend.cpp | 32 + libraries/AP_OSD/AP_OSD_Backend.h | 57 + libraries/AP_OSD/AP_OSD_MAX7456.cpp | 406 + libraries/AP_OSD/AP_OSD_MAX7456.h | 78 + libraries/AP_OSD/fonts/clarity.bin | Bin 0 -> 13824 bytes libraries/AP_OSD/fonts/clarity.mcm | 16385 ++++++++++++++++++++++++++ libraries/AP_OSD/fonts/mcm2bin.py | 21 + 9 files changed, 17318 insertions(+) create mode 100644 libraries/AP_OSD/AP_OSD.cpp create mode 100644 libraries/AP_OSD/AP_OSD.h create mode 100644 libraries/AP_OSD/AP_OSD_Backend.cpp create mode 100644 libraries/AP_OSD/AP_OSD_Backend.h create mode 100644 libraries/AP_OSD/AP_OSD_MAX7456.cpp create mode 100644 libraries/AP_OSD/AP_OSD_MAX7456.h create mode 100644 libraries/AP_OSD/fonts/clarity.bin create mode 100644 libraries/AP_OSD/fonts/clarity.mcm create mode 100755 libraries/AP_OSD/fonts/mcm2bin.py diff --git a/libraries/AP_OSD/AP_OSD.cpp b/libraries/AP_OSD/AP_OSD.cpp new file mode 100644 index 0000000000..0cf973e3d5 --- /dev/null +++ b/libraries/AP_OSD/AP_OSD.cpp @@ -0,0 +1,272 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * AP_OSD partially based on betaflight and inav osd.c implemention. + * clarity.mcm font is taken from inav configurator. + * Many thanks to their authors. + */ + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include + +// Character coordinate and attributes +#define VISIBLE_FLAG 0x0800 +#define VISIBLE(x) (x & VISIBLE_FLAG) +#define OSD_POS(x,y) (x | (y << 5)) +#define OSD_X(x) (x & 0x001F) +#define OSD_Y(x) ((x >> 5) & 0x001F) + +//Symbols +#define SYM_BLANK 0x20 +#define SYM_COLON 0x2D +#define SYM_ZERO_HALF_TRAILING_DOT 192 +#define SYM_ZERO_HALF_LEADING_DOT 208 + +#define SYM_M 177 +#define SYM_ALT_M 177 +#define SYM_BATT_FULL 0x90 +#define SYM_RSSI 0x01 + +#define SYM_VOLT 0x06 +#define SYM_AMP 0x9A +#define SYM_MAH 0x07 + +#define SYM_SAT_L 0x1E +#define SYM_SAT_R 0x1F + +#define AH_SYMBOL_COUNT 9 + +const AP_Param::GroupInfo AP_OSD::var_info[] = { + + // @Param: ENABLED + // @DisplayName: Enable OSD + // @Description: Enable OSD + // @Values: 0:Disabled,1:Enabled + // @User: Standard + AP_GROUPINFO_FLAGS("ENABLED", 0, AP_OSD, osd_enabled, 1, AP_PARAM_FLAG_ENABLE), + + // @Param: UPDATE_FONT + // @DisplayName: Update font + // @Description: Undate font inside osd chip + // @Values: 0:Do not update,1:Update + // @User: Standard + AP_GROUPINFO("UPDATE_FONT", 1, AP_OSD, update_font, 1), + + // @Param: 1_ALTITUDE + // @DisplayName: Altitude position + // @Description: Altitude position and visibility + // @Values: 2048 * visible + x + y * 16 + // @User: Advanced + AP_GROUPINFO("1_ALTITUDE", 2, AP_OSD, pos_altitude, OSD_POS(1, 0) | VISIBLE_FLAG), + + // @Param:1_BATT_VOLTAGE + // @DisplayName: + // @Description: + // @Values: 2048 * visible + x + y * 16 + // @User: Advanced + AP_GROUPINFO("1_BAT_VOLT", 3, AP_OSD, pos_batt_voltage, OSD_POS(12, 0) | VISIBLE_FLAG), + + // @Param:1_RSSI + // @DisplayName: + // @Description: + // @Values: 2048 * visible + x + y * 16 + // @User: Advanced + AP_GROUPINFO("1_RSSI", 4, AP_OSD, pos_rssi, OSD_POS(23, 0) | VISIBLE_FLAG), + + // @Param:1_CURRENT_DRAW + // @DisplayName: + // @Description: + // @Values: 2048 * visible + x + y * 16 + // @User: Advanced + AP_GROUPINFO("1_CUR_DRAW", 5, AP_OSD, pos_current_draw, OSD_POS(1, 3) | VISIBLE_FLAG), + + // @Param:1_MAH_DRAWN + // @DisplayName: + // @Description: + // @Values: 2048 * visible + x + y * 16 + // @User: Advanced + AP_GROUPINFO("1_MAH_DRAWN", 6, AP_OSD, pos_mah_drawn, OSD_POS(1, 4) | VISIBLE_FLAG), + + // @Param:1_GPS_SATS + // @DisplayName: + // @Description: + // @Values: 2048 * visible + x + y * 16 + // @User: Advanced + AP_GROUPINFO("1_GPS_SATS", 7, AP_OSD, pos_gps_sats, OSD_POS(0, 11) | VISIBLE_FLAG), + + // @Param:1_FLYMODE + // @DisplayName: + // @Description: + // @Values: 2048 * visible + x + y * 16 + // @User: Advanced + AP_GROUPINFO("1_FLYMODE", 8, AP_OSD, pos_flymode, OSD_POS(12, 12) | VISIBLE_FLAG), + + // @Param:1_MESSAGES + // @DisplayName: + // @Description: + // @Values: 2048 * visible + x + y * 16 + // @User: Advanced + AP_GROUPINFO("1_MESSAGES", 9, AP_OSD, pos_messages, OSD_POS(1, 13) | VISIBLE_FLAG), + + AP_GROUPEND +}; + +extern const AP_HAL::HAL& hal; + +AP_OSD::AP_OSD() : backend(nullptr), last_update_ms(0) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +void AP_OSD::init() +{ + if (!osd_enabled) { + return; + } + AP_HAL::OwnPtr spi_dev = std::move(hal.spi->get_device("osd")); + if (!spi_dev) { + return; + } + backend = AP_OSD_MAX7456::probe(*this, std::move(spi_dev)); + if (backend == nullptr) { + return; + } + last_update_ms = 0; + hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_OSD::timer, void)); +} + +void AP_OSD::timer() +{ + uint32_t now = AP_HAL::millis(); + + if (now - last_update_ms > 16) { + last_update_ms = now; + update_osd(); + } +} + +void AP_OSD::update_osd() +{ + backend->clear(); + + draw_messages(); + draw_flymode(); + draw_altitude(); + draw_batt_voltage(); + draw_rssi(); + draw_current_draw(); + draw_mah_drawn(); + draw_gps_sats(); + + backend->flush(); +} + +void AP_OSD::draw_altitude() +{ + if (VISIBLE(pos_altitude)) { + uint8_t x = OSD_X(pos_altitude); + uint8_t y = OSD_Y(pos_altitude); + + float alt; + AP_AHRS::get_singleton()->get_relative_position_D_home(alt); + backend->write(x, y, false, "%4.0f%c", alt, SYM_ALT_M); + } +} + +void AP_OSD::draw_batt_voltage() +{ + if (VISIBLE(pos_batt_voltage)) { + uint8_t x = OSD_X(pos_batt_voltage); + uint8_t y = OSD_Y(pos_batt_voltage); + + AP_BattMonitor & battery = AP_BattMonitor::battery(); + uint8_t p = battery.capacity_remaining_pct(); + p = (100 - p) / 16.6; + backend->write(x,y, battery.has_failsafed(), "%c%2.1fV", SYM_BATT_FULL + p, battery.voltage()); + } +} + +void AP_OSD::draw_rssi() +{ + if (VISIBLE(pos_rssi)) { + uint8_t x = OSD_X(pos_rssi); + uint8_t y = OSD_Y(pos_rssi); + int rssi = AP_RSSI::get_instance()->read_receiver_rssi_uint8(); + rssi = (rssi * 99) / 255; + backend->write(x, y, rssi < 5, "%c%2d", SYM_RSSI, rssi); + } +} + +void AP_OSD::draw_current_draw() +{ + if (VISIBLE(pos_current_draw)) { + uint8_t x = OSD_X(pos_current_draw); + uint8_t y = OSD_Y(pos_current_draw); + AP_BattMonitor & battery = AP_BattMonitor::battery(); + float current = battery.current_amps(); + backend->write(x, y, false, "%c%2.1f",SYM_AMP, current); + } +} + +void AP_OSD::draw_flymode() +{ + if (VISIBLE(pos_flymode)) { + uint8_t x = OSD_X(pos_flymode); + uint8_t y = OSD_Y(pos_flymode); + backend->write(x, y, AP_Notify::instance()->get_flight_mode_str()); + } +} + +void AP_OSD::draw_gps_sats() +{ + if (VISIBLE(pos_gps_sats)) { + uint8_t x = OSD_X(pos_gps_sats); + uint8_t y = OSD_Y(pos_gps_sats); + AP_GPS& gps = AP::gps(); + bool has_3dfix = gps.status() <= AP_GPS::GPS_OK_FIX_2D; + backend->write(x, y, !has_3dfix, "%c%c%2d", SYM_SAT_L, SYM_SAT_R, gps.num_sats()); + } +} + +void AP_OSD::draw_mah_drawn() +{ + if (VISIBLE(pos_mah_drawn)) { + uint8_t x = OSD_X(pos_mah_drawn); + uint8_t y = OSD_Y(pos_mah_drawn); + AP_BattMonitor & battery = AP_BattMonitor::battery(); + backend->write(x,y, battery.has_failsafed(), "%c%4.0f", SYM_MAH, battery.consumed_mah()); + } +} + +void AP_OSD::draw_messages() +{ + if (VISIBLE(pos_messages)) { + uint8_t x = OSD_X(pos_messages); + uint8_t y = OSD_Y(pos_messages); + AP_Notify * notify = AP_Notify::instance(); + bool text_is_valid = AP_HAL::millis() - notify->get_text_updated_millis() < 20000; + if (text_is_valid) { + backend->write(x, y, notify->get_text()); + } + } +} diff --git a/libraries/AP_OSD/AP_OSD.h b/libraries/AP_OSD/AP_OSD.h new file mode 100644 index 0000000000..ddffb1fa86 --- /dev/null +++ b/libraries/AP_OSD/AP_OSD.h @@ -0,0 +1,67 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + */ + +#pragma once + +#include + +class AP_OSD_Backend; + +class AP_OSD { +public: + //constructor + AP_OSD(); + + /* Do not allow copies */ + AP_OSD(const AP_OSD &other) = delete; + AP_OSD &operator=(const AP_OSD&) = delete; + + // init - perform required initialisation + void init(); + + // User settable parameters + static const struct AP_Param::GroupInfo var_info[]; + + AP_Int8 osd_enabled; + AP_Int8 update_font; + + AP_Int16 pos_altitude; + AP_Int16 pos_batt_voltage; + AP_Int16 pos_rssi; + AP_Int16 pos_current_draw; + AP_Int16 pos_mah_drawn; + AP_Int16 pos_gps_sats; + AP_Int16 pos_flymode; + AP_Int16 pos_messages; + +private: + void timer(); + void update_osd(); + AP_OSD_Backend *backend; + uint32_t last_update_ms; + + void draw_altitude(); + void draw_batt_voltage(); + void draw_rssi(); + void draw_current_draw(); + void draw_mah_drawn(); + void draw_horizon(); + void draw_ontime_flytime(); + void draw_gps_sats(); + void draw_flymode(); + void draw_messages(); +}; + diff --git a/libraries/AP_OSD/AP_OSD_Backend.cpp b/libraries/AP_OSD/AP_OSD_Backend.cpp new file mode 100644 index 0000000000..7a274368b1 --- /dev/null +++ b/libraries/AP_OSD/AP_OSD_Backend.cpp @@ -0,0 +1,32 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + */ + +#include +#include + +extern const AP_HAL::HAL& hal; + +void AP_OSD_Backend::write(int x, int y, bool blink, const char *fmt, ...) +{ + char buff[32]; + va_list ap; + va_start(ap, fmt); + int res = hal.util->vsnprintf(buff, sizeof(buff), fmt, ap); + if (res < sizeof(buff)) { + write(x, y, buff, blink? AP_OSD_Backend::BLINK : 0); + } + va_end(ap); +} diff --git a/libraries/AP_OSD/AP_OSD_Backend.h b/libraries/AP_OSD/AP_OSD_Backend.h new file mode 100644 index 0000000000..76aeb978b3 --- /dev/null +++ b/libraries/AP_OSD/AP_OSD_Backend.h @@ -0,0 +1,57 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + */ + +#pragma once + +#include +#include + + +class AP_OSD_Backend { + +public: + //constructor + AP_OSD_Backend(AP_OSD &osd): _osd(osd) {}; + + //destructor + virtual ~AP_OSD_Backend(void) {} + + //draw given text to framebuffer + virtual void write(int x, int y, const char* text, uint8_t char_attr = 0) = 0; + + //draw formatted text to framebuffer + virtual void write(int x, int y, bool blink, const char *fmt, ...); + + //initilize framebuffer and underlying hardware + virtual bool init() = 0; + + //update screen + virtual void flush() = 0; + + //clear screen + virtual void clear() = 0; + + enum character_attribute_t { + BLINK = (1 << 4), + INVERT = (1 << 3), + }; + +protected: + AP_OSD& _osd; + +}; + + diff --git a/libraries/AP_OSD/AP_OSD_MAX7456.cpp b/libraries/AP_OSD/AP_OSD_MAX7456.cpp new file mode 100644 index 0000000000..b44c9934f6 --- /dev/null +++ b/libraries/AP_OSD/AP_OSD_MAX7456.cpp @@ -0,0 +1,406 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + * MAX7456 driver partially based on betaflight and inav max7456.c implemention. + * Many thanks to their authors. + */ + +#include + +#include +#include +#include +#include + +#include + +#define VIDEO_BUFFER_CHARS_NTSC 390 +#define VIDEO_BUFFER_CHARS_PAL 480 +#define VIDEO_LINES_NTSC 13 +#define VIDEO_LINES_PAL 16 +#define VIDEO_COLUMNS 30 +#define MAX_UPDATED_CHARS 64 +#define SPI_BUFFER_SIZE ((MAX_UPDATED_CHARS + 1)* 8) +#define NVM_RAM_SIZE 54 + +//MAX7456 registers +#define MAX7456ADD_READ 0x80 +#define MAX7456ADD_VM0 0x00 +#define MAX7456ADD_VM1 0x01 +#define MAX7456ADD_HOS 0x02 +#define MAX7456ADD_VOS 0x03 +#define MAX7456ADD_DMM 0x04 +#define MAX7456ADD_DMAH 0x05 +#define MAX7456ADD_DMAL 0x06 +#define MAX7456ADD_DMDI 0x07 +#define MAX7456ADD_CMM 0x08 +#define MAX7456ADD_CMAH 0x09 +#define MAX7456ADD_CMAL 0x0a +#define MAX7456ADD_CMDI 0x0b +#define MAX7456ADD_OSDM 0x0c +#define MAX7456ADD_RB0 0x10 +#define MAX7456ADD_OSDBL 0x6c +#define MAX7456ADD_STAT 0xA0 + +// VM0 register bits +#define VIDEO_BUFFER_DISABLE 0x01 +#define MAX7456_RESET 0x02 +#define VERTICAL_SYNC_NEXT_VSYNC 0x04 +#define OSD_ENABLE 0x08 +#define VIDEO_MODE_PAL 0x40 +#define VIDEO_MODE_NTSC 0x00 +#define VIDEO_MODE_MASK 0x40 + +#define VIDEO_MODE_IS_PAL(val) (((val) & VIDEO_MODE_MASK) == VIDEO_MODE_PAL) +#define VIDEO_MODE_IS_NTSC(val) (((val) & VIDEO_MODE_MASK) == VIDEO_MODE_NTSC) + +// VM1 register bits +// duty cycle is on_off +#define BLINK_DUTY_CYCLE_50_50 0x00 +#define BLINK_DUTY_CYCLE_33_66 0x01 +#define BLINK_DUTY_CYCLE_25_75 0x02 +#define BLINK_DUTY_CYCLE_75_25 0x03 + +// blinking time +#define BLINK_TIME_0 0x00 +#define BLINK_TIME_1 0x04 +#define BLINK_TIME_2 0x08 +#define BLINK_TIME_3 0x0C + +// background mode brightness (percent) +#define BACKGROUND_BRIGHTNESS_0 (0x00 << 4) +#define BACKGROUND_BRIGHTNESS_7 (0x01 << 4) +#define BACKGROUND_BRIGHTNESS_14 (0x02 << 4) +#define BACKGROUND_BRIGHTNESS_21 (0x03 << 4) +#define BACKGROUND_BRIGHTNESS_28 (0x04 << 4) +#define BACKGROUND_BRIGHTNESS_35 (0x05 << 4) +#define BACKGROUND_BRIGHTNESS_42 (0x06 << 4) +#define BACKGROUND_BRIGHTNESS_49 (0x07 << 4) + +// STAT register bits +#define STAT_PAL 0x01 +#define STAT_NTSC 0x02 +#define STAT_LOS 0x04 +#define STAT_NVR_BUSY 0x20 + +#define STAT_IS_PAL(val) ((val) & STAT_PAL) +#define STAT_IS_NTSC(val) ((val) & STAT_NTSC) +#define STAT_IS_LOS(val) ((val) & STAT_LOS) + +#define VIN_IS_PAL(val) (!STAT_IS_LOS(val) && STAT_IS_PAL(val)) +#define VIN_IS_NTSC(val) (!STAT_IS_LOS(val) && STAT_IS_NTSC(val)) + +// There are occasions that NTSC is not detected even with !LOS (AB7456 specific?) +// When this happens, lower 3 bits of STAT register is read as zero. +// To cope with this case, this macro defines !LOS && !PAL as NTSC. +// Should be compatible with MAX7456 and non-problematic case. +#define VIN_IS_NTSC_ALT(val) (!STAT_IS_LOS(val) && !STAT_IS_PAL(val)) + +//CMM register bits +#define WRITE_NVR 0xA0 + +// DMM special bits +#define DMM_BLINK (1 << 4) +#define DMM_INVERT_PIXEL_COLOR (1 << 3) +#define DMM_CLEAR_DISPLAY (1 << 2) +#define DMM_CLEAR_DISPLAY_VERT (DMM_CLEAR_DISPLAY | 1 << 1) +#define DMM_AUTOINCREMENT (1 << 0) + +// time to check video signal format +#define VIDEO_SIGNAL_CHECK_INTERVAL_MS 1000 +//time to wait for input to stabilize +#define VIDEO_SIGNAL_DEBOUNCE_MS 100 +//time to wait nvm flash complete +#define MAX_NVM_WAIT 10000 + +//black and white level +#ifndef WHITEBRIGHTNESS +#define WHITEBRIGHTNESS 0x01 +#endif +#ifndef BLACKBRIGHTNESS +#define BLACKBRIGHTNESS 0x00 +#endif +#define BWBRIGHTNESS ((BLACKBRIGHTNESS << 2) | WHITEBRIGHTNESS) + + +extern const AP_HAL::HAL &hal; + +AP_OSD_MAX7456::AP_OSD_MAX7456(AP_OSD &osd, AP_HAL::OwnPtr dev): + AP_OSD_Backend(osd), _dev(std::move(dev)) +{ + buffer = nullptr; + frame = nullptr; + shadow_frame = nullptr; + attr = nullptr;; + shadow_attr = nullptr; + video_signal_reg = VIDEO_MODE_PAL | OSD_ENABLE; + max_screen_size = VIDEO_BUFFER_CHARS_PAL; + buffer_offset = 0; + video_detect_time = 0; + last_signal_check = 0; + initialized = false; +} + +AP_OSD_MAX7456::~AP_OSD_MAX7456() +{ + if (buffer != nullptr) { + hal.util->free_type(buffer, SPI_BUFFER_SIZE, AP_HAL::Util::MEM_DMA_SAFE); + } + if (frame != nullptr) { + hal.util->free_type(frame, VIDEO_BUFFER_CHARS_PAL, AP_HAL::Util::MEM_FAST); + } + if (shadow_frame != nullptr) { + hal.util->free_type(shadow_frame, VIDEO_BUFFER_CHARS_PAL, AP_HAL::Util::MEM_FAST); + } + if (attr != nullptr) { + hal.util->free_type(attr, VIDEO_BUFFER_CHARS_PAL, AP_HAL::Util::MEM_FAST); + } + if (shadow_attr != nullptr) { + hal.util->free_type(shadow_attr, VIDEO_BUFFER_CHARS_PAL, AP_HAL::Util::MEM_FAST); + } + +} + +bool AP_OSD_MAX7456::init() +{ + uint8_t status = 0xFF; + buffer = (uint8_t *)hal.util->malloc_type(SPI_BUFFER_SIZE, AP_HAL::Util::MEM_DMA_SAFE); + frame = (uint8_t *)hal.util->malloc_type(VIDEO_BUFFER_CHARS_PAL, AP_HAL::Util::MEM_FAST); + shadow_frame = (uint8_t *)hal.util->malloc_type(VIDEO_BUFFER_CHARS_PAL, AP_HAL::Util::MEM_FAST); + attr = (uint8_t *)hal.util->malloc_type(VIDEO_BUFFER_CHARS_PAL, AP_HAL::Util::MEM_FAST); + shadow_attr = (uint8_t *)hal.util->malloc_type(VIDEO_BUFFER_CHARS_PAL, AP_HAL::Util::MEM_FAST); + + + if (buffer == nullptr || frame == nullptr || shadow_frame == nullptr || attr== nullptr ||shadow_attr == nullptr) { + return false; + } + + _dev->set_speed(AP_HAL::Device::SPEED_HIGH); + + _dev->get_semaphore()->take_blocking(); + _dev->write_register(MAX7456ADD_VM0, MAX7456_RESET); + hal.scheduler->delay(1); + _dev->read_registers(MAX7456ADD_VM0|MAX7456ADD_READ, &status, 1); + _dev->get_semaphore()->give(); + return status == 0; +} + +bool AP_OSD_MAX7456::update_font() +{ + uint32_t font_size; + const uint8_t *font_data = AP_ROMFS::find_file("osd_font.bin", font_size); + if (font_data == nullptr || font_size != NVM_RAM_SIZE * 256) { + return false; + } + + for (int chr=0; chr < 256; chr++) { + uint8_t status; + const uint8_t* chr_font_data = font_data + chr*NVM_RAM_SIZE; + int retry; + buffer_offset = 0; + buffer_add_cmd(MAX7456ADD_VM0, 0); + buffer_add_cmd(MAX7456ADD_CMAH, chr); + for (int x = 0; x < NVM_RAM_SIZE; x++) { + buffer_add_cmd(MAX7456ADD_CMAL, x); + buffer_add_cmd(MAX7456ADD_CMDI, chr_font_data[x]); + } + buffer_add_cmd(MAX7456ADD_CMM, WRITE_NVR); + + _dev->get_semaphore()->take_blocking(); + _dev->transfer(buffer, buffer_offset, nullptr, 0); + _dev->get_semaphore()->give(); + + for (retry = 0; retry < MAX_NVM_WAIT; retry++) { + hal.scheduler->delay(15); + _dev->get_semaphore()->take_blocking(); + _dev->read_registers(MAX7456ADD_STAT, &status, 1); + _dev->get_semaphore()->give(); + if ((status & STAT_NVR_BUSY) == 0x00) { + break; + } + } + if (retry == MAX_NVM_WAIT) { + return false; + } + } + + return true; +} + +AP_OSD_Backend *AP_OSD_MAX7456::probe(AP_OSD &osd, AP_HAL::OwnPtr dev) +{ + if (!dev) { + return nullptr; + } + + AP_OSD_MAX7456 *backend = new AP_OSD_MAX7456(osd, std::move(dev)); + if (!backend || !backend->init()) { + delete backend; + return nullptr; + } + + return backend; +} + +void AP_OSD_MAX7456::buffer_add_cmd(uint8_t reg, uint8_t arg) +{ + if (buffer_offset < SPI_BUFFER_SIZE - 1) { + buffer[buffer_offset++] = reg; + buffer[buffer_offset++] = arg; + } +} + +void AP_OSD_MAX7456::check_reinit() +{ + uint8_t check = 0xFF; + _dev->get_semaphore()->take_blocking(); + + _dev->read_registers(MAX7456ADD_VM0|MAX7456ADD_READ, &check, 1); + + uint32_t now = AP_HAL::millis(); + + // Stall check + if (check != video_signal_reg) { + reinit(); + } else if ((now - last_signal_check) > VIDEO_SIGNAL_CHECK_INTERVAL_MS) { + uint8_t sense; + + // Adjust output format based on the current input format + _dev->read_registers(MAX7456ADD_STAT, &sense, 1); + + if (sense & STAT_LOS) { + video_detect_time = 0; + } else { + if ((VIN_IS_PAL(sense) && VIDEO_MODE_IS_NTSC(video_signal_reg)) + || (VIN_IS_NTSC_ALT(sense) && VIDEO_MODE_IS_PAL(video_signal_reg))) { + if (video_detect_time) { + if (AP_HAL::millis() - video_detect_time > VIDEO_SIGNAL_DEBOUNCE_MS) { + reinit(); + } + } else { + // Wait for signal to stabilize + video_detect_time = AP_HAL::millis(); + } + } + } + last_signal_check = now; + } + _dev->get_semaphore()->give(); +} + +void AP_OSD_MAX7456::reinit() +{ + uint8_t sense; + + //do not init MAX before camera power up correctly + if (AP_HAL::millis() < 1500) { + return; + } + + //check input signal format + _dev->read_registers(MAX7456ADD_STAT, &sense, 1); + if (VIN_IS_PAL(sense)) { + video_signal_reg = VIDEO_MODE_PAL | OSD_ENABLE; + max_screen_size = VIDEO_BUFFER_CHARS_PAL; + } else { + video_signal_reg = VIDEO_MODE_NTSC | OSD_ENABLE; + max_screen_size = VIDEO_BUFFER_CHARS_NTSC; + } + + // set all rows to same character black/white level + for (int x = 0; x < VIDEO_LINES_PAL; x++) { + _dev->write_register(MAX7456ADD_RB0 + x, BWBRIGHTNESS); + } + + // make sure the Max7456 is enabled + _dev->write_register(MAX7456ADD_VM0, video_signal_reg); + _dev->write_register(MAX7456ADD_VM1, BLINK_DUTY_CYCLE_50_50 | BLINK_TIME_3 | BACKGROUND_BRIGHTNESS_28); + _dev->write_register(MAX7456ADD_DMM, DMM_CLEAR_DISPLAY); + + // force redrawing all screen + memset(shadow_frame, 0xFF, VIDEO_BUFFER_CHARS_PAL); + memset(shadow_attr, 0xFF, VIDEO_BUFFER_CHARS_PAL); + + initialized = true; +} + +void AP_OSD_MAX7456::flush() +{ + if (_osd.update_font) { + if (!update_font()) { + hal.console->printf("AP_OSD: error during font update\n"); + } + _osd.update_font.set_and_save(0); + } + check_reinit(); + transfer_frame(); +} + +void AP_OSD_MAX7456::transfer_frame() +{ + int updated_chars = 0; + uint8_t last_attribute = 0xFF; + if (!initialized) { + return; + } + + buffer_offset = 0; + for (int pos=0; pos MAX_UPDATED_CHARS) { + break; + } + shadow_frame[pos] = frame[pos]; + shadow_attr[pos] = attr[pos]; + uint8_t attribute = attr[pos] & (DMM_BLINK | DMM_INVERT_PIXEL_COLOR); + uint8_t chr = frame[pos]; + + if (attribute != last_attribute) { + buffer_add_cmd(MAX7456ADD_DMM, attribute); + last_attribute = attribute; + } + buffer_add_cmd(MAX7456ADD_DMAH, pos >> 8); + buffer_add_cmd(MAX7456ADD_DMAL, pos & 0xFF); + buffer_add_cmd(MAX7456ADD_DMDI, chr); + } + + if (buffer_offset > 0) { + _dev->get_semaphore()->take_blocking(); + _dev->transfer(buffer, buffer_offset, nullptr, 0); + _dev->get_semaphore()->give(); + } +} + +void AP_OSD_MAX7456::clear() +{ + for (int i=0; i= VIDEO_LINES_PAL || text == nullptr) { + return; + } + while ((x < VIDEO_COLUMNS) && (*text != 0)) { + frame[y * VIDEO_COLUMNS + x] = *text; + attr[y * VIDEO_COLUMNS + x] = char_attr; + ++text; + ++x; + } +} diff --git a/libraries/AP_OSD/AP_OSD_MAX7456.h b/libraries/AP_OSD/AP_OSD_MAX7456.h new file mode 100644 index 0000000000..6df47cd2cd --- /dev/null +++ b/libraries/AP_OSD/AP_OSD_MAX7456.h @@ -0,0 +1,78 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + * + */ +#pragma once + +#include + +class AP_OSD_MAX7456 : public AP_OSD_Backend { + +public: + + static AP_OSD_Backend *probe(AP_OSD &osd, AP_HAL::OwnPtr dev); + + //draw given text to framebuffer + virtual void write(int x, int y, const char* text, uint8_t char_attr); + + //initilize display port and underlying hardware + virtual bool init(); + + //flush framebuffer to screen + virtual void flush(); + + //clear framebuffer + virtual void clear(); + +private: + + //constructor + AP_OSD_MAX7456(AP_OSD &osd, AP_HAL::OwnPtr dev); + + //destructor + virtual ~AP_OSD_MAX7456(void); + + void buffer_add_cmd(uint8_t reg, uint8_t arg); + + bool update_font(); + + void check_reinit(); + + void reinit(); + + void transfer_frame(); + + AP_HAL::OwnPtr _dev; + + uint8_t video_signal_reg; + bool initialized; + + uint8_t *frame; + + //frame already transfered to max + //used to optimize number of characters updated + uint8_t *shadow_frame; + + uint8_t *attr; + + uint8_t *shadow_attr; + + uint8_t *buffer; + int buffer_offset; + + uint32_t last_signal_check; + uint32_t video_detect_time; + + uint16_t max_screen_size; +}; diff --git a/libraries/AP_OSD/fonts/clarity.bin b/libraries/AP_OSD/fonts/clarity.bin new file mode 100644 index 0000000000000000000000000000000000000000..def282712a15b2868e3da0b3a04aa14906550efc GIT binary patch literal 13824 zcmeHN&5o-&5_Y0SLah26#d~1I@DwCEEg@Dka&6`j<|z`?NGK05Ylw6u#8b{!HV_lY z&zU*W+(la@#~7FE$5rLB3DF-Zdr|=%0u=^_FbKmyh|RNk1*wSgh7Kpn90oM-h)yN$ z;o?Ok$unbH%3DUlBRW@ba-vL9T&YGD6%`wvn*e(vh386nvgmjc<=i7U_A|3G@13Hr za`9wzl2Dpza4GdE4JbWPTG7FwT#gg!-&{~}k(jfn889=GC@bzM`LQ^HqVCa;19A>^ zwG3#OA{^DX0GfDPj?p9k`4{t0I8>adXsGBw9ZHbgMvvwYV{Qw&prafzROD3(D($&O zn|siYw-XxFYm{uy@_MI@MU)69>rYwVX3-21%fJK{SyG7l-4R>p8XDgy7doj>Q%VfU zd|sj}7K{ga^G@Uk6l^FUuF*zMGHUo1o1dY{gP^pQsV6hnN!=-M<Y2Y~^>WCVm z+MyV6-b~i;#F+jM6cF!LfI!=N#g9{wq!1@-nPFY(R-FRc1yr=kb9mJ@8Zf6P3A@i9 zEieOisOUE)&B@7jf8`vs8Bw)P@zrM1NnV-*D+paf{lB5>L=v`R02&X=p6vMJee9)^Jo4X`w47%2G~Ey&0UWI-Go3r0A^ zaE--kv^WH}wl)xIw99C(i6vVU)QdhV8H6TBTJ117>yY=6$F!DM5YyHM2SFWHns-7vC2r_suzoAn#9VO7At*)%9Y_oGfbeP&>*^7B$(1Hn3aU zK&R~~lx$SYtA99Z>ouNe)raGTO(n(|#PXC4_J3`_+tW2s8M)#f^usJWnOJc{37$#| zVmyVD2nI236xsoqoJDJa1-crhxG{1&TeYiP+LtkA9up2nmikt%`54yZ!0_nHql~uZ z;U*^BndrA#4+AW1@NS_a*io4&L2f;)FE$9H3e-5V%}sGeOKA>~kTh-9wOQO|o@RJd-7w*9zDNI8JJFiW zgHLNu8Ks`t#z+h4^u!EH1i3V~hq5dBPDK&z_fs5Lqou?Cw$0uLoi8;H*XH;G6@VHwrIFbs^j1dInJw6`+7 z8P>=QNU(}VtfdZTSdeZ+yec6YGe%n*lSyx}tFCOU#c^X8wrw7<*NBYErMY*GZi;>+ zHUJ^7wqeYSFQ0hJX2edjgsq$%&wg=@qE}j;8FpJM>`Dt-9Bs^<6^^2!%6IGA;>6q2 z2DVG1hxNSlgY#qnBmxw?STZ|T*|v(_TVLTyuD{?E!$I0aN| z2M{FqE>gQZZoR&W`$~9v;aG=~(v{nuiJ}l9?z;nrbdZzGEmi@Fzkgx_-<(|FINM3y zh2su2+UP<5J*hwuTw+=l!Ynk%#T7_{0kAQ#blXU9!9gsD28ad$Atr?7Y!-sAoGn?0 zP#2VzVY&IJsIy&^^{H^zZVD*Ww0vSN70L44nUZO%4mZ)Z0OAB9)=N{w8aHb=vULv}_R1AkkA|u@^+Q8I^ z-o0d6#(m{W)P83W+)8_FCMiOITLAips}{?y_KRUlMD$>oRm>GEs4*2xyM$=q1tW(t z5kg}Rua$58`{mzf02-X@>i&Uk)3#AS2=GEr-a7z$j~+RA@(Yx2+$TC3U;p2AH8R2< zdW6^@&Wqy!9=77K&Hem#H24?n$Jp2=N*dwyx;(WydoZx@_`p{GCWFD@B;Zq?XW~Hh zg5W8fw*#i+|6zmIYsA8p2;ddOC6>W`jQ#-Y0qLh$tE6AYvU&b3tchpFnim+i8y>^Z zk9Ca(dgeo}Pe>jTA-v1h-D(iE+tjY_8}J$*Z!zYIpl==X(m8lYL7l_aDc(6J$@m@# z0hV&)IY-JP!nbC8_IXmU{o!)B)PQ{u4eJT@m0|k(5_uK+NKTWODdR0R9zV&iJTvbT+(O zHRrglwHl6fb7tkthYU}go(LyB2bo)^HA5oAzxod3IPo~@bER2@iJVDkV!Q$yxL2Rg z{P^uE6X?8yg~|C2gwHY(Y2KYrytk7+#(MnLo@R~@4Pw_1-8gjZxA)r4=IzTb zzv|0ZeLmLb&M)tc%zR46H`$k*^8U-Fb2p7D5P+v0f|h65wu`9+!5D2AEw1|9C;mQ5JCVc7T~ zG6ad+)C78FAAvUHtu{ug`R7N5h*@`j?Z-75?#GW$K7hh~>dFBB6J=gju|9SmehFi& zW4FdU$p$_%D;g`XXr)YRM_9XpW3t4N2g|DFC#zMgU!Nba`q1y9CAJNZz+$qk6nvUG^hg-UCm$)bV(do0P$dPvtaH8G^6a}ge5WSJPfh*46 zOa`cvz}qWCxDo;v!WZ7I-b|Wnfcg9K z3N6kYIQ~EQzRXyxMvKGgYlZpRPKCJ>sQ8c`BPc_+xoV4|Epq3o`H|N6eP`wS@(Qgb z7R0o*0lA6=hb9q?y=Z%m;&XICU3Q|00NXA$4bewQ6iw+UpWB2JiA}$4A};~}(c3mc z7hqq`;&L=#9rqNxhW{A?g(p(4gbo6{_ZfhhojL3P5Lc&S)(iE}^8yy;XDU5Y9PX{2 zVj)%qIw>^%hB>0N$(sa^opW z|MJA<+_!*11WoV;Yw2G?Fv=NM{Wh&<{^h8)(%@K^gJ!*8d-wjou}W*S-n;(gX%3-A zTN_XP>#d`&mP+fdyU@o->#l#T(pq9cM%%w2SK0GI+Zc;-!*ffMgu!YNqF b`{~1S?(d#&4SZ|hTLa%3_}0MRM+5%>cQh#d literal 0 HcmV?d00001 diff --git a/libraries/AP_OSD/fonts/clarity.mcm b/libraries/AP_OSD/fonts/clarity.mcm new file mode 100644 index 0000000000..b984814c78 --- /dev/null +++ b/libraries/AP_OSD/fonts/clarity.mcm @@ -0,0 +1,16385 @@ +MAX7456 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010100 +00100001 +01010101 +01000010 +00100001 +01010100 +00100010 +00100001 +01000010 +00100010 +00100001 +00100010 +00100010 +00100001 +00000000 +00000000 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +00101000 +01010101 +01010000 +10100000 +01010101 +01000010 +10000001 +01010101 +01001010 +00000101 +01010101 +01001010 +00000101 +01010101 +01000010 +10000001 +01010101 +01010000 +10100000 +01010101 +01010100 +00101000 +01010101 +01010100 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010101 +00101000 +00010101 +01010101 +00001010 +00000101 +01010101 +01000010 +10000001 +01010101 +01010000 +10100001 +01010101 +01010000 +10100001 +01010101 +01000010 +10000001 +01010101 +00001010 +00000101 +01010101 +00101000 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +01010101 +01010101 +01001010 +00010101 +01010101 +00101010 +10000101 +01010100 +10100000 +00010101 +01010010 +10000101 +01010101 +01010010 +00000001 +01010101 +01010100 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010100 +10000101 +01010101 +01010010 +10000101 +01010100 +00001010 +00010101 +01010010 +10101000 +01010101 +01010000 +10100001 +01010101 +01010100 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +00101000 +00010101 +01010000 +10101010 +00000101 +01010010 +10101010 +10000101 +01010000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01000000 +01010101 +01001000 +01001000 +01010101 +01001000 +01001000 +01010101 +01001000 +00001000 +01010101 +01001000 +00100000 +01010101 +01001000 +00100001 +01010101 +01001000 +10000001 +01010101 +01001000 +10000101 +01010101 +01000010 +00000101 +01010101 +01010000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +01010101 +01010010 +10100010 +00010101 +01010010 +10101010 +10000101 +01010010 +10001000 +10000101 +01010010 +10001000 +10000101 +01010000 +00000000 +00000101 +01010000 +10101010 +00000101 +01010010 +10000010 +10000101 +01010010 +10101010 +10000101 +01010010 +10000010 +10000101 +01010000 +00000000 +00000101 +01010010 +10000000 +00000101 +01010010 +10101010 +00000101 +01010010 +10000010 +10000101 +01010010 +10000010 +10000101 +01010000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000101 +01010101 +01001010 +10100001 +01010101 +01001010 +10100001 +01010101 +01010000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00000101 +01010100 +10101010 +10100001 +01010100 +10101010 +10100001 +01010101 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000101 +01010101 +01001010 +10100001 +01010101 +01001010 +10100001 +01010101 +01010000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01011010 +10100101 +01010101 +01010000 +00010101 +01010101 +01010010 +00000101 +01010101 +01010010 +10000001 +01010101 +01010010 +10100000 +01010101 +01010010 +10101000 +00010101 +01010010 +10101010 +00010101 +01010010 +10101000 +00010101 +01010010 +10100000 +01010101 +01010010 +10000001 +01010101 +01010010 +00000101 +01010101 +01010000 +00010101 +01010101 +01011010 +10100101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01011010 +10100101 +01010101 +01010100 +00000101 +01010101 +01010000 +10000101 +01010101 +01000010 +10000101 +01010101 +00001010 +10000101 +01010100 +00101010 +10000101 +01010100 +10101010 +10000101 +01010100 +00101010 +10000101 +01010101 +00001010 +10000101 +01010101 +01000010 +10000101 +01010101 +01010000 +10000101 +01010101 +01010100 +00000101 +01010101 +01011010 +10100101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000101 +01001010 +10101010 +10000001 +01001010 +10101010 +10100001 +01001010 +00101000 +10100001 +01001010 +00101000 +10100001 +01001010 +00101000 +10100001 +01001010 +00101000 +10100001 +01001010 +00101000 +10100001 +01000000 +00000000 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00010101 +01010101 +00101010 +00010101 +01010101 +00100010 +00010101 +01010101 +00101010 +00010000 +00000101 +00000000 +00000010 +10000001 +01010101 +01001000 +00100001 +01010101 +01001000 +00000001 +01010100 +00001000 +00000101 +01010100 +10101010 +10000101 +01010100 +00001000 +00000101 +01010101 +01001000 +01010101 +01010101 +01001000 +01010101 +01010101 +01000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00010101 +01010101 +00101010 +00010101 +01010101 +00100010 +00010101 +01010101 +00101010 +00010101 +01010101 +00000000 +00000000 +00000101 +01010101 +00001010 +10000001 +01010101 +00100000 +00100001 +01010101 +00100001 +00000001 +01010101 +00100001 +01010101 +01010101 +00100001 +00000001 +01010101 +00100000 +00100001 +01010101 +00001010 +10000001 +01010101 +01000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00010101 +01010101 +01000010 +00000000 +01010101 +01001000 +10001000 +00010101 +01001000 +00001010 +00010101 +01001010 +00001000 +00000101 +01001000 +00001000 +10000101 +01001000 +01000010 +00000101 +01000000 +01010000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +10101010 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010101 +10101010 +01010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010001 +01010101 +01010101 +01001000 +00000000 +00000101 +00100010 +00101010 +10100001 +00100010 +00000000 +00001000 +00100010 +00010100 +00001000 +00100010 +00000010 +10100001 +00100010 +00101010 +00000101 +01001000 +00000000 +01010101 +01010001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00010101 +01010101 +01010010 +10000101 +01010101 +01001000 +00100001 +01010101 +00100001 +01001000 +01010101 +00100001 +01001000 +01010001 +00100001 +00001000 +01001000 +00100000 +10000001 +00100010 +00100010 +00100001 +00100010 +00100010 +00100001 +00100010 +00100010 +00100001 +01000010 +00100010 +00000101 +01010010 +00100010 +00010101 +01010010 +00100010 +00010101 +01010100 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00000101 +01010010 +10000010 +10000101 +01010010 +10000010 +10000101 +01010010 +10100010 +10000101 +01010010 +10101010 +10000101 +01010010 +10101010 +10000101 +01010010 +10101010 +10000101 +01010010 +10001010 +10000101 +01010010 +10000010 +10000101 +01010010 +10000010 +10000101 +01010010 +10000010 +10000101 +01010000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010000 +10101010 +00000101 +01010010 +10101010 +10000101 +01010010 +10000010 +10000101 +01010010 +10000000 +00000101 +01010000 +10101000 +00010101 +01010100 +00101010 +00000101 +01010000 +00000010 +10000101 +01010010 +10000010 +10000101 +01010010 +10101010 +10000101 +01010000 +10101010 +00000101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00000101 +01010010 +10101010 +10000101 +01010010 +10101010 +10000101 +01010010 +10000000 +00000101 +01010010 +10000000 +01010101 +01010010 +10101000 +01010101 +01010010 +10101000 +01010101 +01010010 +10000000 +01010101 +01010010 +10000000 +00000101 +01010010 +10101010 +10000101 +01010010 +10101010 +10000101 +01010000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010100 +00000001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +00101000 +10100001 +01001010 +00101000 +10100001 +01000010 +10101010 +10000001 +01010010 +10000010 +10000101 +01010010 +10000010 +10000101 +01010000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000101 +01010101 +01010000 +10000001 +01010101 +01000010 +10100000 +01010101 +01001010 +10101000 +01010101 +01000010 +10101000 +01010101 +01010000 +10101010 +01010101 +01010100 +00001000 +01010101 +01010101 +01000010 +01010101 +01010101 +00001010 +01010100 +00000010 +10001010 +01010100 +10100010 +10000000 +01010100 +10100000 +00101000 +01010100 +00000010 +00101001 +01010101 +01010000 +00000001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000001 +01010101 +01010101 +00100001 +01010101 +01010101 +10101000 +01010101 +01010101 +10100000 +01010101 +01010101 +10001000 +00000101 +01010101 +00101010 +10000001 +01010101 +00001010 +10100000 +01010101 +01001010 +10101000 +01010101 +01000010 +10100000 +01010101 +01010000 +10000001 +01010101 +01010100 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000001 +01010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010101 +00000001 +01010101 +01010101 +00000001 +01010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010101 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00010101 +01010101 +01010100 +10000001 +01010101 +01010010 +10001000 +00010101 +01001010 +10101010 +10000101 +01010010 +10001000 +10100001 +01010100 +10000001 +00100001 +01010101 +00010100 +00100001 +01010101 +01010010 +10100001 +01010100 +00001010 +00000101 +01010010 +10101000 +01010101 +01010010 +00000001 +01010101 +01010010 +00000001 +01010101 +01010010 +10101000 +01010101 +01010100 +00001010 +00010101 +01010101 +01010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010010 +10101010 +10000101 +01010100 +10101010 +00010101 +01010101 +00101000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +01010101 +00000101 +01001010 +00010100 +10100101 +01010000 +01000010 +10000101 +01010101 +00001010 +00010101 +01010101 +00101000 +01010101 +01010100 +10100001 +00000101 +01010010 +10000100 +10100001 +01001010 +00010101 +00000101 +01000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000101 +01010101 +01010000 +10100000 +01010101 +01010000 +10100000 +01010101 +01010101 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010101 +01010101 +00001010 +00000101 +01010101 +00001010 +00000101 +01010101 +01000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010100 +10100001 +01010101 +01010010 +10000101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01010010 +10000101 +01010101 +01010100 +10100001 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +01010101 +01010101 +01001010 +00010101 +01010101 +01010010 +10000101 +01010101 +01010100 +10100001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010100 +10100001 +01010101 +01010010 +10000101 +01010101 +01001010 +00010101 +01010101 +01010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010100 +00000001 +01001010 +00000000 +10100001 +01000010 +10000010 +10000001 +01000000 +10101010 +00000001 +01001010 +10101010 +10100001 +01000000 +10101010 +00000001 +01000010 +10000010 +10000001 +01001010 +00000000 +10100001 +01000000 +00010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000001 +01010101 +01010101 +00100001 +01010101 +01010000 +00100000 +00010101 +01010010 +10101010 +00010101 +01010000 +00100000 +00010101 +01010101 +00100001 +01010101 +01010101 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010101 +00101000 +01010101 +01010100 +00101000 +01010101 +01010100 +10100000 +01010101 +01010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00000101 +01010010 +10101010 +10000101 +01010010 +10101010 +10000101 +01010000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000001 +01010101 +01010000 +10100001 +01010101 +01000010 +10100001 +01010101 +00001010 +10000001 +01010100 +00101010 +00000101 +01010000 +10101000 +00010101 +01000010 +10100000 +01010101 +01001010 +10000001 +01010101 +01001010 +00000101 +01010101 +01000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010010 +10101010 +10000101 +01001010 +10000010 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +10000010 +10100001 +01010010 +10101010 +10000101 +01010100 +10101010 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01010101 +01010101 +00101000 +01010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010100 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010100 +00101000 +00010101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01000000 +00000000 +10100001 +01010101 +01010100 +10100001 +01010100 +00000000 +10100001 +01010010 +10101010 +10100001 +01001010 +10101010 +10000101 +01001010 +00000000 +00010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00000000 +00000001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01000000 +00000000 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01000000 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01000000 +10100001 +01010101 +00101010 +10000101 +01010101 +00101010 +10000101 +01010101 +01000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01000000 +00000000 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10000101 +01000000 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00010100 +00000001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10100001 +01010010 +10101010 +10100001 +01010100 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +00000000 +00000001 +01001010 +00010101 +01010101 +01001010 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01000000 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010000 +00000000 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10000101 +01000000 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010010 +10101010 +10000101 +01001010 +10101010 +10000101 +01001010 +00000000 +00000101 +01001010 +00010101 +01010101 +01001010 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10100001 +01010010 +10101010 +10000101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01000000 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010010 +10100001 +01010101 +01010010 +10000101 +01010101 +01001010 +10000101 +01010101 +01001010 +00010101 +01010101 +00101010 +00010101 +01010101 +00101000 +01010101 +01010100 +10101000 +01010101 +01010100 +10100001 +01010101 +01010010 +10100001 +01010101 +01010000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01010010 +10101010 +10000101 +01010010 +10101010 +10000101 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10100001 +01010010 +10101010 +10000101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10100001 +01010010 +10101010 +10100001 +01010100 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010000 +00000000 +10100001 +01010010 +10101010 +10100001 +01010010 +10101010 +10000101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010101 +00101000 +01010101 +01010100 +00101000 +01010101 +01010100 +10100000 +01010101 +01010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000101 +01010101 +01000010 +10000101 +01010101 +00001010 +00000101 +01010100 +00101000 +00010101 +01010000 +10100000 +01010101 +01010010 +10000001 +01010101 +01010010 +10000001 +01010101 +01010000 +10100000 +01010101 +01010100 +00101000 +00010101 +01010101 +00001010 +00000101 +01010101 +01000010 +10000101 +01010101 +01010000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00000101 +01010010 +10101010 +10000101 +01010010 +10101010 +10000101 +01010000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00000101 +01010010 +10101010 +10000101 +01010010 +10101010 +10000101 +01010000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010101 +01010101 +01001010 +00000101 +01010101 +01000010 +10000001 +01010101 +01010000 +10100000 +01010101 +01010100 +00101000 +00010101 +01010101 +00001010 +00010101 +01010101 +00001010 +00010101 +01010100 +00101000 +00010101 +01010000 +10100000 +01010101 +01000010 +10000001 +01010101 +01001010 +00000101 +01010101 +01000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010010 +00000000 +10000101 +01001000 +00000000 +00100001 +00100000 +10100010 +00001000 +00100010 +00001010 +00001000 +00100010 +00000010 +00001000 +00100010 +00001010 +00001000 +00100000 +10100010 +00100000 +00100000 +00000000 +10000001 +00001000 +00000100 +00000101 +01000010 +00000000 +00100001 +01010000 +10101010 +10000001 +01010100 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01000000 +00010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10000101 +01001010 +10101010 +10000101 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10000101 +01000000 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000001 +01010100 +00101010 +10100001 +01010010 +10101010 +10100001 +01000010 +10000000 +00000101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01000010 +10000000 +00000001 +01010010 +10101010 +10100001 +01010100 +00101010 +10100001 +01010101 +00000000 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000001 +01010101 +01001010 +10101000 +00010101 +01001010 +10101010 +10000101 +01001010 +00000010 +10000001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000010 +10000001 +01001010 +10101010 +10000101 +01001010 +10101000 +00010101 +01000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00000001 +01010010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +00000000 +00000101 +01001010 +00010101 +01010101 +01001010 +00000000 +01010101 +01001010 +10101000 +01010101 +01001010 +10101000 +01010101 +01001010 +00000000 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00000000 +00000001 +01001010 +10101010 +10100001 +01010010 +10101010 +10100001 +01010100 +00000000 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00000001 +01010010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +00000000 +00000101 +01001010 +00010101 +01010101 +01001010 +00000000 +00010101 +01001010 +10101010 +00010101 +01001010 +10101010 +00010101 +01001010 +00000000 +00010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000001 +01010100 +00101010 +10100001 +01010010 +10101010 +10100001 +01000010 +10000000 +00000001 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010100 +00000001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01000010 +10000000 +10100001 +01010010 +10101010 +10100001 +01010100 +00101010 +10100001 +01010101 +00000000 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010100 +00000001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01000000 +00010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01000000 +01010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01000010 +10000010 +10000001 +01010010 +10101010 +10000101 +01010100 +00101000 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010100 +00000001 +01001010 +00010100 +10100001 +01001010 +00010010 +10100001 +01001010 +00010010 +10000101 +01001010 +00001010 +10000101 +01001010 +00001010 +00010101 +01001010 +10101000 +01010101 +01001010 +10101000 +01010101 +01001010 +00001010 +00010101 +01001010 +00001010 +10000101 +01001010 +00010010 +10000101 +01001010 +00010010 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01000000 +00010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00000000 +00000001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01000000 +00000000 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01010101 +00000001 +01001000 +01010101 +00100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +10000010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +00101000 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01000000 +00010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01010100 +00000001 +01001010 +00010100 +10100001 +01001010 +10000100 +10100001 +01001010 +10100000 +10100001 +01001010 +10101000 +10100001 +01001010 +00101010 +10100001 +01001010 +00001010 +10100001 +01001010 +00010010 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01000000 +00010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010010 +10101010 +10000101 +01001010 +10000010 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +10000010 +10100001 +01010010 +10101010 +10000101 +01010100 +10101010 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10000101 +01001010 +00000000 +00010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010010 +10101010 +10000101 +01010010 +10000010 +10000101 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +00101000 +10100001 +01001010 +00101010 +10100001 +01001010 +00001010 +10100001 +01000010 +10000010 +10101000 +01010010 +10101010 +10101000 +01010100 +00101000 +00101000 +01010101 +01000001 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10000101 +01001010 +10101010 +10000101 +01001010 +00000010 +10100001 +01001010 +00010000 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01000000 +00010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00000101 +01010010 +10101010 +10000101 +01001010 +10101010 +10000101 +01001010 +00000000 +00010101 +01001010 +00010101 +01010101 +01001010 +00000000 +00010101 +01001010 +10101010 +10000101 +01010010 +10101010 +10100001 +01010100 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01000000 +00000000 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10000101 +01000000 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01000000 +00101000 +00000001 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010100 +00000001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +10000010 +10100001 +01010010 +10101010 +10000101 +01010100 +10101010 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010100 +00000001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01010010 +10000010 +10000101 +01010010 +10000010 +10000101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010100 +00000001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +00101000 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10000010 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001000 +01010101 +00100001 +01000000 +01010101 +00000001 +01000001 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010100 +00000001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +10000010 +10100001 +01010010 +10101010 +10000101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010010 +10101010 +10000101 +01001010 +10000010 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01000000 +00010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010100 +00000001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +10000010 +10100001 +01010010 +10101010 +10000101 +01010100 +10101010 +00010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01000000 +00000010 +10000101 +01010101 +01001010 +10000101 +01010101 +01001010 +00010101 +01010101 +00101010 +00010101 +01010101 +00101000 +01010101 +01010100 +10101000 +01010101 +01010100 +10100001 +01010101 +01010010 +10100001 +01010101 +01010010 +10000000 +00000001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01000000 +00000000 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010100 +10100000 +00010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100000 +00010101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +10000101 +01010101 +01010010 +10000101 +01010101 +01010010 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +10000101 +01010101 +01010010 +10000101 +01010101 +01010010 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010100 +00001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010100 +00001010 +00010101 +01010100 +10101010 +00010101 +01010100 +10101010 +00010101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +00101000 +00010101 +01010000 +10101010 +00000101 +01010010 +10000010 +10000101 +01010010 +00000000 +10000101 +01010000 +00010100 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00000101 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01010000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000101 +01010101 +01010101 +00100001 +01010101 +01010101 +00100001 +01010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010010 +10101010 +00010101 +01010010 +10101010 +00010101 +01001010 +10001010 +10000101 +01001010 +00000010 +10000101 +00101000 +00010000 +10100001 +00100000 +01010100 +00100001 +00000001 +01010101 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000101 +01010101 +01010100 +10000101 +01010101 +01010010 +10000101 +01010101 +01001010 +10000101 +01010101 +00101010 +10000101 +01010100 +10101010 +10000101 +01010010 +10101010 +10000101 +01001010 +10000010 +10000101 +00100000 +00010010 +10000101 +00000101 +01010100 +10000101 +01010101 +01010100 +10000101 +01010101 +01010101 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +01010101 +01010101 +00001000 +01010101 +01000000 +10100001 +01010000 +00101010 +10100001 +00001010 +10101010 +10000101 +00101010 +10101010 +10000101 +00000000 +00001010 +10000101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001000 +01010101 +01010101 +01000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00000000 +00000000 +00101010 +10101010 +10101000 +01000010 +10101010 +10100001 +01010100 +00101010 +10000101 +01010101 +00101010 +00010101 +01010100 +10101000 +01010101 +01010100 +10100001 +01010101 +01010100 +10000101 +01010101 +01010010 +00010101 +01010101 +01010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000001 +01010101 +01010101 +00101000 +00010101 +01010101 +00001010 +10000001 +01010101 +01000010 +10101000 +00010101 +01010000 +10101010 +10000001 +01010100 +00101010 +10101000 +01010000 +10101010 +10000001 +01000010 +10101000 +00010101 +00001010 +10000001 +01010101 +00101000 +00010101 +01010101 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +01010101 +01010101 +01010010 +00010101 +01010101 +01010100 +10000101 +01010101 +01010100 +10100001 +01010101 +01010100 +10101000 +01010101 +01010101 +00101010 +00010101 +01010100 +00101010 +10000101 +01000010 +10101010 +10100001 +00101010 +10101010 +10101000 +00000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01010101 +01010101 +01001000 +01010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +00000000 +00001010 +10000101 +00101010 +10101010 +10000101 +00001010 +10101010 +10000101 +01010000 +00101010 +10100001 +01010101 +01000000 +10100001 +01010101 +01010101 +00001000 +01010101 +01010101 +01010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000101 +01010101 +01010100 +10000101 +00000101 +01010100 +10000101 +00100000 +00010010 +10000101 +01001010 +10000010 +10000101 +01010010 +10101010 +10000101 +01010100 +10101010 +10000101 +01010101 +00101010 +10000101 +01010101 +01001010 +10000101 +01010101 +01010010 +10000101 +01010101 +01010100 +10000101 +01010101 +01010101 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000001 +01010101 +00000001 +00100000 +01010100 +00100001 +00101000 +00010000 +10100001 +01001010 +00000010 +10000101 +01001010 +10001010 +10000101 +01010010 +10101010 +00010101 +01010010 +10101010 +00010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010101 +00100001 +01010101 +01010101 +00100001 +01010101 +01010101 +01000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +01010101 +01010101 +01010010 +00010101 +01010101 +01010010 +00010101 +01010000 +01010010 +10000100 +00001000 +01010010 +10000010 +10100001 +01010010 +10101010 +10000101 +01010010 +10101010 +00010101 +01010010 +10101000 +01010101 +01010010 +10100001 +01010101 +01010010 +10000101 +01010101 +01010010 +00010101 +01010101 +01010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000001 +01010101 +01010101 +00100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010010 +10100000 +00000000 +01010010 +10101010 +10101000 +01010010 +10101010 +10100000 +01001010 +10101000 +00000101 +01001010 +00000001 +01010101 +00100000 +01010101 +01010101 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000101 +01010101 +01010100 +10000101 +01010101 +01010010 +00010101 +01010101 +01001010 +00010101 +01010101 +00101010 +00010101 +01010100 +10101000 +01010101 +01010010 +10101000 +00010101 +01001010 +10101010 +10000001 +00101010 +10101010 +10101000 +00000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01010101 +01010100 +00101000 +01010101 +01000010 +10100000 +01010100 +00101010 +10000001 +01000010 +10101010 +00000101 +00101010 +10101000 +00010101 +01000010 +10101010 +00000101 +01010100 +00101010 +10000001 +01010101 +01000010 +10100000 +01010101 +01010100 +00101000 +01010101 +01010101 +01000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00000000 +00000000 +00101010 +10101010 +10101000 +01001010 +10101010 +10000001 +01010010 +10101000 +00010101 +01010100 +10101000 +01010101 +01010101 +00101010 +00010101 +01010101 +01001010 +00010101 +01010101 +01010010 +00010101 +01010101 +01010100 +10000101 +01010101 +01010101 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000101 +01010101 +01010101 +00100000 +01010101 +01010101 +01001010 +00000001 +01010101 +01001010 +10101000 +00000101 +01010010 +10101010 +10100000 +01010010 +10101010 +10101000 +01010010 +10100000 +00000000 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010101 +00100001 +01010101 +01010101 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +01010101 +01010101 +01010010 +00010101 +01010101 +01010010 +10000101 +01010101 +01010010 +10100001 +01010101 +01010010 +10101000 +01010101 +01010010 +10101010 +00010101 +01010010 +10101010 +10000101 +01010010 +10000010 +10100001 +01010010 +10000100 +00001000 +01010010 +00010101 +01010000 +01010010 +00010101 +01010101 +01010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00000001 +01000010 +10000010 +10100001 +01001000 +00100010 +00001000 +01001000 +00100010 +00001000 +01000010 +10000010 +00001000 +01010000 +00000000 +00000001 +01000000 +01010101 +01010101 +01001000 +01010100 +00000000 +01001000 +00000100 +10001000 +01001000 +10000100 +10100000 +01001010 +00100000 +10000001 +01001000 +00100000 +10000101 +01000000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00000000 +01000010 +00100010 +00001000 +01001000 +00100010 +00001000 +00101010 +00100000 +10101000 +01001000 +00100000 +00001000 +01001000 +00100000 +10100000 +01000000 +00000000 +00000101 +01010010 +00010100 +00000001 +01010010 +00000000 +10001000 +01010010 +00100000 +10100000 +01010010 +10001000 +10000001 +01010010 +00001000 +10000101 +01010000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000101 +01010101 +01010101 +00100001 +01010101 +01010100 +10001000 +01010101 +01010010 +00010010 +00010101 +01010100 +01010100 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000001 +01010101 +01010010 +10101000 +01010101 +01010100 +00001000 +01010101 +01010101 +01001000 +01010101 +01010101 +01001000 +01010101 +01010101 +01010001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00010101 +01010101 +01010100 +10000101 +01010101 +01010101 +00100001 +01010101 +01010101 +01001000 +01010101 +01010101 +00100001 +01010101 +01010100 +10000101 +01010101 +01010101 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010001 +01010101 +01010101 +01001000 +01010101 +01010101 +01001000 +01010101 +01010100 +00001000 +01010101 +01010010 +10101000 +01010101 +01010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +01010100 +01010101 +01010010 +00010010 +00010101 +01010100 +10001000 +01010101 +01010101 +00100001 +01010101 +01010101 +01000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00010101 +01010101 +01010100 +10000101 +01010101 +01010100 +10000101 +01010101 +01010100 +10000000 +01010101 +01010100 +10101010 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010001 +01010101 +01010101 +01001000 +01010101 +01010101 +00100001 +01010101 +01010100 +10000101 +01010101 +01010101 +00100001 +01010101 +01010101 +01001000 +01010101 +01010101 +01010001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010100 +10000000 +01010101 +01010100 +10000101 +01010101 +01010100 +10000101 +01010101 +01010101 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000101 +01010101 +01010100 +10100001 +01010101 +01010010 +10000101 +01010101 +01001010 +00010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01001010 +00010101 +01010101 +01010010 +10000101 +01010101 +01010100 +10100001 +01010101 +01010101 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00010101 +01010101 +01010010 +10000101 +01010101 +01010100 +10100001 +01010101 +01010101 +00101000 +01010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +00101000 +01010101 +01010100 +10100001 +01010101 +01010010 +10000101 +01010101 +01010100 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01000001 +01010101 +01010100 +00101000 +00010101 +00000100 +10101010 +00010000 +10100010 +10010110 +10001010 +10100010 +10010110 +10001010 +00000100 +10101010 +00010000 +01010100 +00101000 +00010101 +01010101 +01000001 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +01000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +10101010 +00000101 +01010000 +10101010 +00000101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010000 +10101010 +00000101 +01010000 +10101010 +00000101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010000 +10101010 +00000101 +01010000 +10101010 +00000101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010000 +10101010 +00000101 +01010000 +10101010 +00000101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010000 +10101010 +00000101 +01010000 +10101010 +00000101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010000 +10101010 +00000101 +01010000 +10101010 +00000101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010000 +10101010 +00000101 +01010000 +10101010 +00000101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010000 +10101010 +00000101 +01010000 +10101010 +00000101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010000 +10101010 +00000101 +01010000 +10101010 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00000000 +00000101 +00000000 +00000000 +00000001 +00000000 +00000000 +00000000 +00000000 +10000000 +00000000 +00000000 +10000000 +00000000 +00000000 +10000000 +00000000 +00001010 +10101000 +00000000 +00000000 +10000000 +00000000 +00000000 +10000000 +00000000 +00000000 +10000000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000001 +00000000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +00000001 +00101000 +01000000 +10100000 +00000000 +00001010 +10101010 +10101010 +10101010 +10101010 +10101010 +10101010 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +00000001 +00101000 +01000000 +10100000 +00000000 +00001010 +10101010 +10101010 +10101010 +10101010 +10101010 +10101010 +10100000 +00000000 +00001010 +00000001 +00101000 +01000000 +01010101 +00101000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +00000001 +00101000 +01000000 +10100000 +00000000 +00001010 +10101010 +10101010 +10101010 +10101010 +10101010 +10101010 +10100000 +00000000 +00001010 +00000001 +00101000 +01000000 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +00000001 +00101000 +01000000 +10100000 +00000000 +00001010 +10101010 +10101010 +10101010 +10101010 +10101010 +10101010 +10100000 +00000000 +00001010 +00000001 +00101000 +01000000 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +00000001 +00101000 +01000000 +10100000 +00000000 +00001010 +10101010 +10101010 +10101010 +10101010 +10101010 +10101010 +10100000 +00000000 +00001010 +00000001 +00101000 +01000000 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +10100000 +00000000 +00001010 +10101010 +10101010 +10101010 +10101010 +10101010 +10101010 +10100000 +00000000 +00001010 +00000001 +00101000 +01000000 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010000 +10101010 +00000101 +01001010 +10000010 +10100001 +01001010 +10000010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010000 +10101010 +00000101 +01001010 +10000010 +10100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010000 +10101010 +00000101 +01001010 +10000010 +10100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010000 +10101010 +00000101 +01001010 +10000010 +10100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010000 +10101010 +00000101 +01001010 +10000010 +10100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010000 +10101010 +00000101 +01001010 +10000010 +10100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010000 +10101010 +00000101 +01001010 +10000010 +10100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001000 +00000000 +00100001 +01001010 +10101010 +10100001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00000000 +00000000 +00001000 +00100010 +10000000 +00100010 +00100010 +00100000 +00101010 +00100010 +10000000 +00100010 +00100010 +00100000 +00100010 +00100010 +00100000 +00000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00000000 +01000000 +00000000 +00000000 +00001010 +10100010 +00000010 +00001000 +00000010 +00000010 +00001000 +00000010 +00000010 +00001000 +00000000 +10001000 +00001000 +10100000 +10001000 +00001000 +00100000 +00100000 +00001000 +00100000 +00100000 +00001000 +00100000 +00100000 +00001010 +10100000 +00100000 +01000000 +00000000 +00000000 +01010000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010000 +10000010 +00000101 +01000010 +00001010 +10000101 +01001010 +10000010 +00000101 +01000010 +00000010 +00000101 +01010010 +00010000 +10000101 +01000000 +00000000 +00000101 +01001010 +10101010 +10000101 +01000000 +00000000 +00000101 +01010100 +00000000 +01010101 +01010000 +10101000 +01010101 +01010010 +10000000 +01010101 +01010000 +00101000 +01010101 +01010010 +10100000 +01010101 +01010000 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +00101000 +00010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +10101010 +00010101 +01010100 +10000010 +00010101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000000 +00000010 +10000010 +10100000 +00001000 +00100010 +00001000 +00001000 +00100010 +00001000 +00000010 +10000010 +00001000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +00001010 +10100000 +10101000 +00001000 +10001000 +10000010 +00001000 +10001000 +10000010 +00001000 +10001000 +10000010 +01000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000000 +00000010 +00100010 +00001000 +00001000 +00100010 +00001000 +00101010 +00100000 +10101000 +00001000 +00100000 +00001000 +00001000 +00100000 +10100000 +00000000 +00000000 +00000000 +00001010 +10100000 +10101000 +00001000 +10001000 +10000010 +00001000 +10001000 +10000010 +00001000 +10001000 +10000010 +01000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01010100 +01010101 +00100010 +00010010 +01010100 +10001000 +10001000 +01010100 +10001000 +10001010 +01010100 +10000000 +10001000 +01010101 +00010101 +00010001 +01010101 +00000000 +00000000 +01010100 +10101010 +10101010 +01010101 +00000000 +00000000 +01010101 +01010100 +00010000 +01010101 +01010010 +00001000 +01010101 +01010010 +00100000 +01010101 +01010010 +10100000 +01010101 +01010010 +00001000 +01010101 +01010100 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000101 +01010101 +01010100 +10000101 +01010101 +00010100 +10000001 +01010101 +10000100 +10001000 +01010101 +00100000 +10100010 +00010101 +10100000 +10000010 +00010101 +00100000 +10000010 +00010101 +01000101 +00010100 +01010101 +00000000 +00000000 +01010101 +10101010 +10101010 +00010101 +00000000 +00000000 +01010101 +00000100 +00010101 +01010101 +00100010 +00010101 +01010101 +10001000 +10000101 +01010101 +10001000 +10000101 +01010101 +10000000 +10000101 +01010101 +00010101 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010010 +10100010 +00000101 +01010010 +10101010 +10000101 +01010010 +10001000 +10000101 +01010010 +10001000 +10000101 +01010010 +10001000 +10000101 +01000000 +00000000 +00000001 +01001010 +10101010 +10100001 +01000000 +00000000 +00000001 +01010000 +10101010 +10000101 +01010010 +10100000 +00000101 +01010000 +10101010 +00000101 +01010000 +00001010 +10000101 +01010010 +10101010 +00000101 +01010000 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00000000 +00000000 +10100000 +10001010 +00101010 +10001000 +10001000 +00001000 +10001000 +10000010 +00001000 +10001000 +10000000 +10001000 +10100000 +10001010 +00001000 +00000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010001 +01010101 +01010101 +01001000 +00000000 +00000101 +01001000 +10001010 +00100001 +01001010 +00001000 +10001000 +01001000 +10001000 +10001000 +01001000 +10001000 +10001000 +01000000 +00000000 +00000000 +01101010 +10101010 +10101000 +01000000 +00000000 +00000001 +01010100 +10000101 +01010101 +01010100 +10000000 +00010101 +01010100 +10101010 +00010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010001 +01010101 +01010101 +01001000 +01010101 +01010101 +00101010 +00010101 +01010100 +10101010 +10000101 +01010010 +10101010 +10100001 +01000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010001 +01010101 +01010101 +01001000 +01010101 +01010101 +00101010 +00010101 +01010100 +10101010 +10000101 +01010010 +10101010 +10100001 +01000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010001 +01010101 +01010101 +01001000 +01010101 +01010101 +00101010 +00010101 +01010100 +10101010 +10000101 +01010010 +10101010 +10100001 +01000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000000 +01010010 +10101010 +10100001 +01010100 +10101010 +10000101 +01010101 +00101010 +00010101 +01010101 +01001000 +01010101 +01010101 +01010001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000000 +01010010 +10101010 +10100001 +01010100 +10101010 +10000101 +01010101 +00101010 +00010101 +01010101 +01001000 +01010101 +01010101 +01010001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000000 +01010010 +10101010 +10100001 +01010100 +10101010 +10000101 +01010101 +00101010 +00010101 +01010101 +01001000 +01010101 +01010101 +01010001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000001 +01000000 +00000000 +00100001 +00001000 +00101010 +00100001 +00100010 +00001000 +00100001 +00101010 +00001000 +00100000 +00100010 +00001000 +00101010 +00100010 +00001000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000101 +00000001 +00000100 +10000100 +00100000 +10000010 +10000100 +10001000 +10100010 +10000100 +10001000 +10001010 +10000000 +10001000 +10001010 +10101000 +00100000 +10000010 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +00101000 +00010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +00101000 +00010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00010101 +01010101 +01010010 +00000000 +01010101 +01001010 +10101010 +00010101 +01001010 +10101010 +10000101 +01010010 +00000000 +10100001 +01010100 +00010100 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010100 +00010100 +00101000 +01010010 +00000000 +10100001 +01001010 +10101010 +10000101 +01001010 +10101010 +00010101 +01010010 +00000000 +01010101 +01010100 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00000000 +00000000 +00001000 +00100000 +10101000 +00100010 +00100000 +00100000 +00101010 +00100000 +00100000 +00100010 +00100000 +00100000 +00100010 +00101010 +00100000 +00000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00010100 +00000101 +01010010 +00010100 +10000101 +01010010 +00000000 +10000101 +01010010 +00000000 +10000101 +01010010 +00101000 +10000101 +01010000 +10101010 +00000101 +01010100 +10000010 +00010101 +01010100 +00000000 +00010101 +01010100 +00000101 +01010101 +01010100 +10000101 +01010101 +01010100 +10000000 +01010101 +01010100 +10001000 +01010101 +01010100 +10100010 +00010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010001 +01010100 +01010101 +01001000 +01010010 +01010101 +01001000 +01010010 +01010101 +01001000 +00000010 +01010101 +01001000 +10100010 +01010101 +01010010 +10101000 +01010101 +01010010 +00001000 +01010101 +01010100 +01010001 +01010101 +00000000 +00000000 +01010100 +10101010 +10101010 +01010101 +00000000 +00000000 +01010101 +01010100 +00010000 +01010101 +01010010 +00001000 +01010101 +01010010 +00100000 +01010101 +01010010 +10100000 +01010101 +01010010 +00001000 +01010101 +01010100 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00100001 +01010101 +01010101 +00100000 +01010101 +01010101 +00100010 +00010101 +01010101 +00101000 +10000101 +01010101 +00100000 +10000101 +01010101 +00100000 +10000101 +01010101 +01000101 +00010101 +01010101 +00000000 +00000000 +01010101 +10101010 +10101010 +00010101 +00000000 +00000000 +01010101 +00000100 +00010101 +01010101 +00100010 +00010101 +01010101 +10001000 +10000101 +01010101 +10001000 +10000101 +01010101 +10000000 +10000101 +01010101 +00010101 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00010100 +00000101 +01010010 +00010100 +10000101 +01010010 +00000000 +10000101 +01010010 +00101000 +10000101 +01010000 +10101010 +00000101 +01010100 +10000010 +00010101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00101010 +10101010 +10101000 +00101010 +10101010 +10101000 +01000000 +00101000 +00000001 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01000000 +00101000 +00000001 +00101010 +10101010 +10101000 +00101010 +10101010 +10101000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000001 +00001000 +10000010 +10100000 +00100010 +00100010 +00001000 +00100010 +00100010 +10100000 +00100000 +00100010 +00000001 +00000000 +00000000 +00010101 +01001010 +10101000 +01010101 +01000000 +00000000 +01010101 +01010100 +10000101 +01010101 +01010100 +10000000 +01010101 +01010100 +10001000 +00010101 +01010100 +10100010 +00010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +01010001 +01000101 +01001010 +00001000 +00100000 +00100000 +10001000 +10101000 +00100000 +10001000 +00100000 +00101010 +10001000 +00100000 +00100000 +10001000 +00001000 +01000101 +00010001 +01010001 +01010101 +01000000 +01010101 +01010101 +00101010 +00010101 +01010100 +10001000 +10000101 +01010100 +10001000 +10000101 +01010100 +10001000 +10000101 +01010101 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +01010001 +01000101 +01001010 +00001000 +00100000 +00100000 +10001000 +10101000 +00100000 +10001000 +00100000 +00101010 +10001000 +00100000 +00100000 +10001000 +00001000 +01000101 +00010001 +01010001 +01000101 +00010100 +01000101 +00100000 +10000010 +00100001 +00100010 +00001000 +10001000 +00101010 +00001000 +10001000 +00100000 +10001000 +00001000 +01000000 +00000001 +01010001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +01010001 +01000101 +01001010 +00001000 +00100001 +00100000 +10001000 +10101000 +00100000 +10001000 +00100000 +00101010 +10001000 +00100000 +00100000 +10001000 +01001000 +01000101 +00010001 +01010001 +01010101 +00010100 +01010101 +01010100 +10000010 +00010101 +01010010 +00001010 +10000101 +01001010 +10000010 +00010101 +01010010 +00010010 +00010101 +01010010 +00010100 +10000101 +01010100 +01010101 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +01010001 +01000101 +01001010 +00001000 +00100001 +00100000 +10001000 +10101000 +00100000 +10001000 +00100000 +00101010 +10001000 +00100000 +00100000 +10001000 +01001000 +01000101 +00010001 +01010001 +01000100 +01010001 +01000101 +00100010 +00001000 +00100001 +00100010 +00100000 +10101000 +00101000 +00101000 +00100001 +00100010 +00100001 +00100001 +00100010 +00100001 +01001000 +01000100 +01000101 +01010001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01000001 +01000101 +00101000 +00101000 +00100001 +00100010 +00100000 +10101000 +00100010 +00101000 +00100001 +00100010 +00001000 +00100001 +00101000 +00101000 +01001000 +01000001 +01000001 +01010001 +01010101 +01000000 +01010101 +01010101 +00101010 +00010101 +01010100 +10001000 +10000101 +01010100 +10001000 +10000101 +01010100 +10001000 +10000101 +01010101 +00010001 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01000001 +01000101 +00101000 +00101000 +00100001 +00100010 +00100000 +10101000 +00100010 +00101000 +00100001 +00100010 +00001000 +00100001 +00101000 +00101000 +01001000 +01000001 +00000000 +01000001 +00100000 +10000010 +00100001 +00100010 +00001000 +10001000 +00101010 +00001000 +10001000 +00100000 +10001000 +00001000 +01000000 +00000001 +01010001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01000001 +01000101 +00101000 +00101000 +00100001 +00100010 +00100000 +10101000 +00100010 +00101000 +00100001 +00100010 +00001000 +00100001 +00101000 +00101000 +01001000 +01000001 +01000001 +01010001 +01010101 +01010100 +01010101 +01010100 +10000010 +00010101 +01010010 +00001010 +10000101 +01001010 +10000010 +00010101 +01010010 +00010010 +00010101 +01010010 +00010100 +10000101 +01010100 +01010101 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01000001 +01000101 +00101000 +00101000 +00100001 +00100010 +00100000 +10101000 +00100010 +00101000 +00100001 +00100010 +00001000 +00100001 +00101000 +00101000 +01001000 +01000001 +01000001 +01010001 +01010100 +00000101 +00000101 +01010010 +10100001 +00100001 +01001000 +10001000 +00100001 +01001000 +10001000 +00100001 +01001000 +10001000 +00100001 +01010001 +00010001 +01000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000001 +01010101 +01010100 +10101000 +01010101 +01010010 +00100010 +00010101 +01010010 +00100010 +00010101 +01010010 +00100010 +00010101 +01010100 +01000100 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +00000000 +01000001 +00100000 +10000010 +00100001 +00100010 +00001000 +10001000 +00101010 +00001000 +10001000 +00100000 +10001000 +00001000 +01000000 +00000001 +01010001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000101 +00000101 +01010010 +10100001 +00100001 +01001000 +10001000 +00100001 +01001000 +10001000 +00100001 +01001000 +10001000 +00100001 +01010001 +00010001 +01000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01000000 +00000000 +00000001 +00000010 +10101010 +10000000 +00101010 +10101010 +10101000 +00101000 +00000000 +00101000 +10100000 +10100000 +00001010 +10100000 +10100000 +00001010 +10100000 +10100000 +00001010 +10100000 +10101010 +10001010 +10100000 +10101010 +10001010 +10100000 +00000000 +00001010 +00101000 +00000000 +00101000 +00101010 +10101010 +10101000 +00000010 +10101010 +10000000 +01000000 +00000000 +00000001 +01010100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000101 +00000000 +00010101 +00100000 +10001010 +10000000 +00100000 +10001000 +00100010 +00100000 +10001000 +00100010 +00101010 +10001000 +00100010 +00100000 +10001000 +00100010 +00100000 +10001000 +00100010 +00100000 +10001010 +10000000 +01000101 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000101 +00000001 +01010101 +10100000 +10101000 +01010101 +00001000 +10000010 +00010001 +00001000 +10000010 +00001000 +00001000 +10101000 +01000000 +00001000 +10000001 +01001000 +00001000 +10000101 +01010001 +10100000 +10000101 +01010101 +00000101 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000101 +01010101 +01000001 +00100001 +01010101 +00101000 +00100001 +01010100 +10101010 +00100001 +01010010 +10101010 +10100001 +01001010 +10101010 +10100001 +00101010 +10101010 +10101000 +01001010 +10101010 +10100001 +01001010 +10000010 +10100001 +01001010 +10000010 +10100001 +01001010 +10000010 +10100001 +01001010 +10101010 +10100001 +01010000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010010 +10101010 +10000101 +01001010 +10000010 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +10000010 +10100000 +01010010 +10101010 +10000010 +01010100 +10101010 +00010010 +01010101 +00000000 +01010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01010101 +01010101 +00101000 +01010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010100 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010100 +00101000 +00010000 +01010100 +10101010 +00010010 +01010100 +10101010 +00010010 +01010100 +00000000 +00010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01000000 +00000000 +10100001 +01010101 +01010100 +10100001 +01010100 +00000000 +10100001 +01010010 +10101010 +10100001 +01001010 +10101010 +10000101 +01001010 +00000000 +00010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +01001010 +00000000 +00000000 +01001010 +10101010 +10100010 +01001010 +10101010 +10100010 +01000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01000000 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01000000 +10100001 +01010101 +00101010 +10000101 +01010101 +00101010 +10000101 +01010101 +01000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01000000 +00000000 +10100000 +01001010 +10101010 +10100010 +01001010 +10101010 +10000010 +01000000 +00000000 +00010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00010100 +00000001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10100001 +01010010 +10101010 +10100001 +01010100 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100000 +01010101 +01010100 +10100010 +01010101 +01010100 +10100010 +01010101 +01010100 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +00000000 +00000001 +01001010 +00010101 +01010101 +01001010 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01000000 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010000 +00000000 +10100000 +01001010 +10101010 +10100010 +01001010 +10101010 +10000010 +01000000 +00000000 +00010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010010 +10101010 +10000101 +01001010 +10101010 +10000101 +01001010 +00000000 +00000101 +01001010 +00010101 +01010101 +01001010 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100000 +01001010 +10101010 +10100010 +01010010 +10101010 +10000010 +01010100 +00000000 +00010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01000000 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010010 +10100001 +01010101 +01010010 +10000101 +01010101 +01001010 +10000101 +01010101 +01001010 +00010101 +01010101 +00101010 +00010101 +01010101 +00101000 +01010101 +01010100 +10101000 +01010000 +01010100 +10100001 +01010010 +01010010 +10100001 +01010010 +01010000 +00000101 +01010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01010010 +10101010 +10000101 +01010010 +10101010 +10000101 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100000 +01001010 +10101010 +10100010 +01010010 +10101010 +10000010 +01010100 +00000000 +00010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10100001 +01010010 +10101010 +10100001 +01010100 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +01010000 +00000000 +10100000 +01010010 +10101010 +10100010 +01010010 +10101010 +10000010 +01010100 +00000000 +00010000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00000000 +01000000 +00000000 +00000000 +00101010 +00001010 +00101000 +00000010 +10001010 +00101000 +00101010 +10001010 +00101000 +10100010 +10001010 +00101000 +00101010 +10000010 +10101000 +00000000 +10100000 +00101000 +00000000 +10100000 +00101000 +00000010 +10101000 +00101010 +00000000 +10100000 +00101000 +00000000 +10100000 +00101000 +00000000 +10101010 +00101000 +01000000 +00101000 +00101000 +01010000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000001 +01010101 +01010101 +00101000 +00000000 +00000101 +00101000 +00000000 +00000001 +10101010 +00000010 +10100000 +00101000 +00001010 +00101000 +00101000 +00001010 +00101000 +00101010 +10001010 +00101000 +00001010 +00000010 +10100000 +00000000 +00000000 +00000000 +00000000 +00000000 +00000000 +10000010 +10101000 +00000000 +10100010 +10001010 +00000000 +10100010 +10000000 +00000000 +10100010 +10000000 +00000000 +10100010 +10000000 +00000001 +00000000 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000001 +01010100 +00000000 +10100001 +01000000 +10101010 +00000001 +01001010 +00000000 +00010101 +01000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000001 +01010101 +01010100 +10101000 +01010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +10101000 +01010101 +01010100 +10001010 +01010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010101 +00010100 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000001 +01001010 +10101010 +10100001 +01000000 +00000000 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000001 +01010101 +01010100 +10101000 +01010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +10101000 +01010101 +01010100 +10001010 +01010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010101 +00010100 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00010101 +01010101 +01001010 +00000000 +00010101 +01000000 +10101010 +00000001 +01010100 +00000000 +10100001 +01010101 +01010100 +00000001 +01010101 +01010101 +01010101 +01010101 +00000001 +01010101 +01010100 +10101000 +01010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +10101000 +01010101 +01010100 +10001010 +01010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010101 +00010100 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000101 +01010101 +01010101 +00100001 +01010101 +01010100 +10101000 +01010101 +01010010 +10101010 +00010101 +01001010 +10101010 +10000101 +00000000 +00000000 +00000001 +01010101 +01010101 +01010101 +01010101 +00000001 +01010101 +01010100 +10101000 +01010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +10101000 +01010101 +01010100 +10000001 +01010101 +01010100 +10000101 +01010101 +01010100 +10000101 +01010101 +01010100 +10000101 +01010101 +01010101 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +01010101 +01010100 +10101010 +00010101 +01010010 +10101010 +10000101 +01001010 +10000010 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +00001010 +10000010 +10100001 +10000010 +10101010 +10000101 +10000100 +10101010 +00010101 +00000101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +01010101 +01010101 +00101000 +01010101 +01010100 +10101000 +01010101 +01010100 +10101000 +01010101 +01010100 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +01010101 +00101000 +01010101 +00000100 +00101000 +00010101 +10000100 +10101010 +00010101 +10000100 +10101010 +00010101 +00000100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01000000 +00000000 +10100001 +01010101 +01010100 +10100001 +01010100 +00000000 +10100001 +01010010 +10101010 +10100001 +01001010 +10101010 +10000101 +01001010 +00000000 +00010101 +01001010 +00010101 +01010101 +01001010 +00010101 +01010101 +00001010 +00000000 +00000001 +10001010 +10101010 +10100001 +10001010 +10101010 +10100001 +00000000 +00000000 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01000000 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01000000 +10100001 +01010101 +00101010 +10000101 +01010101 +00101010 +10000101 +01010101 +01000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +00000000 +00000000 +10100001 +10001010 +10101010 +10100001 +10001010 +10101010 +10000101 +00000000 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010000 +00010100 +00000001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10100001 +01010010 +10101010 +10100001 +01010100 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +00000101 +01010100 +10100001 +10000101 +01010100 +10100001 +10000101 +01010100 +10100001 +00000101 +01010100 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000001 +01001010 +10101010 +10100001 +01001010 +10101010 +10100001 +01001010 +00000000 +00000001 +01001010 +00010101 +01010101 +01001010 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01000000 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +00000000 +00000000 +10100001 +10001010 +10101010 +10100001 +10001010 +10101010 +10000101 +00000000 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010010 +10101010 +10000101 +01001010 +10101010 +10000101 +01001010 +00000000 +00000101 +01001010 +00010101 +01010101 +01001010 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +00001010 +00000000 +10100001 +10001010 +10101010 +10100001 +10000010 +10101010 +10000101 +00000100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00010101 +01001010 +10101010 +10000101 +01001010 +10101010 +10100001 +01000000 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010010 +10100001 +01010101 +01010010 +10000101 +01010101 +01001010 +10000101 +01010101 +01001010 +00010101 +01010101 +00101010 +00010101 +01010101 +00101000 +01010101 +00000100 +10101000 +01010101 +10000100 +10100001 +01010101 +10000010 +10100001 +01010101 +00000000 +00000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01010010 +10101010 +10000101 +01010010 +10101010 +10000101 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00010100 +10100001 +00001010 +00000000 +10100001 +10001010 +10101010 +10100001 +10000010 +10101010 +10000101 +00000100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010100 +00000000 +00010101 +01010010 +10101010 +10000101 +01001010 +10101010 +10100001 +01001010 +00000000 +10100001 +01001010 +00010100 +10100001 +01001010 +00000000 +10100001 +01001010 +10101010 +10100001 +01010010 +10101010 +10100001 +01010100 +00000000 +10100001 +01010101 +01010100 +10100001 +01010101 +01010100 +10100001 +00000000 +00000000 +10100001 +10000010 +10101010 +10100001 +10000010 +10101010 +10000101 +00000100 +00000000 +00010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000000 +01001010 +10101010 +10101010 +01000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00000000 +00000001 +10101010 +10101010 +10100001 +00000000 +00000000 +00100001 +01010101 +01010101 +00100001 +01010101 +01010101 +00100001 +01010101 +01010101 +00100001 +01010101 +01010101 +00100000 +01010101 +01010101 +00101010 +01010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00000000 +00000000 +10101010 +10101010 +10101010 +00000000 +00000000 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01000000 +00000000 +00000000 +01001010 +10101010 +10101010 +01001000 +00000000 +00000000 +01001000 +01010101 +01010101 +01001000 +01010101 +01010101 +01001000 +01010101 +01010101 +00001000 +01010101 +01010101 +10101000 +01010101 +01010101 +00000000 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00000000 +00000001 +10101010 +10101010 +10100001 +00000000 +00000000 +00000001 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +00000001 +01010101 +01010100 +10101000 +01010101 +01010100 +10000010 +00010101 +01010100 +10000010 +00010101 +01010100 +10101000 +01010101 +01010100 +10000001 +01010101 +01010100 +10000101 +01010101 +01010100 +10000101 +01010101 +01010100 +10000101 +01010101 +01010101 +00010101 +01010101 +01010101 +01010101 +01010101 +00000000 +00000000 +00000001 +01001010 +10101010 +10000101 +01010010 +10101010 +00010101 +01010100 +10101000 +01010101 +01010101 +00100001 +01010101 +01010101 +01000101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 +01010101 \ No newline at end of file diff --git a/libraries/AP_OSD/fonts/mcm2bin.py b/libraries/AP_OSD/fonts/mcm2bin.py new file mode 100755 index 0000000000..02fda2f433 --- /dev/null +++ b/libraries/AP_OSD/fonts/mcm2bin.py @@ -0,0 +1,21 @@ +#!/usr/bin/python +import sys; + +if len(sys.argv) < 3: + print "Usage: ./mcm2bin.py clarify.mcm clarify.bin" + exit() + +with open(sys.argv[1]) as inp: + content = inp.readlines() +inp.close(); + +content.pop(0) + +out = open(sys.argv[2], 'wb') +i = -1 +for line in content: + i = i + 1 + if i % 64 < 54: + b = int(line, 2) + out.write(bytearray([b])) +out.close()