Subversion Repositories Projects

Compare Revisions

Ignore whitespace Rev 1701 → Rev 1702

/C-OSD/arducam-osd/ArduCAM_OSD/ArduCAM_OSD.ino
0,0 → 1,216
/*
 
Copyright (c) 2011. All rights reserved.
An Open Source Arduino based OSD and Camera Control project.
Program : ArduCAM-OSD (Supports the variant: minimOSD)
Version : V1.9, 14 February 2012
Author(s): Sandro Benigno
Coauthor(s):
Jani Hirvinen (All the EEPROM routines)
Michael Oborne (OSD Configutator)
Mike Smith (BetterStream and Fast Serial libraries)
Special Contribuitor:
Andrew Tridgell by all the support on MAVLink
Doug Weibel by his great orientation since the start of this project
Contributors: James Goppert, Max Levine
and all other members of DIY Drones Dev team
Thanks to: Chris Anderson, Jordi Munoz
 
This program 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 program 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 <http://www.gnu.org/licenses/>
*/
/* ************************************************************ */
/* **************** MAIN PROGRAM - MODULES ******************** */
/* ************************************************************ */
 
#undef PROGMEM
#define PROGMEM __attribute__(( section(".progmem.data") ))
 
#undef PSTR
#define PSTR(s) (__extension__({static prog_char __c[] PROGMEM = (s); &__c[0];}))
 
#define MAVLINK10
 
/* **********************************************/
/* ***************** INCLUDES *******************/
 
//#define membug
//#define FORCEINIT // You should never use this unless you know what you are doing
 
 
// AVR Includes
#include <FastSerial.h>
#include <AP_Common.h>
#include <AP_Math.h>
#include <math.h>
#include <inttypes.h>
#include <avr/pgmspace.h>
// Get the common arduino functions
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "wiring.h"
#endif
#include <EEPROM.h>
#include <SimpleTimer.h>
#include <GCS_MAVLink.h>
 
#ifdef membug
#include <MemoryFree.h>
#endif
 
// Configurations
#include "OSD_Config.h"
#include "ArduCam_Max7456.h"
#include "OSD_Vars.h"
#include "OSD_Func.h"
 
/* *************************************************/
/* ***************** DEFINITIONS *******************/
 
//OSD Hardware
//#define ArduCAM328
#define MinimOSD
 
#define TELEMETRY_SPEED 57600 // How fast our MAVLink telemetry is coming to Serial port
#define BOOTTIME 2000 // Time in milliseconds that we show boot loading bar and wait user input
 
// Objects and Serial definitions
FastSerialPort0(Serial);
OSD osd; //OSD object
 
SimpleTimer mavlinkTimer;
 
 
/* **********************************************/
/* ***************** SETUP() *******************/
 
void setup()
{
#ifdef ArduCAM328
pinMode(10, OUTPUT); // USB ArduCam Only
#endif
pinMode(MAX7456_SELECT, OUTPUT); // OSD CS
 
Serial.begin(TELEMETRY_SPEED);
// setup mavlink port
mavlink_comm_0_port = &Serial;
#ifdef membug
Serial.println(freeMem());
#endif
 
// Prepare OSD for displaying
unplugSlaves();
osd.init();
// Start
startPanels();
delay(500);
 
// OSD debug for development (Shown at start)
#ifdef membug
osd.setPanel(1,1);
osd.openPanel();
osd.printf("%i",freeMem());
osd.closePanel();
#endif
 
// Just to easy up development things
#ifdef FORCEINIT
InitializeOSD();
#endif
 
 
// Check EEPROM to see if we have initialized it already or not
// also checks if we have new version that needs EEPROM reset
if(readEEPROM(CHK1) + readEEPROM(CHK2) != VER) {
osd.setPanel(6,9);
osd.openPanel();
osd.printf_P(PSTR("Missing/Old Config"));
osd.closePanel();
InitializeOSD();
}
// Get correct panel settings from EEPROM
readSettings();
// Show bootloader bar
loadBar();
 
// Startup MAVLink timers
mavlinkTimer.Set(&OnMavlinkTimer, 120);
 
// House cleaning, clear display and enable timers
osd.clear();
mavlinkTimer.Enable();
} // END of setup();
 
 
 
/* ***********************************************/
/* ***************** MAIN LOOP *******************/
 
// Mother of all happenings, The loop()
// As simple as possible.
void loop()
{
 
if(enable_mav_request == 1){//Request rate control
osd.clear();
osd.setPanel(3,10);
osd.openPanel();
osd.printf_P(PSTR("Requesting DataStreams..."));
osd.closePanel();
for(int n = 0; n < 3; n++){
request_mavlink_rates();//Three times to certify it will be readed
delay(50);
}
enable_mav_request = 0;
delay(2000);
osd.clear();
waitingMAVBeats = 0;
lastMAVBeat = millis();//Preventing error from delay sensing
}
read_mavlink();
mavlinkTimer.Run();
}
 
/* *********************************************** */
/* ******** functions used in main loop() ******** */
void OnMavlinkTimer()
{
setHeadingPatern(); // generate the heading patern
 
osd_battery_pic_A = setBatteryPic(osd_battery_remaining_A); // battery A remmaning picture
//osd_battery_pic_B = setBatteryPic(osd_battery_remaining_B); // battery B remmaning picture
setHomeVars(osd); // calculate and set Distance from home and Direction to home
 
writePanels(); // writing enabled panels (check OSD_Panels Tab)
}
 
 
void unplugSlaves(){
//Unplug list of SPI
#ifdef ArduCAM328
digitalWrite(10, HIGH); // unplug USB HOST: ArduCam Only
#endif
digitalWrite(MAX7456_SELECT, HIGH); // unplug OSD
}
/C-OSD/arducam-osd/ArduCAM_OSD/ArduCam_Max7456.cpp
0,0 → 1,295
 
#include <FastSerial.h>
 
#include "ArduCam_Max7456.h"
// Get the common arduino functions
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "wiring.h"
#endif
#include "Spi.h"
 
volatile int x;
volatile int font_count;
volatile byte character_bitmap[0x40];
 
OSD::OSD()
{
}
 
//------------------ init ---------------------------------------------------
 
void OSD::init()
{
pinMode(MAX7456_SELECT,OUTPUT);
pinMode(MAX7456_VSYNC, INPUT);
digitalWrite(MAX7456_VSYNC,HIGH); //enabling pull-up resistor
 
detectMode();
 
digitalWrite(MAX7456_SELECT,LOW);
//read black level register
Spi.transfer(MAX7456_OSDBL_reg_read);//black level read register
byte osdbl_r = Spi.transfer(0xff);
Spi.transfer(MAX7456_VM0_reg);
Spi.transfer(MAX7456_RESET | video_mode);
delay(50);
//set black level
byte osdbl_w = (osdbl_r & 0xef); //Set bit 4 to zero 11101111
Spi.transfer(MAX7456_OSDBL_reg); //black level write register
Spi.transfer(osdbl_w);
 
// set all rows to same charactor white level, 90%
for (x = 0; x < MAX7456_screen_rows; x++)
{
Spi.transfer(x + 0x10);
Spi.transfer(MAX7456_WHITE_level_120);
}
// define sync (auto,int,ext) and
// making sure the Max7456 is enabled
control(1);
}
 
//------------------ Detect Mode (PAL/NTSC) ---------------------------------
 
void OSD::detectMode()
{
digitalWrite(MAX7456_SELECT,LOW);
//read STAT and auto detect Mode PAL/NTSC
Spi.transfer(MAX7456_STAT_reg_read);//status register
byte osdstat_r = Spi.transfer(0xff);
 
if ((B00000001 & osdstat_r) == 1){
setMode(1);
}
else if((B00000010 & osdstat_r) == 1){
setMode(0);
}
#ifdef MinimOSD
else if (digitalRead(3) == 1){
setMode(1);
}
#endif
else setMode(0);
digitalWrite(MAX7456_SELECT,LOW);
}
 
//------------------ Set Mode (PAL/NTSC) ------------------------------------
 
void OSD::setMode(int themode)
{
switch(themode){
case 0:
video_mode = MAX7456_MODE_MASK_NTCS;
video_center = MAX7456_CENTER_NTSC;
break;
case 1:
video_mode = MAX7456_MODE_MASK_PAL;
video_center = MAX7456_CENTER_PAL;
break;
}
}
 
//------------------ Get Mode (PAL 0/NTSC 1) --------------------------------
 
int OSD::getMode()
{
switch(video_mode){
case MAX7456_MODE_MASK_NTCS:
return 0;
break;
case MAX7456_MODE_MASK_PAL:
return 1;
break;
}
return 0;
}
 
//------------------ Get Center (PAL/NTSC) ----------------------------------
 
int OSD::getCenter()
{
return video_center; //first line for center panel
}
 
//------------------ plug ---------------------------------------------------
 
void OSD::plug()
{
digitalWrite(MAX7456_SELECT,LOW);
}
 
//------------------ clear ---------------------------------------------------
 
void OSD::clear()
{
// clear the screen
digitalWrite(MAX7456_SELECT,LOW);
Spi.transfer(MAX7456_DMM_reg);
Spi.transfer(MAX7456_CLEAR_display);
digitalWrite(MAX7456_SELECT,HIGH);
}
 
//------------------ set panel -----------------------------------------------
 
void
OSD::setPanel(uint8_t st_col, uint8_t st_row){
start_col = st_col;
start_row = st_row;
col = st_col;
row = st_row;
}
 
//------------------ open panel ----------------------------------------------
 
void
OSD::openPanel(void){
unsigned int linepos;
byte settings, char_address_hi, char_address_lo;
//find [start address] position
linepos = row*30+col;
// divide 16 bits into hi & lo byte
char_address_hi = linepos >> 8;
char_address_lo = linepos;
 
//Auto increment turn writing fast (less SPI commands).
//No need to set next char address. Just send them
settings = MAX7456_INCREMENT_auto; //To Enable DMM Auto Increment
digitalWrite(MAX7456_SELECT,LOW);
Spi.transfer(MAX7456_DMM_reg); //dmm
Spi.transfer(settings);
 
Spi.transfer(MAX7456_DMAH_reg); // set start address high
Spi.transfer(char_address_hi);
 
Spi.transfer(MAX7456_DMAL_reg); // set start address low
Spi.transfer(char_address_lo);
//Serial.printf("setPos -> %d %d\n", col, row);
}
 
//------------------ close panel ---------------------------------------------
 
void
OSD::closePanel(void){
Spi.transfer(MAX7456_DMDI_reg);
Spi.transfer(MAX7456_END_string); //This is needed "trick" to finish auto increment
digitalWrite(MAX7456_SELECT,HIGH);
//Serial.println("close");
row++; //only after finish the auto increment the new row will really act as desired
}
 
//------------------ write single char ---------------------------------------------
 
void
OSD::openSingle(uint8_t x, uint8_t y){
unsigned int linepos;
byte char_address_hi, char_address_lo;
//find [start address] position
linepos = y*30+x;
// divide 16 bits into hi & lo byte
char_address_hi = linepos >> 8;
char_address_lo = linepos;
digitalWrite(MAX7456_SELECT,LOW);
Spi.transfer(MAX7456_DMAH_reg); // set start address high
Spi.transfer(char_address_hi);
 
Spi.transfer(MAX7456_DMAL_reg); // set start address low
Spi.transfer(char_address_lo);
//Serial.printf("setPos -> %d %d\n", col, row);
}
 
//------------------ write ---------------------------------------------------
 
size_t
OSD::write(uint8_t c){
if(c == '|'){
closePanel(); //It does all needed to finish auto increment and change current row
openPanel(); //It does all needed to re-enable auto increment
}
else{
Spi.transfer(MAX7456_DMDI_reg);
Spi.transfer(c);
}
return 1;
}
 
//---------------------------------
 
void
OSD::control(uint8_t ctrl){
digitalWrite(MAX7456_SELECT,LOW);
Spi.transfer(MAX7456_VM0_reg);
switch(ctrl){
case 0:
Spi.transfer(MAX7456_DISABLE_display | video_mode);
break;
case 1:
//Spi.transfer((MAX7456_ENABLE_display_vert | video_mode) | MAX7456_SYNC_internal);
//Spi.transfer((MAX7456_ENABLE_display_vert | video_mode) | MAX7456_SYNC_external);
Spi.transfer((MAX7456_ENABLE_display_vert | video_mode) | MAX7456_SYNC_autosync);
break;
}
digitalWrite(MAX7456_SELECT,HIGH);
}
 
void
OSD::write_NVM(int font_count, uint8_t *character_bitmap)
{
byte x;
byte char_address_hi, char_address_lo;
byte screen_char;
 
char_address_hi = font_count;
char_address_lo = 0;
//Serial.println("write_new_screen");
 
// disable display
digitalWrite(MAX7456_SELECT,LOW);
Spi.transfer(MAX7456_VM0_reg);
Spi.transfer(MAX7456_DISABLE_display);
 
Spi.transfer(MAX7456_CMAH_reg); // set start address high
Spi.transfer(char_address_hi);
 
for(x = 0; x < NVM_ram_size; x++) // write out 54 (out of 64) bytes of character to shadow ram
{
screen_char = character_bitmap[x];
Spi.transfer(MAX7456_CMAL_reg); // set start address low
Spi.transfer(x);
Spi.transfer(MAX7456_CMDI_reg);
Spi.transfer(screen_char);
}
 
// transfer a 54 bytes from shadow ram to NVM
Spi.transfer(MAX7456_CMM_reg);
Spi.transfer(WRITE_nvr);
// wait until bit 5 in the status register returns to 0 (12ms)
while ((Spi.transfer(MAX7456_STAT_reg_read) & STATUS_reg_nvr_busy) != 0x00);
 
Spi.transfer(MAX7456_VM0_reg); // turn on screen next vertical
Spi.transfer(MAX7456_ENABLE_display_vert);
digitalWrite(MAX7456_SELECT,HIGH);
}
 
//------------------ pure virtual ones (just overriding) ---------------------
 
int OSD::available(void){
return 0;
}
int OSD::read(void){
return 0;
}
int OSD::peek(void){
return 0;
}
void OSD::flush(void){
}
 
/C-OSD/arducam-osd/ArduCAM_OSD/ArduCam_Max7456.h
0,0 → 1,105
 
#ifndef ArduCam_Max7456_h
#define ArduCam_Max7456_h
 
/******* FROM DATASHEET *******/
 
#define MAX7456_SELECT 6//SS
#define MAX7456_VSYNC 2//INT0
 
#define NTSC 0
#define PAL 1
#define MAX7456_MODE_MASK_PAL 0x40 //PAL mask 01000000
#define MAX7456_CENTER_PAL 0x8
 
#define MAX7456_MODE_MASK_NTCS 0x00 //NTSC mask 00000000 ("|" will do nothing)
#define MAX7456_CENTER_NTSC 0x6
 
//MAX7456 reg read addresses
#define MAX7456_OSDBL_reg_read 0xec //black level
#define MAX7456_STAT_reg_read 0xa0 //0xa[X] Status
 
//MAX7456 reg write addresses
#define MAX7456_VM0_reg 0x00
#define MAX7456_VM1_reg 0x01
#define MAX7456_DMM_reg 0x04
#define MAX7456_DMAH_reg 0x05
#define MAX7456_DMAL_reg 0x06
#define MAX7456_DMDI_reg 0x07
#define MAX7456_OSDM_reg 0x0c //not used. Is to set mix
#define MAX7456_OSDBL_reg 0x6c //black level
 
//MAX7456 reg write addresses to recording NVM process
#define MAX7456_CMM_reg 0x08
#define MAX7456_CMAH_reg 0x09
#define MAX7456_CMAL_reg 0x0a
#define MAX7456_CMDI_reg 0x0b
 
//DMM commands
#define MAX7456_CLEAR_display 0x04
#define MAX7456_CLEAR_display_vert 0x06
 
#define MAX7456_INCREMENT_auto 0x03
#define MAX7456_SETBG_local 0x20 //00100000 force local BG to defined brightness level VM1[6:4]
 
#define MAX7456_END_string 0xff
 
//VM0 commands mixed with mode NTSC or PAL mode
#define MAX7456_ENABLE_display_vert 0x0c //mask with NTSC/PAL
#define MAX7456_RESET 0x02 //mask with NTSC/PAL
#define MAX7456_DISABLE_display 0x00 //mask with NTSC/PAL
 
//VM0 command modifiers
#define MAX7456_SYNC_autosync 0x10
#define MAX7456_SYNC_internal 0x30
#define MAX7456_SYNC_external 0x20
//VM1 command modifiers
#define MAX7456_WHITE_level_80 0x03
#define MAX7456_WHITE_level_90 0x02
#define MAX7456_WHITE_level_100 0x01
#define MAX7456_WHITE_level_120 0x00
 
#define NVM_ram_size 0x36
#define WRITE_nvr 0xa0
#define STATUS_reg_nvr_busy 0x20
 
//If PAL
#ifdef isPAL
#define MAX7456_screen_size 480 //16x30
#define MAX7456_screen_rows 15
#else
#define MAX7456_screen_size 390 //13x30
#define MAX7456_screen_rows 12
#endif
 
//------------------ the OSD class -----------------------------------------------
 
class OSD: public BetterStream
{
public:
OSD(void);
void init(void);
void clear(void);
void plug(void);
void setPanel(uint8_t start_col, uint8_t start_row);
void openPanel(void);
void closePanel(void);
void control(uint8_t ctrl);
void detectMode(void);
void setMode(int mode);
void openSingle(uint8_t x, uint8_t y);
int getMode(void);
int getCenter(void);
virtual int available(void);
virtual int read(void);
virtual int peek(void);
virtual void flush(void);
virtual size_t write(uint8_t c);
void write_NVM(int font_count, uint8_t *character_bitmap);
using BetterStream::write;
private:
uint8_t start_col, start_row, col, row, video_mode, video_center;
};
 
#endif
 
/C-OSD/arducam-osd/ArduCAM_OSD/ArduNOTES.ino
0,0 → 1,82
/*
 
File : ArduCAM-OSD Notes
Version : v1.0.02
Author : Jani Hirvinen
 
File to define all panels that can be used on ArduCAM-OSD hardware. Also their order numbers
and other information.
 
Order number are also used when configuring their location. Look below
 
Register , Order number , Panel name, Data/Size , Definitions
-------------------------------------------------------
panA_REG.0 01 panCenter "IIII" \r "IIII" - Center xrosshair
panA_REG.1 02 panPitch "DDDDII" - Pitch angle with symbols
panA_REG.2 03 panRoll "DDDDII" - Roll angle with symbols
panA_REG.3 04 panBattery1 "DD.DII" - Voltage sensing #1 symbol with voltage reading
panA_REG.4 05 panBattery2 "DD.DII" - Voltage sensing #2 symbol with voltage reading (!Not Implemented)
panA_REG.5 06 panGPSats "I CC" - Amount of locked satelliset with symbols
panA_REG.6 07 panGPL "II" - GPS Lock symbol
panA_REG.7 08 panGPS "I DDD.DDDDDD" \r "I DDD.DDDDDD" - GPS location data (lat/lon)
panB_REG.0 09 panRose "IIIIIIIIIIIII" \r "ICCCCCCCCCCCCI" - Compass rose
panB_REG.1 10 panHeading "IIDDDDI" - Compass heading with symbols
panB_REG.2 11 panMavBeat "II" - MAVLink heartbeat
panB_REG.3 12 panHomeDir "II" N/Y - Home location arrows
panB_REG.4 13 panHomeDis "IDDDDDI" N/Y - Distance to home
panB_REG.5 14 panWPDir "II" N/Y - Waypoint location arrows (!Not Implemented)
panB_REG.6 15 panWPDis "IDDDDDI" - Distance to next waypoint (!Not Implemented)
panB_REG.7 16 panRSSI - RSSI data from RC (!Not Implemented)
panC_REG.0 17 panCurrent1 - Current sensing #1 (!Not Implemented)
panC_REG.1 18 panCurrent2 - Current sensing #2 (!Not Implemented)
panC_REG.2 19 panAlt "IDDDDDI" - Altitude information
panC_REG.3 20 panVel "IDDDDDI" - Velocity information
panC_REG.4 21 panThr "IDDDDDI" - MAVLink Throttle data
panC_REG.5 22 panFMod "II" - Flight mode display
panC_REG.6 05 panHorizon - Artificial Horizon
panC_REG.7 24 --
 
 
I = Icon
D = Digit
C = Char
 
N/Y = Not Yet working
N/C = Not Confirmed
 
Screen sizes:
PAL 15 Rows x 32 Chars
NTSC 13 Rows x 30 Chars
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
*/
/C-OSD/arducam-osd/ArduCAM_OSD/BOOT_Func.ino
0,0 → 1,76
 
 
/* ******************************************************************/
/* *********************** BOOT UP FUNCTIONS ********************** */
 
 
///////////////////////////////////////////////////////
// Function: loadBar(void)
//
// On bootup time we will show loading bar for defined BOOTTIME seconds
// This is interesting to avoid writing to APM during bootup if OSD's TX is connected
// After that, it continue in normal mode eg starting to listen MAVLink commands
 
#define barX 5
#define barY 12
 
void loadBar() { //change name due we don't have CLI anymore
int waitTimer;
byte barStep = 0;
 
// Write plain panel to let users know what to do
panBoot(barX,barY);
 
delay(500); // To give small extra waittime to users
// Serial.flush();
// Our main loop to wait input from user.
for(waitTimer = 0; waitTimer <= BOOTTIME; waitTimer++) {
 
// How often we update our progress bar is depending on modulo
if(waitTimer % (BOOTTIME / 8) == 0) {
barStep++;
// Update bar it self
osd.setPanel(barX + 12, barY);
osd.openPanel();
switch(barStep) {
case 0:
osd.printf_P(PSTR("\xf1\xf2\xf2\xf2\xf2\xf2\xf2"));
break;
case 1:
osd.printf_P(PSTR("\xef\xf2\xf2\xf2\xf2\xf2\xf2"));
break;
case 2:
osd.printf_P(PSTR("\xee\xf0\xf2\xf2\xf2\xf2\xf2"));
break;
case 3:
osd.printf_P(PSTR("\xee\xee\xf0\xf2\xf2\xf2\xf2"));
break;
case 4:
osd.printf_P(PSTR("\xee\xee\xee\xf0\xf2\xf2\xf2"));
break;
case 5:
osd.printf_P(PSTR("\xee\xee\xee\xee\xf0\xf2\xf2"));
break;
case 6:
osd.printf_P(PSTR("\xee\xee\xee\xee\xee\xf0\xf2"));
break;
case 7:
osd.printf_P(PSTR("\xee\xee\xee\xee\xee\xee\xf0"));
break;
case 8:
osd.printf_P(PSTR("\xee\xee\xee\xee\xee\xee\xee"));
break;
case 9:
osd.printf_P(PSTR("\xee\xee\xee\xee\xee\xee\xee\xee"));
break;
}
osd.closePanel();
}
delay(1); // Minor delay to make sure that we stay here long enough
}
}
 
 
/C-OSD/arducam-osd/ArduCAM_OSD/Font.ino
0,0 → 1,93
 
void uploadFont()
{
uint16_t byte_count = 0;
byte bit_count;
byte ascii_binary[0x08];
// move these local to prevent ram usage
uint8_t character_bitmap[0x40];
int font_count = 0;
osd.clear();
osd.setPanel(6,9);
osd.openPanel();
osd.printf_P(PSTR("Update CharSet"));
osd.closePanel();
Serial.printf_P(PSTR("Ready for Font\n"));
while(font_count < 256) {
int8_t incomingByte = Serial.read();
switch(incomingByte) // parse and decode mcm file
{
case 0x0d: // carridge return, end of line
//Serial.println("cr");
if (bit_count == 8 && (ascii_binary[0] == 0x30 || ascii_binary[0] == 0x31))
{
// turn 8 ascii binary bytes to single byte '01010101' = 0x55
// fill in 64 bytes of character data
// made this local to prevent needing a global
byte ascii_byte;
 
ascii_byte = 0;
if (ascii_binary[0] == 0x31) // ascii '1'
ascii_byte = ascii_byte + 128;
 
if (ascii_binary[1] == 0x31)
ascii_byte = ascii_byte + 64;
 
if (ascii_binary[2] == 0x31)
ascii_byte = ascii_byte + 32;
 
if (ascii_binary[3] == 0x31)
ascii_byte = ascii_byte + 16;
 
if (ascii_binary[4] == 0x31)
ascii_byte = ascii_byte + 8;
 
if (ascii_binary[5] == 0x31)
ascii_byte = ascii_byte + 4;
 
if (ascii_binary[6] == 0x31)
ascii_byte = ascii_byte + 2;
 
if (ascii_binary[7] == 0x31)
ascii_byte = ascii_byte + 1;
character_bitmap[byte_count] = ascii_byte;
byte_count++;
bit_count = 0;
}
else
bit_count = 0;
break;
case 0x0a: // line feed, ignore
//Serial.println("ln");
break;
case 0x30: // ascii '0'
case 0x31: // ascii '1'
ascii_binary[bit_count] = incomingByte;
bit_count++;
break;
default:
break;
}
// we have one completed character
// write the character to NVM
if(byte_count == 64)
{
osd.write_NVM(font_count, character_bitmap);
byte_count = 0;
font_count++;
Serial.printf_P(PSTR("Char Done\n"));
}
}
// character_bitmap[]
}
 
 
/C-OSD/arducam-osd/ArduCAM_OSD/MAVLink.ino
0,0 → 1,154
#define MAVLINK_COMM_NUM_BUFFERS 1
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
// this code was moved from libraries/GCS_MAVLink to allow compile
// time selection of MAVLink 1.0
BetterStream *mavlink_comm_0_port;
BetterStream *mavlink_comm_1_port;
 
mavlink_system_t mavlink_system = {12,1,0,0};
 
#include "Mavlink_compat.h"
 
#ifdef MAVLINK10
#include "../GCS_MAVLink/include/mavlink/v1.0/mavlink_types.h"
#include "../GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink.h"
#else
#include "../GCS_MAVLink/include/mavlink/v0.9/mavlink_types.h"
#include "../GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink.h"
#endif
 
// true when we have received at least 1 MAVLink packet
static bool mavlink_active;
static uint8_t crlf_count = 0;
 
static int packet_drops = 0;
static int parse_error = 0;
 
void request_mavlink_rates()
{
const int maxStreams = 6;
const uint8_t MAVStreams[maxStreams] = {MAV_DATA_STREAM_RAW_SENSORS,
MAV_DATA_STREAM_EXTENDED_STATUS,
MAV_DATA_STREAM_RC_CHANNELS,
MAV_DATA_STREAM_POSITION,
MAV_DATA_STREAM_EXTRA1,
MAV_DATA_STREAM_EXTRA2};
const uint16_t MAVRates[maxStreams] = {0x02, 0x02, 0x05, 0x02, 0x05, 0x02};
for (int i=0; i < maxStreams; i++) {
mavlink_msg_request_data_stream_send(MAVLINK_COMM_0,
apm_mav_system, apm_mav_component,
MAVStreams[i], MAVRates[i], 1);
}
}
 
void read_mavlink(){
mavlink_message_t msg;
mavlink_status_t status;
//grabing data
while(Serial.available() > 0) {
uint8_t c = Serial.read();
/* allow CLI to be started by hitting enter 3 times, if no
heartbeat packets have been received */
if (mavlink_active == 0 && millis() < 20000) {
if (c == '\n' || c == '\r') {
crlf_count++;
} else {
crlf_count = 0;
}
if (crlf_count == 3) {
uploadFont();
}
}
//trying to grab msg
if(mavlink_parse_char(MAVLINK_COMM_0, c, &msg, &status)) {
mavlink_active = 1;
//handle msg
switch(msg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT:
{
mavbeat = 1;
apm_mav_system = msg.sysid;
apm_mav_component = msg.compid;
apm_mav_type = mavlink_msg_heartbeat_get_type(&msg);
#ifdef MAVLINK10
osd_mode = mavlink_msg_heartbeat_get_custom_mode(&msg);
osd_nav_mode = 0;
#endif
lastMAVBeat = millis();
if(waitingMAVBeats == 1){
enable_mav_request = 1;
}
}
break;
case MAVLINK_MSG_ID_SYS_STATUS:
{
#ifndef MAVLINK10
osd_vbat_A = (mavlink_msg_sys_status_get_vbat(&msg) / 1000.0f);
osd_mode = mavlink_msg_sys_status_get_mode(&msg);
osd_nav_mode = mavlink_msg_sys_status_get_nav_mode(&msg);
#else
osd_vbat_A = (mavlink_msg_sys_status_get_voltage_battery(&msg) / 1000.0f);
#endif
osd_battery_remaining_A = mavlink_msg_sys_status_get_battery_remaining(&msg);
//osd_mode = apm_mav_component;//Debug
//osd_nav_mode = apm_mav_system;//Debug
}
break;
#ifndef MAVLINK10
case MAVLINK_MSG_ID_GPS_RAW:
{
osd_lat = mavlink_msg_gps_raw_get_lat(&msg);
osd_lon = mavlink_msg_gps_raw_get_lon(&msg);
osd_fix_type = mavlink_msg_gps_raw_get_fix_type(&msg);
}
break;
case MAVLINK_MSG_ID_GPS_STATUS:
{
osd_satellites_visible = mavlink_msg_gps_status_get_satellites_visible(&msg);
}
break;
#else
case MAVLINK_MSG_ID_GPS_RAW_INT:
{
osd_lat = mavlink_msg_gps_raw_int_get_lat(&msg) / 10000000.0f;
osd_lon = mavlink_msg_gps_raw_int_get_lon(&msg) / 10000000.0f;
osd_fix_type = mavlink_msg_gps_raw_int_get_fix_type(&msg);
osd_satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(&msg);
}
break;
#endif
 
case MAVLINK_MSG_ID_VFR_HUD:
{
osd_groundspeed = mavlink_msg_vfr_hud_get_groundspeed(&msg);
osd_heading = mavlink_msg_vfr_hud_get_heading(&msg);// * 3.60f;//0-100% of 360
osd_throttle = mavlink_msg_vfr_hud_get_throttle(&msg);
if(osd_throttle > 100 && osd_throttle < 150) osd_throttle = 100;//Temporary fix for ArduPlane 2.28
if(osd_throttle < 0 || osd_throttle > 150) osd_throttle = 0;//Temporary fix for ArduPlane 2.28
osd_alt = mavlink_msg_vfr_hud_get_alt(&msg);
}
break;
case MAVLINK_MSG_ID_ATTITUDE:
{
osd_pitch = ToDeg(mavlink_msg_attitude_get_pitch(&msg));
osd_roll = ToDeg(mavlink_msg_attitude_get_roll(&msg));
osd_yaw = ToDeg(mavlink_msg_attitude_get_yaw(&msg));
}
break;
default:
//Do nothing
break;
}
}
delayMicroseconds(138);
//next one
}
// Update global packet drops counter
packet_drops += status.packet_rx_drop_count;
parse_error += status.parse_error;
 
}
/C-OSD/arducam-osd/ArduCAM_OSD/OSD_Config.h
0,0 → 1,129
 
#define on 1
#define off 0
 
// Versio number, incrementing this will erase/upload factory settings.
// Only devs should increment this
#define VER 74
 
// EEPROM Stepping, be careful not to overstep.
// We reserved floats for just to be sure if some values needs to be
// changed in future.
// byte = 1
// int = 4
// float = 8
 
// Panel 8bit REGISTER with BIT positions
// panA_REG Byte has:
#define Cen_BIT 0
#define Pit_BIT 1
#define Rol_BIT 2
#define BatA_BIT 3
#define BatB_BIT 4 //(!Not implemented)
#define GPSats_BIT 5
#define GPL_BIT 6
#define GPS_BIT 7
 
// panB_REG Byte has:
#define Rose_BIT 0
#define Head_BIT 1
#define MavB_BIT 2
#define HDir_BIT 3
#define HDis_BIT 4
#define WDir_BIT 5 //(!Not implemented)
#define WDis_BIT 6 //(!Not implemented)
#define RSSI_BIT 7 //(!Not implemented)
 
// panC_REG Byte has:
#define CurA_BIT 0 //(!Not implemented)
#define CurB_BIT 1 //(!Not implemented)
#define Alt_BIT 2
#define Vel_BIT 3
#define Thr_BIT 4
#define FMod_BIT 5
#define Hor_BIT 6
//#define XXC_BIT 7 //Free
 
 
/* *********************************************** */
// EEPROM Storage addresses
 
// First of 8 panels
#define panCenter_en_ADDR 0
#define panCenter_x_ADDR 2
#define panCenter_y_ADDR 4
#define panPitch_en_ADDR 6
#define panPitch_x_ADDR 8
#define panPitch_y_ADDR 10
#define panRoll_en_ADDR 12
#define panRoll_x_ADDR 14
#define panRoll_y_ADDR 16
#define panBatt_A_en_ADDR 18
#define panBatt_A_x_ADDR 20
#define panBatt_A_y_ADDR 22
#define panBatt_B_en_ADDR 24
#define panBatt_B_x_ADDR 26
#define panBatt_B_y_ADDR 28
#define panGPSats_en_ADDR 30
#define panGPSats_x_ADDR 32
#define panGPSats_y_ADDR 34
#define panGPL_en_ADDR 36
#define panGPL_x_ADDR 38
#define panGPL_y_ADDR 40
#define panGPS_en_ADDR 42
#define panGPS_x_ADDR 44
#define panGPS_y_ADDR 46
 
// Second set of 8 panels
#define panRose_en_ADDR 48
#define panRose_x_ADDR 50
#define panRose_y_ADDR 52
#define panHeading_en_ADDR 54
#define panHeading_x_ADDR 56
#define panHeading_y_ADDR 58
#define panMavBeat_en_ADDR 60
#define panMavBeat_x_ADDR 62
#define panMavBeat_y_ADDR 64
#define panHomeDir_en_ADDR 66
#define panHomeDir_x_ADDR 68
#define panHomeDir_y_ADDR 70
#define panHomeDis_en_ADDR 72
#define panHomeDis_x_ADDR 74
#define panHomeDis_y_ADDR 76
#define panWPDir_en_ADDR 80 //(!Not implemented)
#define panWPDir_x_ADDR 82 //
#define panWPDir_y_ADDR 84 //
#define panWPDis_en_ADDR 86 //(!Not implemented)
#define panWPDis_x_ADDR 88 //
#define panWPDis_y_ADDR 90 //
#define panRSSI_en_ADDR 92 //(!Not implemented)
#define panRSSI_x_ADDR 94 //
#define panRSSI_y_ADDR 96 //
 
// Third set of 8 panels
#define panCurA_en_ADDR 98 //(!Not implemented)
#define panCurA_x_ADDR 100 //
#define panCurA_y_ADDR 102 //
#define panCurB_en_ADDR 104 //(!Not implemented)
#define panCurB_x_ADDR 106 //
#define panCurB_y_ADDR 108 //
#define panAlt_en_ADDR 110
#define panAlt_x_ADDR 112
#define panAlt_y_ADDR 114
#define panVel_en_ADDR 116
#define panVel_x_ADDR 118
#define panVel_y_ADDR 120
#define panThr_en_ADDR 122
#define panThr_x_ADDR 124
#define panThr_y_ADDR 126
#define panFMod_en_ADDR 128
#define panFMod_x_ADDR 130
#define panFMod_y_ADDR 132
#define panHorizon_en_ADDR 134
#define panHorizon_x_ADDR 136
#define panHorizon_y_ADDR 138
 
#define CHK1 1000
#define CHK2 1006
 
#define EEPROM_MAX_ADDR 1024 // this is 328 chip
/C-OSD/arducam-osd/ArduCAM_OSD/OSD_Config_Func.ino
0,0 → 1,248
/* ******************************************************************/
/* *********************** GENERAL FUNCTIONS ********************** */
 
//Extract functions (get bits from the positioning bytes
#define ISa(whichBit) getBit(panA_REG, whichBit)
#define ISb(whichBit) getBit(panB_REG, whichBit)
#define ISc(whichBit) getBit(panC_REG, whichBit)
 
boolean getBit(byte Reg, byte whichBit) {
boolean State;
State = Reg & (1 << whichBit);
return State;
}
 
byte setBit(byte &Reg, byte whichBit, boolean stat) {
if (stat) {
Reg = Reg | (1 << whichBit);
}
else {
Reg = Reg & ~(1 << whichBit);
}
return Reg;
}
 
// EEPROM reader/writers
// Utilities for writing and reading from the EEPROM
byte readEEPROM(int address) {
 
return EEPROM.read(address);
}
 
void writeEEPROM(byte value, int address) {
EEPROM.write(address, value);
}
 
 
void InitializeOSD() {
loadBar();
delay(500);
 
writeEEPROM(42, CHK1);
writeEEPROM(VER-42,CHK2);
writeSettings();
osd.setPanel(4,9);
osd.openPanel();
osd.printf_P(PSTR("OSD Initialized, reboot"));
osd.closePanel();
// run for ever so user resets
for(;;) {}
}
 
// Write our latest FACTORY settings to EEPROM
void writeSettings() {
// Writing all default parameters to EEPROM, ON = panel enabled
// All panels have 3 values:
// - Enable/Disable
// - X coordinate on screen
// - Y coordinate on screen
writeEEPROM(off, panCenter_en_ADDR);
writeEEPROM(13, panCenter_x_ADDR);
writeEEPROM(7, panCenter_y_ADDR);
writeEEPROM(on, panPitch_en_ADDR);
writeEEPROM(22, panPitch_x_ADDR);
writeEEPROM(9, panPitch_y_ADDR);
writeEEPROM(on, panRoll_en_ADDR);
writeEEPROM(11, panRoll_x_ADDR);
writeEEPROM(1, panRoll_y_ADDR);
writeEEPROM(on, panBatt_A_en_ADDR);
writeEEPROM(21, panBatt_A_x_ADDR);
writeEEPROM(1, panBatt_A_y_ADDR);
//writeEEPROM(on, panBatt_B_en_ADDR);
//writeEEPROM(21, panBatt_B_x_ADDR);
//writeEEPROM(3, panBatt_B_y_ADDR);
writeEEPROM(on, panGPSats_en_ADDR);
writeEEPROM(2, panGPSats_x_ADDR);
writeEEPROM(13, panGPSats_y_ADDR);
writeEEPROM(on, panGPL_en_ADDR);
writeEEPROM(5, panGPL_x_ADDR);
writeEEPROM(13, panGPL_y_ADDR);
writeEEPROM(on, panGPS_en_ADDR);
writeEEPROM(2, panGPS_x_ADDR);
writeEEPROM(14, panGPS_y_ADDR);
writeEEPROM(on, panRose_en_ADDR);
writeEEPROM(16, panRose_x_ADDR);
writeEEPROM(14, panRose_y_ADDR);
writeEEPROM(on, panHeading_en_ADDR);
writeEEPROM(24, panHeading_x_ADDR);
writeEEPROM(13, panHeading_y_ADDR);
writeEEPROM(on, panMavBeat_en_ADDR);
writeEEPROM(2, panMavBeat_x_ADDR);
writeEEPROM(9, panMavBeat_y_ADDR);
writeEEPROM(on, panHomeDir_en_ADDR);
writeEEPROM(14, panHomeDir_x_ADDR);
writeEEPROM(3, panHomeDir_y_ADDR);
writeEEPROM(on, panHomeDis_en_ADDR);
writeEEPROM(2, panHomeDis_x_ADDR);
writeEEPROM(1, panHomeDis_y_ADDR);
writeEEPROM(off,panWPDir_en_ADDR);
writeEEPROM(0, panWPDir_x_ADDR);
writeEEPROM(0, panWPDir_y_ADDR);
writeEEPROM(off,panWPDis_en_ADDR);
writeEEPROM(0, panWPDis_x_ADDR);
writeEEPROM(0, panWPDis_y_ADDR);
//writeEEPROM(on, panRSSI_en_ADDR);
//writeEEPROM(21, panRSSI_x_ADDR);
//writeEEPROM(5, panRSSI_y_ADDR);
//writeEEPROM(on, panCur_A_en_ADDR);
//writeEEPROM(21, panCur_A_x_ADDR);
//writeEEPROM(2, panCur_A_y_ADDR);
//writeEEPROM(on, panCur_B_en_ADDR);
//writeEEPROM(21, panCur_B_x_ADDR);
//writeEEPROM(4, panCur_B_y_ADDR);
writeEEPROM(on, panAlt_en_ADDR);
writeEEPROM(2, panAlt_x_ADDR);
writeEEPROM(2, panAlt_y_ADDR);
writeEEPROM(on, panVel_en_ADDR);
writeEEPROM(2, panVel_x_ADDR);
writeEEPROM(3, panVel_y_ADDR);
writeEEPROM(on, panThr_en_ADDR);
writeEEPROM(2, panThr_x_ADDR);
writeEEPROM(4, panThr_y_ADDR);
writeEEPROM(on, panFMod_en_ADDR);
writeEEPROM(17, panFMod_x_ADDR);
writeEEPROM(13, panFMod_y_ADDR);
writeEEPROM(on, panHorizon_en_ADDR);
writeEEPROM(8, panHorizon_x_ADDR);
writeEEPROM(7, panHorizon_y_ADDR);
}
 
void readSettings() {
//****** First set of 8 Panels ******
setBit(panA_REG, Cen_BIT, readEEPROM(panCenter_en_ADDR));
panCenter_XY[0] = readEEPROM(panCenter_x_ADDR);
panCenter_XY[1] = checkPAL(readEEPROM(panCenter_y_ADDR));
setBit(panA_REG, Pit_BIT, readEEPROM(panPitch_en_ADDR));
panPitch_XY[0] = readEEPROM(panPitch_x_ADDR);
panPitch_XY[1] = checkPAL(readEEPROM(panPitch_y_ADDR));
setBit(panA_REG, Rol_BIT, readEEPROM(panRoll_en_ADDR));
panRoll_XY[0] = readEEPROM(panRoll_x_ADDR);
panRoll_XY[1] = checkPAL(readEEPROM(panRoll_y_ADDR));
setBit(panA_REG, BatA_BIT, readEEPROM(panBatt_A_en_ADDR));
panBatt_A_XY[0] = readEEPROM(panBatt_A_x_ADDR);
panBatt_A_XY[1] = checkPAL(readEEPROM(panBatt_A_y_ADDR));
 
//setBit(panA_REG, BatB_BIT, readEEPROM(panBatt_B_en_ADDR));
//panBatt_B_XY[0] = readEEPROM(panBatt_B_x_ADDR);
//panBatt_B_XY[1] = checkPAL(readEEPROM(panBatt_B_y_ADDR));
setBit(panA_REG, GPSats_BIT, readEEPROM(panGPSats_en_ADDR));
panGPSats_XY[0] = readEEPROM(panGPSats_x_ADDR);
panGPSats_XY[1] = checkPAL(readEEPROM(panGPSats_y_ADDR));
 
setBit(panA_REG, GPL_BIT, readEEPROM(panGPL_en_ADDR));
panGPL_XY[0] = readEEPROM(panGPL_x_ADDR);
panGPL_XY[1] = checkPAL(readEEPROM(panGPL_y_ADDR));
setBit(panA_REG, GPS_BIT, readEEPROM(panGPS_en_ADDR));
panGPS_XY[0] = readEEPROM(panGPS_x_ADDR);
panGPS_XY[1] = checkPAL(readEEPROM(panGPS_y_ADDR));
 
//****** Second set of 8 Panels ******
setBit(panB_REG, Rose_BIT, readEEPROM(panRose_en_ADDR));
panRose_XY[0] = readEEPROM(panRose_x_ADDR);
panRose_XY[1] = checkPAL(readEEPROM(panRose_y_ADDR));
 
setBit(panB_REG, Head_BIT, readEEPROM(panHeading_en_ADDR));
panHeading_XY[0] = readEEPROM(panHeading_x_ADDR);
panHeading_XY[1] = checkPAL(readEEPROM(panHeading_y_ADDR));
 
setBit(panB_REG, MavB_BIT, readEEPROM(panMavBeat_en_ADDR));
panMavBeat_XY[0] = readEEPROM(panMavBeat_x_ADDR);
panMavBeat_XY[1] = checkPAL(readEEPROM(panMavBeat_y_ADDR));
 
setBit(panB_REG, HDis_BIT, readEEPROM(panHomeDis_en_ADDR));
panHomeDis_XY[0] = readEEPROM(panHomeDis_x_ADDR);
panHomeDis_XY[1] = checkPAL(readEEPROM(panHomeDis_y_ADDR));
 
setBit(panB_REG, HDir_BIT, readEEPROM(panHomeDir_en_ADDR));
panHomeDir_XY[0] = readEEPROM(panHomeDir_x_ADDR);
panHomeDir_XY[1] = checkPAL(readEEPROM(panHomeDir_y_ADDR));
 
//setBit(panB_REG, RSSI_BIT, readEEPROM(panRSSI_en_ADDR));
//panRSSI_XY[0] = readEEPROM(panRSSI_x_ADDR);
//panRSSI_XY[1] = checkPAL(readEEPROM(panRSSI_y_ADDR));
 
//****** Third set of 8 Panels ******
 
//setBit(panC_REG, CurA_BIT, readEEPROM(panCur_A_en_ADDR));
//panCur_A_XY[0] = readEEPROM(panCur_A_x_ADDR);
//panCur_A_XY[1] = checkPAL(readEEPROM(panCur_A_y_ADDR));
 
//setBit(panC_REG, CurB_BIT, readEEPROM(panCur_B_en_ADDR));
//panCur_B_XY[0] = readEEPROM(panCur_B_x_ADDR);
//panCur_B_XY[1] = checkPAL(readEEPROM(panCur_B_y_ADDR));
 
setBit(panC_REG, Alt_BIT, readEEPROM(panAlt_en_ADDR));
panAlt_XY[0] = readEEPROM(panAlt_x_ADDR);
panAlt_XY[1] = checkPAL(readEEPROM(panAlt_y_ADDR));
 
setBit(panC_REG, Vel_BIT, readEEPROM(panVel_en_ADDR));
panVel_XY[0] = readEEPROM(panVel_x_ADDR);
panVel_XY[1] = checkPAL(readEEPROM(panVel_y_ADDR));
 
setBit(panC_REG, Thr_BIT, readEEPROM(panThr_en_ADDR));
panThr_XY[0] = readEEPROM(panThr_x_ADDR);
panThr_XY[1] = checkPAL(readEEPROM(panThr_y_ADDR));
 
setBit(panC_REG, FMod_BIT, readEEPROM(panFMod_en_ADDR));
panFMod_XY[0] = readEEPROM(panFMod_x_ADDR);
panFMod_XY[1] = checkPAL(readEEPROM(panFMod_y_ADDR));
 
setBit(panC_REG, Hor_BIT, readEEPROM(panHorizon_en_ADDR));
panHorizon_XY[0] = readEEPROM(panHorizon_x_ADDR);
panHorizon_XY[1] = checkPAL(readEEPROM(panHorizon_y_ADDR));
 
}
 
int checkPAL(int line){
if(line >= osd.getCenter() && osd.getMode() == 0){
line -= 3;//Cutting lines offset after center if NTSC
}
return line;
}
 
void updateSettings(byte panel, byte panel_x, byte panel_y, byte panel_s ) {
if(panel >= 1 && panel <= 32) {
writeEEPROM(panel_s, (6 * panel) - 6 + 0);
if(panel_s != 0) {
writeEEPROM(panel_x, (6 * panel) - 6 + 2);
writeEEPROM(panel_y, (6 * panel) - 6 + 4);
}
osd.clear();
readSettings();
}
}
 
/C-OSD/arducam-osd/ArduCAM_OSD/OSD_Func.h
0,0 → 1,81
//------------------ Heading and Compass ----------------------------------------
 
static char buf_show[12];
const char buf_Rule[36] = {0xc2,0xc0,0xc0,0xc1,0xc0,0xc0,0xc1,0xc0,0xc0,
0xc4,0xc0,0xc0,0xc1,0xc0,0xc0,0xc1,0xc0,0xc0,
0xc3,0xc0,0xc0,0xc1,0xc0,0xc0,0xc1,0xc0,0xc0,
0xc5,0xc0,0xc0,0xc1,0xc0,0xc0,0xc1,0xc0,0xc0};
void setHeadingPatern()
{
int start;
start = round((osd_heading * 36)/360);
start -= 5;
if(start < 0) start += 36;
for(int x=0; x <= 10; x++){
buf_show[x] = buf_Rule[start];
if(++start > 35) start = 0;
}
buf_show[11] = '\0';
}
 
//------------------ Battery Remaining Picture ----------------------------------
 
char setBatteryPic(uint16_t bat_level)
{
if(bat_level <= 100){
return 0xb4;
}
else if(bat_level <= 300){
return 0xb5;
}
else if(bat_level <= 400){
return 0xb6;
}
else if(bat_level <= 500){
return 0xb7;
}
else if(bat_level <= 800){
return 0xb8;
}
else return 0xb9;
}
 
//------------------ Home Distance and Direction Calculation ----------------------------------
 
void setHomeVars(OSD &osd)
{
float dstlon, dstlat;
long bearing;
if(osd_got_home == 0 && osd_fix_type > 1){
osd_home_lat = osd_lat;
osd_home_lon = osd_lon;
osd_home_alt = osd_alt;
osd_got_home = 1;
}
else if(osd_got_home == 1){
// shrinking factor for longitude going to poles direction
float rads = fabs(osd_home_lat) * 0.0174532925;
double scaleLongDown = cos(rads);
double scaleLongUp = 1.0f/cos(rads);
 
//DST to Home
dstlat = fabs(osd_home_lat - osd_lat) * 111319.5;
dstlon = fabs(osd_home_lon - osd_lon) * 111319.5 * scaleLongDown;
osd_home_distance = sqrt(sq(dstlat) + sq(dstlon));
 
//DIR to Home
dstlon = (osd_home_lon - osd_lon); //OffSet_X
dstlat = (osd_home_lat - osd_lat) * scaleLongUp; //OffSet Y
bearing = 90 + (atan2(dstlat, -dstlon) * 57.295775); //absolut home direction
if(bearing < 0) bearing += 360;//normalization
bearing = bearing - 180;//absolut return direction
if(bearing < 0) bearing += 360;//normalization
bearing = bearing - osd_heading;//relative home direction
if(bearing < 0) bearing += 360; //normalization
osd_home_direction = round((float)(bearing/360.0f) * 16.0f) + 1;//array of arrows =)
if(osd_home_direction > 16) osd_home_direction = 0;
 
}
}
/C-OSD/arducam-osd/ArduCAM_OSD/OSD_Panels.ino
0,0 → 1,570
/******* STARTUP PANEL *******/
 
void startPanels(){
osd.clear();
// Display our logo
panLogo(10,5);
}
 
/******* PANELS - POSITION *******/
 
void writePanels(){
if(millis() < (lastMAVBeat + 2000)){
//osd.clear();
//Testing bits from 8 bit register A
if(ISa(Cen_BIT)) panCenter(panCenter_XY[0], panCenter_XY[1]); //4x2
if(ISa(Pit_BIT)) panPitch(panPitch_XY[0], panPitch_XY[1]); //5x1
if(ISa(Rol_BIT)) panRoll(panRoll_XY[0], panRoll_XY[1]); //5x1
if(ISa(BatA_BIT)) panBatt_A(panBatt_A_XY[0], panBatt_A_XY[1]); //7x1
// if(ISa(BatB_BIT)) panBatt_B(panBatt_B_XY[0], panBatt_B_XY[1]); //7x1
if(ISa(GPSats_BIT)) panGPSats(panGPSats_XY[0], panGPSats_XY[1]); //5x1
if(ISa(GPL_BIT)) panGPL(panGPL_XY[0], panGPL_XY[1]); //2x1
if(ISa(GPS_BIT)) panGPS(panGPS_XY[0], panGPS_XY[1]); //12x3
//Testing bits from 8 bit register B
if(ISb(Rose_BIT)) panRose(panRose_XY[0], panRose_XY[1]); //13x3
if(ISb(Head_BIT)) panHeading(panHeading_XY[0], panHeading_XY[1]); //13x3
if(ISb(MavB_BIT)) panMavBeat(panMavBeat_XY[0], panMavBeat_XY[1]); //13x3
 
if(osd_got_home == 1){
if(ISb(HDis_BIT)) panHomeDis(panHomeDis_XY[0], panHomeDis_XY[1]); //13x3
if(ISb(HDir_BIT)) panHomeDir(panHomeDir_XY[0], panHomeDir_XY[1]); //13x3
}
// if(ISb(WDir_BIT)) panWayPDir(panWayPDir_XY[0], panWayPDir_XY[1]); //??x??
// if(ISb(WDis_BIT)) panWayPDis(panWayPDis_XY[0], panWayPDis_XY[1]); //??x??
// if(ISb(WRSSI_BIT)) panRSSI(panRSSI_XY[0], panRSSI_XY[1]); //??x??
 
//Testing bits from 8 bit register C
//if(osd_got_home == 1){
if(ISc(Alt_BIT)) panAlt(panAlt_XY[0], panAlt_XY[1]); //
if(ISc(Vel_BIT)) panVel(panVel_XY[0], panVel_XY[1]); //
//}
if(ISc(Thr_BIT)) panThr(panThr_XY[0], panThr_XY[1]); //
if(ISc(FMod_BIT)) panFlightMode(panFMod_XY[0], panFMod_XY[1]); //
if(ISc(Hor_BIT)) panHorizon(panHorizon_XY[0], panHorizon_XY[1]); //14x5
}
else{
osd.clear();
waitingMAVBeats = 1;
// Display our logo and wait...
panWaitMAVBeats(5,10); //Waiting for MAVBeats...
}
// OSD debug for development (Shown on top-middle panels)
#ifdef membug
osd.setPanel(13,4);
osd.openPanel();
osd.printf("%i",freeMem());
osd.closePanel();
#endif
}
 
/******* PANELS - DEFINITION *******/
 
 
/* **************************************************************** */
// Panel : panAlt
// Needs : X, Y locations
// Output : Alt symbol and altitude value in meters from MAVLink
// Size : 1 x 7Hea (rows x chars)
// Staus : done
 
void panAlt(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
//osd.printf("%c%5.0f%c",0x85, (double)(osd_alt - osd_home_alt), 0x8D);
osd.printf("%c%5.0f%c",0x85, (double)(osd_alt), 0x8D);
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panVel
// Needs : X, Y locations
// Output : Velocity value from MAVlink with symbols
// Size : 1 x 7 (rows x chars)
// Staus : done
 
void panVel(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf("%c%3.0f%c",0x86,(double)osd_groundspeed,0x88);
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panThr
// Needs : X, Y locations
// Output : Throttle value from MAVlink with symbols
// Size : 1 x 7 (rows x chars)
// Staus : done
 
void panThr(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf("%c%3.0i%c",0x87,osd_throttle,0x25);
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panHomeDis
// Needs : X, Y locations
// Output : Home Symbol with distance to home in meters
// Size : 1 x 7 (rows x chars)
// Staus : done
 
void panHomeDis(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf("%c%5.0f%c", 0x1F, (double)osd_home_distance, 0x8D);
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panCenter
// Needs : X, Y locations
// Output : 2 row croshair symbol created by 2 x 4 chars
// Size : 2 x 4 (rows x chars)
// Staus : done
 
void panCenter(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf_P(PSTR("\x05\x03\x04\x05|\x15\x13\x14\x15"));
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panHorizon
// Needs : X, Y locations
// Output : 12 x 4 Horizon line surrounded by 2 cols (left/right rules)
// Size : 14 x 4 (rows x chars)
// Staus : done
 
void panHorizon(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf_P(PSTR("\xc8\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\xc9|"));
osd.printf_P(PSTR("\xc8\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\xc9|"));
osd.printf_P(PSTR("\xd8\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\xd9|"));
osd.printf_P(PSTR("\xc8\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\xc9|"));
osd.printf_P(PSTR("\xc8\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\x20\xc9"));
osd.closePanel();
showHorizon((first_col + 1), first_line);
}
 
/* **************************************************************** */
// Panel : panPitch
// Needs : X, Y locations
// Output : -+ value of current Pitch from vehicle with degree symbols and pitch symbol
// Size : 1 x 6 (rows x chars)
// Staus : done
 
void panPitch(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf("%4i%c%c",osd_pitch,0xb0,0xb1);
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panRoll
// Needs : X, Y locations
// Output : -+ value of current Roll from vehicle with degree symbols and roll symbol
// Size : 1 x 6 (rows x chars)
// Staus : done
 
void panRoll(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf("%4i%c%c",osd_roll,0xb0,0xb2);
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panBattery A (Voltage 1)
// Needs : X, Y locations
// Output : Voltage value as in XX.X and symbol of over all battery status
// Size : 1 x 8 (rows x chars)
// Staus : done
 
void panBatt_A(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
/*************** This commented code is for the next ArduPlane Version
#ifdef MAVLINK10
if(osd_battery_remaining_A > 100){
osd.printf(" %c%5.2f%c", 0xE2, (double)osd_vbat_A, 0x8E);
}
#else
if(osd_battery_remaining_A > 1000){
osd.printf(" %c%5.2f%c", 0xE2, (double)osd_vbat_A, 0x8E);
}
#endif //MAVLINK10
else osd.printf("%c%5.2f%c%c", 0xE2, (double)osd_vbat_A, 0x8E, osd_battery_pic_A);
*/
osd.printf(" %c%5.2f%c", 0xE2, (double)osd_vbat_A, 0x8E);
osd.closePanel();
}
 
//------------------ Panel: Startup ArduCam OSD LOGO -------------------------------
 
void panLogo(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf_P(PSTR("\x20\x20\x20\x20\xba\xbb\xbc\xbd\xbe|\x20\x20\x20\x20\xca\xcb\xcc\xcd\xce|ArduCam OSD"));
osd.closePanel();
}
 
//------------------ Panel: Waiting for MAVLink HeartBeats -------------------------------
 
void panWaitMAVBeats(int first_col, int first_line){
panLogo(10,5);
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf_P(PSTR("Waiting for|MAVLink heartbeats..."));
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panGPL
// Needs : X, Y locations
// Output : 1 static symbol with changing FIX symbol
// Size : 1 x 2 (rows x chars)
// Staus : done
 
void panGPL(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
switch(osd_fix_type) {
case 0:
osd.printf_P(PSTR("\x10\x20"));
break;
case 1:
osd.printf_P(PSTR("\x10\x20"));
break;
case 2:
osd.printf_P(PSTR("\x11\x20"));//If not APM, x01 would show 2D fix
break;
case 3:
osd.printf_P(PSTR("\x11\x20"));//If not APM, x02 would show 3D fix
break;
}
/* if(osd_fix_type <= 1) {
osd.printf_P(PSTR("\x10"));
} else {
osd.printf_P(PSTR("\x11"));
} */
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panGPSats
// Needs : X, Y locations
// Output : 1 symbol and number of locked satellites
// Size : 1 x 5 (rows x chars)
// Staus : done
 
void panGPSats(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf("%c%2i", 0x0f,osd_satellites_visible);
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panGPS
// Needs : X, Y locations
// Output : two row numeric value of current GPS location with LAT/LON symbols as on first char
// Size : 2 x 12 (rows x chars)
// Staus : done
 
void panGPS(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf("%c%11.6f|%c%11.6f", 0x83, (double)osd_lat, 0x84, (double)osd_lon);
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panHeading
// Needs : X, Y locations
// Output : Symbols with numeric compass heading value
// Size : 1 x 5 (rows x chars)
// Staus : not ready
 
void panHeading(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf("%4.0f%c", (double)osd_heading, 0xb0);
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panRose
// Needs : X, Y locations
// Output : a dynamic compass rose that changes along the heading information
// Size : 2 x 13 (rows x chars)
// Staus : done
 
void panRose(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
//osd_heading = osd_yaw;
//if(osd_yaw < 0) osd_heading = 360 + osd_yaw;
osd.printf("%s|%c%s%c", "\x20\xc0\xc0\xc0\xc0\xc0\xc7\xc0\xc0\xc0\xc0\xc0\x20", 0xd0, buf_show, 0xd1);
osd.closePanel();
}
 
 
/* **************************************************************** */
// Panel : panBoot
// Needs : X, Y locations
// Output : Booting up text and empty bar after that
// Size : 1 x 21 (rows x chars)
// Staus : done
 
void panBoot(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf_P(PSTR("Booting up:\xed\xf2\xf2\xf2\xf2\xf2\xf2\xf2\xf3"));
osd.closePanel();
 
}
 
/* **************************************************************** */
// Panel : panMavBeat
// Needs : X, Y locations
// Output : 2 symbols, one static and one that blinks on every 50th received
// mavlink packet.
// Size : 1 x 2 (rows x chars)
// Staus : done
 
void panMavBeat(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
if(mavbeat == 1){
osd.printf_P(PSTR("\xEA\xEC"));
mavbeat = 0;
}
else{
osd.printf_P(PSTR("\xEA\xEB"));
}
osd.closePanel();
}
 
 
/* **************************************************************** */
// Panel : panWPDir
// Needs : X, Y locations
// Output : 2 symbols that are combined as one arrow, shows direction to next waypoint
// Size : 1 x 2 (rows x chars)
// Staus : not ready
 
void panWPDir(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
showArrow();
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panHomeDir
// Needs : X, Y locations
// Output : 2 symbols that are combined as one arrow, shows direction to home
// Size : 1 x 2 (rows x chars)
// Status : not tested
 
void panHomeDir(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
showArrow();
osd.closePanel();
}
 
/* **************************************************************** */
// Panel : panFlightMode
// Needs : X, Y locations
// Output : 2 symbols, one static name symbol and another that changes by flight modes
// Size : 1 x 2 (rows x chars)
// Status : done
 
void panFlightMode(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
#ifndef MAVLINK10
if(apm_mav_type == 2){//ArduCopter MultiRotor or ArduCopter Heli
if(osd_mode == 100) osd.printf_P(PSTR("\xE0""stab"));//Stabilize
if(osd_mode == 101) osd.printf_P(PSTR("\xE0""acro"));//Acrobatic
if(osd_mode == 102) osd.printf_P(PSTR("\xE0""alth"));//Alt Hold
if(osd_mode == MAV_MODE_AUTO && osd_nav_mode == MAV_NAV_WAYPOINT) osd.printf_P(PSTR("\xE0""auto"));//Auto
if(osd_mode == MAV_MODE_GUIDED && osd_nav_mode == MAV_NAV_WAYPOINT) osd.printf_P(PSTR("\xE0""guid"));//Guided
if(osd_mode == MAV_MODE_AUTO && osd_nav_mode == MAV_NAV_HOLD) osd.printf_P(PSTR("\xE0""loit"));//Loiter
if(osd_mode == MAV_MODE_AUTO && osd_nav_mode == MAV_NAV_RETURNING) osd.printf_P(PSTR("\xE0""retl"));//Return to Launch
if(osd_mode == 107) osd.printf_P(PSTR("\xE0""circ")); // Circle
if(osd_mode == 108) osd.printf_P(PSTR("\xE0""posi")); // Position
if(osd_mode == 109) osd.printf_P(PSTR("\xE0""land")); // Land
if(osd_mode == 110) osd.printf_P(PSTR("\xE0""oflo")); // OF_Loiter
}
else if(apm_mav_type == 1){//ArduPlane
if(osd_mode == MAV_MODE_TEST1 && osd_nav_mode == MAV_NAV_VECTOR) osd.printf_P(PSTR("\xE0""stab"));//Stabilize
if(osd_mode == MAV_MODE_MANUAL && osd_nav_mode == MAV_NAV_VECTOR) osd.printf_P(PSTR("\xE0""manu"));//Manual
if(osd_mode == MAV_MODE_AUTO && osd_nav_mode == MAV_NAV_LOITER) osd.printf_P(PSTR("\xE0""loit"));//Loiter
if(osd_mode == MAV_MODE_AUTO && osd_nav_mode == MAV_NAV_RETURNING) osd.printf_P(PSTR("\xE0""retl"));//Return to Launch
if(osd_mode == MAV_MODE_TEST2 && osd_nav_mode == 1) osd.printf_P(PSTR("\xE0""fbwa"));//FLY_BY_WIRE_A
if(osd_mode == MAV_MODE_TEST2 && osd_nav_mode == 2) osd.printf_P(PSTR("\xE0""fbwb"));//FLY_BY_WIRE_B
if(osd_mode == MAV_MODE_GUIDED) osd.printf_P(PSTR("\xE0""guid"));//GUIDED
if(osd_mode == MAV_MODE_AUTO && osd_nav_mode == MAV_NAV_WAYPOINT) osd.printf_P(PSTR("\xE0""auto"));//AUTO
if(osd_mode == MAV_MODE_TEST3) osd.printf_P(PSTR("\xE0""circ"));//CIRCLE
}
#else
if(apm_mav_type == 2){//ArduCopter MultiRotor or ArduCopter Heli
if(osd_mode == 0) osd.printf_P(PSTR("\xE0""stab"));//Stabilize
if(osd_mode == 1) osd.printf_P(PSTR("\xE0""acro"));//Acrobatic
if(osd_mode == 2) osd.printf_P(PSTR("\xE0""alth"));//Alt Hold
if(osd_mode == 3) osd.printf_P(PSTR("\xE0""auto"));//Auto
if(osd_mode == 4) osd.printf_P(PSTR("\xE0""guid"));//Guided
if(osd_mode == 5) osd.printf_P(PSTR("\xE0""loit"));//Loiter
if(osd_mode == 6) osd.printf_P(PSTR("\xE0""retl"));//Return to Launch
if(osd_mode == 7) osd.printf_P(PSTR("\xE0""circ")); // Circle
if(osd_mode == 8) osd.printf_P(PSTR("\xE0""posi")); // Position
if(osd_mode == 9) osd.printf_P(PSTR("\xE0""land")); // Land
if(osd_mode == 10) osd.printf_P(PSTR("\xE0""oflo")); // OF_Loiter
}
else if(apm_mav_type == 1){//ArduPlane
if(osd_mode == 2 ) osd.printf_P(PSTR("\xE0""stab"));//Stabilize
if(osd_mode == 0) osd.printf_P(PSTR("\xE0""manu"));//Manual
if(osd_mode == 12) osd.printf_P(PSTR("\xE0""loit"));//Loiter
if(osd_mode == 11 ) osd.printf_P(PSTR("\xE0""retl"));//Return to Launch
if(osd_mode == 5 ) osd.printf_P(PSTR("\xE0""fbwa"));//FLY_BY_WIRE_A
if(osd_mode == 6 ) osd.printf_P(PSTR("\xE0""fbwb"));//FLY_BY_WIRE_B
if(osd_mode == 15) osd.printf_P(PSTR("\xE0""guid"));//GUIDED
if(osd_mode == 10 ) osd.printf_P(PSTR("\xE0""auto"));//AUTO
if(osd_mode == 1) osd.printf_P(PSTR("\xE0""circ"));//CIRCLE
}
#endif
osd.closePanel();
}
 
 
// ---------------- EXTRA FUNCTIONS ----------------------
// Show those fancy 2 char arrows
void showArrow() {
switch(osd_home_direction) {
case 0:
osd.printf_P(PSTR("\x90\x91"));
break;
case 1:
osd.printf_P(PSTR("\x90\x91"));
break;
case 2:
osd.printf_P(PSTR("\x92\x93"));
break;
case 3:
osd.printf_P(PSTR("\x94\x95"));
break;
case 4:
osd.printf_P(PSTR("\x96\x97"));
break;
case 5:
osd.printf_P(PSTR("\x98\x99"));
break;
case 6:
osd.printf_P(PSTR("\x9A\x9B"));
break;
case 7:
osd.printf_P(PSTR("\x9C\x9D"));
break;
case 8:
osd.printf_P(PSTR("\x9E\x9F"));
break;
case 9:
osd.printf_P(PSTR("\xA0\xA1"));
break;
case 10:
osd.printf_P(PSTR("\xA2\xA3"));
break;
case 11:
osd.printf_P(PSTR("\xA4\xA5"));
break;
case 12:
osd.printf_P(PSTR("\xA6\xA7"));
break;
case 13:
osd.printf_P(PSTR("\xA8\xA9"));
break;
case 14:
osd.printf_P(PSTR("\xAA\xAB"));
break;
case 15:
osd.printf_P(PSTR("\xAC\xAD"));
break;
case 16:
osd.printf_P(PSTR("\xAE\xAF"));
break;
}
}
 
// Calculate and shows Artificial Horizon
void showHorizon(int start_col, int start_row) {
 
int x, nose, row, minval, hit, subval = 0;
int cols = 12;
int rows = 5;
int col_hit[cols];
float pitch, roll;
(abs(osd_pitch) == 90)?pitch = 89.99 * (90/osd_pitch) * -0.017453293:pitch = osd_pitch * -0.017453293;
(abs(osd_roll) == 90)?roll = 89.99 * (90/osd_roll) * 0.017453293:roll = osd_roll * 0.017453293;
 
nose = round(tan(pitch) * (rows*9));
for(int col=1;col <= cols;col++){
x = (col * 12) - (cols * 6) - 6;//center X point at middle of each col
col_hit[col-1] = (tan(roll) * x) + nose + (rows*9) - 1;//calculating hit point on Y plus offset to eliminate negative values
//col_hit[(col-1)] = nose + (rows * 9);
}
 
for(int col=0;col < cols; col++){
hit = col_hit[col];
if(hit > 0 && hit < (rows * 18)){
row = rows - ((hit-1)/18);
minval = rows*18 - row*18 + 1;
subval = hit - minval;
subval = round((subval*9)/18);
if(subval == 0) subval = 1;
printHit(start_col + col, start_row + row - 1, subval);
}
}
}
 
void printHit(byte col, byte row, byte subval){
osd.openSingle(col, row);
switch (subval){
case 1:
osd.printf_P(PSTR("\x06"));
break;
case 2:
osd.printf_P(PSTR("\x07"));
break;
case 3:
osd.printf_P(PSTR("\x08"));
break;
case 4:
osd.printf_P(PSTR("\x09"));
break;
case 5:
osd.printf_P(PSTR("\x0a"));
break;
case 6:
osd.printf_P(PSTR("\x0b"));
break;
case 7:
osd.printf_P(PSTR("\x0c"));
break;
case 8:
osd.printf_P(PSTR("\x0d"));
break;
case 9:
osd.printf_P(PSTR("\x0e"));
break;
}
}
/C-OSD/arducam-osd/ArduCAM_OSD/OSD_Vars.h
0,0 → 1,88
/*Panels variables*/
//Will come from APM telem port
 
static float osd_vbat_A = 0; // Battery A voltage in milivolt
//static float osd_curr_A = 0; // Battery A current
static uint16_t osd_battery_remaining_A = 0; // 0 to 100 <=> 0 to 1000
static uint8_t osd_battery_pic_A = 0xb4; // picture to show battery remaining
//static float osd_vbat_B = 0; // voltage in milivolt
//static float osd_curr_B = 0; // Battery B current
//static uint16_t osd_battery_remaining_B = 0; // 0 to 100 <=> 0 to 1000
//static uint8_t osd_battery_pic_B = 0xb4; // picture to show battery remaining
 
static uint16_t osd_mode = 0; // Navigation mode from RC AC2 = CH5, APM = CH8
static uint8_t osd_nav_mode = 0; // Navigation mode from RC AC2 = CH5, APM = CH8
 
static float osd_lat = 0; // latidude
static float osd_lon = 0; // longitude
static uint8_t osd_satellites_visible = 0; // number of satelites
static uint8_t osd_fix_type = 0; // GPS lock 0-1=no fix, 2=2D, 3=3D
 
static uint8_t osd_got_home = 0; // tels if got home position or not
static float osd_home_lat = 0; // home latidude
static float osd_home_lon = 0; // home longitude
static float osd_home_alt = 0;
static long osd_home_distance = 0; // distance from home
static uint8_t osd_home_direction; // Arrow direction pointing to home (1-16 to CW loop)
 
static int8_t osd_pitch = 0; // pitch form DCM
static int8_t osd_roll = 0; // roll form DCM
static int8_t osd_yaw = 0; // relative heading form DCM
static float osd_heading = 0; // ground course heading from GPS
static float osd_alt = 0; // altitude
static float osd_groundspeed = 0; // ground speed
static uint16_t osd_throttle = 0; // throtle
 
//MAVLink session control
static boolean mavbeat = 0;
static float lastMAVBeat = 0;
static boolean waitingMAVBeats = 1;
static uint8_t apm_mav_type;
static uint8_t apm_mav_system;
static uint8_t apm_mav_component;
static boolean enable_mav_request = 0;
 
// Panel BIT registers
byte panA_REG = 0b00000000;
byte panB_REG = 0b00000000;
byte panC_REG = 0b00000000;
 
byte modeScreen = 0; //NTSC:0, PAL:1
 
byte SerCMD1 = 0;
byte SerCMD2 = 0;
 
 
int tempvar; // Temporary variable used on many places around the OSD
 
// First 8 panels and their X,Y coordinate holders
byte panCenter_XY[2]; // = { 13,7,0 };
byte panPitch_XY[2]; // = { 11,1 };
byte panRoll_XY[2]; // = { 23,7 };
byte panBatt_A_XY[2]; // = { 23,1 };
//byte panBatt_B_XY[2]; // = { 23,3 };
byte panGPSats_XY[2]; // = { 2,12 };
byte panGPL_XY[2]; // = { 2,11 };
byte panGPS_XY[2]; // = { 2,13 };
 
// Second 8 set of panels and their X,Y coordinate holders
byte panRose_XY[2]; // = { 16,13 };
byte panHeading_XY[2]; // = { 16,12 };
byte panMavBeat_XY[2]; // = { 2,10 };
byte panHomeDir_XY[2]; // = { 0,0 };
byte panHomeDis_XY[2]; // = { 0,0 };
byte panWPDir_XY[2]; // = { 0,0 };
byte panWPDis_XY[2]; // = { 0,0 };
//byte panRSSI_XY[2] = { 0,0 };
 
// Third set of panels and their X,Y coordinate holders
//byte panCur_A_XY[2]; // = { 23,1 };
//byte panCur_B_XY[2]; // = { 23,3 };
byte panAlt_XY[2]; // = { 0,0 };
byte panVel_XY[2]; // = { 0,0 };
byte panThr_XY[2]; // = { 0,0 };
byte panFMod_XY[2]; // = { 0,0 };
byte panHorizon_XY[2]; // = {8,centercalc}
//byte panXXX_XY[2] = { 0,0 };
 
 
/C-OSD/arducam-osd/ArduCAM_OSD/Spi.cpp
0,0 → 1,56
// Get the common arduino functions
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "wiring.h"
#endif
#include "Spi.h"
 
//---------- constructor ----------------------------------------------------
 
SPI::SPI()
{
// initialize the SPI pins
pinMode(SCK_PIN, OUTPUT);
pinMode(MOSI_PIN, OUTPUT);
pinMode(MISO_PIN, INPUT);
pinMode(SS_PIN, OUTPUT); // <------- !!! (Remember! This pin will select USB host chip Max3421)
 
// enable SPI Master, MSB, SPI mode 0, FOSC/4
mode(0);
}
 
//------------------ mode ---------------------------------------------------
 
void SPI::mode(byte config)
{
byte tmp;
 
// enable SPI master with configuration byte specified
SPCR = 0;
SPCR = (config & 0x7F) | (1<<SPE) | (1<<MSTR);
tmp = SPSR;
tmp = SPDR;
}
 
//------------------ transfer -----------------------------------------------
 
byte SPI::transfer(byte value)
{
SPDR = value;
while (!(SPSR & (1<<SPIF))) ;
return SPDR;
}
 
byte SPI::transfer(byte value, byte period)
{
SPDR = value;
if (period > 0) delayMicroseconds(period);
while (!(SPSR & (1<<SPIF))) ;
return SPDR;
}
 
 
//---------- preinstantiate SPI object --------------------------------------
 
SPI Spi = SPI();
/C-OSD/arducam-osd/ArduCAM_OSD/Spi.h
0,0 → 1,27
#ifndef Spi_h
#define Spi_h
 
// Get the common arduino functions
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "wiring.h"
#endif
 
#define SCK_PIN 13
#define MISO_PIN 12
#define MOSI_PIN 11
#define SS_PIN 10 // <------- !!! (Remember! This pin will select USB host chip Max3421)
 
class SPI
{
public:
SPI(void);
void mode(byte);
byte transfer(byte);
byte transfer(byte, byte);
};
 
extern SPI Spi;
 
#endif
/C-OSD/arducam-osd/ArduCamOSD_Beta/ArduCamOSD_Beta.pde
0,0 → 1,269
/*
ArduCam OSD - The Arduino based Remote Camera Control and OSD.
 
File : ArduCamOSD_Beta.pde
Version : v0.95, 17 may 2011
 
Author(s): Sandro Benigno
FastSerial and BetterStream from Michael Smith
USB host and PTP library from Oleg Mazurov - circuitsathome.com
 
This program 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 program 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 <http://www.gnu.org/licenses/>.
*/
 
#include <FastSerial.h>
 
#undef PROGMEM
#define PROGMEM __attribute__(( section(".progmem.data") ))
 
#undef PSTR
#define PSTR(s) (__extension__({static prog_char __c[] PROGMEM = (s); &__c[0];}))
 
#include <inttypes.h>
#include <avr/pgmspace.h>
#include <stdio.h>
 
#include "Spi.h"
#include "Wire.h" //Future i2c comunication. Uncommented to watch hex size
 
/****** USB INCLUDES ******/
#include <Max3421e.h>
#include <Max3421e_constants.h>
#include <Usb.h>
#include <ptp.h>
#include <ptpdebug.h>
#include <canonps.h>
#include <simpletimer.h>
#include "pseventparser.h"
#include "ptpobjinfoparser.h"
 
#define DEV_ADDR 1
//Example -> Canon PowerShot S3 IS
#define DATA_IN_EP 1
#define DATA_OUT_EP 2
#define INTERRUPT_EP 3
#define CONFIG_NUM 1
 
#define MAX_USB_STRING_LEN 64
 
/****** OSD INCLUDES ******/
#include "ArduCam_Max7456.h"
#include "OSD_Vars.h"
 
#define SerPri Serial.print
#define SerPriln Serial.println
#define SerAva Serial.available
#define SerRea Serial.read
 
void setup();
void loop();
 
FastSerialPort0(Serial);
 
/****** CAMSTATES CLASS ******/
class CamStateHandlers : public PSStateHandlers
{
bool stateConnected;
public:
CamStateHandlers() : stateConnected(false) {};
virtual void OnDeviceDisconnectedState(PTP *ptp);
virtual void OnDeviceInitializedState(PTP *ptp);
} CamStates;
/****** END CAMSTATES ******/
 
/****** OBJECTS ******/
OSD osd; //OSD object instance
CanonPS Ps(DEV_ADDR, DATA_IN_EP, DATA_OUT_EP, INTERRUPT_EP, CONFIG_NUM, &CamStates); //Canon PS object instance
SimpleTimer displayTimer, cameraTimer; //Timers
 
/********** HANDLERS**********/
 
void CamStateHandlers::OnDeviceDisconnectedState(PTP *ptp)
{
if (stateConnected)
{
cameraTimer.Disable();
stateConnected = false;
Notify(PSTR("Camera disconnected\r\n"));
}
}
 
void CamStateHandlers::OnDeviceInitializedState(PTP *ptp)
{
if (!stateConnected)
{
Notify(PSTR("Camera connected\r\n"));
stateConnected = true;
cameraTimer.Enable();
}
}
 
/**********END TIMERS HANDLERS******/
 
//Demo vars control (!!! Remember to delete it after APM integration)
float lastGPSUpdate = 0;
float lastBatUpdate = 0;
float lastHeadUpdate = 0;
float headIncrementSignal = 1;
 
void setup()
{
Serial.begin(57600);
pinMode(10, OUTPUT); //usb host CS
pinMode(6, OUTPUT); //OSD CS
unplugSlaves();
 
osd.init();
startPanels();
delay( 200 );
unplugSlaves();
Ps.Setup();
delay( 2000 );
osd.clear();
//Setting Timers
displayTimer.Set(&OnDisplayTimer, 150);
cameraTimer.Set(&OnCameraTimer, 500);
delay( 200 );
 
displayTimer.Enable(); //Starting OSD timer (camera timer depends on camera is attached or not)
}
 
void loop(){
unplugSlaves();
displayTimer.Run();
unplugSlaves();
Ps.Task();
cameraTimer.Run();
}
 
void OnCameraTimer()
{
readSerialCommand();
}
 
void OnDisplayTimer()
{
osd_job();
}
 
void writeOSD() //Interrupt function (ISR)
{
//Serial.println("Interrupt!");
detachInterrupt(0); //It will respect the new aquisition
unplugSlaves();
writePanels();//Check OSD_Panels Tab!
}
 
void osd_job()
{
/*Its the place for data aquisition*/
/*JUST Simulated here as DEMO and test*/
if(millis() > lastGPSUpdate + 100){
lastGPSUpdate = millis();
lat+=0.0001;
lon+=0.002;
hom_dis+=1;
}
if(millis() > lastHeadUpdate + 100){
lastHeadUpdate = millis();
//looping forever
if(head >= 180){
head -= 360;
}else head+=5;
//or ping-pong
/*if(head >= 180) headIncrementSignal = -1;
if(head <= -180) headIncrementSignal = 1;
head += 1.8 * headIncrementSignal;*/
}
if(millis() > lastBatUpdate + 2000){
lastBatUpdate = millis();
alt++;
vel+=5;
bat_val -= 0.1;
}
//Next line will arm OSD function for the next VSync interruption
attachInterrupt(0, writeOSD, FALLING);
}
 
void readSerialCommand() {
char queryType;
if (SerAva()) {
queryType = SerRea();
switch (queryType) {
case 'A': //Activate Capture
Ps.Initialize(true);
//mapping capture target to SD card
Ps.SetDevicePropValue(PS_DPC_CaptureTransferMode, (uint16_t)0x0F);
break;
case 'C': //Capture!!!
Ps.Capture();
break;
case 'D': //Deactivate Capture
Ps.Operation(PS_OC_ViewfinderOff);
Ps.Initialize(false);
break;
case 'L': //Focus Lock
Ps.Operation(PS_OC_FocusLock);
delay(50);
break;
case 'O': //ViewFinder Output. 1 = LCD. 2 = AV.
Ps.SetDevicePropValue(PS_DPC_CameraOutput, (uint16_t)readFloatSerial());
break;
case 'U': //Focus Unlock
Ps.Operation(PS_OC_FocusUnlock);
break;
case 'V': //ViewFinder ON/OFF
if((uint16_t)readFloatSerial() == 0){
Ps.Operation(PS_OC_ViewfinderOff);
}
else Ps.Operation(PS_OC_ViewfinderOn);
break;
case 'X': //Close session forever
Ps.Initialize(false);
break;
case 'Z': //Set Zoom
Ps.SetDevicePropValue(PS_DPC_Zoom, (uint16_t)readFloatSerial());
break;
}
}
}
 
float readFloatSerial() {
byte index = 0;
byte timeout = 0;
char data[128] = "";
 
do {
if (SerAva() == 0) {
delay(10);
timeout++;
}
else {
data[index] = SerRea();
timeout = 0;
index++;
}
}
while ((data[constrain(index-1, 0, 128)] != ';') && (timeout < 5) && (index < 128));
return atof(data);
}
 
void unplugSlaves(){
digitalWrite(10, HIGH); //unplug USB Host
digitalWrite(6, HIGH); //unplug OSD
}
/C-OSD/arducam-osd/ArduCamOSD_Beta/ArduCam_Max7456.cpp
0,0 → 1,160
#include <FastSerial.h>
 
#undef PROGMEM
#define PROGMEM __attribute__(( section(".progmem.data") ))
 
#undef PSTR
#define PSTR(s) (__extension__({static prog_char __c[] PROGMEM = (s); &__c[0];}))
 
#include "ArduCam_Max7456.h"
#include "WProgram.h"
#include "Spi.h"
 
volatile int x;
 
OSD::OSD()
{
}
 
//------------------ init ---------------------------------------------------
 
void OSD::init()
{
pinMode(MAX7456_SELECT,OUTPUT);
digitalWrite(MAX7456_SELECT,HIGH); //disable device
pinMode(MAX7456_VSYNC, INPUT);
//digitalWrite(MAX7456_VSYNC,HIGH); //enabling pull-up resistor
// force soft reset on Max7456
digitalWrite(MAX7456_SELECT,LOW);
Spi.transfer(MAX7456_VM0_reg);
Spi.transfer(MAX7456_RESET);
digitalWrite(MAX7456_SELECT,HIGH);
delay(50);
 
// set all rows to same charactor white level, 90%
digitalWrite(MAX7456_SELECT,LOW);
for (x = 0; x < MAX7456_screen_rows; x++)
{
Spi.transfer(x + 0x10);
Spi.transfer(MAX7456_WHITE_level_120);
}
// define sync (auto,int,ext) and
// making sure the Max7456 is enabled
control(1);
//digitalWrite(MAX7456_SELECT,HIGH);
 
//Serial.println("Initialized!");
}
 
//------------------ plug ---------------------------------------------------
 
void OSD::plug()
{
digitalWrite(MAX7456_SELECT,LOW);
}
 
//------------------ clear ---------------------------------------------------
 
void OSD::clear()
{
// clear the screen
digitalWrite(MAX7456_SELECT,LOW);
Spi.transfer(MAX7456_DMM_reg);
Spi.transfer(MAX7456_CLEAR_display);
digitalWrite(MAX7456_SELECT,HIGH);
}
 
//------------------ set panel -----------------------------------------------
 
void
OSD::setPanel(uint8_t st_col, uint8_t st_row){
start_col = st_col;
start_row = st_row;
col = st_col;
row = st_row;
//Serial.printf("setPanel -> %d %d %d %d\n", start_col, start_row, max_col, max_row);
}
 
//------------------ open panel ----------------------------------------------
 
void
OSD::openPanel(void){
unsigned int linepos;
byte settings, char_address_hi, char_address_lo;
//find [start address] position
linepos = row*30+col;
// divide 16 bits into hi & lo byte
char_address_hi = linepos >> 8;
char_address_lo = linepos;
 
//Auto increment turn writing fast (less SPI commands).
//No need to set next char address. Just send them
settings = MAX7456_INCREMENT_auto; //To Enable DMM Auto Increment
digitalWrite(MAX7456_SELECT,LOW);
Spi.transfer(MAX7456_DMM_reg); //dmm
Spi.transfer(settings);
 
Spi.transfer(MAX7456_DMAH_reg); // set start address high
Spi.transfer(char_address_hi);
 
Spi.transfer(MAX7456_DMAL_reg); // set start address low
Spi.transfer(char_address_lo);
//Serial.printf("setPos -> %d %d\n", col, row);
}
 
//------------------ close panel ---------------------------------------------
 
void
OSD::closePanel(void){
Spi.transfer(MAX7456_DMDI_reg);
Spi.transfer(MAX7456_END_string); //This is needed "trick" to finish auto increment
digitalWrite(MAX7456_SELECT,HIGH);
//Serial.println("close");
row++; //only after finish the auto increment the new row will really act as desired
}
 
//------------------ write ---------------------------------------------------
 
void
OSD::write(uint8_t c){
if(c == '|'){
closePanel(); //It does all needed to finish auto increment and change current row
openPanel(); //It does all needed to re-enable auto increment
}
else{
Spi.transfer(MAX7456_DMDI_reg);
Spi.transfer(c);
}
}
 
//------------------
 
void
OSD::control(uint8_t ctrl){
digitalWrite(MAX7456_SELECT,LOW);
Spi.transfer(MAX7456_VM0_reg);
switch(ctrl){
case 0:
Spi.transfer(MAX7456_DISABLE_display);
break;
case 1:
//Spi.transfer(MAX7456_ENABLE_display_vert | MAX7456_SYNC_internal);
//Spi.transfer(MAX7456_ENABLE_display_vert | MAX7456_SYNC_external);
Spi.transfer(MAX7456_ENABLE_display_vert | MAX7456_SYNC_autosync);
break;
}
digitalWrite(MAX7456_SELECT,HIGH);
}
 
//------------------ pure virtual ones (just overriding) ---------------------
 
int OSD::available(void){
}
int OSD::read(void){
}
int OSD::peek(void){
}
void OSD::flush(void){
}
/C-OSD/arducam-osd/ArduCamOSD_Beta/ArduCam_Max7456.h
0,0 → 1,88
#ifndef ArduCam_Max7456_h
#define ArduCam_Max7456_h
 
/******* FROM DATASHEET *******/
 
//#define isPAL
#define MAX7456_SELECT 6//SS
#define MAX7456_VSYNC 2//INT0
 
#ifdef isPAL
#define MAX7456_MODE 0x40 //PAL mask 10000000
#else
#define MAX7456_MODE 0x00 //NTSC mask 00000000 ("|" will do nothing)
#endif
 
//MAX7456 reg write addresses
#define MAX7456_VM0_reg 0x00
#define MAX7456_VM1_reg 0x01
#define MAX7456_DMM_reg 0x04
#define MAX7456_DMAH_reg 0x05
#define MAX7456_DMAL_reg 0x06
#define MAX7456_DMDI_reg 0x07
#define MAX7456_OSDM_reg 0x0c //not used. Is to set mix
 
//MAX7456 reg write addresses to recording NVM process
#define MAX7456_CMM_reg 0x08
#define MAX7456_CMAH_reg 0x09
#define MAX7456_CMAL_reg 0x0a
#define MAX7456_CMDI_reg 0x0b
#define MAX7456_STAT_reg 0xa0 //0xa[X]
 
//DMM commands
#define MAX7456_CLEAR_display 0x04
#define MAX7456_CLEAR_display_vert 0x06
 
#define MAX7456_INCREMENT_auto 0x03
#define MAX7456_SETBG_local 0x20 //00100000 force local BG to defined brightness level VM1[6:4]
 
#define MAX7456_END_string 0xff
 
//VM0 commands mixed with mode NTSC or PAL mode
#define MAX7456_ENABLE_display (0x08 | MAX7456_MODE) //Don't used. Bad sync. 00001000
#define MAX7456_ENABLE_display_vert (0x0c | MAX7456_MODE) //Much better. Good sync 00001100
#define MAX7456_RESET (0x02 | MAX7456_MODE)
#define MAX7456_DISABLE_display (0x00 | MAX7456_MODE)
//VM0 command modifiers
#define MAX7456_SYNC_autosync 0x10
#define MAX7456_SYNC_internal 0x30
#define MAX7456_SYNC_external 0x20
//VM1 command modifiers
#define MAX7456_WHITE_level_80 0x03
#define MAX7456_WHITE_level_90 0x02
#define MAX7456_WHITE_level_100 0x01
#define MAX7456_WHITE_level_120 0x00
 
//If PAL
#ifdef isPAL
#define MAX7456_screen_size 480
#define MAX7456_screen_rows 15
#else
#define MAX7456_screen_size 390
#define MAX7456_screen_rows 13
#endif
 
//------------------ the OSD class -----------------------------------------------
 
class OSD: public BetterStream
{
public:
OSD(void);
void init(void);
void clear(void);
void plug(void);
void setPanel(uint8_t start_col, uint8_t start_row);
void openPanel(void);
void closePanel(void);
void control(uint8_t ctrl);
virtual int available(void);
virtual int read(void);
virtual int peek(void);
virtual void flush(void);
virtual void write(uint8_t c);
using BetterStream::write;
private:
uint8_t start_col, start_row, col, row;
};
 
#endif
/C-OSD/arducam-osd/ArduCamOSD_Beta/OSD_Panels.pde
0,0 → 1,114
/******* STARTUP PANEL *******/
 
void startPanels(){
osd.clear();
panLogo(10,5);
}
 
/******* PANELS - POSITION *******/
 
void writePanels(){
//osd.clear();
int offset = 2;
#ifdef isPAL
offset = 0;
#endif
//Top = no offset in NTSC
panHome(2,1); //1x2
panBattery(22,1); //7x1
//Bottom = need offset in NTSC
panCenter(13,8-offset); //4x2
panGPS(2,12-offset); //12x3
panCompass(16,12-offset); //13x3
//osd.control(1);
}
 
/******* PANELS - DEFINITION *******/
 
//------------------ Panel: Home ---------------------------------------------------
 
void panHome(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf("%c%5.0f%c|%c%5.0f%c|%c%5.0f%c",0x1f,hom_dis,0x8d,0x85,alt,0x8d,0x86,vel,0x88);
osd.closePanel();
}
 
//------------------ Panel: Center -------------------------------------------------
 
void panCenter(int first_col, int first_line){
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf("%c%c%c%c|%c%c%c%c",0x05,0x03,0x04,0x05,0x15,0x13,0x14,0x15);
osd.closePanel();
}
 
//------------------ Panel: Battery ------------------------------------------------
 
void panBattery(int first_col, int first_line){
char buf_bat[6] = {0xb4,0xb5,0xb6,0xb7,0xb8,0xb9}; //dead, critic, 25%, 50%, 75%, 100%
float critic = bat_cel * 3.0;
float full = bat_cel * 3.7;
float level = round((bat_val - critic) * (5 - 0) / (full - critic) + 0);
level = constrain(level, 0, 5);
if(bat_val < 0) bat_val = 0;
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf("%4.1f%c%c", bat_val, 0x76, buf_bat[(int)level]);
osd.closePanel();
}
 
//------------------ Panel: Startup ArduCam OSD LOGO -------------------------------
 
void panLogo(int first_col, int first_line){
char buf_logo[][12] = { //11 Null terminated
{0x20,0x20,0x20,0x20,0xba,0xbb,0xbc,0xbd,0xbe},
{0x20,0x20,0x20,0x20,0xca,0xcb,0xcc,0xcd,0xce},
{"ArduCam OSD"}
};
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf("%s|%s|%s", buf_logo[0], buf_logo[1], buf_logo[2]);
osd.closePanel();
}
 
//------------------ Panel: GPS ---------------------------------------------------
 
void panGPS(int first_col, int first_line){
char buf_lock[3] = {0x10,0x11};
osd.setPanel(first_col, first_line);
osd.openPanel();
switch (gps_lock){
case 0:
osd.printf("%c%c%2.0f %c|%c%s|%c%s", 0x0f, 0xe3,(float)num_sat, buf_lock[0], 0x83, " ---- ", 0x84, " ---- ");
break;
case 1:
osd.printf("%c%c%2.0f %c|%c%11.6f|%c%11.6f", 0x0f, 0xe3,(float)num_sat, buf_lock[1], 0x83, lat, 0x84, lon);
break;
}
osd.closePanel();
}
 
//------------------ Panel: Compass -----------------------------------------------
 
void panCompass(int first_col, int first_line){
char buf_Rule[36] = {0xc2,0xc0,0xc0,0xc1,0xc0,0xc0,0xc1,0xc0,0xc0,
0xc4,0xc0,0xc0,0xc1,0xc0,0xc0,0xc1,0xc0,0xc0,
0xc3,0xc0,0xc0,0xc1,0xc0,0xc0,0xc1,0xc0,0xc0,
0xc5,0xc0,0xc0,0xc1,0xc0,0xc0,0xc1,0xc0,0xc0};
char buf_mark[14] = {0x20,0xc0,0xc0,0xc0,0xc0,0xc0,0xc7,0xc0,0xc0,0xc0,0xc0,0xc0,0x20,'\0'};
char buf_show[12];
buf_show[11] = '\0';
int start;
start = round((head * 18)/180);
start -= 5;
if(start < 0) start += 36;
for(int x=0; x <= 10; x++){
buf_show[x] = buf_Rule[start];
if(++start > 35) start = 0;
}
osd.setPanel(first_col, first_line);
osd.openPanel();
osd.printf(" %c%c%4.0f%c|%s|%c%s%c", 0xc8, 0xc9, head, 0xb0, buf_mark, 0xd0, buf_show, 0xd1);
osd.closePanel();
}
/C-OSD/arducam-osd/ArduCamOSD_Beta/OSD_Vars.h
0,0 → 1,29
#define on 1
#define off 0
 
/*Enabling disabling Panels Switches*/
//Not working yet!!! Just here to remember:
 
int swBat = on;
int swCam = off;
int swDir = off;
int swGPS = on;
int swAlt = off;
int swTim = off;
int swDis = off;
 
/*Panels variables*/
//Will come from APM telem port
 
float bat_val = 12.05; //current voltage
float bat_cel = 3; //number of cells
float lat = 34.178851; //latidude
float lon = -118.501655; //longitude
float hom_dis = 0; //distance from home <-------- !!! (probably must be calculated here)
float head = 170.0; //heading angle = compass
float alt = 0; //altitude <-------- !!! ( Need to know the default unit meters foots?)
float vel = 0; //velocity <-------- !!! ( Need to know the default unit meters/sec kmeters/h milles/h?)
int num_sat = 3; //number of satelites
int gps_lock = 1; //GPS lock... need verify if is boolean or not <--------- !!! ( Remember!!! Very important on startup time!!!)
 
 
/C-OSD/arducam-osd/ArduCamOSD_Beta/Spi.cpp
0,0 → 1,51
#include "WProgram.h"
#include "Spi.h"
 
//---------- constructor ----------------------------------------------------
 
SPI::SPI()
{
// initialize the SPI pins
pinMode(SCK_PIN, OUTPUT);
pinMode(MOSI_PIN, OUTPUT);
pinMode(MISO_PIN, INPUT);
pinMode(SS_PIN, OUTPUT); // <------- !!! (Remember! This pin will select USB host chip Max3421)
 
// enable SPI Master, MSB, SPI mode 0, FOSC/4
mode(0);
}
 
//------------------ mode ---------------------------------------------------
 
void SPI::mode(byte config)
{
byte tmp;
 
// enable SPI master with configuration byte specified
SPCR = 0;
SPCR = (config & 0x7F) | (1<<SPE) | (1<<MSTR);
tmp = SPSR;
tmp = SPDR;
}
 
//------------------ transfer -----------------------------------------------
 
byte SPI::transfer(byte value)
{
SPDR = value;
while (!(SPSR & (1<<SPIF))) ;
return SPDR;
}
 
byte SPI::transfer(byte value, byte period)
{
SPDR = value;
if (period > 0) delayMicroseconds(period);
while (!(SPSR & (1<<SPIF))) ;
return SPDR;
}
 
 
//---------- preinstantiate SPI object --------------------------------------
 
SPI Spi = SPI();
/C-OSD/arducam-osd/ArduCamOSD_Beta/Spi.h
0,0 → 1,22
#ifndef Spi_h
#define Spi_h
 
#include "WProgram.h"
 
#define SCK_PIN 13
#define MISO_PIN 12
#define MOSI_PIN 11
#define SS_PIN 10 // <------- !!! (Remember! This pin will select USB host chip Max3421)
 
class SPI
{
public:
SPI(void);
void mode(byte);
byte transfer(byte);
byte transfer(byte, byte);
};
 
extern SPI Spi;
 
#endif
/C-OSD/arducam-osd/ArduCamOSD_Beta/pseventparser.cpp
0,0 → 1,86
#include "pseventparser.h"
 
void PSEventParser::Parse(const uint16_t len, const uint8_t *pbuf, const uint32_t &offset)
{
uint16_t cntdn = (uint16_t)len;
uint8_t *p = (uint8_t*)pbuf;
 
switch (nStage)
{
case 0:
p += 12;
cntdn -= 12;
 
if (!cntdn)
return;
nStage ++;
 
case 1:
//Notify(PSTR("\r\nEvent Block Size:\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 2:
if (!valueParser.Parse(&p, &cntdn))
return;
 
//PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 3:
//Notify(PSTR("\r\nNumber of Fields:\t"));
theBuffer.valueSize = 2;
valueParser.Initialize(&theBuffer);
nStage ++;
case 4:
if (!valueParser.Parse(&p, &cntdn))
return;
 
//PrintHex<uint16_t>(*((uint16_t*)theBuffer.pValue));
nStage ++;
case 5:
//Notify(PSTR("\r\nEvent Code:\t"));
theBuffer.valueSize = 2;
valueParser.Initialize(&theBuffer);
nStage ++;
case 6:
if (!valueParser.Parse(&p, &cntdn))
return;
 
eventCode = *((uint16_t*)theBuffer.pValue);
//PrintHex<uint16_t>(*((uint16_t*)theBuffer.pValue));
nStage ++;
case 7:
//Notify(PSTR("\r\nTransaction ID:\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 8:
if (!valueParser.Parse(&p, &cntdn))
return;
 
//PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 9:
if (eventCode == PTP_EC_ObjectAdded)
Notify(PSTR("\r\nObject Added:\t\t"));
 
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 10:
if (eventCode == PTP_EC_ObjectAdded)
{
if (!valueParser.Parse(&p, &cntdn))
return;
 
objHandle = *((uint32_t*)theBuffer.pValue);
PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
Notify(PSTR("\r\n"));
}
if (eventCode == PTP_EC_CaptureComplete)
Notify(PSTR("\r\nCapture complete.\r\n"));
nStage ++;
case 11:
nStage = 0;
}
}
/C-OSD/arducam-osd/ArduCamOSD_Beta/pseventparser.h
0,0 → 1,29
#ifndef __PSEVENTPARSER_H__
#define __PSEVENTPARSER_H__
 
#include <inttypes.h>
#include <avr/pgmspace.h>
#include "ptpcallback.h"
#include "ptpdebug.h"
#include "canonps.h"
 
class PSEventParser : public PTPReadParser
{
MultiValueBuffer theBuffer;
uint32_t varBuffer;
uint8_t nStage;
uint16_t eventCode;
uint32_t objHandle;
 
MultiByteValueParser valueParser;
 
public:
PSEventParser() : nStage(0), varBuffer(0), objHandle(0)
{
theBuffer.pValue = &varBuffer;
};
uint32_t GetObjHandle() { return objHandle; };
virtual void Parse(const uint16_t len, const uint8_t *pbuf, const uint32_t &offset);
};
 
#endif // __PSEVENTPARSER_H__
/C-OSD/arducam-osd/ArduCamOSD_Beta/ptpobjinfoparser.cpp
0,0 → 1,298
#include "ptpobjinfoparser.h"
 
const char* PTPObjInfoParser::acNames[] PROGMEM =
{
msgUndefined,
msgAssociation,
msgScript,
msgExecutable,
msgText,
msgHTML,
msgDPOF,
msgAIFF,
msgWAV,
msgMP3,
msgAVI,
msgMPEG,
msgASF,
msgQT
};
 
const char* PTPObjInfoParser::imNames[] PROGMEM =
{
msgUndefined,
msgEXIF_JPEG,
msgTIFF_EP,
msgFlashPix,
msgBMP,
msgCIFF,
msgUndefined_0x3806,
msgGIF,
msgJFIF,
msgPCD,
msgPICT,
msgPNG,
msgUndefined_0x380C,
msgTIFF,
msgTIFF_IT,
msgJP2,
msgJPX,
};
 
void PTPObjInfoParser::PrintFormat(uint16_t op)
{
Serial.print(op, HEX);
Serial.print("\t");
//Notify(msgTab);
 
if ((((op >> 8) & 0xFF) == 0x30) && ((op & 0xFF) <= (PTP_OFC_QT & 0xFF)))
Notify((char*)pgm_read_word(&acNames[(op & 0xFF)]));
else
if ((((op >> 8) & 0xFF) == 0x38) && ((op & 0xFF) <= (PTP_OFC_JPX & 0xFF)))
Notify((char*)pgm_read_word(&imNames[(op & 0xFF)]));
else
{
switch (op)
{
case MTP_OFC_Undefined_Firmware:
Notify(msgUndefined_Firmware);
break;
case MTP_OFC_Windows_Image_Format:
Notify(msgWindows_Image_Format);
break;
case MTP_OFC_Undefined_Audio:
Notify(msgUndefined_Audio);
break;
case MTP_OFC_WMA:
Notify(msgWMA);
break;
case MTP_OFC_OGG:
Notify(msgOGG);
break;
case MTP_OFC_AAC:
Notify(msgAAC);
break;
case MTP_OFC_Audible:
Notify(msgAudible);
break;
case MTP_OFC_FLAC:
Notify(msgFLAC);
break;
case MTP_OFC_Undefined_Video:
Notify(msgUndefined_Video);
break;
case MTP_OFC_WMV:
Notify(msgWMV);
break;
case MTP_OFC_MP4_Container:
Notify(msgMP4_Container);
break;
case MTP_OFC_MP2:
Notify(msgMP2);
break;
case MTP_OFC_3GP_Container:
Notify(msg3GP_Container);
break;
default:
Notify(PSTR("Vendor defined"));
}
}
Notify(PSTR("\r\n"));
}
 
void PTPObjInfoParser::Parse(const uint16_t len, const uint8_t *pbuf, const uint32_t &offset)
{
uint16_t cntdn = (uint16_t)len;
uint8_t *p = (uint8_t*)pbuf;
 
switch (nStage)
{
case 0:
p += 12;
cntdn -= 12;
nStage ++;
case 1:
Notify(PSTR("Storage ID:\t\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 2:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 3:
Notify(PSTR("\r\nObject Format:\t\t"));
theBuffer.valueSize = 2;
valueParser.Initialize(&theBuffer);
nStage ++;
case 4:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintFormat(*((uint16_t*)theBuffer.pValue));
nStage ++;
case 5:
Notify(PSTR("Protection Status:\t"));
theBuffer.valueSize = 2;
valueParser.Initialize(&theBuffer);
nStage ++;
case 6:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint16_t>(*((uint16_t*)theBuffer.pValue));
nStage ++;
case 7:
Notify(PSTR("\r\nObject Compressed Size:\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 8:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 9:
Notify(PSTR("\r\nThumb Format:\t\t"));
theBuffer.valueSize = 2;
valueParser.Initialize(&theBuffer);
nStage ++;
case 10:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintFormat(*((uint16_t*)theBuffer.pValue));
nStage ++;
case 11:
Notify(PSTR("Thumb Compressed Size:\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 12:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 13:
Notify(PSTR("\r\nThumb Pix Width:\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 14:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 15:
Notify(PSTR("\r\nThumb Pix Height:\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 16:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 17:
Notify(PSTR("\r\nImage Pix Width:\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 18:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 19:
Notify(PSTR("\r\nImage Pix Height:\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 20:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 21:
Notify(PSTR("\r\nImage Bit Depth:\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 22:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 23:
Notify(PSTR("\r\nParent Object:\t\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 24:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 25:
Notify(PSTR("\r\nAssociation Type:\t"));
theBuffer.valueSize = 2;
valueParser.Initialize(&theBuffer);
nStage ++;
case 26:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint16_t>(*((uint16_t*)theBuffer.pValue));
nStage ++;
case 27:
Notify(PSTR("\r\nAssociation Desc:\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 28:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 29:
Notify(PSTR("\r\nSequence Number:\t"));
theBuffer.valueSize = 4;
valueParser.Initialize(&theBuffer);
nStage ++;
case 30:
if (!valueParser.Parse(&p, &cntdn))
return;
PrintHex<uint32_t>(*((uint32_t*)theBuffer.pValue));
nStage ++;
case 31:
Notify(PSTR("\r\nFile Name:\t\t"));
arrayParser.Initialize(1, 2, &theBuffer);
nStage ++;
case 32:
if (!arrayParser.Parse(&p, &cntdn, (PTP_ARRAY_EL_FUNC)&PrintChar))
return;
nStage ++;
case 33:
Notify(PSTR("\r\nCapture Date:\t\t"));
arrayParser.Initialize(1, 2, &theBuffer);
nStage ++;
case 34:
if (!arrayParser.Parse(&p, &cntdn, (PTP_ARRAY_EL_FUNC)&PrintChar))
return;
nStage ++;
case 35:
Notify(PSTR("\r\nModification Date:\t"));
arrayParser.Initialize(1, 2, &theBuffer);
nStage ++;
case 36:
if (!arrayParser.Parse(&p, &cntdn, (PTP_ARRAY_EL_FUNC)&PrintChar))
return;
nStage ++;
case 37:
Notify(PSTR("\r\nKeywords:\t"));
arrayParser.Initialize(1, 2, &theBuffer);
nStage ++;
case 38:
if (!arrayParser.Parse(&p, &cntdn, (PTP_ARRAY_EL_FUNC)&PrintChar))
return;
Notify(PSTR("\r\n"));
nStage = 0;
}
}
/C-OSD/arducam-osd/ArduCamOSD_Beta/ptpobjinfoparser.h
0,0 → 1,83
#ifndef __PTPOBJINFOPARSER_H__
#define __PTPOBJINFOPARSER_H__
 
#include <ptp.h>
#include <mtpconst.h>
#include <ptpcallback.h>
 
const char msgUndefined [] PROGMEM = "Undefined";
 
// Ancillary formats
const char msgAssociation [] PROGMEM = "Association";
const char msgScript [] PROGMEM = "Script";
const char msgExecutable [] PROGMEM = "Executable";
const char msgText [] PROGMEM = "Text";
const char msgHTML [] PROGMEM = "HTML";
const char msgDPOF [] PROGMEM = "DPOF";
const char msgAIFF [] PROGMEM = "AIFF";
const char msgWAV [] PROGMEM = "WAV";
const char msgMP3 [] PROGMEM = "MP3";
const char msgAVI [] PROGMEM = "AVI";
const char msgMPEG [] PROGMEM = "MPEG";
const char msgASF [] PROGMEM = "ASF";
const char msgQT [] PROGMEM = "QT";
 
// Image formats
const char msgEXIF_JPEG [] PROGMEM = "EXIF_JPEG";
const char msgTIFF_EP [] PROGMEM = "TIFF_EP";
const char msgFlashPix [] PROGMEM = "FlashPix";
const char msgBMP [] PROGMEM = "BMP";
const char msgCIFF [] PROGMEM = "CIFF";
const char msgUndefined_0x3806 [] PROGMEM = "Undefined_0x3806";
const char msgGIF [] PROGMEM = "GIF";
const char msgJFIF [] PROGMEM = "JFIF";
const char msgPCD [] PROGMEM = "PCD";
const char msgPICT [] PROGMEM = "PICT";
const char msgPNG [] PROGMEM = "PNG";
const char msgUndefined_0x380C [] PROGMEM = "Undefined_0x380C";
const char msgTIFF [] PROGMEM = "TIFF";
const char msgTIFF_IT [] PROGMEM = "TIFF_IT";
const char msgJP2 [] PROGMEM = "JP2";
const char msgJPX [] PROGMEM = "JPX";
 
// MTP Object Formats
const char msgUndefined_Firmware [] PROGMEM = "Undefined_Firmware";
const char msgWindows_Image_Format [] PROGMEM = "Windows_Image_Format";
const char msgUndefined_Audio [] PROGMEM = "Undefined_Audio";
const char msgWMA [] PROGMEM = "WMA";
const char msgOGG [] PROGMEM = "OGG";
const char msgAAC [] PROGMEM = "AAC";
const char msgAudible [] PROGMEM = "Audible";
const char msgFLAC [] PROGMEM = "FLAC";
const char msgUndefined_Video [] PROGMEM = "Undefined_Video";
const char msgWMV [] PROGMEM = "WMV";
const char msgMP4_Container [] PROGMEM = "MP4_Container";
const char msgMP2 [] PROGMEM = "MP2";
const char msg3GP_Container [] PROGMEM = "3GP_Container";
 
 
class PTPObjInfoParser : public PTPReadParser
{
static const char* acNames[];
static const char* imNames[];
 
MultiValueBuffer theBuffer;
uint32_t varBuffer;
uint8_t nStage;
 
MultiByteValueParser valueParser;
PTPListParser arrayParser;
 
static void PrintChar(MultiValueBuffer *p)
{
if (((unsigned char*)p->pValue)[0])
Serial.print(((unsigned char*)p->pValue)[0]);
};
void PrintFormat(uint16_t op);
 
public:
PTPObjInfoParser() : nStage(0) { theBuffer.pValue = (uint8_t*)&varBuffer; };
virtual void Parse(const uint16_t len, const uint8_t *pbuf, const uint32_t &offset);
};
 
#endif // __PTPOBJINFOPARSER_H__
/C-OSD/arducam-osd/Tools/MAX7456Charwizard.jar
Cannot display: file marked as a binary type.
svn:mime-type = application/octet-stream
Property changes:
Added: svn:mime-type
+application/octet-stream
\ No newline at end of property
/C-OSD/arducam-osd/Tools/MAX_Char_Write/Max_Char_Write.pde
0,0 → 1,345
// Code to copy a MCM font file to the Arduino + Max7456 OSD
//
// MAX7456_font Sketch
// at 9600 baud it take about 3min to download a mcm file
// http://www.maxim-ic.com/tools/evkit/index.cfm?EVKit=558
// max7456 evaluation kit software
 
#define DATAOUT 11//11-MOSI
#define DATAIN 12//12-MISO
#define SPICLOCK 13//13-sck
#define MAX7456SELECT 6 //6
#define USBSELECT 10//10-ss
#define VSYNC 2// INT0
 
//MAX7456 opcodes
#define VM0_reg 0x00
#define VM1_reg 0x01
#define DMM_reg 0x04
#define DMAH_reg 0x05
#define DMAL_reg 0x06
#define DMDI_reg 0x07
#define CMM_reg 0x08
#define CMAH_reg 0x09
#define CMAL_reg 0x0A
#define CMDI_reg 0x0B
#define STAT_reg 0xA0
 
//MAX7456 commands
#define CLEAR_display 0x04
#define CLEAR_display_vert 0x06
#define END_string 0xff
#define WRITE_nvr 0xa0
// with NTSC
#define ENABLE_display 0x08
#define ENABLE_display_vert 0x0c
#define MAX7456_reset 0x02
#define DISABLE_display 0x00
 
// with PAL
// all VM0_reg commands need bit 6 set
//#define ENABLE_display 0x48
//#define ENABLE_display_vert 0x4c
//#define MAX7456_reset 0x42
//#define DISABLE_display 0x40
 
#define WHITE_level_80 0x03
#define WHITE_level_90 0x02
#define WHITE_level_100 0x01
#define WHITE_level_120 0x00
 
#define MAX_font_rom 0xff
#define STATUS_reg_nvr_busy 0x20
#define NVM_ram_size 0x36
 
// with NTSC
#define MAX_screen_rows 0x0d //13
 
// with PAL
//#define MAX_screen_rows 0x10 //16
 
volatile byte screen_buffer[MAX_font_rom];
volatile byte character_bitmap[0x40];
volatile byte ascii_binary[0x08];
 
volatile byte bit_count;
volatile byte byte_count;
volatile int font_count;
volatile int incomingByte;
volatile int count;
 
 
//////////////////////////////////////////////////////////////
void setup()
{
byte spi_junk;
int x;
Serial.begin(38400);
Serial.flush();
 
digitalWrite(USBSELECT,HIGH); //disable USB chip
 
pinMode(MAX7456SELECT,OUTPUT);
digitalWrite(MAX7456SELECT,HIGH); //disable device
 
pinMode(DATAOUT, OUTPUT);
pinMode(DATAIN, INPUT);
pinMode(SPICLOCK,OUTPUT);
pinMode(VSYNC, INPUT);
 
// SPCR = 01010000
//interrupt disabled,spi enabled,msb 1st,master,clk low when idle,
//sample on leading edge of clk,system clock/4 rate (4 meg)
SPCR = (1<<SPE)|(1<<MSTR);
spi_junk=SPSR;
spi_junk=SPDR;
delay(250);
 
// force soft reset on Max7456
digitalWrite(MAX7456SELECT,LOW);
spi_transfer(VM0_reg);
spi_transfer(MAX7456_reset);
digitalWrite(MAX7456SELECT,HIGH);
delay(500);
 
// set all rows to same character white level, 90%
digitalWrite(MAX7456SELECT,LOW);
for (x = 0; x < MAX_screen_rows; x++)
{
spi_transfer(x + 0x10);
spi_transfer(WHITE_level_90);
}
 
// make sure the Max7456 is enabled
spi_transfer(VM0_reg);
spi_transfer(ENABLE_display);
digitalWrite(MAX7456SELECT,HIGH);
 
incomingByte = 0;
count = 0;
bit_count = 0;
byte_count = 0;
font_count = 0;
 
//display all 256 internal MAX7456 characters
for (x = 0; x < MAX_font_rom; x++)
{
screen_buffer[x] = x;
}
count = MAX_font_rom;
write_new_screen();
 
Serial.println("Ready for text file download");
Serial.println("");
delay(100);
}
 
//////////////////////////////////////////////////////////////
void loop()
{
byte x;
if (Serial.available() > 0)
{
// read the incoming byte:
incomingByte = Serial.read();
 
switch(incomingByte) // parse and decode mcm file
{
case 0x0d: // carridge return, end of line
//Serial.println("cr");
if (bit_count == 8 && (ascii_binary[0] == 0x30 || ascii_binary[0] == 0x31))
{
// turn 8 ascii binary bytes to single byte '01010101' = 0x55
// fill in 64 bytes of character data
character_bitmap[byte_count] = decode_ascii_binary();
byte_count++;
bit_count = 0;
}
else
bit_count = 0;
break;
case 0x0a: // line feed, ignore
//Serial.println("ln");
break;
case 0x30: // ascii '0'
case 0x31: // ascii '1'
ascii_binary[bit_count] = incomingByte;
bit_count++;
break;
default:
break;
}
}
// we have one completed character
// write the character to NVM
if(byte_count == 64)
{
write_NVM();
byte_count = 0;
font_count++;
}
 
// we have burned all 256 characters in NVM
if(font_count == 256)
{
font_count = 0;
 
// force soft reset on Max7456
digitalWrite(MAX7456SELECT,LOW);
spi_transfer(VM0_reg);
spi_transfer(MAX7456_reset);
digitalWrite(MAX7456SELECT,HIGH);
delay(500);
 
// display all 256 new internal MAX7456 characters
for (x = 0; x < MAX_font_rom; x++)
{
screen_buffer[x] = x;
}
count = MAX_font_rom;
write_new_screen();
Serial.println("");
Serial.println("Done with file download");
}
}
 
//////////////////////////////////////////////////////////////
byte spi_transfer(volatile byte data)
{
SPDR = data; // Start the transmission
while (!(SPSR & (1<<SPIF))) // Wait the end of the transmission
{
};
return SPDR; // return the received byte
}
 
//////////////////////////////////////////////////////////////
void write_new_screen()
{
int x, local_count;
byte char_address_hi, char_address_lo;
byte screen_char;
local_count = count;
char_address_hi = 0;
char_address_lo = 60; // start on third line
//Serial.println("write_new_screen");
 
// clear the screen
digitalWrite(MAX7456SELECT,LOW);
spi_transfer(DMM_reg);
spi_transfer(CLEAR_display);
digitalWrite(MAX7456SELECT,HIGH);
 
// disable display
digitalWrite(MAX7456SELECT,LOW);
spi_transfer(VM0_reg);
spi_transfer(DISABLE_display);
 
spi_transfer(DMM_reg); //dmm
//spi_transfer(0x21); //16 bit trans background
spi_transfer(0x01); //16 bit trans w/o background
 
spi_transfer(DMAH_reg); // set start address high
spi_transfer(char_address_hi);
 
spi_transfer(DMAL_reg); // set start address low
spi_transfer(char_address_lo);
 
x = 0;
while(local_count) // write out full screen
{
screen_char = screen_buffer[x];
spi_transfer(DMDI_reg);
spi_transfer(screen_char);
x++;
local_count--;
}
 
spi_transfer(DMDI_reg);
spi_transfer(END_string);
 
spi_transfer(VM0_reg); // turn on screen next vertical
spi_transfer(ENABLE_display_vert);
digitalWrite(MAX7456SELECT,HIGH);
}
 
//////////////////////////////////////////////////////////////
byte decode_ascii_binary()
{
byte ascii_byte;
 
ascii_byte = 0;
if (ascii_binary[0] == 0x31) // ascii '1'
ascii_byte = ascii_byte + 128;
 
if (ascii_binary[1] == 0x31)
ascii_byte = ascii_byte + 64;
 
if (ascii_binary[2] == 0x31)
ascii_byte = ascii_byte + 32;
 
if (ascii_binary[3] == 0x31)
ascii_byte = ascii_byte + 16;
 
if (ascii_binary[4] == 0x31)
ascii_byte = ascii_byte + 8;
 
if (ascii_binary[5] == 0x31)
ascii_byte = ascii_byte + 4;
 
if (ascii_binary[6] == 0x31)
ascii_byte = ascii_byte + 2;
 
if (ascii_binary[7] == 0x31)
ascii_byte = ascii_byte + 1;
 
//Serial.print(ascii_byte, HEX);
 
return(ascii_byte);
}
 
//////////////////////////////////////////////////////////////
void write_NVM()
{
byte x;
byte char_address_hi, char_address_lo;
byte screen_char;
 
char_address_hi = font_count;
char_address_lo = 0;
//Serial.println("write_new_screen");
 
// disable display
digitalWrite(MAX7456SELECT,LOW);
spi_transfer(VM0_reg);
spi_transfer(DISABLE_display);
 
spi_transfer(CMAH_reg); // set start address high
spi_transfer(char_address_hi);
 
for(x = 0; x < NVM_ram_size; x++) // write out 54 (out of 64) bytes of character to shadow ram
{
screen_char = character_bitmap[x];
spi_transfer(CMAL_reg); // set start address low
spi_transfer(x);
spi_transfer(CMDI_reg);
spi_transfer(screen_char);
}
 
// transfer a 54 bytes from shadow ram to NVM
spi_transfer(CMM_reg);
spi_transfer(WRITE_nvr);
// wait until bit 5 in the status register returns to 0 (12ms)
while ((spi_transfer(STAT_reg) & STATUS_reg_nvr_busy) != 0x00);
 
spi_transfer(VM0_reg); // turn on screen next vertical
spi_transfer(ENABLE_display_vert);
digitalWrite(MAX7456SELECT,HIGH);
}
/C-OSD/arducam-osd/Tools/OSD/ArduinoSTK.cs
0,0 → 1,334
using System;
using System.Collections.Generic;
using System.Text;
using System.IO.Ports;
using System.Threading;
 
// Written by Michael Oborne
 
namespace ArdupilotMega
{
class ArduinoSTK : SerialPort
{
public delegate void ProgressEventHandler(int progress);
 
public event ProgressEventHandler Progress;
 
public new void Open()
{
// default dtr status is false
 
//from http://svn.savannah.nongnu.org/viewvc/RELEASE_5_11_0/arduino.c?root=avrdude&view=markup
base.Open();
 
base.DtrEnable = false;
base.RtsEnable = false;
 
System.Threading.Thread.Sleep(50);
 
base.DtrEnable = true;
base.RtsEnable = true;
 
System.Threading.Thread.Sleep(50);
}
 
/// <summary>
/// Used to start initial connecting after serialport.open
/// </summary>
/// <returns>true = passed, false = failed</returns>
public bool connectAP()
{
if (!this.IsOpen)
{
return false;
}
int a = 0;
while (a < 50)
{
this.DiscardInBuffer();
this.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
a++;
Thread.Sleep(50);
 
Console.WriteLine("btr {0}", this.BytesToRead);
if (this.BytesToRead >= 2)
{
byte b1 = (byte)this.ReadByte();
byte b2 = (byte)this.ReadByte();
if (b1 == 0x14 && b2 == 0x10)
{
return true;
}
}
}
 
return false;
}
 
/// <summary>
/// Used to keep alive the connection
/// </summary>
/// <returns>true = passed, false = lost connection</returns>
public bool keepalive()
{
return connectAP();
}
/// <summary>
/// Syncs after a private command has been sent
/// </summary>
/// <returns>true = passed, false = failed</returns>
public bool sync()
{
if (!this.IsOpen)
{
return false;
}
this.ReadTimeout = 1000;
int f = 0;
while (this.BytesToRead < 1)
{
f++;
System.Threading.Thread.Sleep(1);
if (f > 1000)
return false;
}
int a = 0;
while (a < 10)
{
if (this.BytesToRead >= 2)
{
byte b1 = (byte)this.ReadByte();
byte b2 = (byte)this.ReadByte();
Console.WriteLine("bytes {0:X} {1:X}", b1, b2);
 
if (b1 == 0x14 && b2 == 0x10)
{
return true;
}
}
Console.WriteLine("btr {0}", this.BytesToRead);
Thread.Sleep(10);
a++;
}
return false;
}
/// <summary>
/// Downloads the eeprom with the given length - set Address first
/// </summary>
/// <param name="length">eeprom length</param>
/// <returns>downloaded data</returns>
public byte[] download(short length)
{
if (!this.IsOpen)
{
throw new Exception();
}
byte[] data = new byte[length];
 
byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'E', (byte)' ' };
this.Write(command, 0, command.Length);
 
if (this.ReadByte() == 0x14)
{ // 0x14
 
int step = 0;
while (step < length)
{
byte chr = (byte)this.ReadByte();
data[step] = chr;
step++;
}
 
if (this.ReadByte() != 0x10) // 0x10
throw new Exception("Lost Sync 0x10");
}
else
{
throw new Exception("Lost Sync 0x14");
}
return data;
}
 
public byte[] downloadflash(short length)
{
if (!this.IsOpen)
{
throw new Exception("Port Not Open");
}
byte[] data = new byte[length];
 
this.ReadTimeout = 1000;
 
byte[] command = new byte[] { (byte)'t', (byte)(length >> 8), (byte)(length & 0xff), (byte)'F', (byte)' ' };
this.Write(command, 0, command.Length);
 
if (this.ReadByte() == 0x14)
{ // 0x14
 
int read = length;
while (read > 0)
{
//Console.WriteLine("offset {0} read {1}", length - read, read);
read -= this.Read(data, length - read, read);
//System.Threading.Thread.Sleep(1);
}
 
if (this.ReadByte() != 0x10) // 0x10
throw new Exception("Lost Sync 0x10");
}
else
{
throw new Exception("Lost Sync 0x14");
}
return data;
}
 
public bool uploadflash(byte[] data, int startfrom, int length, int startaddress)
{
if (!this.IsOpen)
{
return false;
}
int loops = (length / 0x100);
int totalleft = length;
int sending = 0;
 
for (int a = 0; a <= loops; a++)
{
if (totalleft > 0x100)
{
sending = 0x100;
}
else
{
sending = totalleft;
}
 
//startaddress = 256;
if (sending == 0)
return true;
 
setaddress(startaddress);
startaddress += sending;
 
byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'F' };
this.Write(command, 0, command.Length);
Console.WriteLine((startfrom + (length - totalleft)) + " - " + sending);
this.Write(data, startfrom + (length - totalleft), sending);
command = new byte[] { (byte)' ' };
this.Write(command, 0, command.Length);
 
totalleft -= sending;
 
 
if (Progress != null)
Progress((int)(((float)startaddress / (float)length) * 100));
 
if (!sync())
{
Console.WriteLine("No Sync");
return false;
}
}
return true;
}
 
/// <summary>
/// Sets the eeprom start read or write address
/// </summary>
/// <param name="address">address, must be eaven number</param>
/// <returns>true = passed, false = failed</returns>
public bool setaddress(int address)
{
if (!this.IsOpen)
{
return false;
}
 
if (address % 2 == 1)
{
throw new Exception("Address must be an even number");
}
 
Console.WriteLine("Sending address " + ((ushort)(address / 2)));
 
address /= 2;
address = (ushort)address;
 
byte[] command = new byte[] { (byte)'U', (byte)(address & 0xff), (byte)(address >> 8), (byte)' ' };
this.Write(command, 0, command.Length);
 
return sync();
}
/// <summary>
/// Upload data at preset address
/// </summary>
/// <param name="data">array to read from</param>
/// <param name="startfrom">start array index</param>
/// <param name="length">length to send</param>
/// <param name="startaddress">sets eeprom start programing address</param>
/// <returns>true = passed, false = failed</returns>
public bool upload(byte[] data, short startfrom, short length, short startaddress)
{
if (!this.IsOpen)
{
return false;
}
int loops = (length / 0x100);
int totalleft = length;
int sending = 0;
 
for (int a = 0; a <= loops; a++)
{
if (totalleft > 0x100)
{
sending = 0x100;
}
else
{
sending = totalleft;
}
 
if (sending == 0)
return true;
 
setaddress(startaddress);
startaddress += (short)sending;
 
byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'E' };
this.Write(command, 0, command.Length);
Console.WriteLine((startfrom + (length - totalleft)) + " - " + sending);
this.Write(data, startfrom + (length - totalleft), sending);
command = new byte[] { (byte)' ' };
this.Write(command, 0, command.Length);
 
totalleft -= sending;
 
if (!sync())
{
Console.WriteLine("No Sync");
return false;
}
}
return true;
}
 
public new bool Close()
{
try
{
 
byte[] command = new byte[] { (byte)'Q', (byte)' ' };
this.Write(command, 0, command.Length);
}
catch { }
 
if (base.IsOpen)
base.Close();
 
this.DtrEnable = false;
this.RtsEnable = false;
return true;
}
}
}
/C-OSD/arducam-osd/Tools/OSD/MavlinkOther.cs
0,0 → 1,167
using System;
using System.Collections.Generic;
using System.Linq;
using System.Text;
 
namespace ArdupilotMega
{
public partial class MAVLink
{
 
#if !MAVLINK10
enum MAV_CLASS
{
MAV_CLASS_GENERIC = 0, /// Generic autopilot, full support for everything
MAV_CLASS_PIXHAWK = 1, /// PIXHAWK autopilot, http://pixhawk.ethz.ch
MAV_CLASS_SLUGS = 2, /// SLUGS autopilot, http://slugsuav.soe.ucsc.edu
MAV_CLASS_ARDUPILOTMEGA = 3, /// ArduPilotMega / ArduCopter, http://diydrones.com
MAV_CLASS_OPENPILOT = 4, /// OpenPilot, http://openpilot.org
MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, /// Generic autopilot only supporting simple waypoints
MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, /// Generic autopilot supporting waypoints and other simple navigation commands
MAV_CLASS_GENERIC_MISSION_FULL = 7, /// Generic autopilot supporting the full mission command set
MAV_CLASS_NONE = 8, /// No valid autopilot
MAV_CLASS_NB /// Number of autopilot classes
};
 
public enum MAV_ACTION
{
MAV_ACTION_HOLD = 0,
MAV_ACTION_MOTORS_START = 1,
MAV_ACTION_LAUNCH = 2,
MAV_ACTION_RETURN = 3,
MAV_ACTION_EMCY_LAND = 4,
MAV_ACTION_EMCY_KILL = 5,
MAV_ACTION_CONFIRM_KILL = 6,
MAV_ACTION_CONTINUE = 7,
MAV_ACTION_MOTORS_STOP = 8,
MAV_ACTION_HALT = 9,
MAV_ACTION_SHUTDOWN = 10,
MAV_ACTION_REBOOT = 11,
MAV_ACTION_SET_MANUAL = 12,
MAV_ACTION_SET_AUTO = 13,
MAV_ACTION_STORAGE_READ = 14,
MAV_ACTION_STORAGE_WRITE = 15,
MAV_ACTION_CALIBRATE_RC = 16,
MAV_ACTION_CALIBRATE_GYRO = 17,
MAV_ACTION_CALIBRATE_MAG = 18,
MAV_ACTION_CALIBRATE_ACC = 19,
MAV_ACTION_CALIBRATE_PRESSURE = 20,
MAV_ACTION_REC_START = 21,
MAV_ACTION_REC_PAUSE = 22,
MAV_ACTION_REC_STOP = 23,
MAV_ACTION_TAKEOFF = 24,
MAV_ACTION_NAVIGATE = 25,
MAV_ACTION_LAND = 26,
MAV_ACTION_LOITER = 27,
MAV_ACTION_SET_ORIGIN = 28,
MAV_ACTION_RELAY_ON = 29,
MAV_ACTION_RELAY_OFF = 30,
MAV_ACTION_GET_IMAGE = 31,
MAV_ACTION_VIDEO_START = 32,
MAV_ACTION_VIDEO_STOP = 33,
MAV_ACTION_RESET_MAP = 34,
MAV_ACTION_RESET_PLAN = 35,
MAV_ACTION_DELAY_BEFORE_COMMAND = 36,
MAV_ACTION_ASCEND_AT_RATE = 37,
MAV_ACTION_CHANGE_MODE = 38,
MAV_ACTION_LOITER_MAX_TURNS = 39,
MAV_ACTION_LOITER_MAX_TIME = 40,
MAV_ACTION_START_HILSIM = 41,
MAV_ACTION_STOP_HILSIM = 42,
MAV_ACTION_NB /// Number of MAV actions
};
 
public enum MAV_MODE
{
MAV_MODE_UNINIT = 0, /// System is in undefined state
MAV_MODE_LOCKED = 1, /// Motors are blocked, system is safe
MAV_MODE_MANUAL = 2, /// System is allowed to be active, under manual (RC) control
MAV_MODE_GUIDED = 3, /// System is allowed to be active, under autonomous control, manual setpoint
MAV_MODE_AUTO = 4, /// System is allowed to be active, under autonomous control and navigation
MAV_MODE_TEST1 = 5, /// Generic test mode, for custom use
MAV_MODE_TEST2 = 6, /// Generic test mode, for custom use
MAV_MODE_TEST3 = 7, /// Generic test mode, for custom use
MAV_MODE_READY = 8, /// System is ready, motors are unblocked, but controllers are inactive
MAV_MODE_RC_TRAINING = 9 /// System is blocked, only RC valued are read and reported back
};
 
public enum MAV_STATE
{
MAV_STATE_UNINIT = 0,
MAV_STATE_BOOT,
MAV_STATE_CALIBRATING,
MAV_STATE_STANDBY,
MAV_STATE_ACTIVE,
MAV_STATE_CRITICAL,
MAV_STATE_EMERGENCY,
MAV_STATE_HILSIM,
MAV_STATE_POWEROFF
};
 
public enum MAV_NAV
{
MAV_NAV_GROUNDED = 0,
MAV_NAV_LIFTOFF,
MAV_NAV_HOLD,
MAV_NAV_WAYPOINT,
MAV_NAV_VECTOR,
MAV_NAV_RETURNING,
MAV_NAV_LANDING,
MAV_NAV_LOST,
MAV_NAV_LOITER,
MAV_NAV_FREE_DRIFT
};
 
public enum MAV_TYPE
{
MAV_GENERIC = 0,
MAV_FIXED_WING = 1,
MAV_QUADROTOR = 2,
MAV_COAXIAL = 3,
MAV_HELICOPTER = 4,
MAV_GROUND = 5,
OCU = 6,
MAV_AIRSHIP = 7,
MAV_FREE_BALLOON = 8,
MAV_ROCKET = 9,
UGV_GROUND_ROVER = 10,
UGV_SURFACE_SHIP = 11
};
 
public enum MAV_AUTOPILOT_TYPE
{
MAV_AUTOPILOT_GENERIC = 0,
MAV_AUTOPILOT_PIXHAWK = 1,
MAV_AUTOPILOT_SLUGS = 2,
MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
MAV_AUTOPILOT_NONE = 4
};
 
public enum MAV_COMPONENT
{
MAV_COMP_ID_GPS,
MAV_COMP_ID_WAYPOINTPLANNER,
MAV_COMP_ID_BLOBTRACKER,
MAV_COMP_ID_PATHPLANNER,
MAV_COMP_ID_AIRSLAM,
MAV_COMP_ID_MAPPER,
MAV_COMP_ID_CAMERA,
MAV_COMP_ID_IMU = 200,
MAV_COMP_ID_IMU_2 = 201,
MAV_COMP_ID_IMU_3 = 202,
MAV_COMP_ID_UDP_BRIDGE = 240,
MAV_COMP_ID_UART_BRIDGE = 241,
MAV_COMP_ID_SYSTEM_CONTROL = 250
};
 
public enum MAV_FRAME
{
GLOBAL = 0,
LOCAL = 1,
MISSION = 2,
GLOBAL_RELATIVE_ALT = 3,
LOCAL_ENU = 4
};
#endif
}
}
/C-OSD/arducam-osd/Tools/OSD/OSD.Designer.cs
0,0 → 1,434
namespace OSD
{
partial class OSD
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
 
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
 
#region Windows Form Designer generated code
 
/// <summary>
/// Required method for Designer support - do not modify
/// the contents of this method with the code editor.
/// </summary>
private void InitializeComponent()
{
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(OSD));
this.LIST_items = new System.Windows.Forms.CheckedListBox();
this.groupBox1 = new System.Windows.Forms.GroupBox();
this.label2 = new System.Windows.Forms.Label();
this.label1 = new System.Windows.Forms.Label();
this.NUM_Y = new System.Windows.Forms.NumericUpDown();
this.NUM_X = new System.Windows.Forms.NumericUpDown();
this.BUT_WriteOSD = new System.Windows.Forms.Button();
this.CMB_ComPort = new System.Windows.Forms.ComboBox();
this.BUT_ReadOSD = new System.Windows.Forms.Button();
this.statusStrip1 = new System.Windows.Forms.StatusStrip();
this.toolStripProgressBar1 = new System.Windows.Forms.ToolStripProgressBar();
this.toolStripStatusLabel1 = new System.Windows.Forms.ToolStripStatusLabel();
this.menuStrip1 = new System.Windows.Forms.MenuStrip();
this.fileToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.toolStripSeparator2 = new System.Windows.Forms.ToolStripSeparator();
this.loadDefaultsToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.toolStripSeparator1 = new System.Windows.Forms.ToolStripSeparator();
this.exitToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.videoModeToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.nTSCToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.CHK_pal = new System.Windows.Forms.ToolStripMenuItem();
this.optionsToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.checkBox1 = new System.Windows.Forms.ToolStripMenuItem();
this.updateFirmwareToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.customBGPictureToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.sendTLogToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.updateFontToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.helpToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.saveToFileToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.loadFromFileToolStripMenuItem = new System.Windows.Forms.ToolStripMenuItem();
this.pictureBox1 = new System.Windows.Forms.PictureBox();
this.groupBox1.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.NUM_Y)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.NUM_X)).BeginInit();
this.statusStrip1.SuspendLayout();
this.menuStrip1.SuspendLayout();
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).BeginInit();
this.SuspendLayout();
//
// LIST_items
//
this.LIST_items.FormattingEnabled = true;
this.LIST_items.Location = new System.Drawing.Point(13, 24);
this.LIST_items.Name = "LIST_items";
this.LIST_items.Size = new System.Drawing.Size(138, 289);
this.LIST_items.TabIndex = 1;
this.LIST_items.ItemCheck += new System.Windows.Forms.ItemCheckEventHandler(this.checkedListBox1_ItemCheck);
this.LIST_items.SelectedIndexChanged += new System.EventHandler(this.checkedListBox1_SelectedIndexChanged);
this.LIST_items.SelectedValueChanged += new System.EventHandler(this.checkedListBox1_SelectedValueChanged);
//
// groupBox1
//
this.groupBox1.Controls.Add(this.label2);
this.groupBox1.Controls.Add(this.label1);
this.groupBox1.Controls.Add(this.NUM_Y);
this.groupBox1.Controls.Add(this.NUM_X);
this.groupBox1.Location = new System.Drawing.Point(13, 315);
this.groupBox1.Name = "groupBox1";
this.groupBox1.Size = new System.Drawing.Size(138, 82);
this.groupBox1.TabIndex = 2;
this.groupBox1.TabStop = false;
//
// label2
//
this.label2.AutoSize = true;
this.label2.Location = new System.Drawing.Point(7, 48);
this.label2.Name = "label2";
this.label2.Size = new System.Drawing.Size(14, 13);
this.label2.TabIndex = 3;
this.label2.Text = "Y";
//
// label1
//
this.label1.AutoSize = true;
this.label1.Location = new System.Drawing.Point(7, 20);
this.label1.Name = "label1";
this.label1.Size = new System.Drawing.Size(14, 13);
this.label1.TabIndex = 2;
this.label1.Text = "X";
//
// NUM_Y
//
this.NUM_Y.Location = new System.Drawing.Point(30, 46);
this.NUM_Y.Maximum = new decimal(new int[] {
15,
0,
0,
0});
this.NUM_Y.Name = "NUM_Y";
this.NUM_Y.Size = new System.Drawing.Size(91, 20);
this.NUM_Y.TabIndex = 1;
this.NUM_Y.ValueChanged += new System.EventHandler(this.numericUpDown2_ValueChanged);
//
// NUM_X
//
this.NUM_X.Location = new System.Drawing.Point(30, 20);
this.NUM_X.Maximum = new decimal(new int[] {
29,
0,
0,
0});
this.NUM_X.Name = "NUM_X";
this.NUM_X.Size = new System.Drawing.Size(91, 20);
this.NUM_X.TabIndex = 0;
this.NUM_X.ValueChanged += new System.EventHandler(this.numericUpDown1_ValueChanged);
//
// BUT_WriteOSD
//
this.BUT_WriteOSD.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Right)));
this.BUT_WriteOSD.Location = new System.Drawing.Point(555, 376);
this.BUT_WriteOSD.Name = "BUT_WriteOSD";
this.BUT_WriteOSD.Size = new System.Drawing.Size(100, 23);
this.BUT_WriteOSD.TabIndex = 2;
this.BUT_WriteOSD.Text = "Save to OSD";
this.BUT_WriteOSD.UseVisualStyleBackColor = true;
this.BUT_WriteOSD.Click += new System.EventHandler(this.BUT_WriteOSD_Click);
//
// CMB_ComPort
//
this.CMB_ComPort.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Right)));
this.CMB_ComPort.FormattingEnabled = true;
this.CMB_ComPort.Location = new System.Drawing.Point(346, 376);
this.CMB_ComPort.Name = "CMB_ComPort";
this.CMB_ComPort.Size = new System.Drawing.Size(98, 21);
this.CMB_ComPort.TabIndex = 4;
this.CMB_ComPort.SelectedIndexChanged += new System.EventHandler(this.comboBox1_SelectedIndexChanged);
this.CMB_ComPort.Click += new System.EventHandler(this.comboBox1_Click);
//
// BUT_ReadOSD
//
this.BUT_ReadOSD.Anchor = ((System.Windows.Forms.AnchorStyles)((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Right)));
this.BUT_ReadOSD.Location = new System.Drawing.Point(449, 376);
this.BUT_ReadOSD.Name = "BUT_ReadOSD";
this.BUT_ReadOSD.Size = new System.Drawing.Size(100, 23);
this.BUT_ReadOSD.TabIndex = 6;
this.BUT_ReadOSD.Text = "Read From OSD";
this.BUT_ReadOSD.UseVisualStyleBackColor = true;
this.BUT_ReadOSD.Click += new System.EventHandler(this.BUT_ReadOSD_Click);
//
// statusStrip1
//
this.statusStrip1.Items.AddRange(new System.Windows.Forms.ToolStripItem[] {
this.toolStripProgressBar1,
this.toolStripStatusLabel1});
this.statusStrip1.Location = new System.Drawing.Point(0, 403);
this.statusStrip1.Name = "statusStrip1";
this.statusStrip1.Size = new System.Drawing.Size(667, 22);
this.statusStrip1.TabIndex = 8;
this.statusStrip1.Text = "statusStrip1";
//
// toolStripProgressBar1
//
this.toolStripProgressBar1.Name = "toolStripProgressBar1";
this.toolStripProgressBar1.Size = new System.Drawing.Size(500, 16);
//
// toolStripStatusLabel1
//
this.toolStripStatusLabel1.Name = "toolStripStatusLabel1";
this.toolStripStatusLabel1.Size = new System.Drawing.Size(0, 17);
//
// menuStrip1
//
this.menuStrip1.Items.AddRange(new System.Windows.Forms.ToolStripItem[] {
this.fileToolStripMenuItem,
this.videoModeToolStripMenuItem,
this.optionsToolStripMenuItem,
this.helpToolStripMenuItem});
this.menuStrip1.Location = new System.Drawing.Point(0, 0);
this.menuStrip1.Name = "menuStrip1";
this.menuStrip1.Size = new System.Drawing.Size(667, 24);
this.menuStrip1.TabIndex = 10;
this.menuStrip1.Text = "menuStrip1";
//
// fileToolStripMenuItem
//
this.fileToolStripMenuItem.DropDownItems.AddRange(new System.Windows.Forms.ToolStripItem[] {
this.saveToFileToolStripMenuItem,
this.loadFromFileToolStripMenuItem,
this.toolStripSeparator2,
this.loadDefaultsToolStripMenuItem,
this.toolStripSeparator1,
this.exitToolStripMenuItem});
this.fileToolStripMenuItem.Name = "fileToolStripMenuItem";
this.fileToolStripMenuItem.Size = new System.Drawing.Size(37, 20);
this.fileToolStripMenuItem.Text = "File";
//
// toolStripSeparator2
//
this.toolStripSeparator2.Name = "toolStripSeparator2";
this.toolStripSeparator2.Size = new System.Drawing.Size(199, 6);
//
// loadDefaultsToolStripMenuItem
//
this.loadDefaultsToolStripMenuItem.Name = "loadDefaultsToolStripMenuItem";
this.loadDefaultsToolStripMenuItem.Size = new System.Drawing.Size(202, 22);
this.loadDefaultsToolStripMenuItem.Text = "Load Defaults";
this.loadDefaultsToolStripMenuItem.Click += new System.EventHandler(this.loadDefaultsToolStripMenuItem_Click);
//
// toolStripSeparator1
//
this.toolStripSeparator1.Name = "toolStripSeparator1";
this.toolStripSeparator1.Size = new System.Drawing.Size(199, 6);
//
// exitToolStripMenuItem
//
this.exitToolStripMenuItem.Name = "exitToolStripMenuItem";
this.exitToolStripMenuItem.ShortcutKeys = ((System.Windows.Forms.Keys)((System.Windows.Forms.Keys.Alt | System.Windows.Forms.Keys.F4)));
this.exitToolStripMenuItem.Size = new System.Drawing.Size(202, 22);
this.exitToolStripMenuItem.Text = "Exit";
this.exitToolStripMenuItem.Click += new System.EventHandler(this.exitToolStripMenuItem_Click);
//
// videoModeToolStripMenuItem
//
this.videoModeToolStripMenuItem.DropDownItems.AddRange(new System.Windows.Forms.ToolStripItem[] {
this.nTSCToolStripMenuItem,
this.CHK_pal});
this.videoModeToolStripMenuItem.Name = "videoModeToolStripMenuItem";
this.videoModeToolStripMenuItem.Size = new System.Drawing.Size(83, 20);
this.videoModeToolStripMenuItem.Text = "Video Mode";
//
// nTSCToolStripMenuItem
//
this.nTSCToolStripMenuItem.CheckOnClick = true;
this.nTSCToolStripMenuItem.Name = "nTSCToolStripMenuItem";
this.nTSCToolStripMenuItem.Size = new System.Drawing.Size(104, 22);
this.nTSCToolStripMenuItem.Text = "NTSC";
this.nTSCToolStripMenuItem.CheckStateChanged += new System.EventHandler(this.nTSCToolStripMenuItem_CheckStateChanged);
//
// CHK_pal
//
this.CHK_pal.Checked = true;
this.CHK_pal.CheckOnClick = true;
this.CHK_pal.CheckState = System.Windows.Forms.CheckState.Checked;
this.CHK_pal.Name = "CHK_pal";
this.CHK_pal.Size = new System.Drawing.Size(104, 22);
this.CHK_pal.Text = "PAL";
this.CHK_pal.CheckedChanged += new System.EventHandler(this.CHK_pal_CheckedChanged);
this.CHK_pal.CheckStateChanged += new System.EventHandler(this.pALToolStripMenuItem_CheckStateChanged);
//
// optionsToolStripMenuItem
//
this.optionsToolStripMenuItem.DropDownItems.AddRange(new System.Windows.Forms.ToolStripItem[] {
this.checkBox1,
this.updateFirmwareToolStripMenuItem,
this.customBGPictureToolStripMenuItem,
this.sendTLogToolStripMenuItem,
this.updateFontToolStripMenuItem});
this.optionsToolStripMenuItem.Name = "optionsToolStripMenuItem";
this.optionsToolStripMenuItem.ShortcutKeys = ((System.Windows.Forms.Keys)((System.Windows.Forms.Keys.Control | System.Windows.Forms.Keys.G)));
this.optionsToolStripMenuItem.ShowShortcutKeys = false;
this.optionsToolStripMenuItem.Size = new System.Drawing.Size(61, 20);
this.optionsToolStripMenuItem.Text = "Options";
//
// checkBox1
//
this.checkBox1.Checked = true;
this.checkBox1.CheckOnClick = true;
this.checkBox1.CheckState = System.Windows.Forms.CheckState.Checked;
this.checkBox1.Name = "checkBox1";
this.checkBox1.Size = new System.Drawing.Size(183, 22);
this.checkBox1.Text = "Show Grid";
this.checkBox1.CheckedChanged += new System.EventHandler(this.checkBox1_CheckedChanged);
//
// updateFirmwareToolStripMenuItem
//
this.updateFirmwareToolStripMenuItem.Name = "updateFirmwareToolStripMenuItem";
this.updateFirmwareToolStripMenuItem.Size = new System.Drawing.Size(183, 22);
this.updateFirmwareToolStripMenuItem.Text = "Update Firmware...";
this.updateFirmwareToolStripMenuItem.ToolTipText = "Re-Flash the OSD with a new firmware image";
this.updateFirmwareToolStripMenuItem.Click += new System.EventHandler(this.updateFirmwareToolStripMenuItem_Click);
//
// customBGPictureToolStripMenuItem
//
this.customBGPictureToolStripMenuItem.Name = "customBGPictureToolStripMenuItem";
this.customBGPictureToolStripMenuItem.Size = new System.Drawing.Size(183, 22);
this.customBGPictureToolStripMenuItem.Text = "Background Image...";
this.customBGPictureToolStripMenuItem.Click += new System.EventHandler(this.customBGPictureToolStripMenuItem_Click);
//
// sendTLogToolStripMenuItem
//
this.sendTLogToolStripMenuItem.Name = "sendTLogToolStripMenuItem";
this.sendTLogToolStripMenuItem.Size = new System.Drawing.Size(183, 22);
this.sendTLogToolStripMenuItem.Text = "Send TLog...";
this.sendTLogToolStripMenuItem.ToolTipText = "Send a Mavlink transmission log to the OSD to test the layout";
this.sendTLogToolStripMenuItem.Click += new System.EventHandler(this.sendTLogToolStripMenuItem_Click);
//
// updateFontToolStripMenuItem
//
this.updateFontToolStripMenuItem.Name = "updateFontToolStripMenuItem";
this.updateFontToolStripMenuItem.Size = new System.Drawing.Size(183, 22);
this.updateFontToolStripMenuItem.Text = "Update CharSet...";
this.updateFontToolStripMenuItem.ToolTipText = "Update the font file on the OSD";
this.updateFontToolStripMenuItem.Click += new System.EventHandler(this.updateFontToolStripMenuItem_Click);
//
// helpToolStripMenuItem
//
this.helpToolStripMenuItem.Name = "helpToolStripMenuItem";
this.helpToolStripMenuItem.Size = new System.Drawing.Size(44, 20);
this.helpToolStripMenuItem.Text = "Help";
this.helpToolStripMenuItem.Click += new System.EventHandler(this.helpToolStripMenuItem_Click);
//
// saveToFileToolStripMenuItem
//
this.saveToFileToolStripMenuItem.Image = global::OSD.Properties.Resources.saveHS;
this.saveToFileToolStripMenuItem.Name = "saveToFileToolStripMenuItem";
this.saveToFileToolStripMenuItem.ShortcutKeys = ((System.Windows.Forms.Keys)((System.Windows.Forms.Keys.Control | System.Windows.Forms.Keys.S)));
this.saveToFileToolStripMenuItem.Size = new System.Drawing.Size(202, 22);
this.saveToFileToolStripMenuItem.Text = "Save OSD file...";
this.saveToFileToolStripMenuItem.Click += new System.EventHandler(this.saveToFileToolStripMenuItem_Click);
//
// loadFromFileToolStripMenuItem
//
this.loadFromFileToolStripMenuItem.Image = global::OSD.Properties.Resources.openHS;
this.loadFromFileToolStripMenuItem.Name = "loadFromFileToolStripMenuItem";
this.loadFromFileToolStripMenuItem.ShortcutKeys = ((System.Windows.Forms.Keys)((System.Windows.Forms.Keys.Control | System.Windows.Forms.Keys.O)));
this.loadFromFileToolStripMenuItem.Size = new System.Drawing.Size(202, 22);
this.loadFromFileToolStripMenuItem.Text = "Open OSD File...";
this.loadFromFileToolStripMenuItem.Click += new System.EventHandler(this.loadFromFileToolStripMenuItem_Click);
//
// pictureBox1
//
this.pictureBox1.Anchor = ((System.Windows.Forms.AnchorStyles)((((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom)
| System.Windows.Forms.AnchorStyles.Left)
| System.Windows.Forms.AnchorStyles.Right)));
this.pictureBox1.Location = new System.Drawing.Point(158, 27);
this.pictureBox1.Name = "pictureBox1";
this.pictureBox1.Size = new System.Drawing.Size(497, 343);
this.pictureBox1.TabIndex = 0;
this.pictureBox1.TabStop = false;
this.pictureBox1.MouseDown += new System.Windows.Forms.MouseEventHandler(this.pictureBox1_MouseDown);
this.pictureBox1.MouseMove += new System.Windows.Forms.MouseEventHandler(this.pictureBox1_MouseMove);
this.pictureBox1.MouseUp += new System.Windows.Forms.MouseEventHandler(this.pictureBox1_MouseUp);
//
// OSD
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.ClientSize = new System.Drawing.Size(667, 425);
this.Controls.Add(this.statusStrip1);
this.Controls.Add(this.menuStrip1);
this.Controls.Add(this.BUT_ReadOSD);
this.Controls.Add(this.CMB_ComPort);
this.Controls.Add(this.BUT_WriteOSD);
this.Controls.Add(this.groupBox1);
this.Controls.Add(this.LIST_items);
this.Controls.Add(this.pictureBox1);
this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
this.MainMenuStrip = this.menuStrip1;
this.Name = "OSD";
this.Text = "ArduCAM OSD Config - By Michael Oborne";
this.FormClosed += new System.Windows.Forms.FormClosedEventHandler(this.OSD_FormClosed);
this.Load += new System.EventHandler(this.OSD_Load);
this.Resize += new System.EventHandler(this.OSD_Resize);
this.groupBox1.ResumeLayout(false);
this.groupBox1.PerformLayout();
((System.ComponentModel.ISupportInitialize)(this.NUM_Y)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.NUM_X)).EndInit();
this.statusStrip1.ResumeLayout(false);
this.statusStrip1.PerformLayout();
this.menuStrip1.ResumeLayout(false);
this.menuStrip1.PerformLayout();
((System.ComponentModel.ISupportInitialize)(this.pictureBox1)).EndInit();
this.ResumeLayout(false);
this.PerformLayout();
 
}
 
#endregion
 
private System.Windows.Forms.PictureBox pictureBox1;
private System.Windows.Forms.CheckedListBox LIST_items;
private System.Windows.Forms.GroupBox groupBox1;
private System.Windows.Forms.NumericUpDown NUM_Y;
private System.Windows.Forms.NumericUpDown NUM_X;
private System.Windows.Forms.Button BUT_WriteOSD;
private System.Windows.Forms.ComboBox CMB_ComPort;
private System.Windows.Forms.Label label2;
private System.Windows.Forms.Label label1;
private System.Windows.Forms.Button BUT_ReadOSD;
private System.Windows.Forms.StatusStrip statusStrip1;
private System.Windows.Forms.ToolStripProgressBar toolStripProgressBar1;
private System.Windows.Forms.MenuStrip menuStrip1;
private System.Windows.Forms.ToolStripMenuItem videoModeToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem nTSCToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem CHK_pal;
private System.Windows.Forms.ToolStripMenuItem fileToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem saveToFileToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem loadFromFileToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem loadDefaultsToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem optionsToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem checkBox1;
private System.Windows.Forms.ToolStripMenuItem exitToolStripMenuItem;
private System.Windows.Forms.ToolStripSeparator toolStripSeparator2;
private System.Windows.Forms.ToolStripSeparator toolStripSeparator1;
private System.Windows.Forms.ToolStripMenuItem updateFirmwareToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem customBGPictureToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem sendTLogToolStripMenuItem;
private System.Windows.Forms.ToolStripStatusLabel toolStripStatusLabel1;
private System.Windows.Forms.ToolStripMenuItem updateFontToolStripMenuItem;
private System.Windows.Forms.ToolStripMenuItem helpToolStripMenuItem;
}
}
 
/C-OSD/arducam-osd/Tools/OSD/OSD.cs
0,0 → 1,1381
using System;
using System.Collections.Generic;
using System.ComponentModel;
using System.Data;
using System.Drawing;
using System.Linq;
using System.Text;
using System.Windows.Forms;
using System.Runtime.InteropServices;
using System.IO.Ports;
using System.IO;
using ArdupilotMega;
using System.Xml;
 
namespace OSD
{
public partial class OSD : Form
{
//max 7456 datasheet pg 10
//pal = 16r 30 char
//ntsc = 13r 30 char
Size basesize = new Size(30, 16);
/// <summary>
/// the un-scaled font render image
/// </summary>
Bitmap screen = new Bitmap(30 * 12, 16 * 18);
/// <summary>
/// the scaled to size background control
/// </summary>
Bitmap image = new Bitmap(30 * 12, 16 * 18);
/// <summary>
/// Bitmaps of all the chars created from the mcm
/// </summary>
Bitmap[] chars;
/// <summary>
/// record of what panel is using what squares
/// </summary>
string[][] usedPostion = new string[30][];
/// <summary>
/// used to track currently selected panel across calls
/// </summary>
string currentlyselected = "";
/// <summary>
/// used to track current processing panel across calls (because i maintained the original code for panel drawing)
/// </summary>
string processingpanel = "";
/// <summary>
/// use to draw the red outline box is currentlyselected matchs
/// </summary>
bool selectedrectangle = false;
/// <summary>
/// use to as a invalidator
/// </summary>
bool startup = false;
/// <summary>
/// 328 eeprom memory
/// </summary>
byte[] eeprom = new byte[1024];
/// <summary>
/// background image
/// </summary>
Image bgpicture;
 
bool mousedown = false;
 
SerialPort comPort = new SerialPort();
 
Panels pan;
 
Tuple<string, Func<int, int, int>, int, int, int, int, int>[] panelItems = new Tuple<string, Func<int, int, int>, int, int, int, int, int>[30];
 
Graphics gr;
 
// in pixels
int x = 0, y = 0;
 
public OSD()
{
InitializeComponent();
 
// load default font
chars = mcm.readMCM("OSD_SA_v5.mcm");
// load default bg picture
try
{
bgpicture = Image.FromFile("vlcsnap-2012-01-28-07h46m04s95.png");
}
catch { }
 
gr = Graphics.FromImage(screen);
 
pan = new Panels(this);
 
// setup all panel options
setupFunctions();
}
 
void changeToPal(bool pal)
{
if (pal)
{
basesize = new Size(30, 16);
 
screen = new Bitmap(30 * 12, 16 * 18);
image = new Bitmap(30 * 12, 16 * 18);
 
NUM_X.Maximum = 29;
NUM_Y.Maximum = 15;
}
else
{
basesize = new Size(30, 13);
 
screen = new Bitmap(30 * 12, 13 * 18);
image = new Bitmap(30 * 12, 13 * 18);
 
NUM_X.Maximum = 29;
NUM_Y.Maximum = 15;
}
 
}
 
void setupFunctions()
{
currentlyselected = "";
processingpanel = "";
 
int a = 0;
 
for (a = 0; a < usedPostion.Length; a++)
{
usedPostion[a] = new string[16];
}
 
a = 0;
 
// first 8
// Display name,printfunction,X,Y,ENaddress,Xaddress,Yaddress
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Center", pan.panCenter, 13, 8, panCenter_en_ADDR, panCenter_x_ADDR, panCenter_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Pitch", pan.panPitch, 22, 9, panPitch_en_ADDR, panPitch_x_ADDR, panPitch_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Roll", pan.panRoll, 11, 1, panRoll_en_ADDR, panRoll_x_ADDR, panRoll_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Battery A", pan.panBatt_A, 21, 1, panBatt_A_en_ADDR, panBatt_A_x_ADDR, panBatt_A_y_ADDR);
//items[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Battery B", pan.panBatt_B, 21, 3, panBatt_B_en_ADDR, panBatt_B_x_ADDR, panBatt_B_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Visible Sats", pan.panGPSats, 2, 13, panGPSats_en_ADDR, panGPSats_x_ADDR, panGPSats_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("GPS Lock", pan.panGPL, 5, 13, panGPL_en_ADDR, panGPL_x_ADDR, panGPL_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("GPS Coord", pan.panGPS, 2, 14, panGPS_en_ADDR, panGPS_x_ADDR, panGPS_y_ADDR);
 
//second 8
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Heading Rose", pan.panRose, 16, 14, panRose_en_ADDR, panRose_x_ADDR, panRose_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Heading", pan.panHeading, 24, 13, panHeading_en_ADDR, panHeading_x_ADDR, panHeading_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Heart Beat", pan.panMavBeat, 2, 9, panMavBeat_en_ADDR, panMavBeat_x_ADDR, panMavBeat_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Home Direction", pan.panHomeDir, 14, 3, panHomeDir_en_ADDR, panHomeDir_x_ADDR, panHomeDir_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Home Distance", pan.panHomeDis, 2, 1, panHomeDis_en_ADDR, panHomeDis_x_ADDR, panHomeDis_y_ADDR);
//items[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("WP Dir", pan.panWPDir, 14, 4, panWPDir_en_ADDR, panWPDir_x_ADDR, panWPDir_y_ADDR);
//items[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("WP Dir", pan.panWPDis, 14, 4, panWPDis_en_ADDR, panWPDis_x_ADDR, panWPDis_y_ADDR);
// rssi
 
// third 8
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Altitude", pan.panAlt, 2, 2, panAlt_en_ADDR, panAlt_x_ADDR, panAlt_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Velocity", pan.panVel, 2, 3, panVel_en_ADDR, panVel_x_ADDR, panVel_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Throttle", pan.panThr, 2, 4, panThr_en_ADDR, panThr_x_ADDR, panThr_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Flight Mode", pan.panFlightMode, 17, 13, panFMod_en_ADDR, panFMod_x_ADDR, panFMod_y_ADDR);
panelItems[a++] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>("Horizon", pan.panHorizon, 8, 7, panHorizon_en_ADDR, panHorizon_x_ADDR, panHorizon_y_ADDR);
 
LIST_items.Items.Clear();
 
startup = true;
 
foreach (var thing in panelItems)
{
if (thing != null)
{
if (thing.Item1 == "Center")
{
LIST_items.Items.Add(thing.Item1, false);
}
else
{
LIST_items.Items.Add(thing.Item1, true);
}
}
}
 
startup = false;
 
osdDraw();
}
 
private string[] GetPortNames()
{
string[] devs = new string[0];
 
if (Directory.Exists("/dev/"))
devs = Directory.GetFiles("/dev/", "*ACM*");
 
string[] ports = SerialPort.GetPortNames();
 
string[] all = new string[devs.Length + ports.Length];
 
devs.CopyTo(all, 0);
ports.CopyTo(all, devs.Length);
 
return all;
}
 
public void setPanel(int x, int y)
{
this.x = x * 12;
this.y = y * 18;
}
 
public void openPanel()
{
d = 0;
r = 0;
}
 
public void openSingle(int x, int y)
{
setPanel(x, y);
openPanel();
}
 
public int getCenter()
{
if (CHK_pal.Checked)
return 8;
return 6;
}
 
// used for printf tracking line and row
int d = 0, r = 0;
 
public void printf(string format, params object[] args)
{
StringBuilder sb = new StringBuilder();
 
sb = new StringBuilder(AT.MIN.Tools.sprintf(format, args));
 
//sprintf(sb, format, __arglist(args));
 
//Console.WriteLine(sb.ToString());
 
foreach (char ch in sb.ToString().ToCharArray())
{
if (ch == '|')
{
d += 1;
r = 0;
continue;
}
 
try
{
// draw red boxs
if (selectedrectangle)
{
gr.DrawRectangle(Pens.Red, (this.x + r * 12) % screen.Width, (this.y + d * 18), 12, 18);
}
 
int w1 = (this.x / 12 + r) % basesize.Width;
int h1 = (this.y / 18 + d);
 
if (w1 < basesize.Width && h1 < basesize.Height)
{
// check if this box has bene used
if (usedPostion[w1][h1] != null)
{
//System.Diagnostics.Debug.WriteLine("'" + used[this.x / 12 + r * 12 / 12][this.y / 18 + d * 18 / 18] + "'");
}
else
{
gr.DrawImage(chars[ch], (this.x + r * 12) % screen.Width, (this.y + d * 18), 12, 18);
}
 
usedPostion[w1][h1] = processingpanel;
}
}
catch { System.Diagnostics.Debug.WriteLine("printf exception"); }
r++;
}
}
 
string getMouseOverItem(int x, int y)
{
int ansW,ansH;
 
getCharLoc(x, y, out ansW, out ansH);
 
if (usedPostion[ansW][ansH] != null && usedPostion[ansW][ansH] != "")
{
LIST_items.SelectedIndex = LIST_items.Items.IndexOf(usedPostion[ansW][ansH]);
return usedPostion[ansW][ansH];
}
 
return "";
}
 
void getCharLoc(int x, int y,out int xpos, out int ypos)
{
 
x = Constrain(x, 0, pictureBox1.Width - 1);
y = Constrain(y, 0, pictureBox1.Height - 1);
 
float scaleW = pictureBox1.Width / (float)screen.Width;
float scaleH = pictureBox1.Height / (float)screen.Height;
 
int ansW = (int)((x / scaleW / 12) % 30);
int ansH = 0;
if (CHK_pal.Checked)
{
ansH = (int)((y / scaleH / 18) % 16);
}
else
{
ansH = (int)((y / scaleH / 18) % 13);
}
 
xpos = Constrain(ansW,0,30 -1);
ypos = Constrain(ansH,0,16 - 1);
}
 
public void printf_P(string format, params object[] args)
{
printf(format, args);
}
 
public void closePanel()
{
x = 0;
y = 0;
}
 
void osdDraw()
{
if (startup)
return;
 
for (int b = 0; b < usedPostion.Length; b++)
{
usedPostion[b] = new string[16];
}
 
image = new Bitmap(pictureBox1.Width, pictureBox1.Height);
 
float scaleW = pictureBox1.Width / (float)screen.Width;
float scaleH = pictureBox1.Height / (float)screen.Height;
 
screen = new Bitmap(screen.Width, screen.Height);
 
gr = Graphics.FromImage(screen);
 
image = new Bitmap(image.Width, image.Height);
 
Graphics grfull = Graphics.FromImage(image);
 
try
{
grfull.DrawImage(bgpicture, 0, 0, pictureBox1.Width, pictureBox1.Height);
}
catch { }
 
if (checkBox1.Checked)
{
for (int b = 1; b < 16; b++)
{
for (int a = 1; a < 30; a++)
{
grfull.DrawLine(new Pen(Color.Gray, 1), a * 12 * scaleW, 0, a * 12 * scaleW, pictureBox1.Height);
grfull.DrawLine(new Pen(Color.Gray, 1), 0, b * 18 * scaleH, pictureBox1.Width, b * 18 * scaleH);
}
}
}
 
pan.setHeadingPatern();
pan.setBatteryPic();
 
List<string> list = new List<string>();
 
foreach (string it in LIST_items.CheckedItems)
{
list.Add(it);
}
 
list.Reverse();
 
foreach (string it in list)
{
foreach (var thing in panelItems)
{
selectedrectangle = false;
if (thing != null)
{
if (thing.Item1 == it)
{
if (thing.Item1 == currentlyselected)
{
selectedrectangle = true;
}
 
processingpanel = thing.Item1;
 
// ntsc and below the middle line
if (thing.Item4 >= getCenter() && !CHK_pal.Checked)
{
thing.Item2(thing.Item3, thing.Item4 - 3);
}
else // pal and no change
{
thing.Item2(thing.Item3, thing.Item4);
}
 
}
}
}
}
 
grfull.DrawImage(screen, 0, 0, image.Width, image.Height);
 
pictureBox1.Image = image;
}
 
int Constrain(double value, double min, double max)
{
if (value < min)
return (int)min;
if (value > max)
return (int)max;
 
return (int)value;
}
 
private void OSD_Load(object sender, EventArgs e)
{
 
string strVersion = System.Reflection.Assembly.GetExecutingAssembly().GetName().Version.ToString();
this.Text = this.Text + " " + strVersion;
 
CMB_ComPort.Items.AddRange(GetPortNames());
 
if (CMB_ComPort.Items.Count > 0)
CMB_ComPort.SelectedIndex = 0;
 
xmlconfig(false);
 
osdDraw();
}
 
private void checkedListBox1_SelectedIndexChanged(object sender, EventArgs e)
{
string item = ((CheckedListBox)sender).SelectedItem.ToString();
 
currentlyselected = item;
 
osdDraw();
 
foreach (var thing in panelItems)
{
if (thing != null && thing.Item1 == item)
{
NUM_X.Value = Constrain(thing.Item3,0,basesize.Width -1);
NUM_Y.Value = Constrain(thing.Item4,0,16 -1);
}
}
}
 
private void checkedListBox1_SelectedValueChanged(object sender, EventArgs e)
{
if (((CheckedListBox)sender).Text == "Horizon")
{
//groupBox1.Enabled = false;
}
else
{
//groupBox1.Enabled = true;
}
}
 
private void checkedListBox1_ItemCheck(object sender, ItemCheckEventArgs e)
{
// if (((CheckedListBox)sender).SelectedItem != null && ((CheckedListBox)sender).SelectedItem.ToString() == "Horizon")
if (((CheckedListBox)sender).SelectedItem != null)
{
if (((CheckedListBox)sender).SelectedItem.ToString() == "Horizon" && e.NewValue == CheckState.Checked)
{
int index = LIST_items.Items.IndexOf("Center");
LIST_items.SetItemChecked(index, false);
}
else if (((CheckedListBox)sender).SelectedItem.ToString() == "Center" && e.NewValue == CheckState.Checked)
{
int index = LIST_items.Items.IndexOf("Horizon");
LIST_items.SetItemChecked(index, false);
}
}
 
// add a delay to this so it runs after the control value has been defined.
if (this.IsHandleCreated)
this.BeginInvoke((MethodInvoker)delegate { osdDraw(); });
}
 
private void numericUpDown1_ValueChanged(object sender, EventArgs e)
{
string item;
try
{
item = LIST_items.SelectedItem.ToString();
}
catch { return; }
 
for (int a = 0; a < panelItems.Length; a++)
{
if (panelItems[a] != null && panelItems[a].Item1 == item)
{
panelItems[a] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>(panelItems[a].Item1, panelItems[a].Item2, (int)NUM_X.Value, panelItems[a].Item4, panelItems[a].Item5, panelItems[a].Item6, panelItems[a].Item7);
}
}
 
osdDraw();
}
 
private void numericUpDown2_ValueChanged(object sender, EventArgs e)
{
string item;
try
{
item = LIST_items.SelectedItem.ToString();
}
catch { return; }
 
for (int a = 0; a < panelItems.Length; a++)
{
if (panelItems[a] != null && panelItems[a].Item1 == item)
{
panelItems[a] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>(panelItems[a].Item1, panelItems[a].Item2, panelItems[a].Item3, (int)NUM_Y.Value, panelItems[a].Item5, panelItems[a].Item6, panelItems[a].Item7);
 
}
}
 
osdDraw();
}
 
private void BUT_WriteOSD_Click(object sender, EventArgs e)
{
toolStripProgressBar1.Style = ProgressBarStyle.Continuous;
this.toolStripStatusLabel1.Text = "";
 
foreach (string str in this.LIST_items.Items)
{
foreach (var tuple in this.panelItems)
{
if ((tuple != null) && ((tuple.Item1 == str)) && tuple.Item5 != -1)
{
eeprom[tuple.Item5] = (byte)(this.LIST_items.CheckedItems.Contains(str) ? 1 : 0);
eeprom[tuple.Item6] = (byte)tuple.Item3; // x
eeprom[tuple.Item7] = (byte)tuple.Item4; // y
 
Console.WriteLine(str);
}
}
}
 
ArduinoSTK sp;
 
try
{
if (comPort.IsOpen)
comPort.Close();
 
sp = new ArduinoSTK();
sp.PortName = CMB_ComPort.Text;
sp.BaudRate = 57600;
sp.DtrEnable = true;
 
sp.Open();
}
catch { MessageBox.Show("Error opening com port", "Error", MessageBoxButtons.OK, MessageBoxIcon.Error); return; }
 
if (sp.connectAP())
{
try
{
if (sp.upload(eeprom, 0, 200, 0))
{
MessageBox.Show("Done!");
}
else
{
MessageBox.Show("Failed to upload new settings");
}
}
catch (Exception ex) {
MessageBox.Show(ex.Message);
}
}
else
{
MessageBox.Show("Failed to talk to bootloader");
}
 
sp.Close();
}
 
private void comboBox1_SelectedIndexChanged(object sender, EventArgs e)
{
 
}
 
private void comboBox1_Click(object sender, EventArgs e)
{
CMB_ComPort.Items.Clear();
CMB_ComPort.Items.AddRange(GetPortNames());
}
 
 
 
/* *********************************************** */
// EEPROM Storage addresses
 
// First of 8 panels
const int panCenter_en_ADDR = 0;
const int panCenter_x_ADDR = 2;
const int panCenter_y_ADDR = 4;
const int panPitch_en_ADDR = 6;
const int panPitch_x_ADDR = 8;
const int panPitch_y_ADDR = 10;
const int panRoll_en_ADDR = 12;
const int panRoll_x_ADDR = 14;
const int panRoll_y_ADDR = 16;
const int panBatt_A_en_ADDR = 18;
const int panBatt_A_x_ADDR = 20;
const int panBatt_A_y_ADDR = 22;
const int panBatt_B_en_ADDR = 24;
const int panBatt_B_x_ADDR = 26;
const int panBatt_B_y_ADDR = 28;
const int panGPSats_en_ADDR = 30;
const int panGPSats_x_ADDR = 32;
const int panGPSats_y_ADDR = 34;
const int panGPL_en_ADDR = 36;
const int panGPL_x_ADDR = 38;
const int panGPL_y_ADDR = 40;
const int panGPS_en_ADDR = 42;
const int panGPS_x_ADDR = 44;
const int panGPS_y_ADDR = 46;
 
// Second set of 8 panels
const int panRose_en_ADDR = 48;
const int panRose_x_ADDR = 50;
const int panRose_y_ADDR = 52;
const int panHeading_en_ADDR = 54;
const int panHeading_x_ADDR = 56;
const int panHeading_y_ADDR = 58;
const int panMavBeat_en_ADDR = 60;
const int panMavBeat_x_ADDR = 62;
const int panMavBeat_y_ADDR = 64;
const int panHomeDir_en_ADDR = 66;
const int panHomeDir_x_ADDR = 68;
const int panHomeDir_y_ADDR = 70;
const int panHomeDis_en_ADDR = 72;
const int panHomeDis_x_ADDR = 74;
const int panHomeDis_y_ADDR = 76;
const int panWPDir_en_ADDR = 80;
const int panWPDir_x_ADDR = 82;
const int panWPDir_y_ADDR = 84;
const int panWPDis_en_ADDR = 86;
const int panWPDis_x_ADDR = 88;
const int panWPDis_y_ADDR = 90;
const int panRSSI_en_ADDR = 92;
const int panRSSI_x_ADDR = 94;
const int panRSSI_y_ADDR = 96;
 
 
// Third set of 8 panels
const int panCurA_en_ADDR = 98;
const int panCurA_x_ADDR = 100;
const int panCurA_y_ADDR = 102;
const int panCurB_en_ADDR = 104;
const int panCurB_x_ADDR = 106;
const int panCurB_y_ADDR = 108;
const int panAlt_en_ADDR = 110;
const int panAlt_x_ADDR = 112;
const int panAlt_y_ADDR = 114;
const int panVel_en_ADDR = 116;
const int panVel_x_ADDR = 118;
const int panVel_y_ADDR = 120;
const int panThr_en_ADDR = 122;
const int panThr_x_ADDR = 124;
const int panThr_y_ADDR = 126;
const int panFMod_en_ADDR = 128;
const int panFMod_x_ADDR = 130;
const int panFMod_y_ADDR = 132;
const int panHorizon_en_ADDR = 134;
const int panHorizon_x_ADDR = 136;
const int panHorizon_y_ADDR = 138;
 
const int CHK1 = 1000;
const int CHK2 = 1006;
 
private void checkBox1_CheckedChanged(object sender, EventArgs e)
{
osdDraw();
}
 
private void OSD_Resize(object sender, EventArgs e)
{
try
{
osdDraw();
}
catch { }
}
 
private void BUT_ReadOSD_Click(object sender, EventArgs e)
{
toolStripProgressBar1.Style = ProgressBarStyle.Continuous;
this.toolStripStatusLabel1.Text = "";
 
bool fail = false;
ArduinoSTK sp;
 
try
{
if (comPort.IsOpen)
comPort.Close();
 
sp = new ArduinoSTK();
sp.PortName = CMB_ComPort.Text;
sp.BaudRate = 57600;
sp.DtrEnable = true;
 
sp.Open();
}
catch { MessageBox.Show("Error opening com port", "Error", MessageBoxButtons.OK, MessageBoxIcon.Error); return; }
 
if (sp.connectAP())
{
try
{
eeprom = sp.download(1024);
}
catch (Exception ex) {
fail = true;
MessageBox.Show(ex.Message);
}
}
else
{
MessageBox.Show("Failed to talk to bootloader");
fail = true;
}
 
sp.Close();
 
if (!fail)
{
 
for (int a = 0; a < panelItems.Length; a++)
{
if (panelItems[a] != null)
{
if (panelItems[a].Item5 >= 0)
LIST_items.SetItemCheckState(a, eeprom[panelItems[a].Item5] == 0 ? CheckState.Unchecked : CheckState.Checked);
 
if (panelItems[a].Item7 >= 0 || panelItems[a].Item6 >= 0)
panelItems[a] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>(panelItems[a].Item1, panelItems[a].Item2, eeprom[panelItems[a].Item6], eeprom[panelItems[a].Item7], panelItems[a].Item5, panelItems[a].Item6, panelItems[a].Item7);
}
}
}
 
osdDraw();
 
if (!fail)
MessageBox.Show("Done!");
}
 
 
byte[] readIntelHEXv2(StreamReader sr)
{
byte[] FLASH = new byte[1024 * 1024];
 
int optionoffset = 0;
int total = 0;
bool hitend = false;
 
while (!sr.EndOfStream)
{
toolStripProgressBar1.Value = (int)(((float)sr.BaseStream.Position / (float)sr.BaseStream.Length) * 100);
 
string line = sr.ReadLine();
 
if (line.StartsWith(":"))
{
int length = Convert.ToInt32(line.Substring(1, 2), 16);
int address = Convert.ToInt32(line.Substring(3, 4), 16);
int option = Convert.ToInt32(line.Substring(7, 2), 16);
Console.WriteLine("len {0} add {1} opt {2}", length, address, option);
 
if (option == 0)
{
string data = line.Substring(9, length * 2);
for (int i = 0; i < length; i++)
{
byte byte1 = Convert.ToByte(data.Substring(i * 2, 2), 16);
FLASH[optionoffset + address] = byte1;
address++;
if ((optionoffset + address) > total)
total = optionoffset + address;
}
}
else if (option == 2)
{
optionoffset = (int)Convert.ToUInt16(line.Substring(9, 4), 16) << 4;
}
else if (option == 1)
{
hitend = true;
}
int checksum = Convert.ToInt32(line.Substring(line.Length - 2, 2), 16);
 
byte checksumact = 0;
for (int z = 0; z < ((line.Length - 1 - 2) / 2); z++) // minus 1 for : then mins 2 for checksum itself
{
checksumact += Convert.ToByte(line.Substring(z * 2 + 1, 2), 16);
}
checksumact = (byte)(0x100 - checksumact);
 
if (checksumact != checksum)
{
MessageBox.Show("The hex file loaded is invalid, please try again.");
throw new Exception("Checksum Failed - Invalid Hex");
}
}
//Regex regex = new Regex(@"^:(..)(....)(..)(.*)(..)$"); // length - address - option - data - checksum
}
 
if (!hitend)
{
MessageBox.Show("The hex file did no contain an end flag. aborting");
throw new Exception("No end flag in file");
}
 
Array.Resize<byte>(ref FLASH, total);
 
return FLASH;
}
 
void sp_Progress(int progress)
{
toolStripStatusLabel1.Text = "Uploading " + progress + " %";
toolStripProgressBar1.Value = progress;
 
statusStrip1.Refresh();
}
 
private void CHK_pal_CheckedChanged(object sender, EventArgs e)
{
changeToPal(CHK_pal.Checked);
 
osdDraw();
}
 
private void pALToolStripMenuItem_CheckStateChanged(object sender, EventArgs e)
{
nTSCToolStripMenuItem.Checked = !CHK_pal.Checked;
}
 
private void nTSCToolStripMenuItem_CheckStateChanged(object sender, EventArgs e)
{
CHK_pal.Checked = !nTSCToolStripMenuItem.Checked;
}
 
private void saveToFileToolStripMenuItem_Click(object sender, EventArgs e)
{
SaveFileDialog sfd = new SaveFileDialog() { Filter = "*.osd|*.osd" };
 
sfd.ShowDialog();
 
if (sfd.FileName != "")
{
try
{
using (StreamWriter sw = new StreamWriter(sfd.OpenFile()))
{
 
foreach (var item in panelItems)
{
if (item != null)
sw.WriteLine("{0}\t{1}\t{2}\t{3}", item.Item1, item.Item3, item.Item4, LIST_items.GetItemChecked(LIST_items.Items.IndexOf(item.Item1)).ToString());
}
sw.Close();
}
}
catch
{
MessageBox.Show("Error writing file");
}
}
}
 
private void loadFromFileToolStripMenuItem_Click(object sender, EventArgs e)
{
OpenFileDialog ofd = new OpenFileDialog() { Filter = "*.osd|*.osd" };
 
ofd.ShowDialog();
 
if (ofd.FileName != "")
{
try
{
using (StreamReader sr = new StreamReader(ofd.OpenFile()))
{
while (!sr.EndOfStream)
{
string[] strings = sr.ReadLine().Split(new char[] {'\t'},StringSplitOptions.RemoveEmptyEntries);
 
for (int a = 0; a < panelItems.Length; a++)
{
if (panelItems[a] != null && panelItems[a].Item1 == strings[0])
{
// incase there is an invalid line number or to shore
try
{
panelItems[a] = new Tuple<string, Func<int, int, int>, int, int, int, int, int>(panelItems[a].Item1, panelItems[a].Item2, int.Parse(strings[1]), int.Parse(strings[2]), panelItems[a].Item5, panelItems[a].Item6, panelItems[a].Item7);
 
LIST_items.SetItemChecked(a, strings[3] == "True");
}
catch { }
}
}
}
}
}
catch
{
MessageBox.Show("Error Reading file");
}
}
 
osdDraw();
}
 
private void loadDefaultsToolStripMenuItem_Click(object sender, EventArgs e)
{
setupFunctions();
}
 
private void exitToolStripMenuItem_Click(object sender, EventArgs e)
{
Application.Exit();
}
 
private void pictureBox1_MouseUp(object sender, MouseEventArgs e)
{
getMouseOverItem(e.X, e.Y);
 
mousedown = false;
}
 
private void pictureBox1_MouseMove(object sender, MouseEventArgs e)
{
if (e.Button == System.Windows.Forms.MouseButtons.Left && mousedown == true)
{
int ansW, ansH;
getCharLoc(e.X, e.Y, out ansW, out ansH);
if (ansH >= getCenter() && !CHK_pal.Checked)
{
ansH += 3;
}
 
NUM_X.Value = Constrain(ansW, 0, basesize.Width - 1);
NUM_Y.Value = Constrain(ansH, 0, 16 - 1);
 
pictureBox1.Focus();
}
else
{
mousedown = false;
}
}
 
private void pictureBox1_MouseDown(object sender, MouseEventArgs e)
{
currentlyselected = getMouseOverItem(e.X, e.Y);
mousedown = true;
}
 
private void updateFirmwareToolStripMenuItem_Click(object sender, EventArgs e)
{
toolStripProgressBar1.Style = ProgressBarStyle.Continuous;
this.toolStripStatusLabel1.Text = "";
 
OpenFileDialog ofd = new OpenFileDialog();
ofd.Filter = "*.hex|*.hex";
 
ofd.ShowDialog();
 
if (ofd.FileName != "")
{
byte[] FLASH;
try
{
toolStripStatusLabel1.Text = "Reading Hex File";
 
statusStrip1.Refresh();
 
FLASH = readIntelHEXv2(new StreamReader(ofd.FileName));
}
catch { MessageBox.Show("Bad Hex File"); return; }
 
bool fail = false;
ArduinoSTK sp;
 
try
{
if (comPort.IsOpen)
comPort.Close();
 
sp = new ArduinoSTK();
sp.PortName = CMB_ComPort.Text;
sp.BaudRate = 57600;
sp.DtrEnable = true;
 
sp.Open();
}
catch { MessageBox.Show("Error opening com port", "Error", MessageBoxButtons.OK, MessageBoxIcon.Error); return; }
 
toolStripStatusLabel1.Text = "Connecting to Board";
 
if (sp.connectAP())
{
sp.Progress += new ArduinoSTK.ProgressEventHandler(sp_Progress);
try
{
if (!sp.uploadflash(FLASH, 0, FLASH.Length, 0))
{
if (sp.IsOpen)
sp.Close();
 
MessageBox.Show("Upload failed. Lost sync. Try using Arduino to upload instead",
"Error",
MessageBoxButtons.OK,
MessageBoxIcon.Warning);
}
}
catch (Exception ex)
{
fail = true;
MessageBox.Show(ex.Message, "Error", MessageBoxButtons.OK, MessageBoxIcon.Error);
}
 
}
else
{
MessageBox.Show("Failed to talk to bootloader");
}
 
sp.Close();
 
if (!fail)
{
 
toolStripStatusLabel1.Text = "Done";
 
MessageBox.Show("Done!");
}
else
{
toolStripStatusLabel1.Text = "Failed";
}
}
}
 
private void customBGPictureToolStripMenuItem_Click(object sender, EventArgs e)
{
OpenFileDialog ofd = new OpenFileDialog();
ofd.Filter = "jpg or bmp|*.jpg;*.bmp";
 
ofd.ShowDialog();
 
if (ofd.FileName != "")
{
try
{
bgpicture = Image.FromFile(ofd.FileName);
 
}
catch { MessageBox.Show("Bad Image"); }
 
osdDraw();
}
}
 
private void sendTLogToolStripMenuItem_Click(object sender, EventArgs e)
{
 
OpenFileDialog ofd = new OpenFileDialog();
ofd.Filter = "Tlog|*.tlog";
 
ofd.ShowDialog();
 
if (ofd.FileName != "")
{
if (comPort.IsOpen)
comPort.Close();
 
try
{
 
comPort.PortName = CMB_ComPort.Text;
comPort.BaudRate = 57600;
comPort.Open();
 
}
catch { MessageBox.Show("Error opening com port", "Error", MessageBoxButtons.OK, MessageBoxIcon.Error); return; }
 
BinaryReader br = new BinaryReader(ofd.OpenFile());
 
this.toolStripProgressBar1.Style = ProgressBarStyle.Marquee;
this.toolStripStatusLabel1.Text = "Sending TLOG data...";
 
while (br.BaseStream.Position < br.BaseStream.Length && !this.IsDisposed)
{
try
{
byte[] bytes = br.ReadBytes(20);
 
comPort.Write(bytes, 0, bytes.Length);
 
System.Threading.Thread.Sleep(5);
 
Console.Write(comPort.ReadExisting());
 
}
catch { break; }
 
Application.DoEvents();
}
 
try
{
toolStripProgressBar1.Style = ProgressBarStyle.Continuous;
toolStripStatusLabel1.Text = "";
 
comPort.Close();
}
catch { }
}
}
 
private void OSD_FormClosed(object sender, FormClosedEventArgs e)
{
xmlconfig(true);
 
}
 
private void xmlconfig(bool write)
{
if (write || !File.Exists(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"config.xml"))
{
try
{
XmlTextWriter xmlwriter = new XmlTextWriter(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"config.xml", Encoding.ASCII);
xmlwriter.Formatting = Formatting.Indented;
 
xmlwriter.WriteStartDocument();
 
xmlwriter.WriteStartElement("Config");
 
xmlwriter.WriteElementString("comport", CMB_ComPort.Text);
 
xmlwriter.WriteElementString("Pal", CHK_pal.Checked.ToString());
 
xmlwriter.WriteEndElement();
 
xmlwriter.WriteEndDocument();
xmlwriter.Close();
 
//appconfig.Save();
}
catch (Exception ex) { MessageBox.Show(ex.ToString()); }
}
else
{
try
{
using (XmlTextReader xmlreader = new XmlTextReader(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"config.xml"))
{
while (xmlreader.Read())
{
xmlreader.MoveToElement();
try
{
switch (xmlreader.Name)
{
case "comport":
string temp = xmlreader.ReadString();
CMB_ComPort.Text = temp;
break;
case "Pal":
string temp2 = xmlreader.ReadString();
CHK_pal.Checked = (temp2 == "True");
break;
case "Config":
break;
case "xml":
break;
default:
if (xmlreader.Name == "") // line feeds
break;
break;
}
}
catch (Exception ee) { Console.WriteLine(ee.Message); } // silent fail on bad entry
}
}
}
catch (Exception ex) { Console.WriteLine("Bad Config File: " + ex.ToString()); } // bad config file
}
}
 
private void updateFontToolStripMenuItem_Click(object sender, EventArgs e)
{
toolStripProgressBar1.Style = ProgressBarStyle.Continuous;
toolStripStatusLabel1.Text = "";
 
OpenFileDialog ofd = new OpenFileDialog();
ofd.Filter = "mcm|*.mcm";
 
ofd.ShowDialog();
 
if (ofd.FileName != "")
{
if (comPort.IsOpen)
comPort.Close();
 
try
{
 
comPort.PortName = CMB_ComPort.Text;
comPort.BaudRate = 57600;
 
comPort.Open();
 
comPort.DtrEnable = false;
comPort.RtsEnable = false;
 
System.Threading.Thread.Sleep(50);
 
comPort.DtrEnable = true;
comPort.RtsEnable = true;
 
System.Threading.Thread.Sleep(2000);
 
comPort.ReadExisting();
 
comPort.WriteLine("");
comPort.WriteLine("");
comPort.WriteLine("");
comPort.WriteLine("");
comPort.WriteLine("");
 
int timeout = 0;
 
while (comPort.BytesToRead == 0)
{
System.Threading.Thread.Sleep(500);
Console.WriteLine("Waiting...");
timeout++;
 
if (timeout > 6)
{
MessageBox.Show("Error entering font mode - No Data");
comPort.Close();
return;
}
}
 
if (!comPort.ReadLine().Contains("Ready for Font"))
{
MessageBox.Show("Error entering CharSet upload mode - invalid data");
comPort.Close();
return;
}
}
catch { MessageBox.Show("Error opening com port", "Error", MessageBoxButtons.OK, MessageBoxIcon.Error); return; }
 
using (var stream = ofd.OpenFile())
{
 
BinaryReader br = new BinaryReader(stream);
StreamReader sr2 = new StreamReader(br.BaseStream);
 
string device = sr2.ReadLine();
 
if (device != "MAX7456")
{
MessageBox.Show("Invalid MCM");
comPort.Close();
return;
}
 
br.BaseStream.Seek(0, SeekOrigin.Begin);
 
long length = br.BaseStream.Length;
 
while (br.BaseStream.Position < br.BaseStream.Length && !this.IsDisposed)
{
try
{
toolStripProgressBar1.Value = (int)((br.BaseStream.Position / (float)br.BaseStream.Length) * 100);
toolStripStatusLabel1.Text = "CharSet Uploading";
 
 
int read = 256 * 3;// 163847 / 256 + 1; // 163,847 font file
if ((br.BaseStream.Position + read) > br.BaseStream.Length)
{
read = (int)(br.BaseStream.Length - br.BaseStream.Position);
}
length -= read;
 
byte[] buffer = br.ReadBytes(read);
 
comPort.Write(buffer, 0, buffer.Length);
 
int timeout = 0;
 
while (comPort.BytesToRead == 0 && read == 768)
{
System.Threading.Thread.Sleep(10);
timeout++;
 
if (timeout > 10)
{
MessageBox.Show("CharSet upload failed - no response");
comPort.Close();
return;
}
}
 
Console.WriteLine(comPort.ReadExisting());
 
}
catch { break; }
 
Application.DoEvents();
}
 
comPort.WriteLine("\n\n\n\n\n\n\n\n\n\n\n\n\n\n");
 
comPort.DtrEnable = false;
comPort.RtsEnable = false;
 
System.Threading.Thread.Sleep(50);
 
comPort.DtrEnable = true;
comPort.RtsEnable = true;
 
System.Threading.Thread.Sleep(50);
 
comPort.Close();
 
comPort.DtrEnable = false;
comPort.RtsEnable = false;
 
toolStripProgressBar1.Value = 100;
toolStripStatusLabel1.Text = "CharSet Done";
}
}
}
 
private void helpToolStripMenuItem_Click(object sender, EventArgs e)
{
try
{
System.Diagnostics.Process.Start("https://code.google.com/p/arducam-osd/wiki/arducam_osd?tm=6");
}
catch { MessageBox.Show("Webpage open failed... do you have a virus?"); }
}
}
}
/C-OSD/arducam-osd/Tools/OSD/OSD.csproj
0,0 → 1,162
<?xml version="1.0" encoding="utf-8"?>
<Project ToolsVersion="4.0" DefaultTargets="Build" xmlns="http://schemas.microsoft.com/developer/msbuild/2003">
<PropertyGroup>
<Configuration Condition=" '$(Configuration)' == '' ">Debug</Configuration>
<Platform Condition=" '$(Platform)' == '' ">x86</Platform>
<ProductVersion>8.0.30703</ProductVersion>
<SchemaVersion>2.0</SchemaVersion>
<ProjectGuid>{E35F835A-8B3E-42D5-8852-A6E0F41823B5}</ProjectGuid>
<OutputType>WinExe</OutputType>
<AppDesignerFolder>Properties</AppDesignerFolder>
<RootNamespace>OSD</RootNamespace>
<AssemblyName>OSD_Config</AssemblyName>
<TargetFrameworkVersion>v3.5</TargetFrameworkVersion>
<TargetFrameworkProfile>
</TargetFrameworkProfile>
<FileAlignment>512</FileAlignment>
<IsWebBootstrapper>false</IsWebBootstrapper>
<PublishUrl>publish\</PublishUrl>
<Install>true</Install>
<InstallFrom>Disk</InstallFrom>
<UpdateEnabled>false</UpdateEnabled>
<UpdateMode>Foreground</UpdateMode>
<UpdateInterval>7</UpdateInterval>
<UpdateIntervalUnits>Days</UpdateIntervalUnits>
<UpdatePeriodically>false</UpdatePeriodically>
<UpdateRequired>false</UpdateRequired>
<MapFileExtensions>true</MapFileExtensions>
<ApplicationRevision>0</ApplicationRevision>
<ApplicationVersion>1.0.0.%2a</ApplicationVersion>
<UseApplicationTrust>false</UseApplicationTrust>
<BootstrapperEnabled>true</BootstrapperEnabled>
</PropertyGroup>
<PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Debug|x86' ">
<PlatformTarget>x86</PlatformTarget>
<DebugSymbols>true</DebugSymbols>
<DebugType>full</DebugType>
<Optimize>false</Optimize>
<OutputPath>bin\Debug\</OutputPath>
<DefineConstants>DEBUG;TRACE</DefineConstants>
<ErrorReport>prompt</ErrorReport>
<WarningLevel>4</WarningLevel>
</PropertyGroup>
<PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Release|x86' ">
<PlatformTarget>x86</PlatformTarget>
<DebugType>pdbonly</DebugType>
<Optimize>true</Optimize>
<OutputPath>bin\Release\</OutputPath>
<DefineConstants>TRACE</DefineConstants>
<ErrorReport>prompt</ErrorReport>
<WarningLevel>4</WarningLevel>
</PropertyGroup>
<PropertyGroup>
<StartupObject>OSD.Program</StartupObject>
</PropertyGroup>
<PropertyGroup>
<TargetZone>LocalIntranet</TargetZone>
</PropertyGroup>
<PropertyGroup>
<GenerateManifests>true</GenerateManifests>
</PropertyGroup>
<PropertyGroup />
<PropertyGroup>
<SignAssembly>true</SignAssembly>
</PropertyGroup>
<PropertyGroup>
<AssemblyOriginatorKeyFile>key.snk</AssemblyOriginatorKeyFile>
</PropertyGroup>
<PropertyGroup>
<NoWin32Manifest>true</NoWin32Manifest>
</PropertyGroup>
<PropertyGroup>
<ApplicationIcon>osd.ico</ApplicationIcon>
</PropertyGroup>
<ItemGroup>
<Reference Include="System" />
<Reference Include="System.Data" />
<Reference Include="System.Deployment" />
<Reference Include="System.Drawing" />
<Reference Include="System.Windows.Forms" />
<Reference Include="System.XML" />
</ItemGroup>
<ItemGroup>
<Compile Include="ArduinoSTK.cs">
<SubType>Component</SubType>
</Compile>
<Compile Include="MavlinkOther.cs" />
<Compile Include="mcm.cs" />
<Compile Include="OSD.cs">
<SubType>Form</SubType>
</Compile>
<Compile Include="OSD.Designer.cs">
<DependentUpon>OSD.cs</DependentUpon>
</Compile>
<Compile Include="Panels.cs" />
<Compile Include="Program.cs" />
<Compile Include="Properties\AssemblyInfo.cs" />
<Compile Include="Tools.cs" />
<Compile Include="Tuple.cs" />
<EmbeddedResource Include="OSD.resx">
<DependentUpon>OSD.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="Properties\Resources.resx">
<Generator>ResXFileCodeGenerator</Generator>
<LastGenOutput>Resources.Designer.cs</LastGenOutput>
<SubType>Designer</SubType>
</EmbeddedResource>
<Compile Include="Properties\Resources.Designer.cs">
<AutoGen>True</AutoGen>
<DependentUpon>Resources.resx</DependentUpon>
<DesignTime>True</DesignTime>
</Compile>
<None Include="app.config" />
<None Include="key.snk" />
<None Include="OSD_SA_v5.mcm">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None>
<None Include="Properties\app.manifest" />
<None Include="Properties\Settings.settings">
<Generator>SettingsSingleFileGenerator</Generator>
<LastGenOutput>Settings.Designer.cs</LastGenOutput>
</None>
<Compile Include="Properties\Settings.Designer.cs">
<AutoGen>True</AutoGen>
<DependentUpon>Settings.settings</DependentUpon>
<DesignTimeSharedInput>True</DesignTimeSharedInput>
</Compile>
</ItemGroup>
<ItemGroup>
<Content Include="osd.ico" />
<None Include="Resources\saveHS.png" />
<None Include="Resources\openHS.png" />
<Content Include="vlcsnap-2012-01-28-07h46m04s95.png">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</Content>
</ItemGroup>
<ItemGroup />
<ItemGroup>
<BootstrapperPackage Include="Microsoft.Net.Client.3.5">
<Visible>False</Visible>
<ProductName>.NET Framework 3.5 SP1 Client Profile</ProductName>
<Install>false</Install>
</BootstrapperPackage>
<BootstrapperPackage Include="Microsoft.Net.Framework.3.5.SP1">
<Visible>False</Visible>
<ProductName>.NET Framework 3.5 SP1</ProductName>
<Install>true</Install>
</BootstrapperPackage>
<BootstrapperPackage Include="Microsoft.Windows.Installer.3.1">
<Visible>False</Visible>
<ProductName>Windows Installer 3.1</ProductName>
<Install>true</Install>
</BootstrapperPackage>
</ItemGroup>
<Import Project="$(MSBuildToolsPath)\Microsoft.CSharp.targets" />
<!-- To modify your build process, add your task inside one of the targets below and uncomment it.
Other similar extension points exist, see Microsoft.Common.targets.
<Target Name="BeforeBuild">
</Target>
<Target Name="AfterBuild">
</Target>
-->
</Project>
/C-OSD/arducam-osd/Tools/OSD/OSD.resx
0,0 → 1,580
<?xml version="1.0" encoding="utf-8"?>
<root>
<!--
Microsoft ResX Schema
Version 2.0
The primary goals of this format is to allow a simple XML format
that is mostly human readable. The generation and parsing of the
various data types are done through the TypeConverter classes
associated with the data types.
Example:
... ado.net/XML headers & schema ...
<resheader name="resmimetype">text/microsoft-resx</resheader>
<resheader name="version">2.0</resheader>
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
<value>[base64 mime encoded serialized .NET Framework object]</value>
</data>
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
<comment>This is a comment</comment>
</data>
There are any number of "resheader" rows that contain simple
name/value pairs.
Each data row contains a name, and value. The row also contains a
type or mimetype. Type corresponds to a .NET class that support
text/value conversion through the TypeConverter architecture.
Classes that don't support this are serialized and stored with the
mimetype set.
The mimetype is used for serialized objects, and tells the
ResXResourceReader how to depersist the object. This is currently not
extensible. For a given mimetype the value must be set accordingly:
Note - application/x-microsoft.net.object.binary.base64 is the format
that the ResXResourceWriter will generate, however the reader can
read any of the formats listed below.
mimetype: application/x-microsoft.net.object.binary.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
: and then encoded with base64 encoding.
mimetype: application/x-microsoft.net.object.soap.base64
value : The object must be serialized with
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
: and then encoded with base64 encoding.
 
mimetype: application/x-microsoft.net.object.bytearray.base64
value : The object must be serialized into a byte array
: using a System.ComponentModel.TypeConverter
: and then encoded with base64 encoding.
-->
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
<xsd:element name="root" msdata:IsDataSet="true">
<xsd:complexType>
<xsd:choice maxOccurs="unbounded">
<xsd:element name="metadata">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" />
</xsd:sequence>
<xsd:attribute name="name" use="required" type="xsd:string" />
<xsd:attribute name="type" type="xsd:string" />
<xsd:attribute name="mimetype" type="xsd:string" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="assembly">
<xsd:complexType>
<xsd:attribute name="alias" type="xsd:string" />
<xsd:attribute name="name" type="xsd:string" />
</xsd:complexType>
</xsd:element>
<xsd:element name="data">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
<xsd:attribute ref="xml:space" />
</xsd:complexType>
</xsd:element>
<xsd:element name="resheader">
<xsd:complexType>
<xsd:sequence>
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
</xsd:sequence>
<xsd:attribute name="name" type="xsd:string" use="required" />
</xsd:complexType>
</xsd:element>
</xsd:choice>
</xsd:complexType>
</xsd:element>
</xsd:schema>
<resheader name="resmimetype">
<value>text/microsoft-resx</value>
</resheader>
<resheader name="version">
<value>2.0</value>
</resheader>
<resheader name="reader">
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<resheader name="writer">
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
</resheader>
<metadata name="statusStrip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<value>17, 17</value>
</metadata>
<metadata name="menuStrip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
<value>133, 17</value>
</metadata>
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
<data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>
AAABAAQAEBAAAAEACABoBQAARgAAACAgAAABAAgAqAgAAK4FAAAwMAAAAQAIAKgOAABWDgAAgIAAAAEA
CAAoTAAA/hwAACgAAAAQAAAAIAAAAAEACAAAAAAAAAEAABILAAASCwAAAAEAAAABAAB0SCwAdU42AINR
MQCSWjYAmF45AJ5hOgCfYz0AjGRKAIRpWACGd24Aj3tvAI98bwCCd3AAgHp2AJ99aAChZkIApm5KAKZv
TgCjdFYAoXheAKV4WwCmel0ApnpeAKZ7XwCle2AAp3xgAKh9YQCOhX8AmIl/AKuBZgCsgmcAqYFoAKuF
bQCtg2kArYRqAK6FagCvhmwAr4dtAKeLegCth3AArYlxALKFaQC1hWgAsIhvALWJbgCzjXUAs451ALaS
egC4lH0AwJd+AJGPjgCUjYkAmoyEAJ2NgwCbl5UAo46BAKSOgAChkYcArZeJAKCYkwCjnJcAoZ2bAKGe
mwCknpoAu5iCALyZgwC9m4UAv56IAKiinwCro58AsqGWALGknACopKEAqaWjALCoogCzqKEAtqmhALqv
qACzsK4AubCrALi0sQC8tbEAwJmAAMKfiADCo44AwqOPAMCmlQDEpZIAx6qXAMKqmwDHq5gAyqiTAMup
lADLqZUAyKyZAMismgDJrZoAzKyYAM2umgDNrpsAybSnAM2zowDNtKMAzrSjAMK5tADDurUAxbu1AMW8
tQDQuKgA0bmqANG8rQDTvK0A1L2uANfAsgDWwbQA2MS2ANnEtgDbxLUA2MS4ANvGuADcx7kA28i7ANjJ
vwDdyr4A38u+AMbCwADSy8cA1MjAANXIwADWysIA1M3IANnMxADfzsIA3NDHANzRyADc0ckA4M/DAODP
xADi0scA4NHIAOPTyQDj1MkA4dXNAOHVzgDk1csA5dbMAObXzQDo2c4A5tjQAOja0QDp29IA6tvRAOnc
0wDp3dUA693VAOvf1gDt4NcA6+DZAO7h2QDu4toA7+TcAO/l3QDv5t8A8OTcAPDn4ADz6uQA8+vmAPTs
5wD17ukA9u/qAPbv6wAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAgY+Pj4+P
j4+Pj4+Pj4+PmodfIiIvo1ciJUGbIiUlXaeFFpyjX20dqakuhUCpqSudgx2do3Bmim1fFpFAqalBlIMh
nZ1vZhlve5GWQKmpQJSHE3h8MHUWjZAZli2LiRqih3hTQmapeVRUc6RaWl6IqnmTk5OWpaWlpaWlpaWl
paVkPz8/P0hIST+WgE2AlpaaVjlTU0Y2G4s7dYJ9NHBtcigIBhJLIDJZMwtrTAxKRDUnCAAYDQFIIVE+
ajp1fj00Jwk3AjdHBxMKTlAmW1xdYx9pT09PT01qDiksMFtcXGMDBQUFBQUFBQUFBgYQKjFhBA8PDw8P
Dw8PDw8PDw8PEAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAoAAAAIAAAAEAAAAABAAgAAAAAAAAEAAASCwAAEgsAAAABAAAAAQAAHh0cACsc
EgA6JBYAJiYmAD8/PwBGLBwATjMhAEU8NwBoQioAcEYrAHZILABxTDYAflc+AFBIRABSTEkAVVFPAFpT
TgBTUlIAXllWAF1aWABjXlsAb11SAHNXRgB0WUcAfltFAHdlWgB3aF8AdHNzAHt7ewCGVDUAjFYzAI9Y
NQCPWjgAkl07AJleOQCUYD8AnmE6AKBkPwCDXkgAg21fAJZjQgCXak4AmGZGAJxrTACeb1AAn3BRAJ5z
WACEbmEAhnFkAI51ZgCOd2kAj3hqAIJ8dwCGfnoAin10AJx+awChZUAAomlFAKVtSgCiclQAo3ZZAKZ5
XQCrd1cAp3xgAKh9YgCWgnUAq4JnAK6GbACig3AAsYFjALaHawCxi3IAtZJ7ALySdwC7ln4Ah4aGAIiG
hACQhoAAk4uGAJ6QiACZlpQAm5ubAK6VhQCil5AArJ+XALGVhACzm4wAupeAALyahAC4mogAtp+QAKGg
nwCooJsAv6CNALOkmgC3qJ8AvKGQAKampgCrq6sAtq6pALOzswC+vr4Awp+JAMOijQDFp5MAxqiVAMSr
mwDKqZQAya2bAM6wngDEr6IAw7GlAM20pADMtqgAzbmsAMG5tADMvLEA0LenANG4pwDTu6sA1b+xAMzC
vADWwbMA1cW7ANjEtwDaxrkA3cq+AMTEwwDJxMEAzczMANTJwQDbzsYA28/IAN/SyQDW1NMA3NjWAN3d
3ADhzcAA4dHHAOTUygDn2M8A6NnPAOXZ0QDq3dUA5uHdAOzg1wDu4dkA8ObfAOTj4gDp5eMA6ujmAOzs
6wDx5+EA8+rkAPbv6gAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAHmC
g4ODg4ODhIODg4ODhIODhIODhISEg4ODhIOEhIuPeYyRjo6RkpGPj4+Pj4+Oj4+Pj4+Oj46Pj4+Oj4+P
kpKCjJJ9aEpKSmqMlpOYd1hXV1hskZiOaGhqaGhsfpiZmHuMbCMjOzwrISiLmlghKS49LSE9moMhKCoq
KighWJqago4rPY2SkpOOKkmaKEqampqabSGNfiGLmpqamlghj5p7hyNnkpKSk5pCQpMhbZqampp+IYp+
IYuampqagyF8moKFI2mSkZKTmkc9moySmpqamnAhjX4hipqampqLIXyagoUhaJKSkpOaRz2ak2hDPy0o
ID+afiGLmpqamowhepp7gyNokpKSkppHPZpII0NIZmx8mZqDIYqampqaiyF8mnuKI2iSkpKSmkM9mixI
mpqampJ+mX4hi5qampqKIXqago4oSpKSkpKaPEOaK0qampqacCGTfiKKmpqamnghg5qCjkMjZ3B2bUkh
bJpCKmx6eHU9Kpp+IWl1d3BpLCmZmoKOikMjJCEjI2aZmoo7ICMhITt4moMqKioqKitGi5qae46SkpKN
jI2SmpqampqZk5WZmpqampqampqampqampp7i4+PjY+RkZGTmpqampqampqZmpqZmpmampmampqamnKJ
i4uLi4uKi4uTk5OTk5aZmJiYmJiYmJiYmJiYk5iZbnE2NjY2NjY2Nk1OTk5OTk6Cj4+Rj5OPj4+Sj4+P
kpJggmVlZWVlZWVlZWVlZWVlS1OMi41ONTVOjI2NjIyOj0iEYW94eHh3d140NWOLjpRhT4mJjIB/ZQ6J
iYmJiYmJLnscLkVFQkU3YX9hAxp3hWFBd3eJf1SWFHd3al9qancgchwgOCUlKYhlUnmIAFl+YTJra3tk
L5UUa3VMGxsRMB5yHB4lJCVWfwgkIoYbN31lExQHfGQvlRwUUIGDjntrHnIcHiQkInBRAiIic0sdcJSH
lxB8ZC+Oj4+QUQ4QDUEechwgBgUeRJQNARWVGSJnYTKVEHxkL2lra3yXl5aAVR5yHFaUXB0iY5eGl14i
JWdhJpUOY2Qna2tra2tra21tHnIcCyYMCgoKFzIWCgoKUmEJkGJlZCdra2tra2tra20ecn9RUVFRUVFR
UVFRUVFzYQlpbGx1a2tra2tra2trbR5de3x8fHx8e3t7e3t8e4JrIiQkJCQ+SWtra2tra2ttHiIkJCQk
JCQkJCQkJSQkJCQkJCQkJCQlOkZma2tra20eIiQkJCQlJCQkJCQiJCQkJCQkJCQkJCUkJCQ6RUlnbSAk
KiQlJSUlJSUlJSUlJSUlJSUlJSUlJSUlJSUlJTo+IiQ5OTk5OTk5OTk5OTk5OTk5OTk5OTk5OTk5OTk5
OjoAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAACgAAAAwAAAAYAAAAAEACAAAAAAAAAkAABILAAASCwAAAAEAAAABAAAIBwYADwwKABwS
DAAUExIAGxgXABsaGQAkGBEAIiAeACskHwA3IxYAMCQbADgkFwA4JRkAKyUhAC4rKQA0LCYAMS4sAD0t
IgAzMS8AOzErADY0NAA8NjIAOzk5AEA0LABdOiQAXj0oAGI8JQBBQD8ATUE6AGNCLQBoQSgAYkMwAGhJ
NQBsTDgAckcrAH1PMQBzUTwAQkJBAEpGQgBJSEcAW0xDAFZRTgBRUVEAW1paAGBPRQBgUEcAaFZLAGhd
VgByZVwAfWhbAGRjYgBzb2wAfGtgAHNzcwCKVTMAjlo4AJJaNgCSXTsAml45AJRgPgCeYToAoGM+AINi
TQCDZlMAhW5fAJVhQQCZZUQAnGtMAJBrUwCeb1EAkXFbAJ9wUgCNdmgAhnlwAIB/fwCQdGIAlHtrAJh9
bACRf3MAomdCAKJpRgClbUsAp3FPAKJyVACjdlgApXlcAKlzUQCue1sAsH5eAKd8YACofWEAlYF0AJ2H
eACYiH4ApYJsAKuBZgCuhmwAr5J/ALSJbQCyjHMAt5J6ALyUewCFhIIAnJCIAJaWlgCcnJsApZOIAKmS
hACplYgApZ+cALadjQC5loAAvJqEAL6eigC1npAAv6COALagkgC9o5MApqWkAKyopgCrq6sAu6yjALiv
qQC8sqwAtbW1AL23swDCnIQAwJ+KAMGijQDIpY8AxKWRAMWplwDHq5gAyaeSAMqokwDMrZoAz7GfAMKv
owDCtq8AzbOiAMm3rADMua0Axb+7AMu+tQDStqUA0rinANK6qgDVvrAAx8C7AM7EvQDVwbQA0sW8ANfI
vgDbxbYA28a4AN3JvADFxcQAyMfHAM7IwwDMzMsA0cfAANXKwwDSzMkA3M3DAN3RygDU09MA2dTRAN7Z
1QDe3dwA4c/DAOPRxgDk1csA59jPAOjZzwDh19EA5NjQAOTe2gDq3dUA5ODdAO3g1wDu4dkA8OXdAOPi
4gDp5eQA6ujmAOvr6wDx5uAA8+rlAPbv6gD28OwA8PDwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAlZehoaGh
oaGhoaGhoaGhoaGhoaGhoaGhoaGhoaGhoaGYoaGhoaGYoaGhopiYo6SzlaGkr6+vrK+vra+sr6+vr6+v
r6usrK+vr6+vr6+vr6ynrKSsr6+rp6usr6+ns7S0laOvsbGxsbSwsbGxsbGxsbCxs7GxsbSxsbGxs7Gx
tLCzs7Ozs7Szs7Ozs7OytLW0laSxtLSvm5KLkIuSm7G1tbS1tbSqlouLiIuSm7S0tLWsmJqbm5ubmJuk
s7W1tbW1laSxtIdHQjk5OTk5O0WEvLy8t2VCOTs5OTk5QVWqvL2WO0E7Ozs7OztDR4O1vLy+laSxizk5
OVNXX1pTQTk5i728czs5Q1VgYGBHOzlTvLyROTtDQ0NDQ0M5OTtlvL28laSxXzlUqrWzs7S6tGA5VLu8
QjuAvL29vb29m0E5qryRN1+9vLy8vL21czk5s7y8laSxQTqQtbGztbS7vKk5QbG1OTuqvb28vLy9u0M5
mbyROV+9vLy8vLy8tEM5lru8oKSqOTmZtbGzs7W7vLA5OauzOzurvby8vLy8vEU5lruROVW8vLy8vLy8
u185hL28laSjOUGbsbWztbS7vbRCOaO8mpu4vby8vLy8tEM5mLyROV+8vLy8vLy8vF85hL29l6SqOUGb
tLSzs7W7vLRCOaq8vLy7s62qlpGHYjk5tLyNOV+8vLy8vLy8vF85g728laSkOEGbtLS1s7G7vLRCOZu9
vZBVQjk5Ozc5OTtzvLyROVW8vLy8vLy8vUc5hLy9laSqOTqbtLS0tLS1vLRCOaO8kjs3O0NFVV9jc5u8
vLyRN1+8vLy8vLy8vF85g7y+laSpOUGbtLS0s7S1vLRCOaq8YDtfrbS1u7y8vLy8vLyROVW8vLy8vLy8
vV85hL28laSjOUGbsbW0tLO1vLFCOaq8RzuLvby9vLy8u5aRuLyRO1+8vLy8vLy8u1U5g729l6SxOTiS
tbS0tLS0u6s5ObG8QzmRvby8vLy8sUI5tLyROV+7vL28vLy8u0M7kby8l6SxVDljsbS0tLS0un85Rbq8
WjlwvLy8vb28mzk5tbyROV+8vLu8vLy1ljs7pL29nKqvgjk5VG9/goBvWTk5cLy8fzk5Y4CEh3FvRTlF
vLyRN0Jzc3NzZWRfOztVvL29laqxs2U6OTk5OTk5OTlgury8sVQ5OTk5OTk5OUOavLyNOTk5OTk7Ozs5
O1+tvL29l6SttLObhG9lZGRvgqm7vLy8vLWNf3Bwb2+CkrG8vLytiIiRi4iLiIiWq7i8vL29l6qxsbWz
s7O0tLS0s7q8vLy8vLy8vLy8vLy8vLy8vLy8vLy8vLy8vLy8vLy8vb28nKSvtLOzs7Ozs7Ozs7O8vLy7
vLy8u7u8vLy8vLy8u7y8u7y8vLy8vLy8vLy8vL28j6Grr62tra2tq62tra2zu7u7u7u7u7u7u7u7u7u7
u7u7u7y4u7u7u7y7u7u7u7y7jJOpqaqqqqqqqqqqqqqqtbq6urq6urq6urq6urq6urq1tbW1u7W1tbW1
tbW1tbi1iZKTiYmJiYmJiYmJiYmJjZyXnJeenJePj6CxtLG0sbG0tLS0tLS0tLO0tLOztLW0g4l5Gxsb
GxsbGxsbGxslJRsbGyUlJSUlGw6ksbGxsbGts62tsa2ts62xrbGxsbGxcoS3ubm4ubm5ubm5ubm5ubm5
ubm5u7m5thKhq6urq4kpKSkpKXmrpKurq6urq62ta4C3pW2jo6Ojo6Ojo6mgent9o7CwsLC5thKTqaqq
qq54eHh4J2epqampqamqqaurWmSyfBdlZWVlZWVlZUsmJhYFB0mTmpqwthCMmZqTm7m2trm5Ml2ZmZmZ
mZaZmZqbQ1qwfBFYV1dYV1dXRneyubifKgBAkZGxthCEkZGRk7lpMKO5MluRkYh0dHR0c3OWN0WwfAlP
T09PT09Bn76keY64uSsBcYeuthBxh4eHkLlpKJa5MkmHh3QWFhYWFARuNkKwfAk8PDw8PDpqvncuOjpN
uaUDTISutg00QEBMiLhoKJa5MiFAW7e5ubm4ti9zNkKwfAk8PDw8PEKguBQ3Ojw4fbknPoanuEo1NTIP
kLhoIJa+djU1Xbl2e5ubm5GINkKwfAk8PDw8PFCunwMePDw8arkrIlikubm5uZwPi7hoKJa5ubm5ubkr
ExwcHBx0NkKwfAk8Ojo6OjyUuSUCIjojnLkmNj2Zti+JuJwPkLhoKYeRkpGRlLidfHx8eA50NkKwfAk8
CAYGIjxcvpwUAA1mu5wdOj2Ttg5xt5wPkLhoLYaGhoaCiLW4ubm5t3SENkKwfAyXqLAzIjw4e765nai+
sD88PDyXtg1gt5wPi7hoLYaGhoWGhoeHhoeHh4eINkKwfAyHmJhjOj06OWuisKd9RDo6PDyZtgg6sJ0F
KrdoLYaGhoaGhoWGhoaFh4eINkKwfAYaGhoaGhoaGhoZIB8YGhoaGhqKtg05sLilprlpLoaGhoaFhoaG
hYaFh4eINkKwojU1NTU1NTU1NTU1NTU1NTU1NTWcsA05l6Oko6abhYWGhoWGhoaGhoaFh4eINkKwubm5
ubm5ubm5ubm5ubm5ubm5ubm5tyE6PT09PU9XfoGGhoaGhoaGhoaGhoiINjuDi4uLi4uLi4uLi4uLi4eL
i4uLi4uLh1A8PTw8PDw9PVdlgYaGhYaGhoaGhoiINjg6PDw8PDw8Ojw8PDw8PDw8PDw8PDw8PDw8PDw8
PDw9PTw8UGKAhYaGhoaGhoeINjg6PDw8PDw8PDw8PDw8PDw8PDw8PDw8PDw8PDw8PDw8PDw8PT09VmJ+
gYWGhoeINjg6PDw8PDw8PDw8PDw8PDw8PDw8PDw8PDw8PDw8PDw8PDw8PT09PT09PV9ifoaINjo6PT09
PT09PT1CPT09PT09PT09PT1CPT09PT09PT09PT09PT09PT09PT09PVJfODo9T09PT09PT09PT09PT09P
T09PT09PT09PT09PT089PT1QUD09PT09UT09PVJWODxPUFBQUFBQUFBQUFBQUFBQUFBQUFBQUFBQUFBQ
UFA9UFBQUFBQUFBRUT1SUlJSAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAKAAAAIAAAAAAAQAAAQAIAAAA
AAAAQAAAEgsAABILAAAAAQAAAAEAAOrq6gD28OwA0se/AOXl5QCgYz4At45zAKOjowC8nIcAoWVAANC0
ogDx6OIAwZqBAOTRxQDBwcEAuJN8APDl3gDKqZQAklk1AO3g2ADNrpkAtqKXAFc1IQBsQykA4NTLAO7i
2ADm1coA8fHxAHhjVwDiz8IA7N/WAMe9tgDy6uQAPz8/AJhmRQDp2tEAS0lIAMe9tQDb29sA18vDAO/v
7wCLVjMAtYZoAIVxZADXwLEA7uLbAM+wngDj1s8A1r2sAODMvwDm2tEA+vr6AN3KvgDf0soA09PTAOfe
2QDp5uUApWxJAHFrZwD19fUA9eznAK+WhgDp3dQA49nUANnCswDFoYsAvb29AObWzAAVFRUAd3d3AAoH
BQBVRToA5NfQANW+sACVlZUA3si6AO3g1gDm2dEA2c7GAKaJdwCXfW0A9e3oAIiHhwCjaEQA2cW5APHm
4ADo2M0AVVVVAO/k3QDn2M4ApGtGAKp0UgCse1sAz8K5AMvLywDg1MwAq4FmAJpeOQDDppIAsrGxAGhX
TACgaUYAaV9XAPXu6ADq3tYAnJycAMiwoADq3NMAamdlANzMwQDy7ekAxKydAMy5rADTuKYAhVIxAKqf
lwCpfmIA0LioACEdGwD27uoAnmE8AKJnQgCUWzcA3NDJAM+xnwDezsUAnYNzAOTTyAC3qaEAroZsAOfb
0wCncVEAo3hcAOjd1ACeb1AA5d/cAMuvnQApKSkANS0nAIBeSgDm2tAAlY6JAFtNRAD17uoAlXNdAM62
pgCNWjoAo3VYAOTY0AAwIRgA0LKgAJ1gOgDz6+YA7uPcAJ5iOwDh0sgAyberANrMwgDFtKkArZB+AMOw
pADJqJMAyaaRAN/TygBcUUsA18e9ANvQyADs3tUAz87NANvQxwDz7OcAp29NABwSDADi2NIAs56QAHVx
bwDo3tcA1LupANbJwQDLs6UA8+vlAOTa1ACMe3EAgX99AH5sYACOY0gA59fOAO/j2wDOrpsA39HIAKGX
kQDTva4ADg0NAD82MADLqpYAr31dAHlWQABmT0AAnmA6AJ5hOwDu4dgAnmA7AN3RygDq3dYA28/IAMys
mADd0soA3dLJAPLp5ADs3dQA7uLaAJ9hOwDr6+sA4dfQALi3twDm4uAAxLeuAKGNgQDJv7cAq3dXAOPV
zADs4dkA4NXOAJZfPgCcYDsAmGJAAJddOADBqJgA9u/pAKRqRwDs7OsAz7uvANS7qwCPVzQAgFQ4AIda
PQDo3dYAnF85AOrf2ADLrJcA7uLZAO3g2QB4SiwA3tHKAOno5wCka0cA49vWAKNpRACgaUgAy6uXAO7h
2QCeYToAyqiTAOzs7ACSXTsA9u/qAAAAAAAkXFxcXNkkJCQeJB4eJB4eHh4kJCQkHh4kHiQeJCQeHiQk
Hh4eHh4eHh4kHh4eHh4eJB4kHiQeJB4eHiQeHh4kHh4kHiQeHh4eHh4eJB4eHh4eJCQeJCQkHiQeHh4e
Hh4kHiQkHh4eHiQeHiQeHh4kJB4kHh4eHh4e2VwCJjQxXtkCAgImJk16ycnJyc3NzsnNycnJycnJyc7J
ycnOycnJyc3JycnJycnJyc3JycnOycnJzsnNyc3JycnJyc3Jyc3Jzc3Jyc3JycnJzcnJycnOycnNyc7J
yc7JycnJycnNycnJycnOycnJycnJycnJycnJzc7JycnJyaLbTD0Sx7qEHgICsSZNpRcXF15eF14XXl5e
F15eFxdeXl5eXl5eXhdeF14XF15eF14XF15eF14XFxdeFxcXFxcXFxcXXl5eF15eXl5eF15eXl4XXl5e
F14XXl4XFxdeXl5eXl5eF15eXl5eXl4XFxdeF15eXl4XF14XXl4XXhcXLpM9Evnv0YQeXAKxJk2i3S5H
Li4uLi4uLi4uLi4uLkcuLi5HLi4uLi4uLkdHLkcuLi4uLi4uLi4uLi4uLkcuLi4uLi4uLi5HLkcuLi4u
Li4uLi4uLi4uLi5HLi4uLi4uLi4uLi5HLi4uLi4uLi4uLi4uLi4uLi4uLkdHLi4uLi6ThB350bq6hCQC
AiZNel6TTDGLTExMTExMTExMTExMTExMi0xMTExMMTFMTDFMTExMTEwxTExMTExMTItMTExMTExMTEyL
TExMTExMTEyLTExMTExMTExMTExMMUxMTExMTExMTDGLTEwxi0xMTExMi0xMMTFMTExMTEwxTExMTIEd
x+/RurqvHlyxJk00LkyBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGB
gYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGBgYGB
gYGBgYGBZ/n577q6uq8kAgJNel6ThMrKysrKysrKyspnysrKysrKysrKymfKymfKZ8pnysrKymdnZ8rK
ymfKZ8rKymfKymfKZ8rKZ8rKymfKymdnysrKysrKyspnysrKysrKymfKymfKymfKZ8rKZ8rKysrKZ8rK
ymdnysrKysrKymdnysrH+e8supgP6yQCsU2iLjHKEhLHx8cSEhLHEhISEhISxxLHEscSEhISEhLHEhIS
EhLHEscSEscSxxISEsfHEscSEhISxxISEhISEhISxxISEscSEscSEhLHEhISEsfHEscSxxISEhLHEscS
EscSEhISxxLHEhISEhISEhLHEscSEvnv0bq6V1ev2QImTaKTgUv5+fn5GPn5GMfv+cf5x/kY+cfvGPnH
x8f5+cf5+RgY+fn5+fnv+RjH+Rj5GPnH+Rjv+e/H+fn5+cf57/n5+Rj5x8fv+fn5x8f5x/n5+e/5+cfH
+Rj5+fnHx8f5+fn5x8f5x8f57+/H7xj5x8f5x/kY+e+6urpXV6/ZAibLokeBHfnHGMf5+cf5GO/5xwwr
KysrKysrKysM+RjH7/nHGMf5x8f57/n5+fkYx8fH+fkY+fnHSisrKysrKysrKysrWMf5xxj5+fn57/nH
GMfv+cf5+fkY+cfH+e/578f5x/nvx+/H+fn57+/Hx/nH+cfH+fnH0Sy6mFdXr9kCJsuiR4Ed78f5+cf5
i4cOc/39/f39/f39/f39/f39/V8HK1dQUFBQZlBmUGZQUFBQUFBQmgdf/f39/f39/f39/f39/f39/SFf
B5pQUFBQUFBQUGZQUAdfX19fX19fX19fX19fX19fX19fX18OYYczUFBmUFBQZlDjduP+Af6pHgImqKJH
gUvvGO/vDAUh/f39/f39/f39/f39/f39/f39/f39IQ5U/v7+/v7+/v7+/v7+PV/9/f39/f39/f39/f39
/f39/f39/f39/V89/v7+/v7+/v7+/f39/f39/f39/f39/f39/f39/f39/f39/f0hDjP+/v7+/v7+AQEB
AW3ZAibLF0eBS/n5GIch/f39/f39/f39/f39/f39/f39/f39/f39/SE//v7+/v7+/v7+/n4h/f39/f39
/f39/f39/f39/f39/f39/f39/SF+/v7+/v7+/v79/f39/f39/f39/f39/f39/f39/f39/f39/f39/V89
/v7+/v4BAQEBbR4CJsuiR4Ed+fmH/f39/f39/f39/f39/f39/f39/f39/f39/f39/f0//v7+/v7+/v5+
If39/f39/f39/f39/f39/f39/f39/f39/f39/SFU/v7+/v7+/v39/f39/f39/f39/f39/f39/f39/f39
/f39/f39/SF+/v4BAQEBAQFt2QImy6JHgR0YDCH9/f39/f39/f39/f39/f39/f39/f39/f39/f39/SE9
/v7+/v7+/l/9/f39/f39/f39/f39/f39/f39/f39/f39/f39/Q7+/v7+/v7+/f39/f39/f39/f39/f39
/f39/f39/f39/f39/f39/YVU/v7+AQEBAW3ZAibLF0eBHdwF/f39/f39/f2SBUAHQCsrKysrQAdABYP9
/f39/f39/Q7+/v7+/v4z/f39/f39/YUFYWFhMzMzMzMzMzNhYV/9/f39/f39/VT+/v7+/v79/f39/SFf
X19fX19fX19fX19fX19fhf39/f39/f39/WH+/v4BAQEBbR4CJsuiR4ESWP39/f39/f2ADMfv+fnH+cf5
x8fv+VQK/j0F/f39/f39/VT+/v7+/g79/f39/f0//v7+/v7+/v7+/v7+/v7+/lRh/f39/f39dP7+/v7+
/v39/f39X/7+/v7+/v7+/v7+/v7+/v7+VD9f/f39/f39IVT+AQEBAQFtHgImpaKTgRKH/f39/f39h8fH
+fnHx/nH+fn5+fn5Ch/+/v6H/f39/f39dP7+/v7+g/39/f39Yf7+/v7+/v7+/v7+/v7+/v7+/v4F/f39
/f0H/v7+/v7+/f39/f1f/v7+/v7+/v7+/v7+/v7+/v7+/v4H/f39/f39dP7+AQEBAW3ZAibLF0eBSwX9
/f39/XMY+RjHx8fH+e/H7/nHx/nPH/7+/v5f/f39/f0O/v7+/v79/f39/f1U/v7+/v7+/v7+/v7+/v7+
/v7+/j/9/f39/V/+/v7+/v79/f39/V/+/v7+/v7+/v7+/v7+/v7+/v7+/v5f/f39/f0F/v4BAQEBbR4C
Jsuik4Edkv39/f39dPnv+e/vx8f5GO/Hx8fH+R+z/v7+/j/9/f39/YP+/v7+Pf39/f39hf7+/v7+/v7+
/v7+/v7+/v7+/v7+fv39/f39X/7+/v7+/v39/f39X/7+/v7+/v7+/v7+/v7+/v7+/v7+/nT9/f39/YX+
/gEBAQFt2QImy6JHgR39/f39/f2L+fkY+cf5+fnH+fn5+fnHlzv+/v7+Pf39/f39/f7+/v4z/f39/f1f
/v7+/v7+/v7+/v7+/v7+/v7+/v7+/f39/f1f/v7+/v7+/f39/f1f/v7+/v7+/v7+/v7+/v7+/v7+/v7+
Pf39/f39/f7+AQEBAW3ZAiaookeBHf39/f39/e/5+cfv+cfHxxjHx+/HGO87Zv7+/v7+/f39/f39/v7+
/jP9/f39/V/+/v7+/v7+/v7+/v7+/v7+/v7+/v79/f39/YX+/v7+/v79/f39/V/+/v7+/v7+/v7+/v7+
/v7+/v7+/v7+/f39/f392/4BAQEBbdkCJsuiR4FI/f39/f2S+cfH+cf5x/n5+fn5+cf5GDtm/v7+/v79
/f39/f1+/v7+M/39/f39X/7+/v7+/v7+/v7+/v7+/v7+/v7+/v39/f39/f7+/v7+/v39/f39X/7+/v7+
/v7+/v7+/v7+/v7+/v7+/v5f/f39/f0z/gEBAQFt2QImy6JHgUj9/f39/XP5+e/5x/n5GMfHx8cYGO/5
UI7+/v7+/oX9/f39/TP+/v4z/f39/f1f/v7+/v7+/v7+/v7+/v7+/v7+/v7+/f39/f2D/v7+/v7+/f39
/f1f/v7+/v7+/v7+/v7+/v7+/v7+/v7+/l/9/f39/TP+AQEBAW3ZAibLokeBSP39/f39c/nHxxj5x/nv
x/n5x/nHGPlQ/v7+/v7+X/39/f39M/7+/lQFX19fX3T+/v7+/v7+/v7+/v7+/v7+/v7+/jP9/f39/V/+
/v7+/v79/f39/V/+/v7+/v7+/v7+/v7+/v7+/v7+/v7+X/39/f39M/4BAQEBbR4CJqWiR4FI/f39/f1z
xxjH+fnvGMf5x+/HGPnH+VD+/v7+/v5f/f39/f0z/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+
P/39/f39X/7+/v7+/v39/f39X/7+/v7+/v7+/v7+/v7+/v7+/v7+/v5f/f39/f0z/gEBAQFtHgImy6JH
gUj9/f39/XP57/kYx/n5+Rj5x+/v+cf5UHb+/v7+/l/9/f39/TP+/v7+/v7+/v7+/v7+/v7+/v7+/v7+
/v7+/v7+/v4O/f39/f0H/v7+/v7+/f39/f1f/v7+/v7+/v7+/v7+/v7+/v7+/v7+/l/9/f39/TP+AQEB
AW3ZAibLokeBSP39/f39c8fHx/n5+Rj5+RjH+fn5+RhQjv7+/v7+X/39/f39M/7+/v7+/v7+/v7+/v7+
/v7+/v7+/v7+/v7+/v49Yf39/f39/XT+/v7+/v79/f39/V/+/v7+/v7+/v7+/v7+/v7+/v7+/v7+X/39
/f39M/4BAQEBbdkCJsuiR4FI/f39/f1z7+/5x8f57/n578fv78fH+Ttm/v7+/v5f/f39/f0z/v7+/v7+
/v7+/v7+/v7+/v5+MzOHYWEOX1+D/f39/f39/f39VP7+/v7+/v39/f39X/7+/v7+/v7+/v7+/v7+/v7+
/v7+/v5f/f39/f0z/gEBAQFtHgImy6JHgUj9/f39/XMY+e8Y+RjH+cf5+cf5+RjHO1D+/v7+/l/9/f39
/TP+/v7+/v7+/v7+fmEFX/39/f39/f39/f39/f39/f39/f39/Q7+/v7+/v7+/f39/f1f/v7+/v7+/v7+
/v7+/v7+/v7+/v7+/l/9/f39/TP+AQEBAW3ZAibLF0eBSP39/f39c/n57/n5x8f5x+/5x8f5GPmXO/7+
/v7+X/39/f39M/7+/v7+/v7+dIX9/f39/f39/f39/f39/f39/f39/f39/f0hVP7+/v7+/v79/f39/V/+
/v7+/v7+/v7+/v7+/v7+/v7+/v7+X/39/f39M/4BAQEBbdkCJsuiR4FI/f39/f1z7/n5+fn5+fnHx8fH
+cf5GB+z/v7+/v5f/f39/f0z/v7+/v7+VF/9/f39/f39/f39/f39/f39/f39/f39/f39g37+/v7+/v7+
/v39/f39X/7+/v7+/v7+/v7+/v7+/v7+/v7+/v5f/f39/f0z/gEBAQFtHgImy6JHgUj9/f39/XP5+fkY
+cf5x/kY+fnH+Rj5zx/+/v7+/l/9/f39/TP+/v7+/v5f/f39/f39/f39/f39/f39/f39/f39/f39hWFU
/v7+/v7+/v7+/f39/f1f/v7+/v7+/v7+/v7+/v7+/v7+/v7+/l/9/f39/TP+AQEBAW0eAialokeBSP39
/f39c/nHx+/5x8fH78fH+fn578cKz/7+/v7+X/39/f39M/7+/v7+dP39/f39/f39/f39/f39/f39/f0h
X18Hh37+/v7+/v7+/v7+/v79/f39/V/+/v7+/v7+/v7+/v7+/v7+/v7+/v7+X/39/f39M/4BAQEBbdkC
JsuiR4FI/f39/f1zx/n5x/n5+ccY+e/H+fn5+VQK/v7+/v5f/f39/f0z/v7+/v6D/f39/f39/f1fXwVh
YYczM37+/v7+/v7+/v7+/v7+/v7+/v7+/v39/f39X/7+/v7+/v7+/v7+/v7+/v7+/v7+/v5f/f39/f0z
/gEBAQFtHgImy6JHgUj9/f39/XPHx+/Hx/n57/nHx/n5+cf5D1T+/v7+/l/9/f39/TP+/v7+Pf39/f39
/YMz/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/f39/f1f/v7+/v7+/v7+/v7+/v7+/v7+/v7+
/l/9/f39/TP+AQEBAW0eAibLokeBSP39/f39c/n57+/H78f5x/nH+cfHx/lXD/7+/v7+X/39/f39M/7+
/v50/f39/f0hVP7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v79/f39/V/+/v7+/v7+/v7+/v7+
/v7+/v7+/v7+X/39/f39M/4BAQEBbR4CJsuiR4FI/f39/f1z+Rj5GMcY+fnvx/n57/n5x++Yjv7+/v5f
/f39/f0z/v7+/mH9/f39/Q7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v39/f39X/7+/v7+
/v7+/v7+/v7+/v7+/v7+/v5f/f39/f0z/gEBAQFtHgImy6JHgUj9/f39/XMY+e/5+fnvx8cYx8fH7/n5
77o7/v7+/oX9/f39/TP+/v7+B/39/f39h/7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/f39
/f1f/v7+/v7+/v7+/v7+/v7+/v7+/v7+/l/9/f39/TMBAQEBAW3ZAibLokeBSP39/f39kvnv+e/H7/nH
x/kY+RgYx+/v0bP+/v7+/f39/f39fv7+/v5f/f39/f0z/v7+/v7+/v7+/v7+/v7+/v7+/j/9/f39/TP+
/v7+/v79/f39/V/+/v7+/v7+/v7+/v7+/v7+/v7+/v7+g/39/f39M/4BAQEBbdkCJqWiR4Ed/f39/f39
x/n57/nH+fn5+e/H78f57/n5z/7+/v79/f39/f3+/v7+/l/9/f39/TP+/v7+/v7+/v7+/v7+/v7+/v7+
Yf39/f39M/7+/v7+/v39/f39X/7+/v7+/v7+/v7+/v7+/v7+/v7+/v79/f39/f3b/gEBAQFtHgImy6KT
gR39/f39/f0Y+cfvGPkY+e/5+RgY+fnvx8cK/v7+Pf39/f39/f7+/v7+X/39/f39M/7+/v7+/v7+/v7+
/v7+/v7+/v5h/f39/f0z/v7+/v7+/f39/f1f/v7+/v7+/v7+/v7+/v7+/v7+/v7+Pf39/f39/QH+AQEB
AW0eAiaookeBHZL9/f39/XTH+fn5+fnH+e/5+cf57/n5+Vf+/v50/f39/f2D/v7+/v4H/f39/f1h/v7+
/v7+/v7+/v7+/v7+/v7+/g79/f39/TP+/v7+/v79/f39/V/+/v7+/v7+/v7+/v7+/v7+/v7+/v50/f39
/f2F/v4BAQEBbdkCJsuik4EdgP39/f39gPnHxxjvx/nHx/kYx+/H7/nvujv+/l/9/f39/QX+/v7+/mH9
/f39/Q7+/v7+/v7+/v7+/v7+/v7+/v7+X/39/f39M/7+/v7+/v39/f39X/7+/v7+/v7+/v7+/v7+/v7+
/v7+/l/9/f39/QX+AQEBAQFt2QImy6JHgR2H/f39/f39h+/H78fv7/n5x/nH+Rj5+fnRs/50/f39/f39
h/7+/v7+dP39/f39IVT+/v7+/v7+/v7+/v7+/v7+/j39/f39/f0z/v7+/v7+/f39/f1f/v7+/v7+/v7+
/v7+/v7+/v7+/v6H/f39/f39h/7+AQEBAW0eAibLokeBHQz9/f39/f39BQz5GPn5+fnHGPnHx8fv+flC
Dv39/f39/f09/v7+/v5+/f39/f39gz3+/v7+/v7+/v7+/v7+/v5UDv39/f39/f7+/v7+/v79/f39/V/+
/v7+/v7+/v7+/v7+/v7+/v4/X/39/f39/f1UAf4BAQEBbdkCJsuik4Ed+QX9/f39/f39/XNAB4crKysr
Kysrh0AHc/39/f39/f39Bf7+/v7+/v6F/f39/f39/YMHYXQzMzMzMzN0YWEHX/39/f39/f2D/v7+/v7+
/v39/f39hWFhYWFhYWFhYWFhYWEHX1+D/f39/f39/f39Dv4B/gEBAQFt2QImyxdHgR3HDCH9/f39/f39
/f39/f39/f39/f39/f39/f39/f39/f09/v7+/v7+/mH9/f39/f39/f39/f39/f39/f39/f39/f39/f39
/XT+/v7+/v7+/f39/f39/f39/f39/f39/f39/f39/f39/f39/f39/SFU/v7+AQEBAW3ZAialokeBEsf5
h/39/f39/f39/f39/f39/f39/f39/f39/f39/f39dP7+/v7+/v7+VIX9/f39/f39/f39/f39/f39/f39
/f39/f39/f2D/v7+/v7+/v79/f39/f39/f39/f39/f39/f39/f39/f39/f39/f0hfv7+/gEBAQEBbdkC
JqWiR4Ed7xjHhyH9/f39/f39/f39/f39/f39/f39/f39/f39/XT+/v7+/v7+/v7+fiH9/f39/f39/f39
/f39/f39/f39/f39/f39g1T+/v7+/v7+/v39/f39/f39/f39/f39/f39/f39/f39/f39/f39g37+/v7+
/gEBAQFt2QImy6JHgR35xxj5DAX9/f39/f39/f39/f39/f39/f39/f39/Q49/v7+/v7+/v7+/v7+foX9
/f39/f39/f39/f39/f39/f39/f39IWH+/v7+/v7+/v7+/f39/f39/f39/f39/f39/f39/f39/f39/f39
BZD+/v7+/v7+AQEBAW0eAibLokeBHfn5x+/H+ViHBZL9/f39/f39/f39/f39/f2FgJA9/v7+/v7+/v7+
/v7+/v7+/nQOhf39/f39/f39/f39/f39/f2DDnT+/v7+/v7+/v7+/v4FX19fX19fX19fX19fX19fX19f
X19fXwdhM1T+/v7+/v7+/v4BAQEBbdkCJssXR4Ed+fnv+fn5+fn5x/lYKysrKysrKysrKytYx/nHVP7+
/v7+/v7+/v7+/v7+/v7+/v7+/v4zMzMzMzMzMzMzMz3+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+
/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/gEBAQFt2QImy6JHgUv5GMf57xjHx+8Yx/kYx8f5x8fH+e/H
x/n5+e+6UP7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+
/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v4BAQEBAW3ZAibLokeBHfn5+e/5+fn5x/nH+fn5
+fnv+fnHx/nH+Rj5xxgK/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+
/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v4BAQEBbR4CJsuik4Edx/n578f5
+fnHGPnH+Rj5x+/57/n5x/nH+fnvxw9m/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+
/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/gEBAQFt2QImyxdH
gRL5+fnv+e/5+fn5+fn5x/nH+fn5+e/5x/n5+fn50Zf+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+
/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v4BAQEB
AW0kArFN8i5MyktLS0sdSx0SSx0dSx0dHR1LHUtLSx0dHR1LHR1LD2ZQZmZmUGZQZmZQZlBmUFBQUGZQ
UFBQZmZmUGZQZmZQZmZmZlBQZmZmUGZmZmZmUFBmZlBQZmZmZmZQZmZQZmZQUFBmZlBmUFBmUFBmZlBQ
ZlBQjv7+/gEBqSRcApzLF7lq0NDQ0NDQPdDQ0NDQ0NDQ0NBq0NDQ0NDQ0NDQ0NAdHzs7qTs7O6k7Ozs7
Ozs7Ozs7Ozs7Ozs7Ozs7O6k7Ozs7Ozs7Ozs7Ozs7Ozs7Ozs7Ozs7Ozs7Ozs7Ozs7Ozs7Ozs7Ozs7Ozs7
qTs7Ozs7Ozs7OztQUFBmdv6X11yksZya21giIiIiIiIiIiIiIiIiIiIiIiIiIiIiIiIiIiIiIiK6l5ez
s5eXs7Ozl5eXs5eXs5ezl5eXs7OXl7Ozl7OXl7OXl5eXs5eXl7OXs7OXl5eXl5eXs7OXs5eXl7OXs5ez
s7OXl7OXl7Ozl5ezs5ezl5ezl5c7Ozs7UB/X2VykM3yaQlW5WFVVVblVVVW5VblYVVVVWFVVVVVYVVVV
WFW5VSIKHx8fHx8fH88fHx8fHx/PHx/PH88fH88fHx8fHx/PHx8fHx8fHx/PHx/PHx8fHx/PHx8fHx8f
zx8fHx8fHx8fHx8fHx8fHx8fHx8fHx8fzx8fH7OXs5c7Cp3mXFykbBx+GRkZGRkZGRkZGRkZGRkZGRkZ
GRkZGRkZGRkZGRkZGR0KCgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoK
CgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoKCgoKCh8fs7MKn28kP1MzMBwMDAwMDH4MDAwM
fgx+DAwMDAwMfgx+DAwMDAwMDAwMQldUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRU
VFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVAoKCgoKz1Sfm+ZIXFMzMBwc
HBwcHBwcHBwcHBwcHBwcHBwcHBwcHBwcHBwcHBwcIldXVw9XDw8PDw8PD1cPVw8PDw8PDw8PDw8PDw8P
Vw9XDw9XDw9XVw9XVw8PD1dXD1dXD1cPDw8PD1cPDw8PVw8PDw8PDw8PDw8PDw9XDw9XD1RUVAoKV26d
m+ZIP1MzMDAwMDAwMDAwMDAwMDAwMDAwMDAwMDAwMDAwMDAwMDAcHSwsLCwsLCwsLCwsLCwsLCwsLCws
LCwsLCwsLCwsLCwsLCwsLCwsLCwsLCwsLCwsLCwsLCwsLCwsLCwsLCwsLCwsLCwsLCwsLCwsLCwsLCyY
V1cPD1Qsf5+yb+ZIP1NKSkpKSkpKSkpKSkpKSkpKSkpKSkpKSkpKSkpKSkpKSkp+x9zw3Nzc3Nzc3Nzc
3Nzc8Nzc3Nzc3Nzc+fn53Nzw3Nzc3Nzc3Nzc8Nzc8Nzc3Nzw3PDw3Nzw3Nzc8Nzc3Nzc3Nzc3Nzw3Nzc
3Nzc3PDc3NHRLLpXV9wUbp+Qb+eQrWVlZWVlZWVlZWVlZWVlZWVlZWVlZWVlZWVlZWVlZWVlZWU5OTk5
OTk5OTk5OTk5OTk5OTk5OTk5OTk5a65cHR0dph0dph1nHR0dHR0dph2mHWcdHR0dHR0dph0dHR0dHaYd
HaYdHR0dHR0dph2mZ2cdEhLc8NHR7RTibmmydOIq////////////////////////////////////////
////////////////////////////////////////RXJqampqampqampqampqampqampqampqPWpqampq
ampqampqampqampqampqamo9amo9PWqmph0dEvBnreLibmm+b70gICAgICAgICAgICAgICAgICAgICAg
ICAgICAgICAgICAgICAgICAgICAgICAgICAgICAgICAgICAgwP+/f0wiIiIiIiIiIiIiIiIiIiIiIiIi
IiIiIiIiIiIiIiIiIiIiIiIiIiIiIiIiIiIiIiIiImpqatDKZ4EHFOLibqIA8wMDAwMDAwMDAwMDAwMD
AwMDAwMDAwMDAwMDAwMDAwMDAwMDAwMDAwMDAwMDAwMDAwMDAwMDAwMDA/MN/79yWFW5WFhYWFhYWLlY
WFi5uVVVVVVVVVVVVVVVVVVCWFhYWFhYWFhYWFhYuVhYWFhYWFhYWCIiImpqMTytQGHiNPz8/Pz8/Pz8
/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/A3/v3JCGUIZ
QhlCQkJCQkIZQnIjIyMjIyMjIyMjIyMjIL1+GUIZQhlCGUIZQkJCQkIZGRlCQkJCuVhYIiJHPAetQGHL
/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8
Df+/cn5+fn5+fn5+fn5+fn4Xtf//////////////////a35+fn5+fn5+fn5+fn5+fn5+fn5+fhkZQkK5
WNuePAcHQE38/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8
/Pz8/Pz8/PwN/79yDAwMDAwMDAwMDAwMQlhyICAgICAgICAgICAgRf85DAwMDAwMDAwMDAwMDAwMDAwM
DAwMfn4ZGRlCfk4OPAcHnPz8/ABRtn9sMGxsbGxsbGxsbGxsMGxsbGxsbGxsbGxsbGxsbGxsMGzbrzY2
NjY2NjY2NjY2NjY28/z8/A3/v60cHBwcHBwcHBwcHBzW/Pz8/Pz8/Pz8/Pz8/Px1/zkcHBwcHBwcHBwc
HBwcHBwcHBwcHBwcDAx+fhmaTp4ODgex/Pz8AP//Y0BAQEChQEBAQEBAQEBAQEBAQEBAQEBAQEBAG8DA
wMDAwMAgY38wMDAwMDAwMDAwMDA3/Pz8Df+/vTAwMDAwMDAwMDAwMIb8/Pz8/Pz8/Pz8/Pz803X/OTAw
MDAwMDAwMDAwMDAwMDAwMDAwMBwcHAwMDAx9Tk4FDqT8/PwAQ/9jCwsLCwsLCwsLCwsLCwsLCwsLCwsL
CwsOG4lF////////////Q2utSkpKSkpKSkpKSjf8/PwN/7+9SkpKSkpKSkpKSkpKNvz8/Pz8/Pz8/Pz8
/Pz8df9rSkpKSkpKSkpKSkpKSkpKSkpKSkpKSjMwMDAcM4NfX4CAXPz8/ABD/8QFBQUFBQUFBQUFBQUF
BQUFBQUFBQUFgIm/QyBWZWUjIEO//////7+1Pz8/Pz8/Pz9T1vz8/A3/v9g/Pz8/Pz8/Pz8/Pz/1/Pz8
/ADz0/zl/Pz8/NN1/xs/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/U1NTSkpTj4ODc3NI/Pz8AEP/xCkpKSkp
KSkpKSkpKSkpKSkpKSkpKYPAwFFipyUAACVdYrbAv////78qLy8vLy8vLyvW/Pz8Df+/2C8vLy8vLy8v
Ly8vL7T8/PwDa2VyfHw2/Pz8/HX/ZS8vLy8vLy8vLy8vLy8vLy8vLy8vLy8rPz8/Pz8hhYWSkub8/PwA
Q/9GwsLCwsLCwsLCwsLCwsLCwsLCwsKFiVGnGjI6J/z8GjoyJ11EQ////0UqcHBwcHBwsNb8/PwN/7/Y
cHBwcHBwcHBwcHBwrPz8/AP//7dwcLz8/PzTdf9lcHBwcHBwcHBwcHBwcHBwcHBwcHBwsOcvLy8rSLi4
9/eFb/z8/ABD/xZaWlpaWlpaWlpaWlpaWlpaWlpahSNiGjInANPT09PT09MaMvwGiP///0U8lZWVlZVw
1vz8/A3/v32VlZUJlZWVlQmVlQnU/Pz8A7//twmVvPz8/Px1/2WVlZWVlZWVCWG3KioqKioqKioqKioq
Kiq1POfn6t7gISGy/Pz8AEP/Fao4ODg4ODg4ODg4ODg4ODg4OGSjQTIa0/z8Jxo6Ohr8/NP8GjpiiP//
/0a7u7u7u5WG/Pz8Df+/fbu7u7u7u7u7u7u7u938/PwDv/8bLbt8/Pz803X/Y7u7u7u7u7u7Tv//////
/////////////0OjcHAokf393rL8/PwAQ/8VCAgICAgICAgICAgICHgICHh4wGI6J/z8GhrW1VFRQQMa
J/zTJzoGQ///vwfB+Pj4h4b8/PwN/79P+Pj4+Pj4+Pj4+PjuXvz8/AO//xv4+Hz8/Pz8df9j+Pj4+Pj4
zMxORUVFRUVFRUVFRUVFRUX/q6MJCXEo6Hl5afz8/ABD/xWZmZmZd8bSmdKZxtJ3mZnGmZFRGif8/Bol
aEa44HeKowYDGvz8GidrRf//wPv7+xDMhvz8/A3/v0/7EPsQ+xD7EBD7+8Gi/Pz8A7//GxAQbPz8/NN1
/2MQEBAQ+xB88wMlJSUlJSUlJSUlJSUlBkO/o5V7cSjoEXlp/Pz8AEP/Ffr6+sj6xvrGxfrG+vrFxfqZ
jSUn/PwnXSOJYPrGxsX6Fq5dOvzTOl2I//+J+6D7+8yG/Pz8Df+/T/v7+/v7+/v7+/v7EDT8/PwDv/8b
+/ts/Pz8/HX/Y/v7+/v7+8n8/Pz8/Pz8/Pz8/Pz8/PzVQ0ONlS1xKOgReWn8/PwAQ/8VxfrGxsj6+sX6
+sXF+sXGyBaMGvz8GiUjq3HGxsj6xvrG3hsAOtMnGmv//4n7+/v7zIb8/PwN/0XAjUZGRkZGRkZGffsQ
NPz8/AO//xv7+2z8/PzTdf+UjUZGRkZGf/z8/Pz8/Pz8/Pz8/Pz8/F0qt06VLXEo6BF5afz8/ABD/xXF
+vrFxfrF+vr6xvrG+vr6xA0a/CcaUUUVlsb6xsj6+sb6FmgyJ9MyYnX/lKH7+/vMhvz8/EH/////////
//////+3+xA0/Pz8A7//G/v7bPz8/ABD//////////9R/Pz8/Pz8/Pz8/Pz8/Pz8hgm7LXstcSjoEXlp
/Pz8AEP/Ffr6+vrFxsb6+vrI+vr6xvpPNSf8GiWIRRbsxcj6+sbFyPooY/M60zpdwP+UKfv7+8yG/Pz8
pyMjIyMjIyMjIyD/RSr7EDT8/PwDv/8b+/ts/Pz802UjIyMjIyMjIGL8/PxBaGKT1NTU1NTU1Kx8e7st
lS1xKOgReWn8/PwAQ/8V+vr6xvrF+vr6xcbF+sXF+jzW/Pw6aEX/FsX6xcX6xsX6xmAW1Tr8JyUj/6sI
KaD7zIb8/PzTAAAAAAAAAAAAJf//KvsQNPz8/AO//xv7+2z8/Pz8AAAAAAAAAADz0/z8/FZFwBAQEBAQ
EBDB+O67uy17e3Eo6BF5afz8/ABD/xX6yMb6xvr6xvr6+sXF+vr64tP8Jyc5//+U6Pr6xcXGxcXFxZGM
Gif8AFb/lGAEKaHMhvz8/Pz8/Pz8/Pz8/Pw1/0Uq+xA0/Pz8A7//G/v7bPz8/Pz8/Pz8/Pz8/Pz8/Pz8
Vv/Anp6enp6enp6ePDw8QJV7cSjoEXlp/Pz8AEP/Ffr6yMX6yMbFxcbG+sXFxfpu0/wnJzn//0UW+sj6
+sX6xcX6kYwaJ/wAVv+UyMgEKaCG/Pz8/Pz8/Pz8/Pz8/DX//yr7EDT8/PwDv/8b+/ts/Pz8/Pz8/Pz8
/Pz8/Pz8/PxW/0V1dXV1dXV1dXV1Q4lley1xKOgReWn8/PwAQ/8Vxcb6+sj6+sXG+sX6+vrGxTzWJ/wa
aP///5Th+vrF+sb6+mAWYjonJyUj/6v6+sgEKYb8/Pz8/Pz8/Pz8/Pz8Nf9FKvsQNPz8/AO//xv7+3z8
/Pz8/Pz8/Pz8/Pz8/Pz8/CP/////////////////v42Ve3Eo6BF5afz8/ABD/xX6xfr6+vr6+sb6yPr6
+vrFTzUn/Bo1iP///xb6xcj6xvqWeaMDOtM6XcBFFsX6yMXk1Pz8/KcjVhRIK4b8/Pw1//8q+xA0/Pz8
A7//G/v7CUhISEhISEhISEhISOe0/Pz8QWgGaAZoBmgGaAYGRL9Do3t7cSjoEXlp/Pz8AEP/FcX6+vrI
+vrS0tLF+sX6+vrEXRr8Jye2v///Ravxefr6+iiUaDIn/DJidavhxcXF+lI0/Pz8Qf+/T/sQrPz8/DX/
RSr7EDT8/PwDv/8b+/v7+/v7+/v7+/v7+/v7+7z8/Pz8/Pz8/Pz8/Pz8/PxBQ7+Ne3txKOgReWn8/PwA
Q/8VxcbscRYWFhYWFhbx7Pr6+hZJGvzTGjUgRf////+r8fEVRSPWOtMnGq5F8cbF+sbI9jT8/PwN/79P
+8E+/Pz8Nf9FKvsQNPz8/AO//xv7+/v7+/v7+/v7+/v7+/v7vPz8/Pz8/Pz8/Pz8/Pz8/A0gRrd7LXEo
6BF5afz8/ABD/xX6xeGU/////////6t5xcbFxWMlJ/z8Gg0gv////////79WDTr8/Do1iJR5+vrI+vr2
NPz8/A3/v0/7wT78/Pw1//8q+xA0/Pz8A7//G/v7+/v7+/v7+/v7+/v7+/s0/Pz8/Pz8/Pz8/Pz8/Pz8
hgm7LZV7cSjoEXlp/Pz8AEP/FZn0WYlDQ0NDQ0X/q3nFxsjF6UkaJ/wnOjVJiHVFRXUgSdY6/PwnGq6U
4cXFxcb6+vY0/Pz8Df+/T/vBPvz8/DX/RSr7EDT8/PwDv/8b+/v7+/v7+/v7+/v7+/v7+3w3Nzc3Nzc3
Nzc3Nzc3Nze0lbstlS1xKOgReWn8/PwAQ/8VWpysp11dXV1dRP+r4fr6+vr6wEE6J/z8OjolBq6uYiU6
Ovz8JzoGlGD6+sbFyPr69jT8/PwN/0WP+8E+/Pz8Nf9FKvsQNPz8/AO//xv7+/v7+/v7+/v7+/v7+/v7
E5WVlZWVlZWVlZWVlZWVCZW7uy17e3Eo6BF5afz8/ABD/xXahvz8/Pz8/PxR/6t5xcX6+nfoYw0yGtPT
JxoaGhoaGifT/Boy1SB5xcXGxcX6xshSNPz8/A3/RekF+z78/Pw1//8q+6A0/Pz8A7//G/v7+/v7+/v7
+/v7+/v7+/v7+/v7+/v7+/v7+/v7+xDB7hO7LXt7cSjoEXlp/Pz8AEP/FVr1/Pz8/Pz8/L0VFmDGxsXF
+vr9Y9U6MifT/Pz8/PzT/BoyGn/EYPrG+sbGxfrG+vY0/Pz8Df9F8Qgp1Pz8/DX/RbdAByb8/PwDv/8b
+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+8HuE7ste3txKOgReWn8/PwAQ/8V2tb8/Pz8/Pz8
svr6+vr6yPrFxsh5Rr01MjI6Gvz8GjIyGjVRRmDI+sXGxfrGxcXI9jT8/PwN/0Xx+gic/Pz8Nf//dYmJ
Bvz8/AO//xv7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/sQwe4Tuy2Ve3Eo6BF5afz8/ABD/xWq
zHSQkJCQkHQOxfr6xsX6+vrG+sZg/RtJ1TWGAPOGp9WMG+r6+vr6xcbIxfrI+sVSNPz8/A3/RfHICKT8
/Pw1//////9R/Pz8A7//G/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/vB7hO7LZV7cSjoEXlp
/Pz8AEP/FcYEBAQEBAQEBJnIxfr6xvr6+sbF+vqW3+rDg04LC06Pw+n6yPr6+vr6+vr6+sbF+lI0/Pz8
Df9F8cUIpPz8/NZRUVFRUQ38/PwDv/8b+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7EMHuE7st
lXtxKOgReWn8/PwAQ/8V7BERERERERERERERERERERERERERERERERERERERERERERERERERERERERER
ERER4Hr8/PwN/0Xx+gik/Pz8/Pz8/Pz8/Pz8/AO//xv7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7
+/v7we4Tuy17LXEo6BF5afz8/ABD/0VFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVFRUVF
RUVFRUVFRUVFRUVDDfz8/A3/RfH6CKT8/Pz8/Pz8/Pz8/Pz884mUKvv7+/v7+/v7+/v7+/v7+/v7+/v7
+/v7+/v7+/v7+/vB7hO7LZV7cSjoEXlp/Pz8AEX/////////////////////////////////////////
//////////////////////////9B/Pz8Df9F8cgIpPz8/Pz8/Pz8/Pz8/PzTzPv7+/v7+/v7+/v7+/v7
+/v7+/v7+/v7+/v7+/v7+/v7EMHuE7stlS1xKOgReWn8/PzTaElJSUlJSUlJSUlJSUlJSUlJSUlJSUlJ
SUlJSUlJSUlJSUlJSUlJSUlJSUlJSUlJSUlJaCX8/PwN/0Xx+ghT/AAAAAAAAAAA09PT0/PM+/v7+/v7
+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7wcwTuy17LXEo6BF5afz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8
/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/A3/RRb6mVpbW1tbW1tbW1tbXwvB
CRD7+/v7+/v7+/v7+6D7+/v7+/v7+/v7+/v7+/v7+/v7+xDB7hO7LZV7cSjoEXlp/Pz8/Pz8/Pz8/Pz8
/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8DUWr8cbGyMX6xfr6
+vr6+vrGxvQpQPv7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7EMHuE7ste3txKOgRebL8/Pz8
/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pzd+sX6
xcX6lsb6+vr6xsXFxfrFxvo4KQf7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/sQwe4Tuy17e3Eo
6BF5b/z8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8/Pz8
/Pz8/IbGxfrF+vr6yMb6+vrG+vr6xcb6+sbFOCkL+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/v7+/vB
7hO7LXt7cSjoEXlhNvX19fX19fX19fX19fX19fX19fX19fX19fX19fX19fX19fX19fX19fX19fX19fX1
9fX19fX19fX19fX1pMXGxcbFyMb6xcj6+vr6xvrFyMX6yPr6xeTCDvv7+/v7+/v7+/v7+/v7+/v7+/v7
+/v7+/v7EMHME7stlS1xKOgReeFg7Mb6+vr6xfr6+vr6xsX6+vr6+vrFxvrFyPrF+vr6xcXG+vr6+sj6
xvrFxvr6xcX6+vrF+sjG+sXGxvr6xvr6xcX6+vr6+vr6yPr6xsX6+sb6+sj6+sZ4WgVA+/v7+/v7+/v7
+/v7+/v7+/v7+/v7+/sQwe4Tuy2VLXEo6BF54WCWxfrG+vr6yMXF+sX6+sXF+sj6xvrF+sXGxsbF+sXG
xfr6yPr6xcb6xcbIxcbI+sj6+sXFxsXIxfrG+vrF+vr6xfr6+vrI+sX6xfrF+sjFxfrF+vr6xcX6BKop
C6H7+/v7+/v7+/v7+/v7+/v7+/v7+xDB7hO7LXt7cSjoEXnhYJbI+sj6yMXFxsX6yPr6xfr6xfr6xvrF
xvr6yMb6+sbF+sb6xvrG+vr6+sb6xsj6xsb6xsX6+vrI+sb6yMXG+vr6xvr6+sX6+vrFxsj6xvrI+vr6
+sX6xsjF+sUI2gVAofv7+/v7+/v7+/v7+/v7+/v7+8HuE7stlS1xKOgReeFg7MXF+sb6xfr6xcbG+sXF
+sbFxsXGxvrF+vrG+vrGyPr6+vrI+sX6+sXGyPrI+sXGxcXFxvrF+sb6xfr6+vrF+vrF+sX6+vr6xvrF
+sb6+vrGxfrGxvrF+sX6+vr6xTjCBUD7+/v7+/v7+/v7+/v7+/sQwe4Tuy2Ve3Eo6BF54WDsxsb6xcbG
+sX6xsX6xcbFxsjF+sjIxfrFxcb6+sbFxcb6+vr6+sb6xsX6xfrFyMX6+sbGxfrF+sjFxsj6xsXI+sbG
xvrFyMXG+sXFxsX6xsb6yMXIxcXG+sb6xcbGyMWZOMIFB/v7+/v7+/v7+/v7+xDB7hO7LXstcSjoEXnh
YOz6+sjG+sXF+sXGxcbG+vrF+sbF+sX6xvr6+sjFxcXGxfr6+sj6+vrFxsbIxfrFxsXGxfr6+vrI+sbF
+sb6yMX6+vrIxfr6+sX6+vr6yPr6+sj6+sXG+sjG+vrFxfr6+vr6+gRZ2ikLofv7+/v7+/v7+8HuE7st
lXtxKOgReeFg7PrF+vrGxvr6+sX6xcX6+vrGxsX6xvrF+sX6+vr6xcbF+vr6xsb6+vr6xvr6xvr6xcb6
+sb6+sb6yPr6+sb6xvrI+vrF+vr6+sX6xvrFxsX6+vr6+vr6xvr6xsb6xfr6+sj6+sX6mQiCwgVAofv7
+/v7we4Tuy2Ve3Eo6BF54WCW+vrF+sX6xcXF+sbF+sbFxfr6xvr6xcXG+sj6+vr6+vr6xsbG+sjI+vr6
+sXFyPr6lvrF+vrIxcb6+vrFxvrFyPrF+sX6+vr6yPrG+sX6+vrGxcX6xvr6yPr6+sX6+vrF+sbG+sjI
yPr6yAhawgULQKHB7hO7LZV7cSjoEXnhYMjGxcXGxfr6+vr6yPrIxcb6yPr6+sb6lsb6xsX6+sbFxvr6
xfrG+vr6xvrI+vr6+sb6+sX6+vrGxcXFxvr6yPrGyPr6+vr6+vr6xcb6+sXF+vrG+sbG+sXF+sj6xvrI
yMjF+vrGxfrF+sXG+sb6+giqWykLQKATey1xKOh5eeHslpmZmZnGmcZ3xneZmZmZmXeZxpmZmZl3d8aZ
mZl3xpmZxneZxpmZmXfGxsZ3mZmZxneZmXeZmZnGmcbGxsaZmcaZmXfGmcZ3mcbGxneZmZmZd5nGmZl3
mZl3mXfGmcaZmXd3mZmZmXfGmZmZmXeZd5kECPaqWykFDnEoEXl5YJbGBAQEBAQEBAQEBAQEBAQEBAQE
BAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQE
BAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAQEBAh45DiqglqCKOgReeHs+gQICAgICAgICAgI
CAgICAgICAgICAgICAgICAgICAgICAgICAgICAgICAgICAgICAgICAgICAgECAgICAgICAgICAgICAgI
CAgICAgICAgICAgICAgICAgICAgICAgICAgICAgICAgICAgICAgICAgICFJZOKqCWoIoEXnhYMiZCHgI
eHh4eHh4eHh4eHh4eHh4eHh4eHgIeHh4eAh4CHgIeAh4eAh4eHh4eHgIeHh4eHh4CHh4eAh4CHgIeHh4
eHh4eHh4eHh4eHh4CHh4eAgIeHh4eHh4CHgIeHh4CHgIeHh4eHh4CHh4CAh4CHh4eAh45DiqqoJagih5
eWCWxgR4Unh4eHhSeHh4Unh4eHh4eHh4eHhSeHh4eHh4UnhSeHh4eHh4eHh4eHh4eHh4Unh4eHhSeHh4
eHh4eHh4eHh4eHh4eFJ4eHh4Unh4UlJ4eHh4eFJ4eFJ4eHh4eHh4eHhSeHh4Unh4eFJ4Unh4eHh4eFL0
OKqCglqC6Hnh7PoECFJS9vZS9lL2UlL29lJSUlL2UvZSUlL2Uvb29vb2UvZSUvb2Uvb29vb2Uvb29lL2
UvZSUlL29lL29vZSUvb29lJS9vZSUlJS9lJSUvZS9lJS9vZS9lJSUlL2UlJS9lJS9vZSUvZS9vb2UlJS
9lL2UvZS5DiqqoKCWoIRYGD6BAh49llZ5ORZWVlZWeT0WeRZWeRZ5FlZWeRZWfRZ9ORZWfTk5Fnk5OT0
WeTkWeRZ5OT0WVlZWeTkWeT0WeTkWeT0WfRZWVlZWeRZWfRZ5PRZ5PTkWVnkWVlZWVlZWVlZWVnk5PT0
WfTk5FnkWVnkWeRZ9OT0OKqqgoJaghHhYN93CHhkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRk
ZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRkZGRk
ZGRkZGRkZGRkZGRkZGRkZGRkZGRkZPf3ODiFqqqFAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA=
</value>
</data>
</root>
/C-OSD/arducam-osd/Tools/OSD/OSD.sln
0,0 → 1,20

Microsoft Visual Studio Solution File, Format Version 11.00
# Visual C# Express 2010
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "OSD", "OSD.csproj", "{E35F835A-8B3E-42D5-8852-A6E0F41823B5}"
EndProject
Global
GlobalSection(SolutionConfigurationPlatforms) = preSolution
Debug|x86 = Debug|x86
Release|x86 = Release|x86
EndGlobalSection
GlobalSection(ProjectConfigurationPlatforms) = postSolution
{E35F835A-8B3E-42D5-8852-A6E0F41823B5}.Debug|x86.ActiveCfg = Debug|x86
{E35F835A-8B3E-42D5-8852-A6E0F41823B5}.Debug|x86.Build.0 = Debug|x86
{E35F835A-8B3E-42D5-8852-A6E0F41823B5}.Release|x86.ActiveCfg = Release|x86
{E35F835A-8B3E-42D5-8852-A6E0F41823B5}.Release|x86.Build.0 = Release|x86
EndGlobalSection
GlobalSection(SolutionProperties) = preSolution
HideSolutionNode = FALSE
EndGlobalSection
EndGlobal
/C-OSD/arducam-osd/Tools/OSD/OSD_SA_v5.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
00000000
00000000
00010101
00001010
10100000
00010101
00101000
00101000
00010101
00100000
00101000
00010101
00000000
10100000
00010101
00000010
10000000
00010101
00001010
00000000
00010101
00101010
10101000
00010101
00000000
00000000
00000000
00000000
00101010
10000000
01010100
00101000
10100000
01010100
00101000
00101000
01010100
00101000
00101000
01010100
00101000
00101000
01010100
00101000
00101000
01010100
00101000
10100000
01010100
00101010
10000000
01010100
00000000
00000000
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
00000000
00000000
00010101
00101010
10100000
00010101
00000000
00101000
00010101
00000000
00101000
00010101
00001010
10100000
00010101
00000000
00101000
00010101
00000000
00101000
00010101
00101010
10100000
00010101
00000000
00000000
00000000
00000000
00101010
10000000
01010100
00101000
10100000
01010100
00101000
00101000
01010100
00101000
00101000
01010100
00101000
00101000
01010100
00101000
00101000
01010100
00101000
10100000
01010100
00101010
10000000
01010100
00000000
00000000
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010100
01010101
01010101
01010010
01010101
01010101
01010010
01010101
01010101
01010010
01010101
01010101
01010010
01010101
01010101
01010010
01010101
01010101
01010010
01010101
01010101
01010010
01010101
01010101
01001010
01010101
01010100
00101010
01010101
01010010
10101010
01010101
01001010
10000000
01010101
00101000
00010101
01010100
10100001
01010101
01010100
10100001
01010101
01010010
10000101
01010101
01010010
10000101
01010100
01010010
10000101
01010010
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
00010101
01010101
01010101
10000101
01010101
01010101
10000101
01010101
01010101
10000101
01010101
01010101
10000101
01010101
01010101
10000101
01010101
01010101
10000101
01010101
01010101
10000101
01010101
01010101
10100001
01010101
01010101
10101000
00010101
01010101
10101010
10000101
01010101
00000010
10100001
01010101
01010100
00101000
01010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01010010
10000101
00010101
01010010
10000101
10000101
01010010
10000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
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
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
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
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
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
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
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
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
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
00101010
00000101
01000001
10000000
10100001
00101000
10000000
00001000
00101000
10000000
00000010
10000001
10100000
00000010
10000101
10100000
00001000
00100001
00101000
00100000
00001000
01001010
10000000
00001000
01001010
10000000
00000010
01001010
10100000
00000010
01010000
10101010
00000010
01010100
10001010
10101000
01010100
10000000
00000001
01010100
10000101
01010101
01010010
10100001
01010101
01001010
10101000
01010101
00101010
10101010
00000101
00000000
00000000
00000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010100
00000000
00010101
01010010
10101010
10000101
01001010
00000000
10100001
00101000
01010101
00101000
00100001
01010101
01001000
01000101
01010101
01001000
01010101
01010101
01001000
01010101
01010101
01001000
01010101
01010101
01001000
00000000
00000000
00000000
00101010
10101010
10101000
00101000
00000000
00101000
00101000
10101010
10101000
00101000
10100000
00101000
00101000
10101010
00101000
00101000
00000000
00101000
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
01010100
00000000
00010101
01010010
10101010
10000101
01001010
00000000
10100001
00101000
01010101
00101000
00100001
01010101
01001000
00100001
01010101
01001000
00000000
00000000
00000000
00101010
10101010
10101000
00101000
00000000
00101000
00101000
10101010
10101000
00101000
10100000
00101000
00101000
10101010
00101000
00101000
00000000
00101000
00101010
10101010
10101000
00000000
00000000
00000000
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010001
01010101
00010101
01001000
01010100
10000101
01001010
00010100
10100001
01001010
10000010
00000101
01001010
10101000
01010101
01001010
10101000
01010101
01010010
10101010
00010101
01010100
10101010
10000101
01010101
00101010
10100001
01010100
10000000
00000101
01010010
10000101
01010101
01001000
10000101
01010101
00100000
10000101
01010101
00000000
00000000
00010101
00101010
10101010
10000101
00000000
00000000
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010010
10000101
01010010
01010010
10000101
01010100
01010010
10000101
01010101
01010100
10100001
01010101
01010100
10100001
01010101
01010101
00101000
00010101
01010101
01001010
10000000
01010101
01010010
10101010
01010101
01010100
00101010
01010101
01010101
01001010
01010101
01010101
01010010
01010101
01010101
01010010
01010101
01010101
01010010
01010101
01010101
01010010
01010101
01010101
01010010
01010101
01010101
01010010
01010101
01010101
01010010
01010101
01010101
01010100
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
10000101
01010010
10000101
00010101
01010010
10000101
01010101
01010010
10000101
01010101
01001010
00010101
01010101
01001010
00010101
01010100
00101000
01010101
00000010
10100001
01010101
10101010
10000101
01010101
10101000
00010101
01010101
10100001
01010101
01010101
10000101
01010101
01010101
10000101
01010101
01010101
10000101
01010101
01010101
10000101
01010101
01010101
10000101
01010101
01010101
10000101
01010101
01010101
10000101
01010101
01010101
00010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
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
01010101
01010101
01010101
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
01010000
10101010
00000101
01010010
00000000
10000101
01010010
00010100
10000101
01010100
01010100
10000101
01010101
01010100
10000101
01010101
01010100
10000101
01010100
00000000
00000101
01010010
10101010
10000101
01001010
00000000
10100001
01001010
00101010
10100001
01001010
00000000
10100001
01001010
00101010
10100001
01001010
00101010
10100001
01000010
10101010
10000001
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
01010000
10101010
00000101
01010010
00000000
10000101
01010010
00010100
10000101
01010010
00010100
10000101
01010000
00000000
00000101
01010010
10101010
10000101
01001010
00000000
10100001
01001010
00101010
10100001
01001010
00000000
10100001
01001010
00101010
10100001
01001010
00101010
10100001
01000010
10101010
10000001
01010000
00000000
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010100
00000000
00000000
01010000
10101010
10101010
01000010
10101010
10101010
01001010
10000000
00101010
01001010
10000000
00101010
01001010
10000000
00101010
01001010
10101010
10101010
01001010
10101010
10101010
01001010
10101010
10101010
01001010
10101010
10101010
01001010
10101010
10101010
01001010
10101010
10101010
01000010
10101010
10101010
01010000
10101010
10101010
01010100
00000000
00000000
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
00000000
00000000
00000101
10101010
10101010
10000001
10101010
10101010
10100000
10101010
10101010
00001000
10100000
00001010
00001000
10000000
00000010
10101000
00000000
00000000
10101000
00000000
00000000
10101000
00000000
00000000
10101000
00000000
00000000
10101000
10000000
00000010
10101000
10100000
00001010
10101000
10101010
10101010
10100000
10101010
10101010
10000001
00000000
00000000
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
00000000
00000000
00000101
10101010
10101010
10000001
10101010
10101010
10100000
10101010
10101010
00001000
10100000
00001010
00001000
10000000
00000010
10101000
00000000
00000000
10101000
00001010
10100000
10101000
00101010
10101000
10101000
00101010
10101000
10101000
00101010
10101000
10101000
00101010
10101000
10101000
10001010
10100010
10100000
10100000
00001010
10000001
00000000
00000000
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
00001010
10101010
10000001
00000000
00001010
00000001
00000000
00101000
00000001
00000010
10100000
00000001
00001010
10101010
10000001
00000000
00000000
00000001
00001010
10101010
10000001
00001010
00000010
10000001
00001010
10101010
10000001
00000000
00000000
00000001
00001010
10101010
10000001
00001010
00000010
10000001
00001010
10101010
10000001
00000000
00000000
00000001
00001010
10001010
10000001
00001010
00100010
10000001
00001010
00000010
10000001
00001010
00000010
10000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
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
01010101
01010101
01010000
01010101
01010101
01000010
01010101
01010101
00001010
01010101
01010100
00101010
01010101
01010000
10101010
01010101
01000010
10101010
01010101
00001010
10101010
01010100
00001010
10101010
01010000
01001010
10101010
01010001
01001010
10101010
01010101
01001010
00000000
01010101
01001010
00000000
01010101
01001010
00000000
01010101
01001010
00000000
01010101
01001010
00000000
01010101
01001010
00000000
01010101
01000000
00000000
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
00010101
01010101
01010101
00000101
01010101
01010101
10000001
01010101
01010101
10100000
01010101
01010101
10101000
00010101
01010101
10101010
00000101
01010101
10101010
10000001
01010101
00000000
10100000
01010101
00000000
10100000
00010101
00000000
10100001
00000101
10101010
10100001
01000101
00000000
10100001
01010101
00000000
10100001
01010101
00000000
10100001
01010101
00000000
10100001
01010101
00000000
10100001
01010101
00000000
10100001
01010101
00000000
00000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000001
01010101
01010100
00101000
00010101
01010000
10101010
00000101
01000010
10101010
10000001
00001010
10101010
10100000
00000000
00000000
00000000
00101010
10101010
10101000
00101010
10101000
00001000
00101010
10101000
00001000
00100000
00001000
00001000
00100000
00001010
10101000
00100000
00001010
10101000
00100000
00001010
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
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
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
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
01010100
01010101
00010101
01010010
00010100
10000101
01001010
10000010
10100001
01010010
10000100
10100001
01010100
10000101
00100001
01010100
10000101
00100001
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010100
00010100
00010101
01010010
10000010
10000101
01010010
10000010
10000101
01000010
10000010
10000001
00101010
10101010
10101000
00101010
10101010
10101000
01000010
10000010
10000001
01000010
10000010
10000001
00101010
10101010
10101000
00101010
10101010
10101000
01000010
10000010
10000001
01010010
10000010
10000101
01010010
10000010
10000101
01010100
00010100
00010101
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
00101000
00010101
01010010
10101010
10000101
01001010
10101010
10100001
01001010
00101000
10100001
01001010
00101000
00000101
01001010
10101010
00010101
01010010
10101010
10000101
01010000
00101000
10100001
01001010
00101000
10100001
01001010
10101010
10100001
01010010
10101010
10000101
01010100
00101000
00010101
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
01010000
01010101
00000101
01001010
00010100
10100001
01001010
00010010
10100001
01010000
01001010
10000101
01010101
00101010
00010101
01010100
10101000
01010101
01010010
10100001
00000101
01001010
10000100
10100001
01001010
00010100
10100001
01010000
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
00000001
01010101
01010100
10101000
01010101
01010010
10000010
00010101
01010010
00010010
00010101
01010010
00010010
00010101
01010010
00001000
01010101
01010100
10100001
01010101
01010100
10100001
01010101
01010010
00001000
00000101
01001000
01010010
00100001
01001000
01010100
10000101
01001000
00000010
00100001
01010010
10101000
01001000
01010100
00000001
01010001
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
01010101
01001010
00010101
01010101
01010010
00010101
01010101
01010010
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
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
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
01000101
01010101
01010001
00100001
01010101
01001000
00101000
01010101
00101000
01001010
00010100
10100001
01010010
10000010
10000101
01000000
10101010
00000001
00101010
10101010
10101000
01000000
10101010
00000001
01010010
10000010
10000101
01001010
00010100
10100001
00101000
01010101
00101000
00100001
01010101
01001000
01000101
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
01000001
01010101
01010101
00101000
01010101
01010100
00101000
00010101
01010010
10101010
10000101
01010010
10101010
10000101
01010100
00101000
00010101
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
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
01010101
01010101
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
01010010
10101010
10000101
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010100
10101000
01010101
01010010
10100001
01010101
01001010
10000101
01010101
00101010
00010101
01010100
10101000
01010101
01010010
10100001
01010101
01001010
10000101
01010101
00101010
00010101
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
01010100
00000000
00010101
01010010
10101010
10000101
01001010
10101010
10100001
01001010
00000000
10100001
01001010
00010100
10100001
01001010
00010100
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010100
10101000
01010101
01010010
10101000
01010101
01010010
10101000
01010101
01010100
00101000
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010100
00101000
00010101
01010010
10101010
10000101
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
01010101
01010101
01010101
01010101
01010101
01010100
00000000
00010101
01010010
10101010
10000101
01001010
10101010
10100001
01001010
00000000
10100001
01001010
00010010
10100001
01010000
01001010
10000101
01010101
00101010
00010101
01010100
10101000
01010101
01010010
10100000
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
01010000
00000000
00010101
01001010
10101010
10000101
01001010
10101010
10100001
01010000
00000000
10100001
01010101
00000000
10100001
01010100
10101010
10000101
01010100
10101010
10000101
01010101
00000000
10100001
01010000
00000000
10100001
01001010
10101010
10100001
01001010
10101010
10000101
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
01010000
00010101
01010101
01001010
10000101
01010101
00101010
10000101
01010100
10100010
10000101
01010010
10000010
10000101
01001010
00000010
10000101
01001010
10101010
10100001
01001010
10101010
10100001
01010000
00000010
10000101
01010101
01010010
10000101
01010101
01010010
10000101
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
01010000
00000000
00000101
01001010
10101010
10100001
01001010
10101010
10100001
01001010
00000000
00000101
01001010
10101010
10000101
01001010
10101010
10100001
01010000
00000000
10100001
01010000
01010100
10100001
01001010
00000000
10100001
01001010
10101010
10100001
01000010
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
01010101
01010101
01010101
01010101
01010101
01010100
00000000
00010101
01010010
10101010
10000101
01001010
10101010
10000101
01001010
00000000
00010101
01001010
00000000
00010101
01001010
10101010
10000101
01001010
10101010
10100001
01001010
00000000
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
00000000
00000101
01001010
10101010
10100001
01001010
10101010
10100001
01010000
00000000
10100001
01010101
01010010
10100001
01010101
01001010
10000101
01010101
00101010
00010101
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
01010101
01010101
01010101
01010101
01010101
01010101
01010100
00000000
00010101
01010010
10101010
10000101
01001010
10101010
10100001
01001010
00000000
10100001
01001010
00000000
10100001
01010010
10101010
10000101
01010010
10101010
10000101
01001010
00000000
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010100
00000000
00010101
01010010
10101010
10000101
01001010
10101010
10100001
01001010
00000000
10100001
01001010
00000000
10100001
01001010
10101010
10100001
01010010
10101010
10100001
01010100
00000000
10100001
01010000
00000000
10100001
01001010
10101010
10100001
01001010
10101010
10000101
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
01000001
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
01000001
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
01000001
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
01000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010101
00101000
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010100
00010101
01010101
01010010
10000101
01010101
01001010
00010101
01010101
00101000
01010101
01010100
10100001
01010101
01010010
10000101
01010101
01010010
10000101
01010101
01010100
10100001
01010101
01010101
00101000
01010101
01010101
01001010
00010101
01010101
01010010
10000101
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
01010100
00000000
00010101
01010010
10101010
10000101
01010010
10101010
10000101
01010100
00000000
00010101
01010101
01010101
01010101
01010101
01010101
01010101
01010100
00000000
00010101
01010010
10101010
10000101
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
01010101
01010101
01001010
00010101
01010101
01010010
10000101
01010101
01010100
10100001
01010101
01010101
00101000
01010101
01010101
01001010
00010101
01010101
01001010
00010101
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
01010100
00000000
00010101
01010010
10101010
10000101
01001010
10101010
10100001
00101010
00000000
10101000
00101000
01010101
00101000
01000001
01010101
00101000
01010101
01010100
10101000
01010101
01010010
10100001
01010101
01001010
10000101
01010101
00101010
00010101
01010101
00101000
01010101
01010101
01000001
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
00000000
01010101
01010100
10101010
00010101
01010010
00000000
10000101
01001000
00000100
00100001
00100000
10100010
00001000
00100010
00001010
00001000
00100010
00000010
00001000
00100010
00001010
00001000
00100000
10100010
00100001
00100001
00000100
10000101
01001000
01010101
00000101
01010010
00000000
00100001
01010100
10101010
10000101
01010101
00000000
00010101
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
10101010
10100001
01001010
10000010
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
01010000
01010101
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
00000000
01010101
01001010
10101010
00010101
01001010
10101010
10000101
01001010
00000010
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00000010
10100001
01001010
10101010
10000101
01001010
10101010
10000101
01001010
00000010
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00000010
10100001
01001010
10101010
10000101
01001010
10101010
00010101
01010000
00000000
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
00010101
00000101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
00000101
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
01010000
00000000
01010101
01001010
10101010
00010101
01001010
10101010
10000101
01001010
00000010
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
00000010
10100001
01001010
10101010
10000101
01001010
10101010
00010101
01010000
00000000
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
01001010
00000000
00000101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00000000
01010101
01001010
10101010
00010101
01001010
10101010
00010101
01001010
00000000
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
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
01010000
00000000
00000101
01001010
10101010
10100001
01001010
10101010
10100001
01001010
00000000
00000101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00000000
01010101
01001010
10101010
00010101
01001010
10101010
00010101
01001010
00000000
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01010000
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010100
00000000
01010101
01010010
10101010
00010101
01001010
10101010
10000101
01001010
10000010
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010101
00000101
01001010
00010000
00000101
01001010
00001010
10100001
01001010
00001010
10100001
01001010
00010000
10100001
01001010
00010100
10100001
01001010
00000000
10100001
01001010
10101010
10100001
01010010
10101010
10100001
01010100
00000000
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
01010101
00000101
01001010
00010100
10100001
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
01010000
01010101
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010100
00000000
00010101
01010010
10101010
10000101
01010010
10101010
10000101
01010100
00101000
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
01010100
00101000
00010101
01010010
10101010
10000101
01010010
10101010
10000101
01010100
00000000
00010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
00000000
00000101
01010100
10101010
10100001
01010100
10101010
10100001
01010101
00001010
00000101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010000
01001010
00010101
01001010
00001010
00010101
01001010
00001010
00010101
01001010
00001010
00010101
01001010
00001010
00010101
01001010
00001010
00010101
01001010
10101010
00010101
01010010
10101000
01010101
01010100
00000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
01010101
01010101
01001010
00010101
00000101
01001010
00010100
10100001
01001010
00010010
10100001
01001010
00001010
10000101
01001010
00101010
00010101
01001010
10101000
01010101
01001010
10100001
01010101
01001010
10000101
01010101
01001010
10100001
01010101
01001010
10101000
01010101
01001010
00101010
00010101
01001010
00001010
10000101
01001010
00010010
10100001
01001010
00010100
10100001
01010000
01010101
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
01010101
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
00010101
01010101
01001010
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
01010000
01010101
00000101
01001010
00010100
10100001
01001010
10000010
10100001
01001010
10101010
10100001
01001010
10101010
10100001
01001010
00101000
10100001
01001010
00101000
10100001
01001010
00000000
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01010000
01010101
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
01010101
00000101
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
10000100
10100001
01001010
10000100
10100001
01001010
10100000
10100001
01001010
10101000
10100001
01001010
00101010
10100001
01001010
00001010
10100001
01001010
00010010
10100001
01001010
00010010
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01010000
01010101
00000101
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
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
01010000
00000000
01010101
01001010
10101010
00010101
01001010
10101010
10000101
01001010
00000010
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00000010
10100001
01001010
10101010
10000101
01001010
10101010
00010101
01001010
00000000
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01010000
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
00000000
10100001
01001010
00101000
10100001
01001010
00101010
10100001
01001010
10001010
10000101
01010010
10101010
10100001
01010100
10101000
10100001
01010101
00000001
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
00000000
01010101
01001010
10101010
00010101
01001010
10101010
10000101
01001010
00000010
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00000010
10100001
01001010
10101010
10000101
01001010
10101000
00010101
01001010
10101000
01010101
01001010
00101010
00010101
01001010
00001010
10000101
01001010
00010010
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01010000
01010101
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
00000000
00010101
01010100
10101010
10000101
01010010
10101010
10100001
01001010
10000000
10100001
01001010
00010101
00000101
01001010
00010101
01010101
01001010
10000000
01010101
01010010
10101010
00010101
01010100
10101010
10000101
01010101
00000010
10100001
01010101
01010100
10100001
01010000
01010100
10100001
01001010
00000010
10100001
01001010
10101010
10000101
01010010
10101010
00010101
01010100
00000000
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
00101000
00000101
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
01010000
01010101
00000101
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
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
01010000
01010101
00000101
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
10000010
10000101
01010010
10101010
10000101
01010100
10101010
00010101
01010101
00101000
01010101
01010101
01000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
01010101
00000101
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00000000
10100001
01001010
00101000
10100001
01001010
00101000
10100001
01001010
00101000
10100001
01001010
00101000
10100001
01001010
00101000
10100001
01001010
00101000
10100001
01001010
10101010
10100001
01010010
10101010
10000101
01010010
10000010
10000101
01010100
00010100
00010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
01010101
00000101
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01010010
10000010
10000101
01010100
10101010
00010101
01010101
00101000
01010101
01010101
00101000
01010101
01010100
10101010
00010101
01010010
10000010
10000101
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01010000
01010101
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
01010101
00000101
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
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
01010000
00000000
00000101
01001010
10101010
10100001
01001010
10101010
10100001
01010000
00000000
10100001
01010101
01010100
10100001
01010101
01010010
10100001
01010101
01001010
10000101
01010101
00101010
00010101
01010100
10101000
01010101
01010010
10100001
01010101
01001010
10000101
01010101
01001010
00010101
01010101
01001010
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
01000000
00010101
01010101
00101010
10000101
01010101
00101010
10000101
01010101
00101000
00010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
00101000
00010101
01010101
00101010
10000101
01010101
00101010
10000101
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
01000001
01010101
01010101
00101000
01010101
01010101
00101010
00010101
01010101
01001010
10000101
01010101
01010010
10100001
01010101
01010100
10101000
01010101
01010101
00101010
00010101
01010101
01001010
10000101
01010101
01010010
10100001
01010101
01010100
10101000
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
01010100
00000001
01010101
01010010
10101000
01010101
01010010
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
01010101
01010010
10101000
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
01000001
01010101
01010101
00101000
01010101
01010100
10101010
00010101
01010010
10000010
10000101
01010010
00010100
10000101
01010000
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
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
00000001
00101010
10101010
10101000
00101010
10101010
10101000
01000000
00000000
00000001
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
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
01010101
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
00000000
10100001
01001010
00000000
10100001
01001010
10101010
10100001
01001010
10101010
10100001
01001010
00000000
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01010000
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
01010000
00000000
00010101
01001010
10101010
10000101
01001010
10101010
10100001
01001010
00000000
10100001
01001010
00000000
10100001
01001010
10101010
10000101
01001010
10101010
10000101
01001010
00000000
10100001
01001010
00000000
10100001
01001010
10101010
10100001
01001010
10101010
10000101
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
01010100
00000000
00010101
01010010
10101010
10000101
01001010
10101010
10100001
01001010
00000000
10100001
01001010
00010101
00000101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
00000101
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
00000000
01010101
01001010
10101010
00010101
01001010
10101010
10000101
01001010
00000010
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00000010
10100001
01001010
10101010
10000101
01001010
10101010
00010101
01010000
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
01010000
00000000
00000101
01001010
10101010
10100001
01001010
10101010
10100001
01001010
00000000
00000101
01001010
00000000
01010101
01001010
10101010
00010101
01001010
10101010
00010101
01001010
00000000
01010101
01001010
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
01010000
00000000
00000101
01001010
10101010
10100001
01001010
10101010
10100001
01001010
00000000
00000101
01001010
00000000
00010101
01001010
10101010
10000101
01001010
10101010
10000101
01001010
00000000
00010101
01001010
00010101
01010101
01001010
00010101
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
01010101
01010101
01010101
01010100
00000000
00010101
01010010
10101010
10000101
01001010
10101010
10100001
01001010
10000000
10100001
01001010
00000000
00000101
01001010
00001010
10100001
01001010
00001010
10100001
01001010
00000000
10100001
01001010
10000000
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
01010101
00000101
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
01010000
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
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
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
01000000
00000101
01010101
00101010
10100001
01010101
00101010
10100001
01010101
01000010
10000101
01010101
01010010
10000101
01010101
01010010
10000101
01010101
01010010
10000101
01010100
00010010
10000101
01010010
10000010
10000101
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
01010101
00000101
01001010
00010100
10100001
01001010
00010010
10100001
01001010
00001010
10000101
01001010
00101010
00010101
01001010
10101000
01010101
01001010
10101000
01010101
01001010
10101010
00010101
01001010
00001010
10000101
01001010
00010010
10100001
01001010
00010100
10100001
01010000
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
01010000
01010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
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
01010000
01010101
00000101
01001010
00010100
10100001
01001010
10000010
10100001
01001010
10101010
10100001
01001010
00101000
10100001
01001010
00101000
10100001
01001010
00000000
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01010000
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
01010000
01010101
00000101
01001010
00010100
10100001
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
01010000
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
01010100
00000000
00010101
01010010
10101010
10000101
01001010
10101010
10100001
01001010
00000000
10100001
01001010
00010100
10100001
01001010
00010100
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
00000000
00010101
01001010
10101010
10000101
01001010
10101010
10100001
01001010
00000000
10100001
01001010
00000000
10100001
01001010
10101010
10100001
01001010
10101010
10000101
01001010
00000000
00010101
01001010
00010101
01010101
01001010
00010101
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
01010101
01010101
01010101
01010100
00000000
00010101
01010010
10101010
10000101
01001010
10101010
10100001
01001010
00000000
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010000
10100001
01001010
00001010
10100001
01001010
00001010
10000101
01001010
10101010
10100001
01010010
10101000
10100001
01010100
00000001
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
01010000
00000000
00010101
01001010
10101010
10000101
01001010
10101010
10100001
01001010
00000000
10100001
01001010
00000000
10100001
01001010
10101010
10000101
01001010
10101000
00010101
01001010
00101010
00010101
01001010
00001010
10000101
01001010
00010010
10100001
01001010
00010100
10100001
01010000
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
01010100
00000000
00010101
01010010
10101010
10000101
01001010
10101010
10100001
01001010
00000000
10100001
01001010
00000000
00000101
01001010
10101010
10000101
01010010
10101010
10100001
01010000
00000000
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
00000000
00000101
01001010
10101010
10100001
01001010
10101010
10100001
01010000
00101000
00000101
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
01010101
01010101
01010101
01010101
01010101
01010101
01010000
01010101
00000101
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
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
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
01010101
00000101
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
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
01010000
01010101
00000101
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00010100
10100001
01001010
00000000
10100001
01001010
00101000
10100001
01001010
00101000
10100001
01001010
10101010
10100001
01010010
10101010
10000101
01010010
10000010
10000101
01010100
00010100
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
01010101
00000101
01001010
00010100
10100001
01001010
10000010
10100001
01010010
10101010
10000101
01010100
10101010
00010101
01010101
00101000
01010101
01010101
00101000
01010101
01010100
10101010
00010101
01010010
10101010
10000101
01001010
10000010
10100001
01001010
00010100
10100001
01010000
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
01010000
01010101
00000101
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
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
01010000
00000000
00000101
01001010
10101010
10100001
01001010
10101010
10100001
01010000
00000010
10100001
01010101
01001010
10000101
01010101
00101010
00010101
01010100
10101000
01010101
01010010
10100001
01010101
01001010
10000000
00000101
01001010
10101010
10100001
01001010
10101010
10100001
01010000
00000000
00000101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
00010101
01010101
01001010
10000101
01010101
01001010
10000101
01010101
00101010
10000101
01010101
00101000
00010101
01010101
00101000
01010101
01010101
00101000
01010101
01010100
10100001
01010101
01010100
10100001
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
00101000
00010101
01010101
00101010
10000101
01010101
01001010
10000101
01010101
01001010
10000101
01010101
01010000
00010101
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
01010100
00000101
01010101
01010010
10100001
01010101
01010010
10101000
01010101
01010010
10101000
01010101
01010100
00101000
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
00101000
01010101
01010101
00101000
01010101
01010100
00101000
01010101
01010010
10101000
01010101
01010010
10101000
01010101
01010010
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
00000101
01010001
01010100
10100001
01001000
01010010
10101000
00101000
01001010
00001010
10100001
00101000
01010010
10000101
01000001
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
01000000
00010101
01010101
01001000
10000101
01010101
01001000
10100001
01010101
01001000
10101000
01010101
01001000
10101010
00010101
01001000
10101010
10000101
01001000
10101010
00010101
01001000
10101000
01010101
01001000
10100001
01010101
01001000
10000101
01010101
01001000
00010101
01010101
01001000
01010101
01010101
01001000
01010101
01010101
01001000
01010101
01010101
00001000
00010101
01010101
00101010
00010101
01010101
00000000
00010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000000
00000001
01010101
00101000
00101000
01010101
00101000
10100000
01010101
00101010
00000000
01010101
00101000
10100000
01010101
00101000
00101000
01010101
01000000
00000000
00000001
00101000
10001010
10101000
00101000
10000000
10000001
00100010
10000000
10000101
00100010
10000000
10000101
01000000
00000000
00000001
01010101
00101000
00101000
01010101
00101000
00101000
01010101
00101010
10101000
01010101
00101000
00101000
01010101
00101000
00101000
01010101
01000000
00000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000001
01000001
01010101
00101000
00101000
01010101
00101000
10100001
01010101
00101010
00000101
01010101
00101000
10100001
01010101
00101000
00101000
01010101
01000000
00000000
00000101
01010010
10100010
10100001
01010010
10001000
10100001
01010010
10001000
10100001
01010010
10000000
10100001
01010100
00000000
00000001
01010101
00101001
01101000
01010101
00101000
00101000
01010101
00101010
10101000
01010101
00101000
00101000
01010101
00101000
00101000
01010101
01000001
01000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000000
00000000
01010101
00101010
10101010
00010101
00101000
10001010
00010101
00101000
10001010
00010101
00101000
00001010
00010101
01000000
00000000
00010101
01010101
00101010
10000101
01010101
00100000
10000101
01010100
10101010
10100001
01010100
10100000
10100001
01010100
10100000
10100001
01010101
00000000
00000001
01010101
00101000
00101000
01010101
00101000
00101000
01010101
00101010
10101000
01010101
00101000
00101000
01010101
00101000
00101000
01010101
01000001
01000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
00101000
00000001
01010101
00101010
10101000
01010101
00101010
10101000
01010101
01000000
00000000
00010101
01010100
10101010
10000101
01010010
10000000
10100001
01010010
10101010
10100001
01010010
10000000
10100001
01010100
00000000
00000000
01010101
00101010
10101000
01010101
00101010
10101000
01010101
01000010
10000001
01010101
01010010
10000101
01010101
01010010
10000101
01010101
01010100
00010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000001
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
00101000
00000001
01010101
00101010
10101000
01010101
00101010
10101000
01010101
01000000
00000000
00010101
01010010
10101010
10000101
01001010
10000010
10100001
01001010
10000010
10100001
01010010
10101010
10000101
01010100
00000000
00000001
01010100
10101000
00101000
01010100
10101010
00101000
01010100
10101010
10101000
01010100
10100010
10101000
01010100
10100000
10101000
01010101
00000000
00000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000000
00000000
01010101
00001010
10101000
01010101
00101000
00001010
00010101
00101010
10101010
00010101
00101000
00001010
00010101
01000000
00000000
01010101
01010010
10000101
01010101
01010010
10000101
01010101
01010010
10000000
00010101
01010010
10101010
10000101
01010010
10101010
10000101
01010100
00000000
00000001
01010101
00101010
10101000
01010101
00101010
10101000
01010101
01000010
10000001
01010101
01010010
10000101
01010101
01010010
10000101
01010101
01010100
00010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000001
01000001
01010101
00101000
00101000
01010101
00101000
00101000
01010101
01001010
10100001
01010101
01010010
10000101
01010101
01010100
00000000
00010101
01010010
10101010
10000101
01010010
10000000
00010101
01010010
10101010
01010101
01010010
10000000
00010101
01010010
10101010
10000101
01010100
00000000
00010101
01010101
01001010
00010101
01010101
01001010
00010101
01010101
01001010
00000001
01010101
01001010
10101000
01010101
01001010
10101000
01010101
01010000
00000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000000
00000001
01010101
00101010
10101000
01010101
00101010
10101000
01010101
01000010
10000001
01010101
01010010
10000101
01010101
01010010
10000101
01010101
01010100
00000100
00010101
01010100
10100010
10000101
01010100
10101010
10000101
01010100
10100010
10000101
01010100
10100010
10000101
01010101
00000000
00000101
01010101
01001010
10100001
01010101
01001000
00001000
01010101
01001000
00101000
01010101
01001010
10100000
01010101
01001010
00101000
01010101
01010000
01000000
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000001
01000001
01010101
00101000
00101000
01010101
00101010
10101000
01010101
00100010
10001000
01010101
00100000
00001000
01010101
01000000
00000001
01010101
00101010
10101000
01010101
01000000
00000001
01010101
00101010
10101000
01010101
00100000
00000001
01010101
00101010
10101000
01010101
01000000
00001000
01010101
00101010
10101000
01010101
01000000
00000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010000
00000001
01010101
01001010
10101000
01010101
00101000
00001010
00010101
00101010
10101010
00010101
00101000
00001010
00010101
01000001
00000000
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
00101000
01010101
01010101
00000000
00000001
01010101
00101010
10101000
01010101
00100000
00101000
01010101
00101010
10000001
01010101
00101000
10100001
01010101
00101000
00101000
01010101
01000001
01000001
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01000000
01000000
01010101
00101010
00101010
00010101
00101000
10001010
00010101
00101000
10001010
00010101
00101000
10001010
00010101
00101000
10001010
00010101
00000000
00000000
00010101
01010100
10101010
10000101
01010010
10000000
10100001
01010010
10101010
10100001
01010010
10000000
10100001
01010000
00000000
00000001
01010101
00101000
00101000
01010101
00101000
00101000
01010101
00101000
00101000
01010101
01001010
10100001
01010101
01010010
10000101
01010101
01010100
00010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010001
01010000
00000000
01001000
01010000
00000000
01001000
01010000
10100000
01001000
01010010
00001000
00000000
00010010
00001000
00101010
00010010
00001000
00000000
00010010
00001000
00101010
00010000
10100000
00101010
00010000
00000000
00101010
00010000
00000000
00101010
00010010
00001000
00101010
00010010
00001000
01000000
01010010
00100000
01001000
01010010
10000000
01001000
01010010
00100000
01001000
01010010
00001000
01001000
01010010
00001000
01001000
01010000
00000000
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010101
01010001
01010000
00000000
01001000
01010010
00000000
01001000
01010010
00000000
01001000
01010010
00000000
00000000
00010010
10101000
00101010
00010000
00000000
00000000
00010000
10100000
00101010
00010010
00001000
00101010
00010010
00001000
00101010
00010010
00001000
00101010
00010000
10100000
00101010
00010000
00000000
01000000
01010010
10101000
01001000
01010010
00000000
01001000
01010010
10101000
01001000
01010000
00001000
01001000
01010010
10101000
01001000
01010000
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
01000001
01010100
00010101
00101000
01010010
10000101
00101010
00001010
10000101
00101010
10101010
10000101
00101000
10100010
10000101
00101000
10100010
10000101
00101000
00000010
10000101
00101000
01010010
10000101
01000001
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
01010101
01010101
01000001
01010000
01010101
00101000
01001010
00010101
00101000
01001010
00010101
00101000
01001010
00010101
00101000
01001010
00010101
01001010
00101000
01010101
01001010
10101000
01010101
01010010
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