diff --git a/AeroQuad/AeroQuad.h b/AeroQuad/AeroQuad.h
new file mode 100644
index 00000000..0cbe3750
--- /dev/null
+++ b/AeroQuad/AeroQuad.h
@@ -0,0 +1,252 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_GLOBAL_HEADER_DEFINITION_H_
+#define _AQ_GLOBAL_HEADER_DEFINITION_H_
+
+
+#include
+#include
+#include "Arduino.h"
+#include "pins_arduino.h"
+
+// Flight Software Version
+#define SOFTWARE_VERSION 3.0
+
+#define BAUD 115200
+//#define BAUD 111111 // use this to be compatible with USB and XBee connections
+//#define BAUD 57600
+
+// Analog Reference Value
+// This value provided from Configurator
+// Use a DMM to measure the voltage between AREF and GND
+// Enter the measured voltage below to define your value for aref
+// If you don't have a DMM use the following:
+// AeroQuad Shield v1.7, aref = 3.0
+// AeroQuad Shield v1.6 or below, aref = 2.8
+float aref; // Read in from EEPROM
+//////////////////////////////////////////////////////
+
+/**
+ * Heading and heading hold global declaration section
+ */
+byte headingHoldConfig = 0;
+float headingHold = 0; // calculated adjustment for quad to go to heading (PID output)
+float heading = 0; // measured heading from yaw gyro (process variable)
+float relativeHeading = 0; // current heading the quad is set to (set point)
+byte headingHoldState = OFF;
+//////////////////////////////////////////////////////
+
+/**
+ * battery monitor and battery monitor throttle correction global declaration section
+ */
+int batteyMonitorThrottleCorrection = 0;
+#if defined (BattMonitor)
+ #define BattMonitorAlarmVoltage 10.0 // required by battery monitor macro, this is overriden by readEEPROM()
+ float batteryMonitorAlarmVoltage = 10.0;
+ int batteryMonitorStartThrottle = 0;
+ int batteryMonitorThrottleTarget = 1450;
+ unsigned long batteryMonitorStartTime = 0;
+ unsigned long batteryMonitorGoinDownTime = 60000;
+
+ #if defined BattMonitorAutoDescent
+ int batteryMonitorAlarmCounter = 0;
+ #define BATTERY_MONITOR_MAX_ALARM_COUNT 50
+ #endif
+#endif
+//////////////////////////////////////////////////////
+
+/**
+ * ESC calibration process global declaration
+ */
+byte calibrateESC = 0;
+int testCommand = 1000;
+//////////////////////////////////////////////////////
+
+/**
+ * Flight control global declaration
+ */
+#define RATE_FLIGHT_MODE 0
+#define ATTITUDE_FLIGHT_MODE 1
+byte flightMode = RATE_FLIGHT_MODE;
+unsigned long frameCounter = 0; // main loop executive frame counter
+int minArmedThrottle = MIN_ARMED_THROTTLE; // Read in from EEPROM, defines min throttle during flips
+
+float G_Dt = 0.002;
+int throttle = 1000;
+byte motorArmed = OFF;
+byte safetyCheck = OFF;
+// main loop time variable
+unsigned long previousTime = 0;
+unsigned long currentTime = 0;
+unsigned long deltaTime = 0;
+// sub loop time variable
+unsigned long tenHZpreviousTime = 0;
+unsigned long fiftyHZpreviousTime = 0;
+unsigned long hundredHZpreviousTime = 0;
+
+void readPilotCommands();
+void calculateFlightError();
+void processHeading();
+void processAltitudeHold();
+void processCalibrateESC();
+void processFlightControl();
+void processAltitudeHold();
+//////////////////////////////////////////////////////
+
+/**
+ * Altitude control global declaration
+ */
+#if defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+ // special state that allows immediate turn off of Altitude hold if large throttle changesa are made at the TX
+ int altitudeHoldBump = 90;
+ int altitudeHoldPanicStickMovement = 250;
+
+ float altitudeToHoldTarget = 0.0;
+ int altitudeHoldThrottle = 1000;
+ boolean isStoreAltitudeNeeded = false;
+ boolean altitudeHoldState = OFF; // ON, OFF or ALTPANIC
+#endif
+int minThrottleAdjust = -50;
+int maxThrottleAdjust = 50;
+
+float getAltitudeFromSensors();
+//////////////////////////////////////////////////////
+
+
+/**
+ * Serial communication global declaration
+ */
+#define SERIAL_PRINT SERIAL_PORT.print
+#define SERIAL_PRINTLN SERIAL_PORT.println
+#define SERIAL_AVAILABLE SERIAL_PORT.available
+#define SERIAL_READ SERIAL_PORT.read
+#define SERIAL_FLUSH SERIAL_PORT.flush
+#define SERIAL_BEGIN SERIAL_PORT.begin
+
+HardwareSerial *binaryPort;
+
+void readSerialCommand();
+void sendSerialTelemetry();
+void printInt(int data);
+float readFloatSerial();
+void sendBinaryFloat(float);
+void sendBinaryuslong(unsigned long);
+void fastTelemetry();
+void comma();
+void reportVehicleState();
+//////////////////////////////////////////////////////
+
+/**
+ * EEPROM global section
+ */
+typedef struct {
+ float p;
+ float i;
+ float d;
+} t_NVR_PID;
+
+typedef struct {
+ float slope;
+ float offset;
+ float smooth_factor;
+} t_NVR_Receiver;
+
+typedef struct {
+ t_NVR_PID ROLL_PID_GAIN_ADR;
+ t_NVR_PID LEVELROLL_PID_GAIN_ADR;
+ t_NVR_PID YAW_PID_GAIN_ADR;
+ t_NVR_PID PITCH_PID_GAIN_ADR;
+ t_NVR_PID LEVELPITCH_PID_GAIN_ADR;
+ t_NVR_PID HEADING_PID_GAIN_ADR;
+ t_NVR_PID LEVEL_GYRO_ROLL_PID_GAIN_ADR;
+ t_NVR_PID LEVEL_GYRO_PITCH_PID_GAIN_ADR;
+ t_NVR_PID ALTITUDE_PID_GAIN_ADR;
+ t_NVR_PID ZDAMP_PID_GAIN_ADR;
+ t_NVR_Receiver RECEIVER_DATA[LASTCHANNEL];
+
+ float SOFTWARE_VERSION_ADR;
+ float WINDUPGUARD_ADR;
+ float XMITFACTOR_ADR;
+ float GYROSMOOTH_ADR;
+ float ACCSMOOTH_ADR;
+ float AREF_ADR;
+ float FLIGHTMODE_ADR;
+ float HEADINGHOLD_ADR;
+ float ACCEL_1G_ADR;
+ float ALTITUDE_MAX_THROTTLE_ADR;
+ float ALTITUDE_MIN_THROTTLE_ADR;
+ float ALTITUDE_SMOOTH_ADR;
+ float ALTITUDE_WINDUP_ADR;
+ float ALTITUDE_BUMP_ADR;
+ float ALTITUDE_PANIC_ADR;
+ float SERVOMINPITCH_ADR;
+ float SERVOMINROLL_ADR;
+ float GYRO_ROLL_ZERO_ADR;
+ float GYRO_PITCH_ZERO_ADR;
+ float GYRO_YAW_ZERO_ADR;
+ // Accel Calibration
+ float XAXIS_ACCEL_BIAS_ADR;
+ float XAXIS_ACCEL_SCALE_FACTOR_ADR;
+ float YAXIS_ACCEL_BIAS_ADR;
+ float YAXIS_ACCEL_SCALE_FACTOR_ADR;
+ float ZAXIS_ACCEL_BIAS_ADR;
+ float ZAXIS_ACCEL_SCALE_FACTOR_ADR;
+ // Mag Calibration
+ float XAXIS_MAG_BIAS_ADR;
+ float YAXIS_MAG_BIAS_ADR;
+ float ZAXIS_MAG_BIAS_ADR;
+ // Battery Monitor
+ float BATT_ALARM_VOLTAGE_ADR;
+ float BATT_THROTTLE_TARGET_ADR;
+ float BATT_DOWN_TIME_ADR;
+} t_NVR_Data;
+
+
+void readEEPROM();
+void initSensorsZeroFromEEPROM();
+void storeSensorsZeroToEEPROM();
+void initReceiverFromEEPROM();
+
+float nvrReadFloat(int address); // defined in DataStorage.h
+void nvrWriteFloat(float value, int address); // defined in DataStorage.h
+void nvrReadPID(unsigned char IDPid, unsigned int IDEeprom);
+void nvrWritePID(unsigned char IDPid, unsigned int IDEeprom);
+
+#define GET_NVR_OFFSET(param) ((int)&(((t_NVR_Data*) 0)->param))
+#define readFloat(addr) nvrReadFloat(GET_NVR_OFFSET(addr))
+#define writeFloat(value, addr) nvrWriteFloat(value, GET_NVR_OFFSET(addr))
+#define readPID(IDPid, addr) nvrReadPID(IDPid, GET_NVR_OFFSET(addr))
+#define writePID(IDPid, addr) nvrWritePID(IDPid, GET_NVR_OFFSET(addr))
+
+
+/**
+ * Debug utility global declaration
+ * Debug code should never be part of a release sofware
+ * @see Kenny
+ */
+//#define DEBUG
+byte fastTransfer = OFF; // Used for troubleshooting
+//unsigned long fastTelemetryTime = 0;
+//byte testSignal = LOW;
+//////////////////////////////////////////////////////
+
+#endif // _AQ_GLOBAL_HEADER_DEFINITION_H_
+
diff --git a/AeroQuad/AeroQuad.ino b/AeroQuad/AeroQuad.ino
new file mode 100644
index 00000000..5470189f
--- /dev/null
+++ b/AeroQuad/AeroQuad.ino
@@ -0,0 +1,1436 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+/****************************************************************************
+ Before flight, select the different user options for your AeroQuad below
+ If you need additional assitance go to http://www.aeroquad.com/forum.php
+ or talk to us live on IRC #aeroquad
+*****************************************************************************/
+
+/****************************************************************************
+ ************************* Hardware Configuration ***************************
+ ****************************************************************************/
+// Select which hardware you wish to use with the AeroQuad Flight Software
+
+
+// 328p platform
+//#define AeroQuad_v1 // Arduino 2009 with AeroQuad Shield v1.7 and below
+//#define AeroQuad_v1_IDG // Arduino 2009 with AeroQuad Shield v1.7 and below using IDG yaw gyro
+//#define AeroQuad_v18 // Arduino 2009 with AeroQuad Shield v1.8 or greater
+#define AeroQuad_Mini // Arduino Pro Mini with AeroQuad Mini Shield v1.0
+//#define AeroQuad_Wii // Arduino 2009 with Wii Sensors and AeroQuad Shield v1.x
+//#define AeroQuad_Paris_v3 // Define along with either AeroQuad_Wii to include specific changes for MultiWiiCopter Paris v3.0 board
+
+// Mega platform
+//#define AeroQuadMega_v1 // Arduino Mega with AeroQuad Shield v1.7 and below
+//#define AeroQuadMega_v2 // Arduino Mega with AeroQuad Shield v2.0
+//#define AeroQuadMega_v21 // Arduino Mega with AeroQuad Shield v2.1
+//#define AeroQuadMega_Wii // Arduino Mega with Wii Sensors and AeroQuad Shield v2.x
+//#define ArduCopter // ArduPilot Mega (APM) with Oilpan Sensor Board
+//#define AeroQuadMega_CHR6DM // Clean Arduino Mega with CHR6DM as IMU/heading ref.
+//#define APM_OP_CHR6DM // ArduPilot Mega with CHR6DM as IMU/heading ref., Oilpan for barometer (just uncomment AltitudeHold for baro), and voltage divider
+
+
+/****************************************************************************
+ *********************** Define Flight Configuration ************************
+ ****************************************************************************/
+// Use only one of the following definitions
+//#define quadXConfig
+//#define quadPlusConfig
+//#define hexPlusConfig
+//#define hexXConfig // EXPERIMENTAL: not completely re-tested
+//#define triConfig
+//#define quadY4Config
+#define hexY6Config
+//#define octoX8Config
+//#define octoPlusConfig // EXPERIMENTAL: not completely re-tested
+//#define octoXConfig // EXPERIMENTAL: not completely re-tested
+
+//#define CHANGE_YAW_DIRECTION // if you want to reverse the yaw correction direction
+
+// ******************************************************************************************************************************
+// Define minimum speed for your motors to run. this also defines minimum throttle during flips
+// Some motors or ESC setups may need more or less define here to start all the montors evenly.
+// ******************************************************************************************************************************
+#define MIN_ARMED_THROTTLE 1150
+
+//
+// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+// In the 3.0 code the motor numbering has changed to simplify motor configuration.
+// Please refer to the .h files in ..\Libraries\AQ_FlightControlProcessor to see the new numbering for your flight model
+// Also check the http://www.aeroquad.com/showwiki.php "Build Instructions" for more detail on the 3.0 motor changes
+// the OLD_MOTOR_NUMBERING is compatible with the 2.x versions of the AeroQuad code and will not need re-ordering to work
+// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+//#define OLD_MOTOR_NUMBERING // Uncomment this for old motor numbering setup, FOR QUAD +/X MODE ONLY
+
+//
+// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+// You must define *only* one of the following flightAngle calculations
+// If you only want DCM, then don't define either of the below
+// Use FlightAngleARG if you do not have a magnetometer, use DCM if you have a magnetometer installed
+// +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+//#define FlightAngleMARG // EXPERIMENTAL! Fly at your own risk! Use this if you have a magnetometer installed and enabled HeadingMagHold above
+#define FlightAngleARG // Use this if you do not have a magnetometer installed
+
+//
+// *******************************************************************************************************************************
+// Optional Sensors
+// Warning: If you enable HeadingHold or AltitudeHold and do not have the correct sensors connected, the flight software may hang
+// *******************************************************************************************************************************
+//#define HeadingMagHold // Enables Magnetometer, gets automatically selected if CHR6DM is defined
+//#define AltitudeHoldBaro // Enables BMP085 Barometer (experimental, use at your own risk)
+//#define AltitudeHoldRangeFinder // EXPERIMENTAL : Enable altitude hold with range finder
+//#define RateModeOnly // Use this if you only have a gyro sensor, this will disable any attitude modes.
+
+//
+// *******************************************************************************************************************************
+// Battery Monitor Options
+// For more information on how to setup Battery Monitor please refer to http://aeroquad.com/showwiki.php?title=BatteryMonitor+h
+// *******************************************************************************************************************************
+#define BattMonitor // Enable Battery monitor
+#define BattMonitorAutoDescent // if you want the craft to auto descent when the battery reach the alarm voltage
+#define BattCellCount 3 // set number of Cells (0 == autodetect 1S-3S)
+#define POWERED_BY_VIN // Uncomment this if your v2.x is powered directly by the vin/gnd of the arduino
+
+//
+// *******************************************************************************************************************************
+// Optional Receiver
+// *******************************************************************************************************************************
+//#define RemotePCReceiver // EXPERIMENTAL Use PC as transmitter via serial communicator with XBEE
+//#define ReceiverPPM // Use a ppm receiver
+//#define ReceiverHWPPM // Use a ppm receiver with HW timer, needs a HW modification (see Libraries/AQ_Receiver/Receiver_HWPPM.h)
+// You need to select one of these channel order definitions for PPM receiver
+//#define SKETCH_SERIAL_SUM_PPM SERIAL_SUM_PPM_1 //For Graupner/Spektrum (DEFAULT)
+//#define SKETCH_SERIAL_SUM_PPM SERIAL_SUM_PPM_2 //For Robe/Hitec/Futaba
+//#define SKETCH_SERIAL_SUM_PPM SERIAL_SUM_PPM_3 //For some Hitec/Sanwa/Others
+
+//
+// *******************************************************************************************************************************
+// Optional telemetry (for debug or ground station tracking purposes)
+// For more information on how to setup Telemetry please refer to http://aeroquad.com/showwiki.php?title=Xbee+Installation
+// *******************************************************************************************************************************
+//#define WirelessTelemetry // Enables Wireless telemetry on Serial3 // Wireless telemetry enable
+//#define BinaryWrite // Enables fast binary transfer of flight data to Configurator
+//#define BinaryWritePID // Enables fast binary transfer of attitude PID data
+//#define OpenlogBinaryWrite // Enables fast binary transfer to serial1 and openlog hardware
+
+//
+// *******************************************************************************************************************************
+// Define how many channels are connected from your R/C receiver
+// Please note that the flight software currently only supports 6 channels, additional channels will be supported in the future
+// Additionally 8 receiver channels are only available when not using the Arduino Uno
+// *******************************************************************************************************************************
+#define LASTCHANNEL 6
+//#define LASTCHANNEL 8 // - warning, this needs to be debugged, incorrect COM behaviour appears when selecting this
+
+//
+// *******************************************************************************************************************************
+// Camera Stabilization
+// Servo output goes to D11(pitch), D12(roll), D13(yaw) on AeroQuad v1.8 shield
+// If using v2.0 Shield place jumper between:
+// D12 to D33 for roll, connect servo to SERVO1
+// D11 to D34 for pitch, connect servo to SERVO2
+// D13 to D35 for yaw, connect servo to SERVO3
+// Please note that you will need to have battery connected to power on servos with v2.0 shield
+// *******************************************************************************************************************************
+//#define CameraControl
+
+//
+// *******************************************************************************************************************************
+// On screen display implementation using MAX7456 chip. See MAX7456.h in libraries for more info and configuration.
+// For more information on how to setup OSD please refer to http://aeroquad.com/showwiki.php?title=On-Screen-Display
+// *******************************************************************************************************************************
+//#define OSD
+//Choose your (default in case autodetect enabled) video standard: default=NTSC
+//#define PAL
+//#define AUTODETECT_VIDEO_STANDARD // detect automatically, signal must be present at Arduino powerup!
+//#define ShowReticle // Displays a reticle in the centre of the screen.
+//#define ShowFlightTimer // Displays how long the motors have been armed for since the Arduino was last reset
+//#define ShowAttitudeIndicator // Display the attitude indicator calculated by the AHRS
+//#define ShowCallSign // Show AQ string
+//#define ShowRSSI // Show Receiver RSSI
+//#define feet //Comment this line out for altitude measured in metres, uncomment it for feet
+
+// Menu system, currently only usable with OSD
+//#define OSD_SYSTEM_MENU
+
+
+
+/****************************************************************************
+ ****************************************************************************
+ ****************************************************************************
+ ********************* End of User Definition Section ***********************
+ ****************************************************************************
+ ****************************************************************************
+ ****************************************************************************/
+
+// Checks to make sure we have the right combinations defined
+#if defined(FlightAngleMARG) && !defined(HeadingMagHold)
+ #undef FlightAngleMARG
+#elif defined(HeadingMagHold) && defined(FlightAngleMARG) && defined(FlightAngleARG)
+ #undef FlightAngleARG
+#endif
+
+#include
+#include
+#include
+#include "AeroQuad.h"
+#include "PID.h"
+#include
+#include
+#ifdef BattMonitor
+ #include
+#endif
+
+
+//********************************************************
+//********************************************************
+//********* PLATFORM SPECIFIC SECTION ********************
+//********************************************************
+//********************************************************
+#ifdef AeroQuad_v1
+ #define LED_Green 13
+ #define LED_Red 12
+ #define LED_Yellow 12
+
+ // Gyroscope declaration
+ #include
+
+ // Accelerometer declaration
+ #include
+
+ // Receiver declaration
+ #define RECEIVER_328P
+
+ // Motor declaration
+ #define MOTOR_PWM
+
+ // unsuported in v1
+ #undef AltitudeHoldBaro
+ #undef AltitudeHoldRangeFinder
+ #undef HeadingMagHold
+ #undef BattMonitor
+ #undef CameraControl
+ #undef OSD
+
+ /**
+ * Put AeroQuad_v1 specific intialization need here
+ */
+ void initPlatform() {
+ setGyroAref(aref);
+ }
+
+ /**
+ * Measure critical sensors
+ */
+ void measureCriticalSensors() {
+ if (deltaTime >= 10000) {
+ measureGyro();
+ measureAccel();
+ }
+ }
+#endif
+
+#ifdef AeroQuad_v1_IDG
+ #define LED_Green 13
+ #define LED_Red 12
+ #define LED_Yellow 12
+
+ // Gyroscope declaration
+ #include
+
+ // Accelerometer declaration
+ #include
+
+ // Receiver declaration
+ #define RECEIVER_328P
+
+ // Motor declaration
+ #define MOTOR_PWM
+
+ // unsuported in v1
+ #undef AltitudeHoldBaro
+ #undef AltitudeHoldRangeFinder
+ #undef HeadingMagHold
+ #undef BattMonitor
+ #undef CameraControl
+ #undef OSD
+
+ /**
+ * Put AeroQuad_v1_IDG specific intialization need here
+ */
+ void initPlatform() {
+ setGyroAref(aref);
+ }
+
+ /**
+ * Measure critical sensors
+ */
+ void measureCriticalSensors() {
+ if (deltaTime >= 10000) {
+ measureGyro();
+ measureAccel();
+ }
+ }
+#endif
+
+#ifdef AeroQuad_v18
+ #define LED_Green 13
+ #define LED_Red 12
+ #define LED_Yellow 12
+
+ #include
+
+ // Gyroscope declaration
+ #include
+
+ // Accelerometer declaraion
+ #include
+
+ // Receiver declaration
+ #define RECEIVER_328P
+
+ // Motor declaration
+ #define MOTOR_PWM_Timer
+
+ // heading mag hold declaration
+ #ifdef HeadingMagHold
+ #define HMC5843
+ #endif
+
+ // Battery Monitor declaration
+ #ifdef BattMonitor
+ struct BatteryData batteryData[] = {
+ BM_DEFINE_BATTERY_V(BattCellCount, 0, ((5.0 / 1024.0) * (15.0 + 7.5) / 7.5), 0.9)};
+ #endif
+
+ #undef AltitudeHoldBaro
+ #undef AltitudeHoldRangeFinder
+ #undef CameraControl
+ #undef OSD
+
+ /**
+ * Put AeroQuad_v18 specific intialization need here
+ */
+ void initPlatform() {
+
+ pinMode(LED_Red, OUTPUT);
+ digitalWrite(LED_Red, LOW);
+ pinMode(LED_Yellow, OUTPUT);
+ digitalWrite(LED_Yellow, LOW);
+
+ Wire.begin();
+ TWBR = 12;
+ }
+
+ /**
+ * Measure critical sensors
+ */
+ void measureCriticalSensors() {
+ measureAccelSum();
+ measureGyroSum();
+ }
+
+#endif
+
+#ifdef AeroQuad_Mini
+ #define LED_Green 13
+ #define LED_Red 12
+ #define LED_Yellow 12
+
+ #include
+
+ // Gyroscope declaration
+ #include
+
+ // Accelerometer declaration
+ #include
+
+ // Receiver declaration
+ #define RECEIVER_328P
+
+ // Motor declaration
+ #define MOTOR_PWM
+
+ // heading mag hold declaration
+ #ifdef HeadingMagHold
+ #define HMC5843
+ #endif
+
+ // Battery Monitor declaration
+ #ifdef BattMonitor
+ struct BatteryData batteryData[] = {
+ BM_DEFINE_BATTERY_V(BattCellCount, 0, ((5.0 / 1024.0) * (15.0 + 7.5) / 7.5), 0.53)};
+ #endif
+
+ // unsuported in mini
+ #undef AltitudeHoldBaro
+ #undef AltitudeHoldRangeFinder
+ #undef CameraControl
+ #undef OSD
+
+ /**
+ * Put AeroQuad_Mini specific intialization need here
+ */
+ void initPlatform() {
+ gyroAddress = ITG3200_ADDRESS-1;
+
+ pinMode(LED_Red, OUTPUT);
+ digitalWrite(LED_Red, LOW);
+ pinMode(LED_Yellow, OUTPUT);
+ digitalWrite(LED_Yellow, LOW);
+
+ Wire.begin();
+ TWBR = 12;
+ }
+
+ /**
+ * Measure critical sensors
+ */
+ void measureCriticalSensors() {
+ measureAccelSum();
+ measureGyroSum();
+ }
+#endif
+
+#ifdef AeroQuadMega_v1
+ #define LED_Green 13
+ #define LED_Red 4
+ #define LED_Yellow 31
+
+ // Special thanks to Wilafau for fixes for this setup
+ // http://aeroquad.com/showthread.php?991-AeroQuad-Flight-Software-v2.0&p=11466&viewfull=1#post11466
+ // Gyroscope declaration
+ #include
+
+ // Accelerometer declaration
+ #include
+
+ // Reveiver declaration
+ #define OLD_RECEIVER_PIN_ORDER
+ #define RECEIVER_MEGA
+
+ // Motor declaration
+ #define MOTOR_PWM
+
+ // unsuported on mega v1
+ #undef AltitudeHoldBaro
+ #undef AltitudeHoldRangeFinder
+ #undef HeadingMagHold
+ #undef BattMonitor
+ #undef CameraControl
+ #undef OSD
+
+ /**
+ * Put AeroQuadMega_v1 specific intialization need here
+ */
+ void initPlatform() {
+ setGyroAref(aref);
+ }
+
+ /**
+ * Measure critical sensors
+ */
+ void measureCriticalSensors() {
+ if (deltaTime >= 10000) {
+ measureGyro();
+ measureAccel();
+ }
+ }
+#endif
+
+#ifdef AeroQuadMega_v2
+ #define LED_Green 13
+ #define LED_Red 4
+ #define LED_Yellow 31
+
+ #include
+
+ // Gyroscope declaration
+ #include
+
+ // Accelerometer declaration
+ #include
+
+ // Receiver Declaration
+ #define RECEIVER_MEGA
+
+ // Motor declaration
+ #define MOTOR_PWM_Timer
+
+ // heading mag hold declaration
+ #ifdef HeadingMagHold
+// #define SPARKFUN_5883L_BOB
+// #define HMC5883L
+ #define HMC5843
+ #endif
+
+ // Altitude declaration
+ #ifdef AltitudeHoldBaro
+ #define BMP085
+ #endif
+ #ifdef AltitudeHoldRangeFinder
+ #define XLMAXSONAR
+ #endif
+
+ // Battery Monitor declaration
+ #ifdef BattMonitor
+ #ifdef POWERED_BY_VIN
+ struct BatteryData batteryData[] = {
+ BM_DEFINE_BATTERY_V(BattCellCount, 0, ((5.0 / 1024.0) * (15.0 + 7.5) / 7.5), 0.0)};// v2 shield powered via VIN (no diode)
+ #else
+ struct BatteryData batteryData[] = {
+ BM_DEFINE_BATTERY_V(BattCellCount, 0, ((5.0 / 1024.0) * (15.0 + 7.5) / 7.5),0.82)}; // v2 shield powered via power jack
+ #endif
+ #endif
+
+ #ifdef OSD
+ #define MAX7456_OSD
+ #endif
+
+ /**
+ * Put AeroQuadMega_v2 specific intialization need here
+ */
+ void initPlatform() {
+
+ pinMode(LED_Red, OUTPUT);
+ digitalWrite(LED_Red, LOW);
+ pinMode(LED_Yellow, OUTPUT);
+ digitalWrite(LED_Yellow, LOW);
+
+ // pins set to INPUT for camera stabilization so won't interfere with new camera class
+ pinMode(33, INPUT); // disable SERVO 1, jumper D12 for roll
+ pinMode(34, INPUT); // disable SERVO 2, jumper D11 for pitch
+ pinMode(35, INPUT); // disable SERVO 3, jumper D13 for yaw
+ pinMode(43, OUTPUT); // LED 1
+ pinMode(44, OUTPUT); // LED 2
+ pinMode(45, OUTPUT); // LED 3
+ pinMode(46, OUTPUT); // LED 4
+ digitalWrite(43, HIGH); // LED 1 on
+ digitalWrite(44, HIGH); // LED 2 on
+ digitalWrite(45, HIGH); // LED 3 on
+ digitalWrite(46, HIGH); // LED 4 on
+
+ Wire.begin();
+ TWBR = 12;
+ }
+
+ /**
+ * Measure critical sensors
+ */
+ void measureCriticalSensors() {
+ measureAccelSum();
+ measureGyroSum();
+
+ }
+#endif
+
+#ifdef AeroQuadMega_v21
+ #define LED_Green 13
+ #define LED_Red 4
+ #define LED_Yellow 31
+
+ #define SPARKFUN_9DOF
+
+ #include
+
+ // Gyroscope declaration
+ #include
+
+ // Accelerometer declaration
+ #include
+
+ // Receiver Declaration
+ #define RECEIVER_MEGA
+
+ // Motor declaration
+ #define MOTOR_PWM_Timer
+
+ // heading mag hold declaration
+ #ifdef HeadingMagHold
+ #define HMC5883L
+ #endif
+
+ // Altitude declaration
+ #ifdef AltitudeHoldBaro
+ #define BMP085
+ #endif
+ #ifdef AltitudeHoldRangeFinder
+ #define XLMAXSONAR
+ #endif
+
+
+ // Battery Monitor declaration
+ #ifdef BattMonitor
+ #ifdef POWERED_BY_VIN
+ struct BatteryData batteryData[] = {
+ BM_DEFINE_BATTERY_V(BattCellCount, 0, ((5.0 / 1024.0) * (15.0 + 7.5) / 7.5), 0.0)};// v2 shield powered via VIN (no diode)
+ #else
+ struct BatteryData batteryData[] = {
+ BM_DEFINE_BATTERY_V(BattCellCount, 0, ((5.0 / 1024.0) * (15.0 + 7.5) / 7.5),0.82)}; // v2 shield powered via power jack
+ #endif
+ #endif
+
+ #ifdef OSD
+ #define MAX7456_OSD
+ #endif
+
+ /**
+ * Put AeroQuadMega_v21 specific intialization need here
+ */
+ void initPlatform() {
+
+ pinMode(LED_Red, OUTPUT);
+ digitalWrite(LED_Red, LOW);
+ pinMode(LED_Yellow, OUTPUT);
+ digitalWrite(LED_Yellow, LOW);
+
+ // pins set to INPUT for camera stabilization so won't interfere with new camera class
+ pinMode(33, INPUT); // disable SERVO 1, jumper D12 for roll
+ pinMode(34, INPUT); // disable SERVO 2, jumper D11 for pitch
+ pinMode(35, INPUT); // disable SERVO 3, jumper D13 for yaw
+ pinMode(43, OUTPUT); // LED 1
+ pinMode(44, OUTPUT); // LED 2
+ pinMode(45, OUTPUT); // LED 3
+ pinMode(46, OUTPUT); // LED 4
+ digitalWrite(43, HIGH); // LED 1 on
+ digitalWrite(44, HIGH); // LED 2 on
+ digitalWrite(45, HIGH); // LED 3 on
+ digitalWrite(46, HIGH); // LED 4 on
+
+ Wire.begin();
+ TWBR = 12;
+ }
+
+ /**
+ * Measure critical sensors
+ */
+ void measureCriticalSensors() {
+ measureAccelSum();
+ measureGyroSum();
+ }
+#endif
+
+#ifdef ArduCopter
+ #define LED_Green 37
+ #define LED_Red 35
+ #define LED_Yellow 36
+
+ #if defined (HeadingMagHold) || defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+ #include
+ #else
+ #include
+ #endif
+ #include
+ #include
+
+ // Gyroscope declaration
+ #include
+
+ // Accelerometer Declaration
+ #include
+
+ // Receiver Declaration
+ #define RECEIVER_APM
+
+ // Motor Declaration
+ #define MOTOR_APM
+
+ // heading mag hold declaration
+ #ifdef HeadingMagHold
+ #define HMC5843
+ #endif
+ #ifdef AltitudeHoldRangeFinder
+ #define XLMAXSONAR
+ #endif
+
+
+ // Altitude declaration
+ #ifdef AltitudeHoldBaro
+ #define BMP085
+ #endif
+
+ // Battery monitor declaration
+ #ifdef BattMonitor
+ struct BatteryData batteryData[] = {
+ BM_DEFINE_BATTERY_V(BattCellCount, 0, ((3.27 / 1024.0) * (10.050 + 3.26) / 3.26), 0.306)};
+ #endif
+
+ #undef CameraControl
+ #undef OSD
+
+
+ /**
+ * Put ArduCopter specific intialization need here
+ */
+ void initPlatform() {
+ pinMode(LED_Red, OUTPUT);
+ pinMode(LED_Yellow, OUTPUT);
+ pinMode(LED_Green, OUTPUT);
+
+ initializeADC();
+ initRC();
+
+ Wire.begin();
+ TWBR = 12;
+ }
+
+ /**
+ * Measure critical sensors
+ */
+ void measureCriticalSensors() {
+ if (deltaTime >= 10000) {
+ measureGyro();
+ measureAccel();
+ }
+ }
+#endif
+
+#ifdef AeroQuad_Wii
+ #define LED_Green 13
+ #define LED_Red 12
+ #define LED_Yellow 12
+
+ #include
+
+ // Platform Wii declaration
+ #include
+
+ // Gyroscope declaration
+ #include
+
+ // Accelerometer declaration
+ #include
+
+ // Receiver declaration
+ #define RECEIVER_328P
+
+ // Motor declaration
+ #define MOTOR_PWM
+
+ // heading mag hold declaration
+ // unsuported on mega v1
+ #undef AltitudeHoldBaro
+ #undef AltitudeHoldRangeFinder
+ #undef HeadingMagHold
+ #undef BattMonitor
+ #undef CameraControl
+ #undef OSD
+
+ /**
+ * Put AeroQuad_Wii specific intialization need here
+ */
+ void initPlatform() {
+ Wire.begin();
+
+ #if defined(AeroQuad_Paris_v3)
+ initializeWiiSensors(true);
+ #else
+ initializeWiiSensors();
+ #endif
+ }
+
+ /**
+ * Measure critical sensors
+ */
+ void measureCriticalSensors() {
+ if (deltaTime >= 10000) {
+ readWiiSensors();
+ measureGyro();
+ measureAccel();
+ }
+ }
+#endif
+
+#ifdef AeroQuadMega_Wii
+ #define LED_Green 13
+ #define LED_Red 4
+ #define LED_Yellow 31
+
+ #include
+
+ // Platform Wii declaration
+ #include
+
+ // Gyroscope declaration
+ #include
+
+ // Accelerometer declaration
+ #include
+
+ // Receiver declaration
+ #define RECEIVER_MEGA
+
+ // Motor declaration
+ #define MOTOR_PWM
+
+ // heading mag hold declaration
+ #ifdef HeadingMagHold
+ #define HMC5843
+ #endif
+
+ // Altitude declaration
+ #ifdef AltitudeHoldBaro
+ #define BMP085
+ #endif
+ #ifdef AltitudeHoldRangeFinder
+ #define XLMAXSONAR
+ #endif
+
+ // Battery monitor declaration
+ #ifdef BattMonitor
+ struct BatteryData batteryData[] = {
+ BM_DEFINE_BATTERY_V(BattCellCount, 0, ((5.0 / 1024.0) * (15.0 + 7.5) / 7.5), 0.9)};
+ #endif
+
+ #ifdef OSD
+ #define MAX7456_OSD
+ #endif
+
+ /**
+ * Put AeroQuadMega_Wii specific intialization need here
+ */
+ void initPlatform() {
+ Wire.begin();
+
+ initializeWiiSensors();
+ }
+
+ /**
+ * Measure critical sensors
+ */
+ void measureCriticalSensors() {
+ if (deltaTime >= 10000) {
+ readWiiSensors();
+ measureGyro();
+ measureAccel();
+ }
+ }
+#endif
+
+#ifdef AeroQuadMega_CHR6DM
+ #define LED_Green 13
+ #define LED_Red 4
+ #define LED_Yellow 31
+
+ #include
+ #include
+ CHR6DM chr6dm;
+
+ // Gyroscope declaration
+ #include
+
+ // Accelerometer declaration
+ #include
+
+ // Receiver declaration
+ #define RECEIVER_MEGA
+
+ // Motor declaration
+ #define MOTOR_PWM
+
+ // Kinematics declaration
+ #include "Kinematics_CHR6DM.h"
+
+ // Compas declaration
+ #define HeadingMagHold
+ #define COMPASS_CHR6DM
+ #include
+
+ #ifdef OSD
+ #define MAX7456_OSD
+ #endif
+
+ // Altitude declaration
+ #ifdef AltitudeHoldBaro
+ #define BMP085
+ #endif
+ #ifdef AltitudeHoldRangeFinder
+ #define XLMAXSONAR
+ #endif
+
+ // Battery monitor declaration
+ #ifdef BattMonitor
+ struct BatteryData batteryData[] = {
+ BM_DEFINE_BATTERY_V(BattCellCount, 0, ((3.27 / 1024.0) * (10.050 + 3.260) / 3.260), 0.9)};
+ #endif
+
+ /**
+ * Put AeroQuadMega_CHR6DM specific intialization need here
+ */
+ void initPlatform() {
+ Serial1.begin(BAUD);
+ PORTD = B00000100;
+
+ Wire.begin();
+
+ chr6dm.resetToFactory();
+ chr6dm.setListenMode();
+ chr6dm.setActiveChannels(CHANNEL_ALL_MASK);
+ chr6dm.requestPacket();
+
+ gyroChr6dm = &chr6dm;
+ accelChr6dm = &chr6dm;
+ kinematicsChr6dm = &chr6dm;
+ compassChr6dm = &chr6dm;
+ }
+
+ /**
+ * Measure critical sensors
+ */
+ void measureCriticalSensors() {
+ if (deltaTime >= 10000) {
+ chr6dm.read();
+ measureGyro();
+ measureAccel();
+ }
+ }
+#endif
+
+#ifdef APM_OP_CHR6DM
+ #define LED_Green 37
+ #define LED_Red 35
+ #define LED_Yellow 36
+
+ #include
+ #include
+ CHR6DM chr6dm;
+
+ // Gyroscope declaration
+ #include
+
+ // Accelerometer declaration
+ #include
+
+ // Receiver declaration
+ #define RECEIVER_APM
+
+ // Motor declaration
+ #define MOTOR_APM
+
+ // Kinematics declaration
+ #include "Kinematics_CHR6DM.h"
+
+ // Compas declaration
+ #define HeadingMagHold
+ #define COMPASS_CHR6DM
+ #include
+
+ // Altitude declaration
+ #ifdef AltitudeHoldBaro
+ #define BMP085
+ #endif
+ #ifdef AltitudeHoldRangeFinder
+ #define XLMAXSONAR
+ #endif
+
+
+ // Battery monitor declaration
+ #ifdef BattMonitor
+ struct BatteryData batteryData[] = {
+ BM_DEFINE_BATTERY_V(BattCellCount, 0, ((3.27 / 1024.0) * (10.050 + 3.260) / 3.260), 0.306)};
+ #endif
+
+ #undef CameraControl
+ #undef OSD
+
+ /**
+ * Put APM_OP_CHR6DM specific intialization need here
+ */
+ void initPlatform() {
+ pinMode(LED_Red, OUTPUT);
+ pinMode(LED_Yellow, OUTPUT);
+ pinMode(LED_Green, OUTPUT);
+
+ Serial1.begin(BAUD);
+ PORTD = B00000100;
+
+ Wire.begin();
+
+ chr6dm.resetToFactory();
+ chr6dm.setListenMode();
+ chr6dm.setActiveChannels(CHANNEL_ALL_MASK);
+ chr6dm.requestPacket();
+
+ gyroChr6dm = &chr6dm;
+ accelChr6dm = &chr6dm;
+ kinematicsChr6dm = &chr6dm;
+// tempKinematics.setGyroscope(&gyroSpecific);
+ compassChr6dm = &chr6dm;
+ }
+
+ /**
+ * Measure critical sensors
+ */
+ void measureCriticalSensors() {
+ if (deltaTime >= 10000) {
+ chr6dm.read();
+ measureGyro();
+ measureAccel();
+ }
+ }
+#endif
+
+//********************************************************
+//********************************************************
+//********* HARDWARE GENERALIZATION SECTION **************
+//********************************************************
+//********************************************************
+
+//********************************************************
+//****************** KINEMATICS DECLARATION **************
+//********************************************************
+#include "Kinematics.h"
+#if defined (AeroQuadMega_CHR6DM) || defined (APM_OP_CHR6DM)
+ // CHR6DM have it's own kinematics, so, initialize in it's scope
+#elif defined FlightAngleNewARG
+ #include "Kinematics_NewMARG.h"
+#elif defined FlightAngleARG
+ #include "Kinematics_ARG.h"
+#elif defined FlightAngleMARG
+ #include "Kinematics_MARG.h"
+#else
+ #include "Kinematics_DCM.h"
+#endif
+
+//********************************************************
+//******************** RECEIVER DECLARATION **************
+//********************************************************
+#if defined ReceiverHWPPM
+ #include
+#elif defined ReceiverPPM
+ #include
+#elif defined (AeroQuad_Mini) && (defined (hexPlusConfig) || defined (hexXConfig) || defined (hexY6Config))
+ #include
+#elif defined RemotePCReceiver
+ #include
+#elif defined RECEIVER_328P
+ #include
+#elif defined RECEIVER_MEGA
+ #include
+#elif defined RECEIVER_APM
+ #include
+#endif
+
+
+//********************************************************
+//********************** MOTORS DECLARATION **************
+//********************************************************
+#if defined triConfig
+ #include
+#elif defined MOTOR_PWM
+ #include
+#elif defined MOTOR_PWM_Timer
+ #include
+#elif defined MOTOR_APM
+ #include
+#elif defined MOTOR_I2C
+ #include
+#endif
+
+//********************************************************
+//******* HEADING HOLD MAGNETOMETER DECLARATION **********
+//********************************************************
+#if defined (HMC5843)
+ #include
+#elif defined (HMC5883L)
+ #include
+#elif defined (COMPASS_CHR6DM)
+#endif
+
+//********************************************************
+//******* ALTITUDE HOLD BAROMETER DECLARATION ************
+//********************************************************
+#if defined (BMP085)
+ #include
+#endif
+#if defined (XLMAXSONAR)
+ #include
+#endif
+//********************************************************
+//*************** BATTERY MONITOR DECLARATION ************
+//********************************************************
+#ifdef BattMonitor
+ #include
+#endif
+//********************************************************
+//************** CAMERA CONTROL DECLARATION **************
+//********************************************************
+// used only on mega for now
+#ifdef CameraControl
+ #include
+#endif
+
+
+//********************************************************
+//******** FLIGHT CONFIGURATION DECLARATION **************
+//********************************************************
+#if defined quadXConfig
+ #include "FlightControlQuadX.h"
+#elif defined quadPlusConfig
+ #include "FlightControlQuadPlus.h"
+#elif defined hexPlusConfig
+ #include "FlightControlHexPlus.h"
+#elif defined hexXConfig
+ #include "FlightControlHexX.h"
+#elif defined triConfig
+ #include "FlightControlTri.h"
+#elif defined quadY4Config
+ #include "FlightControlQuadY4.h"
+#elif defined hexY6Config
+ #include "FlightControlHexY6.h"
+#elif defined octoX8Config
+ #include "FlightControlOctoX8.h"
+#elif defined octoXConfig
+ #include "FlightControlOctoX.h"
+#elif defined octoPlusConfig
+ #include "FlightControlOctoPlus.h"
+#endif
+
+//********************************************************
+//****************** OSD DEVICE DECLARATION **************
+//********************************************************
+#ifdef MAX7456_OSD // only OSD supported for now is the MAX7456
+ #include
+ #include "OSDDisplayController.h"
+ #include "MAX7456.h"
+ #ifdef OSD_SYSTEM_MENU
+ #include "OSDMenu.h"
+ #endif
+#else
+ #undef OSD_SYSTEM_MENU // can't use menu system without an osd,
+#endif
+
+//********************************************************
+//****************** SERIAL PORT DECLARATION *************
+//********************************************************
+#if defined (WirelessTelemetry)
+ #if defined (__AVR_ATmega1280__) || defined (__AVR_ATmega2560__)
+ #define SERIAL_PORT Serial3
+ #else // force 328p to use the normal port
+ #define SERIAL_PORT Serial
+ #endif
+#else
+ #define SERIAL_PORT Serial
+#endif
+
+// Include this last as it contains objects from above declarations
+#include "AltitudeControlProcessor.h"
+#include "FlightControlProcessor.h"
+#include "FlightCommandProcessor.h"
+#include "HeadingHoldProcessor.h"
+#include "DataStorage.h"
+#include "SerialCom.h"
+
+
+
+/**
+ * Main setup function, called one time at bootup
+ * initalize all system and sub system of the
+ * Aeroquad
+ */
+void setup() {
+ SERIAL_BEGIN(BAUD);
+ pinMode(LED_Green, OUTPUT);
+ digitalWrite(LED_Green, LOW);
+
+ #ifdef CHANGE_YAW_DIRECTION
+ YAW_DIRECTION = -1;
+ #endif
+
+ // Read user values from EEPROM
+ readEEPROM(); // defined in DataStorage.h
+ if (readFloat(SOFTWARE_VERSION_ADR) != SOFTWARE_VERSION) { // If we detect the wrong soft version, we init all parameters
+ initializeEEPROM();
+ writeEEPROM();
+ }
+
+ initPlatform();
+
+ // Configure motors
+ #if defined(quadXConfig) || defined(quadPlusConfig) || defined(quadY4Config) || defined(triConfig)
+ initializeMotors(FOUR_Motors);
+ #elif defined(hexPlusConfig) || defined(hexXConfig) || defined (hexY6Config)
+ initializeMotors(SIX_Motors);
+ #elif defined (octoX8Config) || defined (octoXConfig) || defined (octoPlusConfig)
+ initializeMotors(EIGHT_Motors);
+ #endif
+
+ // Setup receiver pins for pin change interrupts
+ initializeReceiver(LASTCHANNEL);
+ initReceiverFromEEPROM();
+
+ // Initialize sensors
+ // If sensors have a common initialization routine
+ // insert it into the gyro class because it executes first
+ initializeGyro(); // defined in Gyro.h
+ initializeAccel(); // defined in Accel.h
+ initSensorsZeroFromEEPROM();
+
+ // Calibrate sensors
+ calibrateGyro();
+ computeAccelBias();
+ zeroIntegralError();
+
+ // Flight angle estimation
+ #ifdef HeadingMagHold
+ initializeMagnetometer();
+ initializeKinematics(getHdgXY(XAXIS), getHdgXY(YAXIS));
+ #else
+ initializeKinematics(1.0, 0.0); // with no compass, DCM matrix initalizes to a heading of 0 degrees
+ #endif
+ // Integral Limit for attitude mode
+ // This overrides default set in readEEPROM()
+ // Set for 1/2 max attitude command (+/-0.75 radians)
+ // Rate integral not used for now
+ PID[ATTITUDE_XAXIS_PID_IDX].windupGuard = 0.375;
+ PID[ATTITUDE_YAXIS_PID_IDX].windupGuard = 0.375;
+
+ // Optional Sensors
+ #ifdef AltitudeHoldBaro
+ initializeBaro();
+ #endif
+ #ifdef AltitudeHoldRangeFinder
+ inititalizeRangeFinder(ALTITUDE_RANGE_FINDER_INDEX);
+ #endif
+
+
+ // Battery Monitor
+ #ifdef BattMonitor
+ // batteryMonitorAlarmVoltage updated in readEEPROM()
+ initializeBatteryMonitor(sizeof(batteryData) / sizeof(struct BatteryData), batteryMonitorAlarmVoltage);
+ vehicleState |= BATTMONITOR_ENABLED;
+ #endif
+
+ // Camera stabilization setup
+ #if defined (CameraControl)
+ initializeCameraStabilization();
+ setmCameraRoll(318.3); // Need to figure out nice way to reverse servos
+ setCenterRoll(1500); // Need to figure out nice way to set center position
+ setmCameraPitch(318.3);
+ setCenterPitch(1300);
+ vehicleState |= CAMERASTABLE_ENABLED;
+ #endif
+
+ #if defined(MAX7456_OSD)
+ initializeSPI();
+ initializeOSD();
+ #endif
+
+ #if defined(BinaryWrite) || defined(BinaryWritePID)
+ #ifdef OpenlogBinaryWrite
+ binaryPort = &Serial1;
+ binaryPort->begin(115200);
+ delay(1000);
+ #else
+ binaryPort = &Serial;
+ #endif
+ #endif
+
+ setupFourthOrder();
+
+ previousTime = micros();
+ digitalWrite(LED_Green, HIGH);
+ safetyCheck = 0;
+}
+
+/*******************************************************************
+ // tasks (microseconds of interval)
+ ReadGyro readGyro ( 5000); // 200hz
+ ReadAccel readAccel ( 5000); // 200hz
+ RunDCM runDCM ( 10000); // 100hz
+ FlightControls flightControls( 10000); // 100hz
+ ReadReceiver readReceiver ( 20000); // 50hz
+ ReadBaro readBaro ( 40000); // 25hz
+ ReadCompass readCompass ( 100000); // 10Hz
+ ProcessTelem processTelem ( 100000); // 10Hz
+ ReadBattery readBattery ( 100000); // 10Hz
+
+ Task *tasks[] = {&readGyro, &readAccel, &runDCM, &flightControls, \
+ &readReceiver, &readBaro, &readCompass, \
+ &processTelem, &readBattery};
+
+ TaskScheduler sched(tasks, NUM_TASKS(tasks));
+
+ sched.run();
+*******************************************************************/
+void loop () {
+ currentTime = micros();
+ deltaTime = currentTime - previousTime;
+
+ measureCriticalSensors();
+
+ // Main scheduler loop set for 100hz
+ if (deltaTime >= 10000) {
+
+ frameCounter++;
+
+ // ================================================================
+ // 100hz task loop
+ // ================================================================
+ if (frameCounter % 1 == 0) { // 100 Hz tasks
+
+ G_Dt = (currentTime - hundredHZpreviousTime) / 1000000.0;
+ hundredHZpreviousTime = currentTime;
+
+ evaluateMetersPerSec();
+ evaluateGyroRate();
+
+ float filteredAccelRoll = computeFourthOrder(meterPerSec[XAXIS], &fourthOrder[AX_FILTER]);
+ float filteredAccelPitch = computeFourthOrder(meterPerSec[YAXIS], &fourthOrder[AY_FILTER]);
+ float filteredAccelYaw = computeFourthOrder(meterPerSec[ZAXIS], &fourthOrder[AZ_FILTER]);
+
+ // ****************** Calculate Absolute Angle *****************
+ #if defined FlightAngleNewARG
+ calculateKinematics(gyroRate[XAXIS],
+ gyroRate[YAXIS],
+ gyroRate[ZAXIS],
+ filteredAccelRoll,
+ filteredAccelPitch,
+ filteredAccelYaw,
+ 0.0,
+ 0.0,
+ 0.0,
+ G_Dt);
+
+ #elif defined HeadingMagHold && defined FlightAngleMARG
+ calculateKinematics(gyroRate[XAXIS],
+ gyroRate[YAXIS],
+ gyroRate[ZAXIS],
+ filteredAccelRoll,
+ filteredAccelPitch,
+ filteredAccelYaw,
+ getMagnetometerRawData(XAXIS),
+ getMagnetometerRawData(YAXIS),
+ getMagnetometerRawData(ZAXIS),
+ G_Dt);
+ #elif defined FlightAngleARG
+ calculateKinematics(gyroRate[XAXIS],
+ gyroRate[YAXIS],
+ gyroRate[ZAXIS],
+ filteredAccelRoll,
+ filteredAccelPitch,
+ filteredAccelYaw,
+ 0.0,
+ 0.0,
+ 0.0,
+ G_Dt);
+ #elif defined HeadingMagHold && !defined FlightAngleMARG && !defined FlightAngleARG
+ calculateKinematics(gyroRate[XAXIS],
+ gyroRate[YAXIS],
+ gyroRate[ZAXIS],
+ filteredAccelRoll,
+ filteredAccelPitch,
+ filteredAccelYaw,
+ accelOneG,
+ getHdgXY(XAXIS),
+ getHdgXY(YAXIS),
+ G_Dt);
+ #elif !defined HeadingMagHold && !defined FlightAngleMARG && !defined FlightAngleARG
+ calculateKinematics(gyroRate[XAXIS],
+ gyroRate[YAXIS],
+ gyroRate[ZAXIS],
+ filteredAccelRoll,
+ filteredAccelPitch,
+ filteredAccelYaw,
+ accelOneG,
+ 0.0,
+ 0.0,
+ G_Dt);
+ #endif
+
+ // Combines external pilot commands and measured sensor data to generate motor commands
+ processFlightControl();
+
+ #ifdef BinaryWrite
+ if (fastTransfer == ON) {
+ // write out fastTelemetry to Configurator or openLog
+ fastTelemetry();
+ }
+ #endif
+
+ #ifdef AltitudeHoldRangeFinder
+ readRangeFinderDistanceSum(ALTITUDE_RANGE_FINDER_INDEX);
+ #endif
+ }
+
+ // ================================================================
+ // 50hz task loop
+ // ================================================================
+ if (frameCounter % 2 == 0) { // 50 Hz tasks
+
+ G_Dt = (currentTime - fiftyHZpreviousTime) / 1000000.0;
+ fiftyHZpreviousTime = currentTime;
+
+ // Reads external pilot commands and performs functions based on stick configuration
+ readPilotCommands(); // defined in FlightCommand.pde
+
+ #if defined AltitudeHoldBaro
+ measureBaro(); // defined in altitude.h
+ #endif
+ #ifdef AltitudeHoldRangeFinder
+ evaluateDistanceFromSample(ALTITUDE_RANGE_FINDER_INDEX);
+ #endif
+
+ #if defined(CameraControl)
+ cameraControlSetPitch(kinematicsAngle[YAXIS]);
+ cameraControlSetRoll(kinematicsAngle[XAXIS]);
+ cameraControlSetYaw(kinematicsAngle[ZAXIS]);
+ cameraControlMove();
+ #endif
+ }
+
+ // ================================================================
+ // 10hz task loop
+ // ================================================================
+ if (frameCounter % 10 == 0) { // 10 Hz tasks
+
+ G_Dt = (currentTime - tenHZpreviousTime) / 1000000.0;
+ tenHZpreviousTime = currentTime;
+
+ #if defined(HeadingMagHold)
+ measureMagnetometer(kinematicsAngle[XAXIS], kinematicsAngle[YAXIS]);
+ #endif
+ #if defined(BattMonitor)
+ measureBatteryVoltage(G_Dt);
+ #endif
+
+
+ // Listen for configuration commands and reports telemetry
+ readSerialCommand(); // defined in SerialCom.pde
+ sendSerialTelemetry(); // defined in SerialCom.pde
+
+ #ifdef OSD_SYSTEM_MENU
+ updateOSDMenu();
+ #endif
+
+ #ifdef MAX7456_OSD
+ updateOSD();
+ #endif
+ }
+
+ previousTime = currentTime;
+ }
+ if (frameCounter >= 100) {
+ frameCounter = 0;
+ }
+}
+
+
diff --git a/AeroQuad/AltitudeControlProcessor.h b/AeroQuad/AltitudeControlProcessor.h
new file mode 100644
index 00000000..70a7826a
--- /dev/null
+++ b/AeroQuad/AltitudeControlProcessor.h
@@ -0,0 +1,123 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+// FlightControl.pde is responsible for combining sensor measurements and
+// transmitter commands into motor commands for the defined flight configuration (X, +, etc.)
+//////////////////////////////////////////////////////////////////////////////
+/////////////////////////// calculateFlightError /////////////////////////////
+//////////////////////////////////////////////////////////////////////////////
+
+/**
+ * Altitude control processor do the premilary treatment on throttle correction
+ * to control the altitude of the craft. It then modify directly the
+ * throttle variable use by the motor matrix calculation
+ */
+
+#ifndef _AQ_ALTITUDE_CONTROL_PROCESSOR_H_
+#define _AQ_ALTITUDE_CONTROL_PROCESSOR_H_
+
+/**
+ * getAltitudeFromSensors
+ *
+ * @return the current craft altitude depending of the sensors used
+ */
+#if defined (AltitudeHoldBaro) && defined (AltitudeHoldRangeFinder)
+
+ /**
+ * @return the most precise altitude, sonar if the reading is ok, otherwise baro
+ * it also correct the baro ground altitude to have a smoot sensor switch
+ */
+ float getAltitudeFromSensors() {
+
+ if (rangeFinderRange[ALTITUDE_RANGE_FINDER_INDEX] != INVALID_ALTITUDE) {
+ baroGroundAltitude = baroRawAltitude - rangeFinderRange[ALTITUDE_RANGE_FINDER_INDEX];
+ return (rangeFinderRange[ALTITUDE_RANGE_FINDER_INDEX]);
+ }
+ else {
+ return getBaroAltitude();
+ }
+ }
+
+#elif defined (AltitudeHoldBaro) && !defined (AltitudeHoldRangeFinder)
+
+ /**
+ * @return the baro altitude
+ */
+ float getAltitudeFromSensors() {
+ return getBaroAltitude();
+ }
+
+#elif !defined (AltitudeHoldBaro) && defined (AltitudeHoldRangeFinder)
+ /**
+ * @return the sonar altitude
+ */
+ float getAltitudeFromSensors() {
+ return (rangeFinderRange[ALTITUDE_RANGE_FINDER_INDEX]);
+ }
+
+#endif
+
+
+/**
+ * processAltitudeHold
+ *
+ * This function is responsible to process the throttle correction
+ * to keep the current altitude if selected by the user
+ */
+void processAltitudeHold()
+{
+ // ****************************** Altitude Adjust *************************
+ // Thanks to Honk for his work with altitude hold
+ // http://aeroquad.com/showthread.php?792-Problems-with-BMP085-I2C-barometer
+ // Thanks to Sherbakov for his work in Z Axis dampening
+ // http://aeroquad.com/showthread.php?359-Stable-flight-logic...&p=10325&viewfull=1#post10325
+ #if defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+ if (altitudeHoldState == ON) {
+ float currentAltitude = getAltitudeFromSensors();
+ if (currentAltitude == INVALID_ALTITUDE) {
+ throttle = receiverCommand[THROTTLE];
+ return;
+ }
+ int altitudeHoldThrottleCorrection = updatePID(altitudeToHoldTarget, currentAltitude, &PID[ALTITUDE_HOLD_PID_IDX]);
+ altitudeHoldThrottleCorrection = constrain(altitudeHoldThrottleCorrection, minThrottleAdjust, maxThrottleAdjust);
+ if (abs(altitudeHoldThrottle - receiverCommand[THROTTLE]) > altitudeHoldPanicStickMovement) {
+ altitudeHoldState = ALTPANIC; // too rapid of stick movement so PANIC out of ALTHOLD
+ } else {
+ if (receiverCommand[THROTTLE] > (altitudeHoldThrottle + altitudeHoldBump)) { // AKA changed to use holdThrottle + ALTBUMP - (was MAXCHECK) above 1900
+ altitudeToHoldTarget += 0.01;
+ }
+ if (receiverCommand[THROTTLE] < (altitudeHoldThrottle - altitudeHoldBump)) { // AKA change to use holdThorrle - ALTBUMP - (was MINCHECK) below 1100
+ altitudeToHoldTarget -= 0.01;
+ }
+ }
+ throttle = altitudeHoldThrottle + altitudeHoldThrottleCorrection;
+ }
+ else {
+ throttle = receiverCommand[THROTTLE];
+ }
+ #else
+ throttle = receiverCommand[THROTTLE];
+ #endif
+}
+
+
+
+#endif // _AQ_ALTITUDE_CONTROL_PROCESSOR_H_
+
diff --git a/AeroQuad/DataStorage.h b/AeroQuad/DataStorage.h
new file mode 100644
index 00000000..3d75034f
--- /dev/null
+++ b/AeroQuad/DataStorage.h
@@ -0,0 +1,340 @@
+/*
+ AeroQuad v2.4 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+// Special thanks for 1k space optimization update from Ala42
+// http://aeroquad.com/showthread.php?1369-The-big-enhancement-addition-to-2.0-code&p=13359&viewfull=1#post13359
+
+#ifndef _AQ_DATA_STORAGE_H_
+#define _AQ_DATA_STORAGE_H_
+
+// Utilities for writing and reading from the EEPROM
+float nvrReadFloat(int address) {
+ union floatStore {
+ byte floatByte[4];
+ unsigned short floatUShort[2];
+ float floatVal;
+ } floatOut;
+
+#ifdef EEPROM_USES_16BIT_WORDS
+ for (int i = 0; i < 2; i++)
+ floatOut.floatUShort[i] = EEPROM.read(address + 2*i);
+#else
+ for (int i = 0; i < 4; i++)
+ floatOut.floatByte[i] = EEPROM.read(address + i);
+#endif
+
+ return floatOut.floatVal;
+}
+
+void nvrWriteFloat(float value, int address) {
+ union floatStore {
+ byte floatByte[4];
+ unsigned short floatUShort[2];
+ float floatVal;
+ } floatIn;
+
+ floatIn.floatVal = value;
+#ifdef EEPROM_USES_16BIT_WORDS
+ for (int i = 0; i < 2; i++)
+ EEPROM.write(address + 2*i, floatIn.floatUShort[i]);
+#else
+ for (int i = 0; i < 4; i++)
+ EEPROM.write(address + i, floatIn.floatByte[i]);
+#endif
+}
+
+void nvrReadPID(unsigned char IDPid, unsigned int IDEeprom) {
+ struct PIDdata* pid = &PID[IDPid];
+ pid->P = nvrReadFloat(IDEeprom);
+ pid->I = nvrReadFloat(IDEeprom+4);
+ pid->D = nvrReadFloat(IDEeprom+8);
+ pid->lastPosition = 0;
+ pid->integratedError = 0;
+}
+
+void nvrWritePID(unsigned char IDPid, unsigned int IDEeprom) {
+ struct PIDdata* pid = &PID[IDPid];
+ nvrWriteFloat(pid->P, IDEeprom);
+ nvrWriteFloat(pid->I, IDEeprom+4);
+ nvrWriteFloat(pid->D, IDEeprom+8);
+}
+
+// contains all default values when re-writing EEPROM
+void initializeEEPROM() {
+ PID[RATE_XAXIS_PID_IDX].P = 100.0;
+ PID[RATE_XAXIS_PID_IDX].I = 0.0;
+ PID[RATE_XAXIS_PID_IDX].D = -300.0;
+ PID[RATE_YAXIS_PID_IDX].P = 100.0;
+ PID[RATE_YAXIS_PID_IDX].I = 0.0;
+ PID[RATE_YAXIS_PID_IDX].D = -300.0;
+ PID[ZAXIS_PID_IDX].P = 200.0;
+ PID[ZAXIS_PID_IDX].I = 5.0;
+ PID[ZAXIS_PID_IDX].D = 0.0;
+ PID[ATTITUDE_XAXIS_PID_IDX].P = 4.0;
+ PID[ATTITUDE_XAXIS_PID_IDX].I = 0.0;
+ PID[ATTITUDE_XAXIS_PID_IDX].D = 0.0;
+ PID[ATTITUDE_YAXIS_PID_IDX].P = 4.0;
+ PID[ATTITUDE_YAXIS_PID_IDX].I = 0.0;
+ PID[ATTITUDE_YAXIS_PID_IDX].D = 0.0;
+ PID[HEADING_HOLD_PID_IDX].P = 3.0;
+ PID[HEADING_HOLD_PID_IDX].I = 0.1;
+ PID[HEADING_HOLD_PID_IDX].D = 0.0;
+ // AKA PID experiements
+ PID[ATTITUDE_GYRO_XAXIS_PID_IDX].P = 100.0;
+ PID[ATTITUDE_GYRO_XAXIS_PID_IDX].I = 0.0;
+ PID[ATTITUDE_GYRO_XAXIS_PID_IDX].D = -300.0;
+ PID[ATTITUDE_GYRO_YAXIS_PID_IDX].P = 100.0;
+ PID[ATTITUDE_GYRO_YAXIS_PID_IDX].I = 0.0;
+ PID[ATTITUDE_GYRO_YAXIS_PID_IDX].D = -300.0;
+
+ PID[ALTITUDE_HOLD_PID_IDX].P = 25.0;
+ PID[ALTITUDE_HOLD_PID_IDX].I = 0.6;
+ PID[ALTITUDE_HOLD_PID_IDX].D = 0.0;
+ PID[ALTITUDE_HOLD_PID_IDX].windupGuard = 25.0; //this prevents the 0.1 I term to rise too far
+ PID[ZDAMPENING_PID_IDX].P = 0.0;
+ PID[ZDAMPENING_PID_IDX].I = 0.0;
+ PID[ZDAMPENING_PID_IDX].D = 0.0;
+
+ #if defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+ minThrottleAdjust = -50.0;
+ maxThrottleAdjust = 50.0; //we don't want it to be able to take over totally
+ #if defined AltitudeHoldBaro
+ baroSmoothFactor = 0.1;
+ #endif
+ altitudeHoldBump = 90;
+ altitudeHoldPanicStickMovement = 250;
+ #endif
+
+ // Accel Cal
+ accelScaleFactor[XAXIS] = 1.0;
+ runTimeAccelBias[XAXIS] = 0.0;
+ accelScaleFactor[YAXIS] = 1.0;
+ runTimeAccelBias[YAXIS] = 0.0;
+ accelScaleFactor[ZAXIS] = 1.0;
+ runTimeAccelBias[ZAXIS] = 0.0;
+
+ #ifdef HeadingMagHold
+ magBias[XAXIS] = 0.0;
+ magBias[YAXIS] = 0.0;
+ magBias[ZAXIS] = 0.0;
+ #endif
+ windupGuard = 1000.0;
+
+ // AKA - added so that each PID has its own windupGuard, will need to be removed once each PID's range is established and put in the eeprom
+ for (byte i = XAXIS; i <= ZDAMPENING_PID_IDX; i++ ) {
+ if (i != ALTITUDE_HOLD_PID_IDX) {
+ PID[i].windupGuard = windupGuard;
+ }
+ }
+
+ receiverXmitFactor = 1.0;
+ gyroSmoothFactor = 1.0;
+ accelSmoothFactor = 1.0;
+ // AKA - old setOneG not in SI - accel->setOneG(500);
+ accelOneG = -9.80665; // AKA set one G to 9.8 m/s^2
+ for (byte channel = XAXIS; channel < LASTCHANNEL; channel++) {
+ receiverSlope[channel] = 1.0;
+ receiverOffset[channel] = 0.0;
+ receiverSmoothFactor[channel] = 1.0;
+ }
+ receiverSmoothFactor[ZAXIS] = 0.5;
+
+ flightMode = RATE_FLIGHT_MODE;
+ headingHoldConfig = ON;
+ aref = 5.0; // Use 3.0 if using a v1.7 shield or use 2.8 for an AeroQuad Shield < v1.7
+
+ // Battery Monitor
+ #ifdef BattMonitor
+ batteryMonitorAlarmVoltage = 3.33;
+ batteryMonitorThrottleTarget = 1450;
+ batteryMonitorGoinDownTime = 60000;
+ #endif
+}
+
+void readEEPROM() {
+ readPID(XAXIS, ROLL_PID_GAIN_ADR);
+ readPID(YAXIS, PITCH_PID_GAIN_ADR);
+ readPID(ZAXIS, YAW_PID_GAIN_ADR);
+ readPID(ATTITUDE_XAXIS_PID_IDX, LEVELROLL_PID_GAIN_ADR);
+ readPID(ATTITUDE_YAXIS_PID_IDX, LEVELPITCH_PID_GAIN_ADR);
+ readPID(HEADING_HOLD_PID_IDX, HEADING_PID_GAIN_ADR);
+ readPID(ATTITUDE_GYRO_XAXIS_PID_IDX, LEVEL_GYRO_ROLL_PID_GAIN_ADR);
+ readPID(ATTITUDE_GYRO_YAXIS_PID_IDX, LEVEL_GYRO_PITCH_PID_GAIN_ADR);
+
+ // Leaving separate PID reads as commented for now
+ // Previously had issue where EEPROM was not reading right data
+ readPID(ALTITUDE_HOLD_PID_IDX, ALTITUDE_PID_GAIN_ADR);
+ PID[ALTITUDE_HOLD_PID_IDX].windupGuard = readFloat(ALTITUDE_WINDUP_ADR);
+ minThrottleAdjust = readFloat(ALTITUDE_MIN_THROTTLE_ADR);
+ maxThrottleAdjust = readFloat(ALTITUDE_MAX_THROTTLE_ADR);
+ #if defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+ #if defined AltitudeHoldBaro
+ baroSmoothFactor = readFloat(ALTITUDE_SMOOTH_ADR);
+ #endif
+ altitudeHoldBump = readFloat(ALTITUDE_BUMP_ADR);
+ altitudeHoldPanicStickMovement = readFloat(ALTITUDE_PANIC_ADR);
+ #endif
+ readPID(ZDAMPENING_PID_IDX, ZDAMP_PID_GAIN_ADR);
+
+ // Accel calibration
+ accelScaleFactor[XAXIS] = readFloat(XAXIS_ACCEL_SCALE_FACTOR_ADR);
+ runTimeAccelBias[XAXIS] = readFloat(XAXIS_ACCEL_BIAS_ADR);
+ accelScaleFactor[YAXIS] = readFloat(YAXIS_ACCEL_SCALE_FACTOR_ADR);
+ runTimeAccelBias[YAXIS] = readFloat(YAXIS_ACCEL_BIAS_ADR);
+ accelScaleFactor[ZAXIS] = readFloat(ZAXIS_ACCEL_SCALE_FACTOR_ADR);
+ runTimeAccelBias[ZAXIS] = readFloat(ZAXIS_ACCEL_BIAS_ADR);
+
+ // Mag calibration
+ #ifdef HeadingMagHold
+ magBias[XAXIS] = readFloat(XAXIS_MAG_BIAS_ADR);
+ magBias[YAXIS] = readFloat(YAXIS_MAG_BIAS_ADR);
+ magBias[ZAXIS] = readFloat(ZAXIS_MAG_BIAS_ADR);
+ #endif
+
+ // Battery Monitor
+ #ifdef BattMonitor
+ batteryMonitorAlarmVoltage = readFloat(BATT_ALARM_VOLTAGE_ADR);
+ batteryMonitorThrottleTarget = readFloat(BATT_THROTTLE_TARGET_ADR);
+ batteryMonitorGoinDownTime = readFloat(BATT_DOWN_TIME_ADR);
+ #endif
+
+ windupGuard = readFloat(WINDUPGUARD_ADR);
+ // AKA - added so that each PID has its own windupGuard, will need to be removed once each PID's range is established and put in the eeprom
+ for (byte i = XAXIS; i <= ZDAMPENING_PID_IDX; i++ ) {
+ if (i != ALTITUDE_HOLD_PID_IDX) {
+ PID[i].windupGuard = windupGuard;
+ }
+ }
+
+ aref = readFloat(AREF_ADR);
+ flightMode = readFloat(FLIGHTMODE_ADR);
+ accelOneG = readFloat(ACCEL_1G_ADR);
+ headingHoldConfig = readFloat(HEADINGHOLD_ADR);
+ if (headingHoldConfig) {
+ vehicleState |= HEADINGHOLD_ENABLED;
+ }
+ else {
+ vehicleState &= ~HEADINGHOLD_ENABLED;
+ }
+}
+
+void writeEEPROM(){
+ cli(); // Needed so that APM sensor data doesn't overflow
+ writePID(XAXIS, ROLL_PID_GAIN_ADR);
+ writePID(YAXIS, PITCH_PID_GAIN_ADR);
+ writePID(ATTITUDE_XAXIS_PID_IDX, LEVELROLL_PID_GAIN_ADR);
+ writePID(ATTITUDE_YAXIS_PID_IDX, LEVELPITCH_PID_GAIN_ADR);
+ writePID(ZAXIS, YAW_PID_GAIN_ADR);
+ writePID(HEADING_HOLD_PID_IDX, HEADING_PID_GAIN_ADR);
+ writePID(ATTITUDE_GYRO_XAXIS_PID_IDX, LEVEL_GYRO_ROLL_PID_GAIN_ADR);
+ writePID(ATTITUDE_GYRO_YAXIS_PID_IDX, LEVEL_GYRO_PITCH_PID_GAIN_ADR);
+ writePID(ALTITUDE_HOLD_PID_IDX, ALTITUDE_PID_GAIN_ADR);
+ writeFloat(PID[ALTITUDE_HOLD_PID_IDX].windupGuard, ALTITUDE_WINDUP_ADR);
+ writeFloat(minThrottleAdjust, ALTITUDE_MIN_THROTTLE_ADR);
+ writeFloat(maxThrottleAdjust, ALTITUDE_MAX_THROTTLE_ADR);
+ #if defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+ #if defined AltitudeHoldBaro
+ writeFloat(baroSmoothFactor, ALTITUDE_SMOOTH_ADR);
+ #else
+ writeFloat(0, ALTITUDE_SMOOTH_ADR);
+ #endif
+ writeFloat(altitudeHoldBump, ALTITUDE_BUMP_ADR);
+ writeFloat(altitudeHoldPanicStickMovement, ALTITUDE_PANIC_ADR);
+ #else
+ writeFloat(0.1, ALTITUDE_SMOOTH_ADR);
+ writeFloat(90, ALTITUDE_BUMP_ADR);
+ writeFloat(250, ALTITUDE_PANIC_ADR);
+ #endif
+ writePID(ZDAMPENING_PID_IDX, ZDAMP_PID_GAIN_ADR);
+ // Accel Cal
+ writeFloat(accelScaleFactor[XAXIS], XAXIS_ACCEL_SCALE_FACTOR_ADR);
+ writeFloat(runTimeAccelBias[XAXIS], XAXIS_ACCEL_BIAS_ADR);
+ writeFloat(accelScaleFactor[YAXIS], YAXIS_ACCEL_SCALE_FACTOR_ADR);
+ writeFloat(runTimeAccelBias[YAXIS], YAXIS_ACCEL_BIAS_ADR);
+ writeFloat(accelScaleFactor[ZAXIS], ZAXIS_ACCEL_SCALE_FACTOR_ADR);
+ writeFloat(runTimeAccelBias[ZAXIS], ZAXIS_ACCEL_BIAS_ADR);
+ #ifdef HeadingMagHold
+ writeFloat(magBias[XAXIS], XAXIS_MAG_BIAS_ADR);
+ writeFloat(magBias[YAXIS], YAXIS_MAG_BIAS_ADR);
+ writeFloat(magBias[ZAXIS], ZAXIS_MAG_BIAS_ADR);
+ #endif
+ writeFloat(windupGuard, WINDUPGUARD_ADR);
+ writeFloat(receiverXmitFactor, XMITFACTOR_ADR);
+ writeFloat(gyroSmoothFactor, GYROSMOOTH_ADR);
+ writeFloat(accelSmoothFactor, ACCSMOOTH_ADR);
+
+ for(byte channel = XAXIS; channel < LASTCHANNEL; channel++) {
+ writeFloat(receiverSlope[channel], RECEIVER_DATA[channel].slope);
+ writeFloat(receiverOffset[channel], RECEIVER_DATA[channel].offset);
+ writeFloat(receiverSmoothFactor[channel], RECEIVER_DATA[channel].smooth_factor);
+ }
+
+ writeFloat(aref, AREF_ADR);
+ writeFloat(flightMode, FLIGHTMODE_ADR);
+ writeFloat(headingHoldConfig, HEADINGHOLD_ADR);
+ writeFloat(accelOneG, ACCEL_1G_ADR);
+ writeFloat(SOFTWARE_VERSION, SOFTWARE_VERSION_ADR);
+
+ // Battery Monitor
+ #ifdef BattMonitor
+ writeFloat(batteryMonitorAlarmVoltage, BATT_ALARM_VOLTAGE_ADR);
+ writeFloat(batteryMonitorThrottleTarget, BATT_THROTTLE_TARGET_ADR);
+ writeFloat(batteryMonitorGoinDownTime, BATT_DOWN_TIME_ADR);
+ #endif
+
+ sei(); // Restart interrupts
+}
+
+void initSensorsZeroFromEEPROM() {
+ // Gyro initialization from EEPROM
+ gyroZero[XAXIS] = readFloat(GYRO_ROLL_ZERO_ADR);
+ gyroZero[YAXIS] = readFloat(GYRO_PITCH_ZERO_ADR);
+ gyroZero[ZAXIS] = readFloat(GYRO_YAW_ZERO_ADR);
+ gyroSmoothFactor = readFloat(GYROSMOOTH_ADR);
+
+ // Accel initialization from EEPROM
+ accelOneG = readFloat(ACCEL_1G_ADR);
+ accelSmoothFactor = readFloat(ACCSMOOTH_ADR);
+}
+
+void storeSensorsZeroToEEPROM() {
+ // Store gyro data to EEPROM
+ writeFloat(gyroZero[XAXIS], GYRO_ROLL_ZERO_ADR);
+ writeFloat(gyroZero[YAXIS], GYRO_PITCH_ZERO_ADR);
+ writeFloat(gyroZero[ZAXIS], GYRO_YAW_ZERO_ADR);
+ writeFloat(gyroSmoothFactor, GYROSMOOTH_ADR);
+
+ // Store accel data to EEPROM
+ writeFloat(accelOneG, ACCEL_1G_ADR);
+ writeFloat(accelSmoothFactor, ACCSMOOTH_ADR);
+}
+
+void initReceiverFromEEPROM() {
+ receiverXmitFactor = readFloat(XMITFACTOR_ADR);
+
+ for(byte channel = XAXIS; channel < LASTCHANNEL; channel++) {
+ receiverSlope[channel] = readFloat(RECEIVER_DATA[channel].slope);
+ receiverOffset[channel] = readFloat(RECEIVER_DATA[channel].offset);
+ receiverSmoothFactor[channel] = readFloat(RECEIVER_DATA[channel].smooth_factor);
+ }
+}
+
+#endif // _AQ_DATA_STORAGE_H_
+
diff --git a/AeroQuad/FlightCommandProcessor.h b/AeroQuad/FlightCommandProcessor.h
new file mode 100644
index 00000000..46cb4109
--- /dev/null
+++ b/AeroQuad/FlightCommandProcessor.h
@@ -0,0 +1,125 @@
+/*
+ AeroQuad v2.4 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+// FlightCommand.pde is responsible for decoding transmitter stick combinations
+// for setting up AeroQuad modes such as motor arming and disarming
+
+#ifndef _AQ_FLIGHT_COMMAND_READER_
+#define _AQ_FLIGHT_COMMAND_READER_
+
+
+/**
+ * readPilotCommands
+ *
+ * This function is responsible to read receiver
+ * and process command from the users
+ */
+void readPilotCommands() {
+
+ readReceiver();
+ if (receiverCommand[THROTTLE] < MINCHECK) {
+ zeroIntegralError();
+
+ // Disarm motors (left stick lower left corner)
+ if (receiverCommand[ZAXIS] < MINCHECK && motorArmed == ON) {
+ commandAllMotors(MINCOMMAND);
+ digitalWrite(LED_Red,LOW);
+ motorArmed = OFF;
+
+ #ifdef OSD
+ notifyOSD(OSD_CENTER|OSD_WARN, "MOTORS UNARMED");
+ #endif
+
+ #if defined BattMonitorAutoDescent
+ batteryMonitorAlarmCounter = 0;
+ batteryMonitorStartThrottle = 0;
+ batteyMonitorThrottleCorrection = 0.0;
+ #endif
+ }
+
+ // Zero Gyro and Accel sensors (left stick lower left, right stick lower right corner)
+ if ((receiverCommand[ZAXIS] < MINCHECK) && (receiverCommand[XAXIS] > MAXCHECK) && (receiverCommand[YAXIS] < MINCHECK)) {
+ calibrateGyro();
+ computeAccelBias();
+ storeSensorsZeroToEEPROM();
+ calibrateKinematics();
+ zeroIntegralError();
+ pulseMotors(3);
+ }
+
+ // Arm motors (left stick lower right corner)
+ if (receiverCommand[ZAXIS] > MAXCHECK && motorArmed == OFF && safetyCheck == ON) {
+ zeroIntegralError();
+ for (byte motor = 0; motor < LASTMOTOR; motor++) {
+ motorCommand[motor] = MINTHROTTLE;
+ }
+ digitalWrite(LED_Red,HIGH);
+ motorArmed = ON;
+
+ #ifdef OSD
+ notifyOSD(OSD_CENTER|OSD_WARN, "!MOTORS ARMED!");
+ #endif
+
+
+ }
+ // Prevents accidental arming of motor output if no transmitter command received
+ if (receiverCommand[ZAXIS] > MINCHECK) {
+ safetyCheck = ON;
+ }
+ }
+
+ #ifdef RateModeOnly
+ flightMode = ACRO;
+ #else
+ // Check Mode switch for Acro or Stable
+ if (receiverCommand[MODE] > 1500) {
+ flightMode = ATTITUDE_FLIGHT_MODE;
+ }
+ else {
+ flightMode = RATE_FLIGHT_MODE;
+ }
+ #endif
+
+ #if defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+ if (receiverCommand[AUX] < 1750) {
+ if (altitudeHoldState != ALTPANIC ) { // check for special condition with manditory override of Altitude hold
+ if (isStoreAltitudeNeeded) {
+ altitudeToHoldTarget = getAltitudeFromSensors();
+ altitudeHoldThrottle = receiverCommand[THROTTLE];
+ PID[ALTITUDE_HOLD_PID_IDX].integratedError = 0;
+ PID[ALTITUDE_HOLD_PID_IDX].lastPosition = altitudeToHoldTarget; // add to initialize hold position on switch turn on.
+ isStoreAltitudeNeeded = false;
+ }
+ altitudeHoldState = ON;
+ vehicleState |= ALTITUDEHOLD_ENABLED;
+ }
+ // note, Panic will stay set until Althold is toggled off/on
+ }
+ else {
+ isStoreAltitudeNeeded = true;
+ altitudeHoldState = OFF;
+ vehicleState &= ~ALTITUDEHOLD_ENABLED;
+ }
+ #endif
+}
+
+#endif // _AQ_FLIGHT_COMMAND_READER_
+
+
diff --git a/AeroQuad/FlightControlProcessor.h b/AeroQuad/FlightControlProcessor.h
new file mode 100644
index 00000000..0f46107c
--- /dev/null
+++ b/AeroQuad/FlightControlProcessor.h
@@ -0,0 +1,261 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+// FlightControl.pde is responsible for combining sensor measurements and
+// transmitter commands into motor commands for the defined flight configuration (X, +, etc.)
+
+
+#ifndef _AQ_PROCESS_FLIGHT_CONTROL_H_
+#define _AQ_PROCESS_FLIGHT_CONTROL_H_
+
+#define ATTITUDE_SCALING (0.75 * PWM2RAD)
+
+
+/**
+ * calculateFlightError
+ *
+ * Calculate roll/pitch axis error with gyro/accel data to
+ * compute motor command thrust so used command are executed
+ */
+void calculateFlightError()
+{
+ if (flightMode == ATTITUDE_FLIGHT_MODE) {
+ float rollAttitudeCmd = updatePID((receiverCommand[XAXIS] - receiverZero[XAXIS]) * ATTITUDE_SCALING, kinematicsAngle[XAXIS], &PID[ATTITUDE_XAXIS_PID_IDX]);
+ float pitchAttitudeCmd = updatePID((receiverCommand[YAXIS] - receiverZero[YAXIS]) * ATTITUDE_SCALING, -kinematicsAngle[YAXIS], &PID[ATTITUDE_YAXIS_PID_IDX]);
+ motorAxisCommandRoll = updatePID(rollAttitudeCmd, correctedRateVector[XAXIS], &PID[ATTITUDE_GYRO_XAXIS_PID_IDX]);
+ motorAxisCommandPitch = updatePID(pitchAttitudeCmd, -correctedRateVector[YAXIS], &PID[ATTITUDE_GYRO_YAXIS_PID_IDX]);
+ }
+ else {
+ motorAxisCommandRoll = updatePID(getReceiverSIData(XAXIS), correctedRateVector[XAXIS], &PID[RATE_XAXIS_PID_IDX]);
+ motorAxisCommandPitch = updatePID(getReceiverSIData(YAXIS), -correctedRateVector[YAXIS], &PID[RATE_YAXIS_PID_IDX]);
+ }
+}
+
+/**
+ * processCalibrateESC
+ *
+ * Proces esc calibration command with the help of the configurator
+ */
+void processCalibrateESC()
+{
+ switch (calibrateESC) { // used for calibrating ESC's
+ case 1:
+ for (byte motor = 0; motor < LASTMOTOR; motor++)
+ motorCommand[motor] = MAXCOMMAND;
+ break;
+ case 3:
+ for (byte motor = 0; motor < LASTMOTOR; motor++)
+ motorCommand[motor] = constrain(testCommand, 1000, 1200);
+ break;
+ case 5:
+ for (byte motor = 0; motor < LASTMOTOR; motor++)
+ motorCommand[motor] = constrain(motorConfiguratorCommand[motor], 1000, 1200);
+ safetyCheck = ON;
+ break;
+ default:
+ for (byte motor = 0; motor < LASTMOTOR; motor++)
+ motorCommand[motor] = MINCOMMAND;
+ }
+ // Send calibration commands to motors
+ writeMotors(); // Defined in Motors.h
+}
+
+/**
+ * processBatteryMonitorThrottleAdjustment
+ *
+ * Check battery alarm and if in alarm, increment a counter
+ * When this counter reach BATTERY_MONITOR_MAX_ALARM_COUNT, then
+ * we are now in auto-descent mode.
+ *
+ * When in auto-descent mode, the user can pass throttle keep when the
+ * alarm was reach, and the throttle is slowly decrease for a minute til
+ * batteryMonitorThrottle that is configurable with the configurator
+ */
+#if defined BattMonitor && defined BattMonitorAutoDescent
+ void processBatteryMonitorThrottleAdjustment() {
+
+ if (batteryMonitorAlarmCounter < BATTERY_MONITOR_MAX_ALARM_COUNT) {
+ if (batteryAlarm) {
+ batteryMonitorAlarmCounter++;
+ }
+ }
+ else {
+ #if defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+ if (altitudeHoldState == ON) {
+ altitudeToHoldTarget -= 0.01;
+ }
+ else {
+ #endif
+ if (batteryMonitorStartThrottle == 0) { // init battery monitor throttle correction!
+ batteryMonitorStartTime = millis();
+ if (throttle < batteryMonitorThrottleTarget) {
+ batteryMonitorStartThrottle = batteryMonitorThrottleTarget;
+ }
+ else {
+ batteryMonitorStartThrottle = throttle;
+ }
+ }
+ int batteryMonitorThrottle = map(millis()-batteryMonitorStartTime, 0, batteryMonitorGoinDownTime, batteryMonitorStartThrottle, batteryMonitorThrottleTarget);
+ if (batteryMonitorThrottle < batteryMonitorThrottleTarget) {
+ batteryMonitorThrottle = batteryMonitorThrottleTarget;
+ }
+ if (throttle < batteryMonitorThrottle) {
+ batteyMonitorThrottleCorrection = 0;
+ }
+ else {
+ batteyMonitorThrottleCorrection = batteryMonitorThrottle - throttle;
+ }
+ #if defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+ }
+ #endif
+ }
+ }
+#endif
+
+
+/**
+ * processThrottleCorrection
+ *
+ * This function will add some throttle imput if the craft is angled
+ * this prevent the craft to loose altitude when angled.
+ * it also add the battery throttle correction in case
+ * of we are in auto-descent.
+ *
+ * Special thank to Ziojo for this.
+ */
+void processThrottleCorrection() {
+
+ int throttleAsjust = throttle / (cos (radians (kinematicsAngle[XAXIS])) * cos (radians (kinematicsAngle[YAXIS])));
+ throttleAsjust = constrain ((throttleAsjust - throttle), 0, 160); //compensate max +/- 25 deg XAXIS or YAXIS or +/- 18 ( 18(XAXIS) + 18(YAXIS))
+ throttle = throttle + throttleAsjust + (int)batteyMonitorThrottleCorrection;
+
+ throttle = constrain(throttle,MINCOMMAND,MAXCOMMAND-150); // limmit throttle to leave some space for motor correction in max throttle manuever
+}
+
+
+/**
+ * processHardManuevers
+ *
+ * In case of a roll/pitch stick at one edge to do a loop, this function
+ * will prevent the lower throttle motor side to have too much low throtte.
+ */
+void processHardManuevers() {
+
+ if ((receiverCommand[XAXIS] < MINCHECK) ||
+ (receiverCommand[XAXIS] > MAXCHECK) ||
+ (receiverCommand[YAXIS] < MINCHECK) ||
+ (receiverCommand[YAXIS] > MAXCHECK)) {
+
+ for (int motor = 0; motor < LASTMOTOR; motor++) {
+ motorMinCommand[motor] = minArmedThrottle;
+ motorMaxCommand[motor] = MAXCOMMAND;
+ }
+ }
+}
+
+/**
+ * processMinMaxCommand
+ *
+ * This function correct too low/max throttle when manuevering
+ * preventing some wobbling behavior
+ */
+void processMinMaxCommand()
+{
+ for (byte motor = 0; motor < LASTMOTOR; motor++)
+ {
+ motorMinCommand[motor] = minArmedThrottle;
+ motorMaxCommand[motor] = MAXCOMMAND;
+ }
+
+ int maxMotor = motorCommand[0];
+
+ for (byte motor=1; motor < LASTMOTOR; motor++) {
+ if (motorCommand[motor] > maxMotor) {
+ maxMotor = motorCommand[motor];
+ }
+ }
+
+ for (byte motor = 0; motor < LASTMOTOR; motor++) {
+ if (maxMotor > MAXCOMMAND) {
+ motorCommand[motor] = motorCommand[motor] - (maxMotor - MAXCOMMAND);
+ }
+ }
+}
+
+/**
+ * processFlightControl
+ *
+ * Main flight control processos function
+ */
+void processFlightControl() {
+
+ // ********************** Calculate Flight Error ***************************
+ calculateFlightError();
+
+ // ********************** Update Yaw ***************************************
+ processHeading();
+
+ if (frameCounter % 10 == 0) { // 10 Hz tasks
+ // ********************** Process Altitude hold **************************
+ processAltitudeHold();
+ // ********************** Process Battery monitor hold **************************
+ #if defined BattMonitor && defined BattMonitorAutoDescent
+ processBatteryMonitorThrottleAdjustment();
+ #endif
+ // ********************** Process throttle correction ********************
+ processThrottleCorrection();
+ }
+
+ // ********************** Calculate Motor Commands *************************
+ if (motorArmed && safetyCheck) {
+ applyMotorCommand();
+ }
+
+ // *********************** process min max motor command *******************
+ processMinMaxCommand();
+
+ // Allows quad to do acrobatics by lowering power to opposite motors during hard manuevers
+ processHardManuevers();
+
+ // If throttle in minimum position, don't apply yaw
+ if (receiverCommand[THROTTLE] < MINCHECK) {
+ for (byte motor = 0; motor < LASTMOTOR; motor++) {
+ motorMinCommand[motor] = minArmedThrottle;
+ }
+ }
+
+ // Apply limits to motor commands
+ for (byte motor = 0; motor < LASTMOTOR; motor++) {
+ motorCommand[motor] = constrain(motorCommand[motor], motorMinCommand[motor], motorMaxCommand[motor]);
+ }
+
+ // ESC Calibration
+ if (motorArmed == OFF) {
+ processCalibrateESC();
+ }
+
+ // *********************** Command Motors **********************
+ if (motorArmed == ON && safetyCheck == ON) {
+ writeMotors();
+ }
+}
+
+#endif //#define _AQ_PROCESS_FLIGHT_CONTROL_H_
+
diff --git a/AeroQuad/HeadingHoldProcessor.h b/AeroQuad/HeadingHoldProcessor.h
new file mode 100644
index 00000000..d70c3abf
--- /dev/null
+++ b/AeroQuad/HeadingHoldProcessor.h
@@ -0,0 +1,110 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+
+#ifndef _AQ_HEADING_CONTROL_PROCESSOR_H_
+#define _AQ_HEADING_CONTROL_PROCESSOR_H_
+
+
+float setHeading = 0;
+unsigned long headingTime = micros();
+
+/**
+ * processHeading
+ *
+ * This function will calculate the craft heading correction depending
+ * of the users command. Heading correction is process with the gyro
+ * or a magnetometer
+ */
+void processHeading()
+{
+ if (headingHoldConfig == ON) {
+
+ #if defined(HeadingMagHold)
+ heading = degrees(kinematicsAngle[ZAXIS]);
+ #else
+ heading = degrees(gyroHeading);
+ #endif
+
+ // Always center relative heading around absolute heading chosen during yaw command
+ // This assumes that an incorrect yaw can't be forced on the AeroQuad >180 or <-180 degrees
+ // This is done so that AeroQuad does not accidentally hit transition between 0 and 360 or -180 and 180
+ // AKA - THERE IS A BUG HERE - if relative heading is greater than 180 degrees, the PID will swing from negative to positive
+ // Doubt that will happen as it would have to be uncommanded.
+ relativeHeading = heading - setHeading;
+ if (heading <= (setHeading - 180)) {
+ relativeHeading += 360;
+ }
+ if (heading >= (setHeading + 180)) {
+ relativeHeading -= 360;
+ }
+
+ // Apply heading hold only when throttle high enough to start flight
+ if (receiverCommand[THROTTLE] > MINCHECK ) {
+
+ if ((receiverCommand[ZAXIS] > (MIDCOMMAND + 25)) || (receiverCommand[ZAXIS] < (MIDCOMMAND - 25))) {
+
+ // If commanding yaw, turn off heading hold and store latest heading
+ setHeading = heading;
+ headingHold = 0;
+ PID[HEADING_HOLD_PID_IDX].integratedError = 0;
+ headingHoldState = OFF;
+ headingTime = currentTime;
+ }
+ else {
+ if (relativeHeading < 0.25 && relativeHeading > -0.25) {
+ headingHold = 0;
+ PID[HEADING_HOLD_PID_IDX].integratedError = 0;
+ }
+ else if (headingHoldState == OFF) { // quick fix to soften heading hold on new heading
+ if ((currentTime - headingTime) > 500000) {
+ headingHoldState = ON;
+ headingTime = currentTime;
+ setHeading = heading;
+ headingHold = 0;
+ }
+ }
+ else {
+ // No new yaw input, calculate current heading vs. desired heading heading hold
+ // Relative heading is always centered around zero
+ headingHold = updatePID(0, relativeHeading, &PID[HEADING_HOLD_PID_IDX]);
+ headingTime = currentTime; // quick fix to soften heading hold, wait 100ms before applying heading hold
+ }
+ }
+ }
+ else {
+ // minimum throttle not reached, use off settings
+ setHeading = heading;
+ headingHold = 0;
+ PID[HEADING_HOLD_PID_IDX].integratedError = 0;
+ }
+ }
+ // NEW SI Version
+ const float commandedYaw = constrain(getReceiverSIData(ZAXIS) + radians(headingHold), -PI, PI);
+ motorAxisCommandYaw = updatePID(commandedYaw, gyroRate[ZAXIS], &PID[ZAXIS_PID_IDX]);
+}
+
+#endif
+
+
+
+
+
+
diff --git a/AeroQuad/OSDDisplayController.h b/AeroQuad/OSDDisplayController.h
new file mode 100644
index 00000000..ec169e9f
--- /dev/null
+++ b/AeroQuad/OSDDisplayController.h
@@ -0,0 +1,74 @@
+/*
+ AeroQuad v3.0 - Nov 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+ */
+
+#ifndef _OSD_DISPLAY_CONTROLLER_H_
+#define _OSD_DISPLAY_CONTROLLER_H_
+
+#include "OSD.h"
+
+void updateOSD() {
+
+ // OSD is updated fully in 4 rounds, these are (using bit)
+ // 0x01 - Attitude Indicator
+ // 0x02 - Altitude, Heading, Timer, RSSI, Reticle
+ // 0x04 - Attitude Indicator
+ // 0x08 - Battery info
+
+ // Check notify first, if it did something we dont't have time for other stuff
+ if (displayNotify()) {
+ return;
+ }
+
+ #ifdef ShowAttitudeIndicator
+ if ((OSDsched&0x01) || (OSDsched&0x04)) {
+ displayArtificialHorizon(kinematicsAngle[XAXIS], kinematicsAngle[YAXIS]);
+ }
+ #endif
+
+ if (OSDsched&0x02) {
+ #if defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+ displayAltitude(getAltitudeFromSensors(), altitudeToHoldTarget, altitudeHoldState);
+ #endif
+ #ifdef HeadingMagHold
+ displayHeading(kinematicsGetDegreesHeading(ZAXIS));
+ #endif
+ #ifdef ShowFlightTimer
+ displayFlightTime(motorArmed);
+ #endif
+ #ifdef ShowRSSI
+ displayRSSI();
+ #endif
+ #ifdef ShowReticle
+ displayReticle(flightMode);
+ #endif
+ }
+
+ if (OSDsched&0x08) {
+ #ifdef BattMonitor
+ displayVoltage(motorArmed);
+ #endif
+ }
+ OSDsched <<= 1;
+ if (OSDsched & 0x10) {
+ OSDsched = 0x01;
+ }
+}
+
+#endif
diff --git a/AeroQuad/OSDMenu.h b/AeroQuad/OSDMenu.h
new file mode 100644
index 00000000..8d18b086
--- /dev/null
+++ b/AeroQuad/OSDMenu.h
@@ -0,0 +1,715 @@
+/*
+ AeroQuad v3.0 - Nov 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+ */
+
+/* Menu system implementation, usable with OSD */
+
+#ifndef _AQ_OSD_MENU_
+#define _AQ_OSD_MENU_
+
+//#define MENU_GOPRO // enable GoPro controls... not usable atm.
+
+struct MenuItem {
+ const byte level; // menu level the item is on
+ const char *text; // text to show
+ void (*function)(byte,byte); // handler func on leaf level
+ const byte mode; // data to give for handler function
+};
+
+extern const struct MenuItem menuData[];
+
+#define MENU_INIT 0
+#define MENU_UP 1
+#define MENU_DOWN 2
+#define MENU_SELECT 3
+#define MENU_EXIT 4
+#define MENU_CALLBACK 5
+
+#define MENU_NOFUNC 0
+
+#define MENU_SYM_BOTH '\015'
+#define MENU_SYM_UP '\016'
+#define MENU_SYM_DOWN '\017'
+
+
+byte menuInFunc = 0; // tells if a handler func is active
+ // 0 - we're in base menu
+ // 1 - call handler on stick actions
+ // 2-255 countdown and callback when it gets to 1 - no sticks
+byte menuEntry = 255; // Active menu entry
+byte menuAtExit = 0; // are we at the exit at the top
+byte stickWaitNeutral = 1; // wait for stick to center
+
+boolean menuShouldExit(); // This can be used to check if continous output mode should be ended
+
+// DATA that menu functions can freely use to store state
+byte menuFuncData[10]; // 10 bytes of data for funcs to use as they wish...
+float menuFuncDataFloat; // float for menufuncs use
+
+#ifdef CameraControl
+void menuHandleCam(byte mode, byte action) {
+
+ switch (action) {
+ case MENU_INIT:
+ menuFuncData[0]=0;
+ menuFuncData[1]=0;
+ break;
+
+ case MENU_EXIT:
+ if (menuFuncData[0]==0) {
+ menuInFunc=0;
+ return;
+ }
+ else {
+ menuFuncData[0]--;
+ }
+ break;
+
+ case MENU_SELECT:
+ if (menuFuncData[0]<1) {
+ menuFuncData[0]++;
+ }
+ break;
+ case MENU_UP:
+ case MENU_DOWN:
+ if (menuFuncData[0]==0) {
+ if (action==MENU_UP) {
+ if (menuFuncData[1] < 3) {
+ menuFuncData[1]++;
+ }
+ }
+ else {
+ if (menuFuncData[1]>0) {
+ menuFuncData[1]--;
+ }
+ }
+ }
+ else if (menuFuncData[0]==1) {
+ int val = (action == MENU_UP) ? 10 : -10;
+ switch (menuFuncData[1]) {
+ case 0:
+ setMode(action==MENU_UP?1:0);
+ break;
+ case 1:
+ setCenterPitch(constrain(getCenterPitch() + val, getServoMinPitch(), getServoMaxPitch()));
+ break;
+ case 2:
+ setCenterRoll(constrain(getCenterRoll() + val, getServoMinRoll(), getServoMaxRoll()));
+ break;
+ case 3:
+ setCenterYaw(constrain(getCenterYaw() + val, getServoMinYaw(), getServoMaxYaw()));
+ break;
+ }
+ }
+ break;
+ }
+
+ if (menuFuncData[1] == 0) {
+ notifyOSDmenu(OSD_NOCLEAR | OSD_CURSOR, menuFuncData[0] ? 18 : 1, menuFuncData[0] ? 18 : 16, "%cStabilizer mode: %1d", MENU_SYM_BOTH, getMode());
+ }
+ else {
+ notifyOSDmenu(OSD_NOCLEAR|OSD_CURSOR,
+ menuFuncData[0] ? 15 : 8, menuFuncData[0] ? 18 : 12,
+ "%cCenter %s: %04d", MENU_SYM_BOTH,
+ (menuFuncData[1] == 1)?"Pitch":
+ (menuFuncData[1] == 2)?"Roll ":
+ "Yaw ",
+ (menuFuncData[1] == 1) ? getCenterPitch():
+ (menuFuncData[1] == 2) ? getCenterRoll():
+ getCenterYaw());
+ }
+}
+#endif
+
+void menuHandleOSD(byte mode, byte action) {
+
+ switch (mode) {
+ case 0:
+ armedTime = 0;
+ break;
+ }
+ menuInFunc = 0;
+}
+
+#ifdef MENU_GOPRO
+const char *gopro_b_txt[3] = { "Shutter", "Mode", "Power" };
+
+void menuHandleGoPro(byte mode, byte action) {
+
+ switch (action) {
+ case MENU_CALLBACK:
+ // depress I/O line...
+ menuInFunc=0; // exit to menu
+ break;
+ case MENU_INIT:
+ // activate I/O
+ memset(buf, 0, MENU_BUFSIZE);
+ snprintf(buf, MENU_BUFSIZE, "%s pressed", gopro_b_txt[mode]);
+ menuRefresh();
+ if (mode == 2) {
+ menuInFunc = 35; //3.5 sec
+ }
+ else {
+ menuInFunc = 10; // 1 sec
+ }
+ break;
+ default:
+ break;
+ }
+}
+#endif
+
+// edit digit with of form [+/-][i*#].[d*#]
+// pos: 0=sign, 1-(i)=intpart, (i+1)-(i+d+1)=decimals
+void menuEditFloat(float *f, byte i, byte d, byte pos, byte action, float min, float max) {
+
+ if (pos > (1 + i + d)) {
+ return;
+ }
+ // if ((action!=MENU_UP)&&(action!=MENU_DOWN)) return;
+ if (pos == 0 && min * max < 0) { // change sign only if min/max are different sign
+ *f = -*f;
+ }
+ else {
+ *f += (action == MENU_UP ? 1.0 : -1.0) * pow(10.0, i-pos);
+ }
+ *f = constrain(*f, min, max);
+}
+
+const char *pidNames[10] = {
+ "RRoll", "RPitc", "RYaw ", "ARoll", "APitc",
+ "Headi", "AGRol", "AGPit", "Altit", "ZDamp"};
+
+void menuHandlePidTune(byte mode, byte action) {
+
+ switch (action) {
+ case MENU_INIT:
+ menuFuncData[0]=0; //level 0-select PID;1-select P/I/D;>=2-edit value
+ menuFuncData[1]=0; // PIDno
+ menuFuncData[2]=0; // 0=P/1=I/2=D
+ break;
+
+ case MENU_EXIT:
+ if (menuFuncData[0]>0) {
+ menuFuncData[0]--;
+ }
+ else {
+ menuInFunc=0;
+ return;
+ }
+ menuFuncData[3]=0;
+ break;
+
+ case MENU_SELECT:
+ if (menuFuncData[0] < 9) {
+ menuFuncData[0]++;
+ }
+ else {
+ if (menuFuncData[3]) {
+ switch (menuFuncData[2]) {
+ case 0:
+ PID[menuFuncData[1]].P = menuFuncDataFloat;
+ break;
+ case 1:
+ PID[menuFuncData[1]].I = menuFuncDataFloat;
+ break;
+ case 2:
+ PID[menuFuncData[1]].D = menuFuncDataFloat;
+ break;
+ }
+ notifyOSD(OSD_NOCLEAR, "PID value saved!!");
+ }
+ else {
+ notifyOSD(OSD_NOCLEAR, "PID value not saved!!");
+ }
+ menuInFunc = 10; // callback after 1 second
+ menuFuncData[0] = 1; //return to P/I/D selection
+ return;
+ }
+ break;
+
+ case MENU_UP:
+ if (menuFuncData[0] == 0) {
+ if (menuFuncData[1] < 9) menuFuncData[1]++;
+ }
+ else if (menuFuncData[0] == 1) {
+ if (menuFuncData[2] < 2) menuFuncData[2]++;
+ }
+ else if (menuFuncData[0] == 9) {
+ menuFuncData[3] = 1;
+ }
+ else {
+ menuEditFloat(&menuFuncDataFloat, 4, 2, menuFuncData[0]-2, MENU_UP, -1000, 1000);
+ }
+ break;
+
+ case MENU_DOWN:
+ if (menuFuncData[0] < 2) {
+ if (menuFuncData[menuFuncData[0] +1 ] > 0) menuFuncData[menuFuncData[0] + 1]--;
+ }
+ else if (menuFuncData[0] == 9) {
+ menuFuncData[3] = 0;
+ }
+ else {
+ menuEditFloat(&menuFuncDataFloat, 4, 2, menuFuncData[0]-2, MENU_DOWN, -1000, 1000);
+ }
+ break;
+ }
+
+ float old = (menuFuncData[2] == 0 ? PID[menuFuncData[1]].P:
+ menuFuncData[2] == 1 ? PID[menuFuncData[1]].I:
+ PID[menuFuncData[1]].D);
+
+ if (menuFuncData[0] < 2) {
+ // update value if edited value might have changed
+ menuFuncDataFloat = old;
+ }
+
+ if (menuFuncData[0] < 9) {
+ // determine 'cursor' position
+ // assume we are editing the number
+ byte cl = ((menuFuncData[0] > 6) ? 12 : 11) + menuFuncData[0];
+ byte cr = cl;
+ byte updn = MENU_SYM_BOTH;
+ // check if it is something else
+ if (menuFuncData[0] == 0) {
+ // selecting PID
+ cl = 5;
+ cr = 9;
+ if (menuFuncData[1] == 0) updn = MENU_SYM_UP;
+ if (menuFuncData[1] == 9) updn = MENU_SYM_DOWN;
+ }
+ else if (menuFuncData[0] == 1) {
+ // selecting P/I/D
+ cl = 11;
+ cr = cl;
+ if (menuFuncData[2] == 0) updn = MENU_SYM_UP;
+ if (menuFuncData[2] == 2) updn = MENU_SYM_DOWN;
+ }
+ notifyOSDmenu(OSD_CURSOR | OSD_NOCLEAR, cl, cr, "%cPID %s:%c=%c%04d.%02d",
+ updn, pidNames[menuFuncData[1]], menuFuncData[2]==0 ? 'P' : menuFuncData[2]==1 ? 'I' : 'D',
+ (menuFuncDataFloat >= 0) ? '+' : '-',
+ (int)abs(menuFuncDataFloat), (int)abs((menuFuncDataFloat - (int)menuFuncDataFloat) * 100.0));
+ }
+ else {
+ // asking confirmation for changing the value
+ notifyOSDmenu(OSD_CURSOR|OSD_NOCLEAR,21,21,"C %c%04d.%02d->%c%04d.%02d?%c",
+ (old>=0)?'+':'-',(int)abs(old),(int)abs((old-(int)old)*100.0),
+ (menuFuncDataFloat>=0)?'+':'-',(int)abs(menuFuncDataFloat),(int)abs((menuFuncDataFloat-(int)menuFuncDataFloat)*100.0),
+ menuFuncData[3] ? 'Y' : 'N');
+ }
+}
+
+void writeEEPROM();
+void initializeEEPROM();
+
+void menuEeprom(byte mode, byte action) {
+
+ // TODO(kha): make up an generic confirmation routine
+ switch (action) {
+ case MENU_CALLBACK:
+ menuInFunc=0; // exit to menu
+ break;
+
+ case MENU_INIT:
+ case MENU_UP:
+ case MENU_DOWN:
+ {
+ menuFuncData[0] = 0;
+ if (action == MENU_UP) {
+ menuFuncData[0] = 1;
+ }
+ byte cpos = strlen(menuData[menuEntry].text) + 4;
+ notifyOSDmenu(OSD_CURSOR|OSD_NOCLEAR, cpos, cpos, "%c%s? %c",
+ menuFuncData[0] ? MENU_SYM_DOWN : MENU_SYM_UP,
+ menuData[menuEntry].text,menuFuncData[0] ? 'Y' : 'N');
+ }
+ break;
+
+ case MENU_EXIT:
+ menuInFunc = 0;
+ return;
+
+ case MENU_SELECT:
+ if (menuFuncData[0] == 1) {
+ switch (mode) {
+ case 0:
+ writeEEPROM(); // defined in DataStorage.h
+ zeroIntegralError();
+ notifyOSD(OSD_NOCLEAR, "EEPROM data saved");
+ break;
+ case 1:
+ // Initialize EEPROM with default values
+ initializeEEPROM(); // defined in DataStorage.h
+ calibrateGyro();
+ computeAccelBias();
+ zeroIntegralError();
+#ifdef HeadingMagHold
+ initializeMagnetometer();
+#endif
+#if defined AltitudeHoldBaro
+ initializeBaro();
+#endif
+ notifyOSD(OSD_NOCLEAR, "EEPROM reinitialized");
+ break;
+ }
+ menuInFunc = 10; // callback after 1s
+ }
+ else {
+ menuInFunc = 0;
+ }
+ }
+}
+
+#ifdef BattMonitor
+#include
+void menuHandleBatt(byte mode, byte action){
+
+ if (action == MENU_INIT) {
+ switch (mode) {
+ case 0:
+ for (int i=0; i menuData[menuEntry-1].level)) {
+ menuAtExit=1;
+ }
+ else {
+ for (byte i=menuEntry-1; i>=0; i--) {
+ if (menuData[menuEntry].level == menuData[i].level) {
+ menuEntry = i;
+ break;
+ }
+ }
+ }
+ menuShow(menuEntry);
+}
+
+void menuDown() {
+
+ if (255 == menuEntry) {
+ return;
+ }
+ if (menuInFunc) {
+ MENU_CALLFUNC(menuEntry, MENU_DOWN)
+ return;
+ }
+ if (menuAtExit) {
+ menuAtExit = 0;
+ }
+ else {
+ if (menuIsLast(menuEntry)) return;
+ for (byte i = menuEntry + 1; i < menuNumEntries; i++) {
+ if (menuData[menuEntry].level == menuData[i].level) {
+ menuEntry = i;
+ break;
+ }
+ }
+ }
+ menuShow(menuEntry);
+}
+
+void menuSelect() {
+ if (255==menuEntry) {
+ // enable menu
+ menuAtExit=0;
+ menuEntry=0;
+ }
+ else if (menuInFunc) {
+ MENU_CALLFUNC(menuEntry,MENU_SELECT)
+ if (menuInFunc) return; // redisplay menu if we exited from handler
+ }
+ else if (menuAtExit) {
+ if (0==menuEntry) {
+ menuEntry=255;
+ }
+ else {
+ // leave submenu
+ menuEntry--;
+ menuAtExit=0;
+ }
+ }
+ else if (menuData[menuEntry].function != MENU_NOFUNC) {
+ menuInFunc = 1;
+ MENU_CALLFUNC(menuEntry, MENU_INIT)
+ return;
+ }
+ else if (menuData[menuEntry].level < menuData[menuEntry + 1].level) {
+ // enter submenu
+ menuEntry++;
+ }
+ menuShow(menuEntry);
+}
+
+void menuExit() {
+
+ if (255 == menuEntry)
+ return;
+
+ if ((0 == menuEntry) || (0 == menuData[menuEntry].level)) {
+ menuEntry = 255;
+ }
+ else if (menuInFunc) {
+ MENU_CALLFUNC(menuEntry, MENU_EXIT)
+ if (menuInFunc)
+ return;
+ }
+ else {
+ // leave submenu
+ for (byte i = menuEntry-1; i>=0; i--) {
+ if (menuData[i].level < menuData[menuEntry].level) {
+ menuEntry = i;
+ menuAtExit = 0;
+ break;
+ }
+ }
+ }
+ menuShow(menuEntry);
+}
+
+boolean menuShouldExit() {
+ const short roll = receiverCommand[XAXIS] - MENU_STICK_CENTER; // pitch/roll should be -500 - +500
+ if (roll < -MENU_STICK_ACTIVE) {
+ stickWaitNeutral = 1;
+ return true;
+ }
+ return false;
+}
+
+void updateOSDMenu() {
+
+ // check if armed, menu is only operational when not armed
+ if (motorArmed == true) {
+ if (menuEntry != 255) {
+ // BAIL OUT of menu if armed
+ notifyOSD(0, NULL); // clear menuline
+ menuInFunc = 0;
+ menuEntry = 255;
+ }
+ return;
+ }
+
+ // check if we're waiting for callback to happen
+ if (menuInFunc > 1) {
+ menuInFunc--;
+ if (menuInFunc == 1) {
+ // call the callback when counter hits 1
+ MENU_CALLFUNC(menuEntry, MENU_CALLBACK)
+ // show the menu entry if the handler function 'exited'
+ if (menuInFunc == 0) {
+ menuShow(menuEntry);
+ }
+ }
+ return;
+ }
+
+
+ const short roll = receiverCommand[XAXIS] - MENU_STICK_CENTER; // pitch/roll should be -500 - +500
+ const short pitch = receiverCommand[YAXIS] - MENU_STICK_CENTER;
+
+ if (abs(roll) < MENU_STICK_NEUTRAL) {
+ if (abs(pitch) < MENU_STICK_NEUTRAL) {
+ // stick at center
+ stickWaitNeutral = 0;
+ return;
+ }
+ else {
+ // roll at neutral, pitch not
+ if (abs(pitch) > MENU_STICK_REPEAT) {
+ // above repeat threshold so allow redoing action
+ stickWaitNeutral = 0;
+ }
+
+ // check if we are waiting for neutral (after single action)
+ if (stickWaitNeutral) {
+ return;
+ }
+
+ // call action function if stick active
+ if (abs(pitch) > MENU_STICK_ACTIVE) {
+ if (pitch > 0) {
+ menuUp();
+ }
+ else {
+ menuDown();
+ }
+
+ // action done, further actions only after centering (or repeat)
+ stickWaitNeutral = 1;
+ }
+ }
+ }
+ else {
+ if (abs(pitch) >= MENU_STICK_NEUTRAL) {
+ return; // both ways active - no action
+ }
+ if (abs(roll) > MENU_STICK_ACTIVE) {
+ if (roll > 0) {
+ if (!stickWaitNeutral) {
+ menuSelect();
+ }
+ }
+ else {
+ if ((!stickWaitNeutral) || (abs(roll) >= MENU_STICK_REPEAT)) {
+ menuExit();
+ }
+ }
+ stickWaitNeutral = 1;
+ }
+ }
+ return;
+}
+
+#endif // Menu_h
diff --git a/AeroQuad/PID.h b/AeroQuad/PID.h
new file mode 100644
index 00000000..dd80d682
--- /dev/null
+++ b/AeroQuad/PID.h
@@ -0,0 +1,82 @@
+/*
+ AeroQuad v2.4 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_PID_H_
+#define _AQ_PID_H_
+
+
+#define RATE_XAXIS_PID_IDX 0
+#define RATE_YAXIS_PID_IDX 1
+#define ZAXIS_PID_IDX 2
+#define ATTITUDE_XAXIS_PID_IDX 3
+#define ATTITUDE_YAXIS_PID_IDX 4
+#define HEADING_HOLD_PID_IDX 5
+#define ATTITUDE_GYRO_XAXIS_PID_IDX 6
+#define ATTITUDE_GYRO_YAXIS_PID_IDX 7
+#define ALTITUDE_HOLD_PID_IDX 8
+#define ZDAMPENING_PID_IDX 9
+
+
+// PID Variables
+struct PIDdata {
+ float P, I, D;
+ float lastPosition;
+ // AKA experiments with PID
+ float previousPIDTime;
+ float integratedError;
+ float windupGuard; // Thinking about having individual wind up guards for each PID
+} PID[10];
+// This struct above declares the variable PID[] to hold each of the PID values for various functions
+// The following constants are declared in AeroQuad.h
+// ROLL = 0, PITCH = 1, YAW = 2 (used for Arcobatic Mode, gyros only)
+// ROLLLEVEL = 3, PITCHLEVEL = 4, LEVELGYROROLL = 6, LEVELGYROPITCH = 7 (used for Stable Mode, accels + gyros)
+// HEADING = 5 (used for heading hold)
+// ALTITUDE = 8 (used for altitude hold)
+// ZDAMPENING = 9 (used in altitude hold to dampen vertical accelerations)
+float windupGuard; // Read in from EEPROM
+
+
+// Modified from http://www.arduino.cc/playground/Main/BarebonesPIDForEspresso
+float updatePID(float targetPosition, float currentPosition, struct PIDdata *PIDparameters) {
+
+ // AKA PID experiments
+ const float deltaPIDTime = (currentTime - PIDparameters->previousPIDTime) / 1000000.0;
+
+ PIDparameters->previousPIDTime = currentTime; // AKA PID experiments
+ float error = targetPosition - currentPosition;
+
+ PIDparameters->integratedError += error * deltaPIDTime;
+ PIDparameters->integratedError = constrain(PIDparameters->integratedError, -PIDparameters->windupGuard, PIDparameters->windupGuard);
+ float dTerm = PIDparameters->D * (currentPosition - PIDparameters->lastPosition) / (deltaPIDTime * 100); // dT fix from Honk
+ PIDparameters->lastPosition = currentPosition;
+ return (PIDparameters->P * error) + (PIDparameters->I * (PIDparameters->integratedError)) + dTerm;
+}
+
+void zeroIntegralError() __attribute__ ((noinline));
+void zeroIntegralError() {
+ for (byte axis = 0; axis <= ATTITUDE_YAXIS_PID_IDX; axis++) {
+ PID[axis].integratedError = 0;
+ PID[axis].previousPIDTime = currentTime;
+ }
+}
+
+#endif // _AQ_PID_H_
+
+
diff --git a/AeroQuad/SerialCom.h b/AeroQuad/SerialCom.h
new file mode 100644
index 00000000..9e1a6922
--- /dev/null
+++ b/AeroQuad/SerialCom.h
@@ -0,0 +1,771 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+// SerialCom.pde is responsible for the serial communication for commands and telemetry from the AeroQuad
+// This comtains readSerialCommand() which listens for a serial command and it's arguments
+// This also contains readSerialTelemetry() which listens for a telemetry request and responds with the requested data
+// For more information on each command/telemetry look at: http://aeroquad.com/content.php?117
+
+// Includes re-write / fixes from Aadamson and ala42, special thanks to those guys!
+// http://aeroquad.com/showthread.php?1461-We-have-some-hidden-warnings&p=14618&viewfull=1#post14618
+
+#ifndef _AQ_SERIAL_COMM_
+#define _AQ_SERIAL_COMM_
+
+char queryType = 'X';
+
+
+//***************************************************************************************************
+//********************************** Serial Commands ************************************************
+//***************************************************************************************************
+bool validateCalibrateCommand(byte command)
+{
+ if (readFloatSerial() == 123.45) {// use a specific float value to validate full throttle call is being sent
+ motorArmed = OFF;
+ calibrateESC = command;
+ return true;
+ } else {
+ calibrateESC = 0;
+ testCommand = 1000;
+ return false;
+ }
+}
+
+void readSerialPID(unsigned char PIDid) {
+ struct PIDdata* pid = &PID[PIDid];
+ pid->P = readFloatSerial();
+ pid->I = readFloatSerial();
+ pid->D = readFloatSerial();
+ pid->lastPosition = 0;
+ pid->integratedError = 0;
+}
+
+void readSerialCommand() {
+ // Check for serial message
+ if (SERIAL_AVAILABLE()) {
+ queryType = SERIAL_READ();
+ switch (queryType) {
+ case 'A': // Receive roll and pitch rate mode PID
+ readSerialPID(XAXIS);
+ readSerialPID(RATE_YAXIS_PID_IDX);
+ break;
+
+ case 'B': // Receive roll/pitch attitude mode PID
+ readSerialPID(ATTITUDE_XAXIS_PID_IDX);
+ readSerialPID(ATTITUDE_YAXIS_PID_IDX);
+ readSerialPID(ATTITUDE_GYRO_XAXIS_PID_IDX);
+ readSerialPID(ATTITUDE_GYRO_YAXIS_PID_IDX);
+ windupGuard = readFloatSerial(); // defaults found in setup() of AeroQuad.pde
+ break;
+
+ case 'C': // Receive yaw PID
+ readSerialPID(ZAXIS_PID_IDX);
+ readSerialPID(HEADING_HOLD_PID_IDX);
+ headingHoldConfig = readFloatSerial();
+ heading = 0;
+ relativeHeading = 0;
+ headingHold = 0;
+ if (headingHoldConfig)
+ vehicleState |= HEADINGHOLD_ENABLED;
+ else
+ vehicleState &= ~HEADINGHOLD_ENABLED;
+ break;
+
+ case 'D': // Altitude hold PID
+ #if defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+ readSerialPID(ALTITUDE_HOLD_PID_IDX);
+ PID[ALTITUDE_HOLD_PID_IDX].windupGuard = readFloatSerial();
+ altitudeHoldBump = readFloatSerial();
+ altitudeHoldPanicStickMovement = readFloatSerial();
+ minThrottleAdjust = readFloatSerial();
+ maxThrottleAdjust = readFloatSerial();
+ #if defined AltitudeHoldBaro
+ baroSmoothFactor = readFloatSerial();
+ #else
+ readFloatSerial();
+ #endif
+ readSerialPID(ZDAMPENING_PID_IDX);
+ #endif
+ break;
+
+ case 'E': // Receive sensor filtering values
+ gyroSmoothFactor = readFloatSerial();
+ accelSmoothFactor = readFloatSerial();
+ readFloatSerial(); // timeConstant was not used anymore, removed! Mikro, clean this!
+ aref = readFloatSerial();
+ break;
+
+ case 'F': // Receive transmitter smoothing values
+ receiverXmitFactor = readFloatSerial();
+ for(byte channel = XAXIS; channel> 8;
+ lsb = data & 0xff;
+
+ binaryPort->write(msb);
+ binaryPort->write(lsb);
+}
+
+void sendBinaryFloat(float data) {
+ union binaryFloatType {
+ byte floatByte[4];
+ float floatVal;
+ } binaryFloat;
+
+ binaryFloat.floatVal = data;
+ binaryPort->write(binaryFloat.floatByte[3]);
+ binaryPort->write(binaryFloat.floatByte[2]);
+ binaryPort->write(binaryFloat.floatByte[1]);
+ binaryPort->write(binaryFloat.floatByte[0]);
+}
+
+void sendBinaryuslong(unsigned long data) {
+ union binaryuslongType {
+ byte uslongByte[4];
+ unsigned long uslongVal;
+ } binaryuslong;
+
+ binaryuslong.uslongVal = data;
+ binaryPort->write(binaryuslong.uslongByte[3]);
+ binaryPort->write(binaryuslong.uslongByte[2]);
+ binaryPort->write(binaryuslong.uslongByte[1]);
+ binaryPort->write(binaryuslong.uslongByte[0]);
+}
+
+
+void fastTelemetry()
+{
+ // **************************************************************
+ // ***************** Fast Transfer Of Sensor Data ***************
+ // **************************************************************
+ // AeroQuad.h defines the output rate to be 10ms
+ // Since writing to UART is done by hardware, unable to measure data rate directly
+ // Through analysis: 115200 baud = 115200 bits/second = 14400 bytes/second
+ // If float = 4 bytes, then 3600 floats/second
+ // If 10 ms output rate, then 36 floats/10ms
+ // Number of floats written using sendBinaryFloat is 15
+
+ if (motorArmed == ON) {
+ #ifdef OpenlogBinaryWrite
+ printInt(21845); // Start word of 0x5555
+ sendBinaryuslong(currentTime);
+ printInt((int)flightMode);
+ for (byte axis = XAXIS; axis <= YAXIS; axis++) {
+ sendBinaryFloat(gyroRate[axis]);
+ }
+ for (byte axis = XAXIS; axis <= YAXIS; axis++) {
+ sendBinaryFloat(meterPerSec[axis]);
+ }
+ sendBinaryFloat(accelOneG);
+ #ifdef HeadingMagHold
+ sendBinaryFloat(hdgX);
+ sendBinaryFloat(hdgY);
+ sendBinaryFloat(getMagnetometerRawData(XAXIS));
+ sendBinaryFloat(getMagnetometerRawData(YAXIS));
+ sendBinaryFloat(getMagnetometerRawData(ZAXIS));
+ #else
+ sendBinaryFloat(0.0);
+ sendBinaryFloat(0.0);
+ sendBinaryFloat(0.0);
+ #endif
+ for (byte axis = XAXIS; axis < ZAXIS; axis++) {
+ sendBinaryFloat(kinematicsAngle[axis]);
+ }
+ printInt(32767); // Stop word of 0x7FFF
+ #else
+ printInt(21845); // Start word of 0x5555
+ for (byte axis = XAXIS; axis < LASTAXIS; axis++) {
+ sendBinaryFloat(gyroRate[axis]);
+ }
+ for (byte axis = XAXIS; axis < LASTAXIS; axis++) {
+ sendBinaryFloat(meterPerSec[axis]);
+ }
+ for (byte axis = XAXIS; axis < LASTAXIS; axis++)
+ #ifdef HeadingMagHold
+ sendBinaryFloat(getMagnetometerRawData(axis));
+ #else
+ sendBinaryFloat(0);
+ #endif
+ for (byte axis = XAXIS; axis < LASTAXIS; axis++) {
+ sendBinaryFloat(getGyroUnbias(axis));
+ }
+ for (byte axis = XAXIS; axis < LASTAXIS; axis++) {
+ sendBinaryFloat(kinematicsAngle[axis]);
+ }
+ printInt(32767); // Stop word of 0x7FFF
+ #endif
+ }
+}
+#endif // BinaryWrite
+
+void printVehicleState(const char *sensorName, unsigned long state, const char *message) {
+ SERIAL_PRINT(sensorName);
+ SERIAL_PRINT(": ");
+ if (!(vehicleState & state))
+ SERIAL_PRINT("Not ");
+ SERIAL_PRINTLN(message);
+}
+
+void reportVehicleState() {
+ // Tell Configurator how many vehicle state values to expect
+ SERIAL_PRINTLN(14);
+ SERIAL_PRINT("SW Version: ");
+ SERIAL_PRINTLN(SOFTWARE_VERSION, 1);
+ SERIAL_PRINT("Board Type: ");
+ #if defined(AeroQuad_v1)
+ SERIAL_PRINTLN("v1.x");
+ #elif defined(AeroQuadMega_v1)
+ SERIAL_PRINTLN("Mega v1.x");
+ #elif defined(AeroQuad_v18)
+ SERIAL_PRINTLN("v1.8 and greater");
+ #elif defined(AeroQuadMega_v2)
+ SERIAL_PRINTLN("Mega v2");
+ #elif defined(AeroQuadMega_v21)
+ SERIAL_PRINTLN("Mega v21");
+ #elif defined(AutonavShield)
+ SERIAL_PRINTLN("AutonavShield");
+ #elif defined(AeroQuad_Wii)
+ SERIAL_PRINTLN("Wii");
+ #elif defined(AeroQuadMega_Wii)
+ SERIAL_PRINTLN("Mega Wii");
+ #elif defined(ArduCopter)
+ SERIAL_PRINTLN("ArduCopter");
+ #elif defined(AeroQuadMega_CHR6DM)
+ SERIAL_PRINTLN("CHR6DM");
+ #elif defined(APM_OP_CHR6DM)
+ SERIAL_PRINTLN("APM w/ CHR6DM");
+ #elif defined(AeroQuad_Mini)
+ SERIAL_PRINTLN("Mini");
+ #elif defined(AeroQuadSTM32)
+ SERIAL_PRINTLN("STM32");
+ #endif
+ SERIAL_PRINT("Flight Config: ");
+ #if defined(quadPlusConfig)
+ SERIAL_PRINTLN("Quad +");
+ #elif defined(quadXConfig)
+ SERIAL_PRINTLN("Quad X");
+ #elif defined (quadY4Config)
+ SERIAL_PRINTLN("Quad Y4");
+ #elif defined (triConfig)
+ SERIAL_PRINTLN("Tri");
+ #elif defined(hexPlusConfig)
+ SERIAL_PRINTLN("Hex +");
+ #elif defined(hexXConfig)
+ SERIAL_PRINTLN("Hex X");
+ #elif defined(hexY6Config)
+ SERIAL_PRINTLN("Hex Y6");
+ #elif defined(octoX8Config)
+ SERIAL_PRINTLN("Octo X8");
+ #elif defined(octoXConfig)
+ SERIAL_PRINTLN("Octo X");
+ #elif defined(octoXPlusConfig)
+ SERIAL_PRINTLN("Octo X+");
+ #endif
+ SERIAL_PRINT("Receiver Ch's: ");
+ SERIAL_PRINTLN(LASTCHANNEL);
+ SERIAL_PRINT("Motors: ");
+ SERIAL_PRINTLN(LASTMOTOR);
+ printVehicleState("Gyroscope", GYRO_DETECTED, "Detected");
+ printVehicleState("Accelerometer", ACCEL_DETECTED, "Detected");
+ printVehicleState("Barometer", BARO_DETECTED, "Detected");
+ printVehicleState("Magnetometer", MAG_DETECTED, "Detected");
+ printVehicleState("Heading Hold", HEADINGHOLD_ENABLED, "Enabled");
+ printVehicleState("Altitude Hold", ALTITUDEHOLD_ENABLED, "Enabled");
+ printVehicleState("Battery Monitor", BATTMONITOR_ENABLED, "Enabled");
+ printVehicleState("Camera Stability", CAMERASTABLE_ENABLED, "Enabled");
+ printVehicleState("Range Detection", RANGE_ENABLED, "Enabled");
+}
+
+#endif // _AQ_SERIAL_COMM_
diff --git a/AeroQuad_ICD.xlsx b/AeroQuad_ICD.xlsx
new file mode 100644
index 00000000..535ff2a4
Binary files /dev/null and b/AeroQuad_ICD.xlsx differ
diff --git a/GPL.txt b/GPL.txt
new file mode 100644
index 00000000..94a9ed02
--- /dev/null
+++ b/GPL.txt
@@ -0,0 +1,674 @@
+ GNU GENERAL PUBLIC LICENSE
+ Version 3, 29 June 2007
+
+ Copyright (C) 2007 Free Software Foundation, Inc.
+ Everyone is permitted to copy and distribute verbatim copies
+ of this license document, but changing it is not allowed.
+
+ Preamble
+
+ The GNU General Public License is a free, copyleft license for
+software and other kinds of works.
+
+ The licenses for most software and other practical works are designed
+to take away your freedom to share and change the works. By contrast,
+the GNU General Public License is intended to guarantee your freedom to
+share and change all versions of a program--to make sure it remains free
+software for all its users. We, the Free Software Foundation, use the
+GNU General Public License for most of our software; it applies also to
+any other work released this way by its authors. You can apply it to
+your programs, too.
+
+ When we speak of free software, we are referring to freedom, not
+price. Our General Public Licenses are designed to make sure that you
+have the freedom to distribute copies of free software (and charge for
+them if you wish), that you receive source code or can get it if you
+want it, that you can change the software or use pieces of it in new
+free programs, and that you know you can do these things.
+
+ To protect your rights, we need to prevent others from denying you
+these rights or asking you to surrender the rights. Therefore, you have
+certain responsibilities if you distribute copies of the software, or if
+you modify it: responsibilities to respect the freedom of others.
+
+ For example, if you distribute copies of such a program, whether
+gratis or for a fee, you must pass on to the recipients the same
+freedoms that you received. You must make sure that they, too, receive
+or can get the source code. And you must show them these terms so they
+know their rights.
+
+ Developers that use the GNU GPL protect your rights with two steps:
+(1) assert copyright on the software, and (2) offer you this License
+giving you legal permission to copy, distribute and/or modify it.
+
+ For the developers' and authors' protection, the GPL clearly explains
+that there is no warranty for this free software. For both users' and
+authors' sake, the GPL requires that modified versions be marked as
+changed, so that their problems will not be attributed erroneously to
+authors of previous versions.
+
+ Some devices are designed to deny users access to install or run
+modified versions of the software inside them, although the manufacturer
+can do so. This is fundamentally incompatible with the aim of
+protecting users' freedom to change the software. The systematic
+pattern of such abuse occurs in the area of products for individuals to
+use, which is precisely where it is most unacceptable. Therefore, we
+have designed this version of the GPL to prohibit the practice for those
+products. If such problems arise substantially in other domains, we
+stand ready to extend this provision to those domains in future versions
+of the GPL, as needed to protect the freedom of users.
+
+ Finally, every program is threatened constantly by software patents.
+States should not allow patents to restrict development and use of
+software on general-purpose computers, but in those that do, we wish to
+avoid the special danger that patents applied to a free program could
+make it effectively proprietary. To prevent this, the GPL assures that
+patents cannot be used to render the program non-free.
+
+ The precise terms and conditions for copying, distribution and
+modification follow.
+
+ TERMS AND CONDITIONS
+
+ 0. Definitions.
+
+ "This License" refers to version 3 of the GNU General Public License.
+
+ "Copyright" also means copyright-like laws that apply to other kinds of
+works, such as semiconductor masks.
+
+ "The Program" refers to any copyrightable work licensed under this
+License. Each licensee is addressed as "you". "Licensees" and
+"recipients" may be individuals or organizations.
+
+ To "modify" a work means to copy from or adapt all or part of the work
+in a fashion requiring copyright permission, other than the making of an
+exact copy. The resulting work is called a "modified version" of the
+earlier work or a work "based on" the earlier work.
+
+ A "covered work" means either the unmodified Program or a work based
+on the Program.
+
+ To "propagate" a work means to do anything with it that, without
+permission, would make you directly or secondarily liable for
+infringement under applicable copyright law, except executing it on a
+computer or modifying a private copy. Propagation includes copying,
+distribution (with or without modification), making available to the
+public, and in some countries other activities as well.
+
+ To "convey" a work means any kind of propagation that enables other
+parties to make or receive copies. Mere interaction with a user through
+a computer network, with no transfer of a copy, is not conveying.
+
+ An interactive user interface displays "Appropriate Legal Notices"
+to the extent that it includes a convenient and prominently visible
+feature that (1) displays an appropriate copyright notice, and (2)
+tells the user that there is no warranty for the work (except to the
+extent that warranties are provided), that licensees may convey the
+work under this License, and how to view a copy of this License. If
+the interface presents a list of user commands or options, such as a
+menu, a prominent item in the list meets this criterion.
+
+ 1. Source Code.
+
+ The "source code" for a work means the preferred form of the work
+for making modifications to it. "Object code" means any non-source
+form of a work.
+
+ A "Standard Interface" means an interface that either is an official
+standard defined by a recognized standards body, or, in the case of
+interfaces specified for a particular programming language, one that
+is widely used among developers working in that language.
+
+ The "System Libraries" of an executable work include anything, other
+than the work as a whole, that (a) is included in the normal form of
+packaging a Major Component, but which is not part of that Major
+Component, and (b) serves only to enable use of the work with that
+Major Component, or to implement a Standard Interface for which an
+implementation is available to the public in source code form. A
+"Major Component", in this context, means a major essential component
+(kernel, window system, and so on) of the specific operating system
+(if any) on which the executable work runs, or a compiler used to
+produce the work, or an object code interpreter used to run it.
+
+ The "Corresponding Source" for a work in object code form means all
+the source code needed to generate, install, and (for an executable
+work) run the object code and to modify the work, including scripts to
+control those activities. However, it does not include the work's
+System Libraries, or general-purpose tools or generally available free
+programs which are used unmodified in performing those activities but
+which are not part of the work. For example, Corresponding Source
+includes interface definition files associated with source files for
+the work, and the source code for shared libraries and dynamically
+linked subprograms that the work is specifically designed to require,
+such as by intimate data communication or control flow between those
+subprograms and other parts of the work.
+
+ The Corresponding Source need not include anything that users
+can regenerate automatically from other parts of the Corresponding
+Source.
+
+ The Corresponding Source for a work in source code form is that
+same work.
+
+ 2. Basic Permissions.
+
+ All rights granted under this License are granted for the term of
+copyright on the Program, and are irrevocable provided the stated
+conditions are met. This License explicitly affirms your unlimited
+permission to run the unmodified Program. The output from running a
+covered work is covered by this License only if the output, given its
+content, constitutes a covered work. This License acknowledges your
+rights of fair use or other equivalent, as provided by copyright law.
+
+ You may make, run and propagate covered works that you do not
+convey, without conditions so long as your license otherwise remains
+in force. You may convey covered works to others for the sole purpose
+of having them make modifications exclusively for you, or provide you
+with facilities for running those works, provided that you comply with
+the terms of this License in conveying all material for which you do
+not control copyright. Those thus making or running the covered works
+for you must do so exclusively on your behalf, under your direction
+and control, on terms that prohibit them from making any copies of
+your copyrighted material outside their relationship with you.
+
+ Conveying under any other circumstances is permitted solely under
+the conditions stated below. Sublicensing is not allowed; section 10
+makes it unnecessary.
+
+ 3. Protecting Users' Legal Rights From Anti-Circumvention Law.
+
+ No covered work shall be deemed part of an effective technological
+measure under any applicable law fulfilling obligations under article
+11 of the WIPO copyright treaty adopted on 20 December 1996, or
+similar laws prohibiting or restricting circumvention of such
+measures.
+
+ When you convey a covered work, you waive any legal power to forbid
+circumvention of technological measures to the extent such circumvention
+is effected by exercising rights under this License with respect to
+the covered work, and you disclaim any intention to limit operation or
+modification of the work as a means of enforcing, against the work's
+users, your or third parties' legal rights to forbid circumvention of
+technological measures.
+
+ 4. Conveying Verbatim Copies.
+
+ You may convey verbatim copies of the Program's source code as you
+receive it, in any medium, provided that you conspicuously and
+appropriately publish on each copy an appropriate copyright notice;
+keep intact all notices stating that this License and any
+non-permissive terms added in accord with section 7 apply to the code;
+keep intact all notices of the absence of any warranty; and give all
+recipients a copy of this License along with the Program.
+
+ You may charge any price or no price for each copy that you convey,
+and you may offer support or warranty protection for a fee.
+
+ 5. Conveying Modified Source Versions.
+
+ You may convey a work based on the Program, or the modifications to
+produce it from the Program, in the form of source code under the
+terms of section 4, provided that you also meet all of these conditions:
+
+ a) The work must carry prominent notices stating that you modified
+ it, and giving a relevant date.
+
+ b) The work must carry prominent notices stating that it is
+ released under this License and any conditions added under section
+ 7. This requirement modifies the requirement in section 4 to
+ "keep intact all notices".
+
+ c) You must license the entire work, as a whole, under this
+ License to anyone who comes into possession of a copy. This
+ License will therefore apply, along with any applicable section 7
+ additional terms, to the whole of the work, and all its parts,
+ regardless of how they are packaged. This License gives no
+ permission to license the work in any other way, but it does not
+ invalidate such permission if you have separately received it.
+
+ d) If the work has interactive user interfaces, each must display
+ Appropriate Legal Notices; however, if the Program has interactive
+ interfaces that do not display Appropriate Legal Notices, your
+ work need not make them do so.
+
+ A compilation of a covered work with other separate and independent
+works, which are not by their nature extensions of the covered work,
+and which are not combined with it such as to form a larger program,
+in or on a volume of a storage or distribution medium, is called an
+"aggregate" if the compilation and its resulting copyright are not
+used to limit the access or legal rights of the compilation's users
+beyond what the individual works permit. Inclusion of a covered work
+in an aggregate does not cause this License to apply to the other
+parts of the aggregate.
+
+ 6. Conveying Non-Source Forms.
+
+ You may convey a covered work in object code form under the terms
+of sections 4 and 5, provided that you also convey the
+machine-readable Corresponding Source under the terms of this License,
+in one of these ways:
+
+ a) Convey the object code in, or embodied in, a physical product
+ (including a physical distribution medium), accompanied by the
+ Corresponding Source fixed on a durable physical medium
+ customarily used for software interchange.
+
+ b) Convey the object code in, or embodied in, a physical product
+ (including a physical distribution medium), accompanied by a
+ written offer, valid for at least three years and valid for as
+ long as you offer spare parts or customer support for that product
+ model, to give anyone who possesses the object code either (1) a
+ copy of the Corresponding Source for all the software in the
+ product that is covered by this License, on a durable physical
+ medium customarily used for software interchange, for a price no
+ more than your reasonable cost of physically performing this
+ conveying of source, or (2) access to copy the
+ Corresponding Source from a network server at no charge.
+
+ c) Convey individual copies of the object code with a copy of the
+ written offer to provide the Corresponding Source. This
+ alternative is allowed only occasionally and noncommercially, and
+ only if you received the object code with such an offer, in accord
+ with subsection 6b.
+
+ d) Convey the object code by offering access from a designated
+ place (gratis or for a charge), and offer equivalent access to the
+ Corresponding Source in the same way through the same place at no
+ further charge. You need not require recipients to copy the
+ Corresponding Source along with the object code. If the place to
+ copy the object code is a network server, the Corresponding Source
+ may be on a different server (operated by you or a third party)
+ that supports equivalent copying facilities, provided you maintain
+ clear directions next to the object code saying where to find the
+ Corresponding Source. Regardless of what server hosts the
+ Corresponding Source, you remain obligated to ensure that it is
+ available for as long as needed to satisfy these requirements.
+
+ e) Convey the object code using peer-to-peer transmission, provided
+ you inform other peers where the object code and Corresponding
+ Source of the work are being offered to the general public at no
+ charge under subsection 6d.
+
+ A separable portion of the object code, whose source code is excluded
+from the Corresponding Source as a System Library, need not be
+included in conveying the object code work.
+
+ A "User Product" is either (1) a "consumer product", which means any
+tangible personal property which is normally used for personal, family,
+or household purposes, or (2) anything designed or sold for incorporation
+into a dwelling. In determining whether a product is a consumer product,
+doubtful cases shall be resolved in favor of coverage. For a particular
+product received by a particular user, "normally used" refers to a
+typical or common use of that class of product, regardless of the status
+of the particular user or of the way in which the particular user
+actually uses, or expects or is expected to use, the product. A product
+is a consumer product regardless of whether the product has substantial
+commercial, industrial or non-consumer uses, unless such uses represent
+the only significant mode of use of the product.
+
+ "Installation Information" for a User Product means any methods,
+procedures, authorization keys, or other information required to install
+and execute modified versions of a covered work in that User Product from
+a modified version of its Corresponding Source. The information must
+suffice to ensure that the continued functioning of the modified object
+code is in no case prevented or interfered with solely because
+modification has been made.
+
+ If you convey an object code work under this section in, or with, or
+specifically for use in, a User Product, and the conveying occurs as
+part of a transaction in which the right of possession and use of the
+User Product is transferred to the recipient in perpetuity or for a
+fixed term (regardless of how the transaction is characterized), the
+Corresponding Source conveyed under this section must be accompanied
+by the Installation Information. But this requirement does not apply
+if neither you nor any third party retains the ability to install
+modified object code on the User Product (for example, the work has
+been installed in ROM).
+
+ The requirement to provide Installation Information does not include a
+requirement to continue to provide support service, warranty, or updates
+for a work that has been modified or installed by the recipient, or for
+the User Product in which it has been modified or installed. Access to a
+network may be denied when the modification itself materially and
+adversely affects the operation of the network or violates the rules and
+protocols for communication across the network.
+
+ Corresponding Source conveyed, and Installation Information provided,
+in accord with this section must be in a format that is publicly
+documented (and with an implementation available to the public in
+source code form), and must require no special password or key for
+unpacking, reading or copying.
+
+ 7. Additional Terms.
+
+ "Additional permissions" are terms that supplement the terms of this
+License by making exceptions from one or more of its conditions.
+Additional permissions that are applicable to the entire Program shall
+be treated as though they were included in this License, to the extent
+that they are valid under applicable law. If additional permissions
+apply only to part of the Program, that part may be used separately
+under those permissions, but the entire Program remains governed by
+this License without regard to the additional permissions.
+
+ When you convey a copy of a covered work, you may at your option
+remove any additional permissions from that copy, or from any part of
+it. (Additional permissions may be written to require their own
+removal in certain cases when you modify the work.) You may place
+additional permissions on material, added by you to a covered work,
+for which you have or can give appropriate copyright permission.
+
+ Notwithstanding any other provision of this License, for material you
+add to a covered work, you may (if authorized by the copyright holders of
+that material) supplement the terms of this License with terms:
+
+ a) Disclaiming warranty or limiting liability differently from the
+ terms of sections 15 and 16 of this License; or
+
+ b) Requiring preservation of specified reasonable legal notices or
+ author attributions in that material or in the Appropriate Legal
+ Notices displayed by works containing it; or
+
+ c) Prohibiting misrepresentation of the origin of that material, or
+ requiring that modified versions of such material be marked in
+ reasonable ways as different from the original version; or
+
+ d) Limiting the use for publicity purposes of names of licensors or
+ authors of the material; or
+
+ e) Declining to grant rights under trademark law for use of some
+ trade names, trademarks, or service marks; or
+
+ f) Requiring indemnification of licensors and authors of that
+ material by anyone who conveys the material (or modified versions of
+ it) with contractual assumptions of liability to the recipient, for
+ any liability that these contractual assumptions directly impose on
+ those licensors and authors.
+
+ All other non-permissive additional terms are considered "further
+restrictions" within the meaning of section 10. If the Program as you
+received it, or any part of it, contains a notice stating that it is
+governed by this License along with a term that is a further
+restriction, you may remove that term. If a license document contains
+a further restriction but permits relicensing or conveying under this
+License, you may add to a covered work material governed by the terms
+of that license document, provided that the further restriction does
+not survive such relicensing or conveying.
+
+ If you add terms to a covered work in accord with this section, you
+must place, in the relevant source files, a statement of the
+additional terms that apply to those files, or a notice indicating
+where to find the applicable terms.
+
+ Additional terms, permissive or non-permissive, may be stated in the
+form of a separately written license, or stated as exceptions;
+the above requirements apply either way.
+
+ 8. Termination.
+
+ You may not propagate or modify a covered work except as expressly
+provided under this License. Any attempt otherwise to propagate or
+modify it is void, and will automatically terminate your rights under
+this License (including any patent licenses granted under the third
+paragraph of section 11).
+
+ However, if you cease all violation of this License, then your
+license from a particular copyright holder is reinstated (a)
+provisionally, unless and until the copyright holder explicitly and
+finally terminates your license, and (b) permanently, if the copyright
+holder fails to notify you of the violation by some reasonable means
+prior to 60 days after the cessation.
+
+ Moreover, your license from a particular copyright holder is
+reinstated permanently if the copyright holder notifies you of the
+violation by some reasonable means, this is the first time you have
+received notice of violation of this License (for any work) from that
+copyright holder, and you cure the violation prior to 30 days after
+your receipt of the notice.
+
+ Termination of your rights under this section does not terminate the
+licenses of parties who have received copies or rights from you under
+this License. If your rights have been terminated and not permanently
+reinstated, you do not qualify to receive new licenses for the same
+material under section 10.
+
+ 9. Acceptance Not Required for Having Copies.
+
+ You are not required to accept this License in order to receive or
+run a copy of the Program. Ancillary propagation of a covered work
+occurring solely as a consequence of using peer-to-peer transmission
+to receive a copy likewise does not require acceptance. However,
+nothing other than this License grants you permission to propagate or
+modify any covered work. These actions infringe copyright if you do
+not accept this License. Therefore, by modifying or propagating a
+covered work, you indicate your acceptance of this License to do so.
+
+ 10. Automatic Licensing of Downstream Recipients.
+
+ Each time you convey a covered work, the recipient automatically
+receives a license from the original licensors, to run, modify and
+propagate that work, subject to this License. You are not responsible
+for enforcing compliance by third parties with this License.
+
+ An "entity transaction" is a transaction transferring control of an
+organization, or substantially all assets of one, or subdividing an
+organization, or merging organizations. If propagation of a covered
+work results from an entity transaction, each party to that
+transaction who receives a copy of the work also receives whatever
+licenses to the work the party's predecessor in interest had or could
+give under the previous paragraph, plus a right to possession of the
+Corresponding Source of the work from the predecessor in interest, if
+the predecessor has it or can get it with reasonable efforts.
+
+ You may not impose any further restrictions on the exercise of the
+rights granted or affirmed under this License. For example, you may
+not impose a license fee, royalty, or other charge for exercise of
+rights granted under this License, and you may not initiate litigation
+(including a cross-claim or counterclaim in a lawsuit) alleging that
+any patent claim is infringed by making, using, selling, offering for
+sale, or importing the Program or any portion of it.
+
+ 11. Patents.
+
+ A "contributor" is a copyright holder who authorizes use under this
+License of the Program or a work on which the Program is based. The
+work thus licensed is called the contributor's "contributor version".
+
+ A contributor's "essential patent claims" are all patent claims
+owned or controlled by the contributor, whether already acquired or
+hereafter acquired, that would be infringed by some manner, permitted
+by this License, of making, using, or selling its contributor version,
+but do not include claims that would be infringed only as a
+consequence of further modification of the contributor version. For
+purposes of this definition, "control" includes the right to grant
+patent sublicenses in a manner consistent with the requirements of
+this License.
+
+ Each contributor grants you a non-exclusive, worldwide, royalty-free
+patent license under the contributor's essential patent claims, to
+make, use, sell, offer for sale, import and otherwise run, modify and
+propagate the contents of its contributor version.
+
+ In the following three paragraphs, a "patent license" is any express
+agreement or commitment, however denominated, not to enforce a patent
+(such as an express permission to practice a patent or covenant not to
+sue for patent infringement). To "grant" such a patent license to a
+party means to make such an agreement or commitment not to enforce a
+patent against the party.
+
+ If you convey a covered work, knowingly relying on a patent license,
+and the Corresponding Source of the work is not available for anyone
+to copy, free of charge and under the terms of this License, through a
+publicly available network server or other readily accessible means,
+then you must either (1) cause the Corresponding Source to be so
+available, or (2) arrange to deprive yourself of the benefit of the
+patent license for this particular work, or (3) arrange, in a manner
+consistent with the requirements of this License, to extend the patent
+license to downstream recipients. "Knowingly relying" means you have
+actual knowledge that, but for the patent license, your conveying the
+covered work in a country, or your recipient's use of the covered work
+in a country, would infringe one or more identifiable patents in that
+country that you have reason to believe are valid.
+
+ If, pursuant to or in connection with a single transaction or
+arrangement, you convey, or propagate by procuring conveyance of, a
+covered work, and grant a patent license to some of the parties
+receiving the covered work authorizing them to use, propagate, modify
+or convey a specific copy of the covered work, then the patent license
+you grant is automatically extended to all recipients of the covered
+work and works based on it.
+
+ A patent license is "discriminatory" if it does not include within
+the scope of its coverage, prohibits the exercise of, or is
+conditioned on the non-exercise of one or more of the rights that are
+specifically granted under this License. You may not convey a covered
+work if you are a party to an arrangement with a third party that is
+in the business of distributing software, under which you make payment
+to the third party based on the extent of your activity of conveying
+the work, and under which the third party grants, to any of the
+parties who would receive the covered work from you, a discriminatory
+patent license (a) in connection with copies of the covered work
+conveyed by you (or copies made from those copies), or (b) primarily
+for and in connection with specific products or compilations that
+contain the covered work, unless you entered into that arrangement,
+or that patent license was granted, prior to 28 March 2007.
+
+ Nothing in this License shall be construed as excluding or limiting
+any implied license or other defenses to infringement that may
+otherwise be available to you under applicable patent law.
+
+ 12. No Surrender of Others' Freedom.
+
+ If conditions are imposed on you (whether by court order, agreement or
+otherwise) that contradict the conditions of this License, they do not
+excuse you from the conditions of this License. If you cannot convey a
+covered work so as to satisfy simultaneously your obligations under this
+License and any other pertinent obligations, then as a consequence you may
+not convey it at all. For example, if you agree to terms that obligate you
+to collect a royalty for further conveying from those to whom you convey
+the Program, the only way you could satisfy both those terms and this
+License would be to refrain entirely from conveying the Program.
+
+ 13. Use with the GNU Affero General Public License.
+
+ Notwithstanding any other provision of this License, you have
+permission to link or combine any covered work with a work licensed
+under version 3 of the GNU Affero General Public License into a single
+combined work, and to convey the resulting work. The terms of this
+License will continue to apply to the part which is the covered work,
+but the special requirements of the GNU Affero General Public License,
+section 13, concerning interaction through a network will apply to the
+combination as such.
+
+ 14. Revised Versions of this License.
+
+ The Free Software Foundation may publish revised and/or new versions of
+the GNU General Public License from time to time. Such new versions will
+be similar in spirit to the present version, but may differ in detail to
+address new problems or concerns.
+
+ Each version is given a distinguishing version number. If the
+Program specifies that a certain numbered version of the GNU General
+Public License "or any later version" applies to it, you have the
+option of following the terms and conditions either of that numbered
+version or of any later version published by the Free Software
+Foundation. If the Program does not specify a version number of the
+GNU General Public License, you may choose any version ever published
+by the Free Software Foundation.
+
+ If the Program specifies that a proxy can decide which future
+versions of the GNU General Public License can be used, that proxy's
+public statement of acceptance of a version permanently authorizes you
+to choose that version for the Program.
+
+ Later license versions may give you additional or different
+permissions. However, no additional obligations are imposed on any
+author or copyright holder as a result of your choosing to follow a
+later version.
+
+ 15. Disclaimer of Warranty.
+
+ THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY
+APPLICABLE LAW. EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT
+HOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM "AS IS" WITHOUT WARRANTY
+OF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,
+THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM
+IS WITH YOU. SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF
+ALL NECESSARY SERVICING, REPAIR OR CORRECTION.
+
+ 16. Limitation of Liability.
+
+ IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING
+WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS
+THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY
+GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE
+USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF
+DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD
+PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),
+EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF
+SUCH DAMAGES.
+
+ 17. Interpretation of Sections 15 and 16.
+
+ If the disclaimer of warranty and limitation of liability provided
+above cannot be given local legal effect according to their terms,
+reviewing courts shall apply local law that most closely approximates
+an absolute waiver of all civil liability in connection with the
+Program, unless a warranty or assumption of liability accompanies a
+copy of the Program in return for a fee.
+
+ END OF TERMS AND CONDITIONS
+
+ How to Apply These Terms to Your New Programs
+
+ If you develop a new program, and you want it to be of the greatest
+possible use to the public, the best way to achieve this is to make it
+free software which everyone can redistribute and change under these terms.
+
+ To do so, attach the following notices to the program. It is safest
+to attach them to the start of each source file to most effectively
+state the exclusion of warranty; and each file should have at least
+the "copyright" line and a pointer to where the full notice is found.
+
+
+ Copyright (C)
+
+ 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 .
+
+Also add information on how to contact you by electronic and paper mail.
+
+ If the program does terminal interaction, make it output a short
+notice like this when it starts in an interactive mode:
+
+ Copyright (C)
+ This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.
+ This is free software, and you are welcome to redistribute it
+ under certain conditions; type `show c' for details.
+
+The hypothetical commands `show w' and `show c' should show the appropriate
+parts of the General Public License. Of course, your program's commands
+might be different; for a GUI interface, you would use an "about box".
+
+ You should also get your employer (if you work as a programmer) or school,
+if any, to sign a "copyright disclaimer" for the program, if necessary.
+For more information on this, and how to apply and follow the GNU GPL, see
+.
+
+ The GNU General Public License does not permit incorporating your program
+into proprietary programs. If your program is a subroutine library, you
+may consider it more useful to permit linking proprietary applications with
+the library. If this is what you want to do, use the GNU Lesser General
+Public License instead of this License. But first, please read
+.
diff --git a/InstallationInstructions.txt b/InstallationInstructions.txt
new file mode 100644
index 00000000..2e732ffb
--- /dev/null
+++ b/InstallationInstructions.txt
@@ -0,0 +1,14 @@
+Version 3.0 of the AeroQuad Flight Software takes advantage of the use of libraries within the Arduino IDE environment. There are two install methods to use to make sure the AeroQuad libraries are properly deteced by the Arduino IDE.
+
+Method 1:
+- Save the AeroQuad folder into your location of choice.
+- In the Arduino IDE, go to File->Preferences->Sketchbook location:
+- Select Browse and navigate to the folder where you saved the AeroQuad Flight Software
+- To verify that the libraries can be found, restart the Arduino IDE
+- Go to File->Sketchbook->Libraries
+- You should see multiple libraries prefaced with "AQ_"
+
+Method 2 (Use if you have other custom Arduino libraries you still want access to):
+- Copy the Libraries folder from the AeroQuad Flight Software to ./arduino-1.0/libraries (basically the libary path of the Arduino IDE itself)
+
+Important note: This version of the AeroQuad Flight Software is only compatible with the Arduino v1.0 IDE or greater.
\ No newline at end of file
diff --git a/Libraries/AQ_Accelerometer/Accelerometer.h b/Libraries/AQ_Accelerometer/Accelerometer.h
new file mode 100644
index 00000000..3bcebce4
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Accelerometer.h
@@ -0,0 +1,44 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_ACCELEROMETER_H_
+#define _AEROQUAD_ACCELEROMETER_H_
+
+#include "Arduino.h"
+#include "GlobalDefined.h"
+
+#define SAMPLECOUNT 400.0
+
+float accelScaleFactor[3] = {0.0,0.0,0.0};
+float runTimeAccelBias[3] = {0, 0, 0};
+float accelSmoothFactor = 1.0; // can we remove if we go with 4th order filter?
+float accelOneG = 0.0;
+float meterPerSec[3] = {0.0,0.0,0.0};
+
+long accelSample[3] = {0,0,0};
+byte accelSampleCount = 0;
+
+void initializeAccel();
+void measureAccel();
+void measureAccelSum();
+void evaluateMetersPerSec();
+void computeAccelBias();
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_Accelerometer/Accelerometer_ADXL345.h b/Libraries/AQ_Accelerometer/Accelerometer_ADXL345.h
new file mode 100644
index 00000000..3c55b5a0
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Accelerometer_ADXL345.h
@@ -0,0 +1,92 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_ACCELEROMETER_ADXL345_H_
+#define _AEROQUAD_ACCELEROMETER_ADXL345_H_
+
+#include
+#include
+
+#define ACCEL_ADDRESS 0x53
+
+void initializeAccel() {
+
+ if (readWhoI2C(ACCEL_ADDRESS) != 0xE5) { // page 14 of datasheet
+ vehicleState |= ACCEL_DETECTED;
+ }
+
+ updateRegisterI2C(ACCEL_ADDRESS, 0x2D, 1<<3); // set device to *measure*
+ updateRegisterI2C(ACCEL_ADDRESS, 0x31, 0x08); // set full range and +/- 2G
+ updateRegisterI2C(ACCEL_ADDRESS, 0x2C, 8+2+1); // 200hz sampling
+ delay(10);
+}
+
+void measureAccel() {
+
+ sendByteI2C(ACCEL_ADDRESS, 0x32);
+ Wire.requestFrom(ACCEL_ADDRESS, 6);
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ meterPerSec[axis] = readReverseShortI2C() * accelScaleFactor[axis] + runTimeAccelBias[axis];
+ }
+}
+
+void measureAccelSum() {
+
+ sendByteI2C(ACCEL_ADDRESS, 0x32);
+ Wire.requestFrom(ACCEL_ADDRESS, 6);
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ accelSample[axis] += readReverseShortI2C();
+ }
+ accelSampleCount++;
+}
+
+void evaluateMetersPerSec() {
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ meterPerSec[axis] = (accelSample[axis] / accelSampleCount) * accelScaleFactor[axis] + runTimeAccelBias[axis];
+ accelSample[axis] = 0;
+ }
+ accelSampleCount = 0;
+}
+
+void computeAccelBias() {
+
+ for (int samples = 0; samples < SAMPLECOUNT; samples++) {
+ measureAccelSum();
+ delayMicroseconds(2500);
+ }
+
+ for (byte axis = 0; axis < 3; axis++) {
+ meterPerSec[axis] = (float(accelSample[axis])/SAMPLECOUNT) * accelScaleFactor[axis];
+ accelSample[axis] = 0;
+ }
+ accelSampleCount = 0;
+
+ runTimeAccelBias[XAXIS] = -meterPerSec[XAXIS];
+ runTimeAccelBias[YAXIS] = -meterPerSec[YAXIS];
+ runTimeAccelBias[ZAXIS] = -9.8065 - meterPerSec[ZAXIS];
+
+ accelOneG = abs(meterPerSec[ZAXIS] + runTimeAccelBias[ZAXIS]);
+}
+
+
+
+#endif
diff --git a/Libraries/AQ_Accelerometer/Accelerometer_ADXL345_9DOF.h b/Libraries/AQ_Accelerometer/Accelerometer_ADXL345_9DOF.h
new file mode 100644
index 00000000..8c17db69
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Accelerometer_ADXL345_9DOF.h
@@ -0,0 +1,93 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_ACCELEROMETER_ADXL345_H_
+#define _AEROQUAD_ACCELEROMETER_ADXL345_H_
+
+#include
+#include
+
+#define ACCEL_ADDRESS 0x53
+
+void initializeAccel() {
+
+ if (readWhoI2C(ACCEL_ADDRESS) != 0xE5) { // page 14 of datasheet
+ vehicleState |= ACCEL_DETECTED;
+ }
+
+ updateRegisterI2C(ACCEL_ADDRESS, 0x2D, 1<<3); // set device to *measure*
+ updateRegisterI2C(ACCEL_ADDRESS, 0x31, 0x08); // set full range and +/- 2G
+ updateRegisterI2C(ACCEL_ADDRESS, 0x2C, 8+2+1); // 200hz sampling
+ delay(10);
+}
+
+void measureAccel() {
+
+ sendByteI2C(ACCEL_ADDRESS, 0x32);
+ Wire.requestFrom(ACCEL_ADDRESS, 6);
+
+ meterPerSec[YAXIS] = readReverseShortI2C() * accelScaleFactor[YAXIS] + runTimeAccelBias[YAXIS];
+ meterPerSec[XAXIS] = readReverseShortI2C() * accelScaleFactor[XAXIS] + runTimeAccelBias[XAXIS];
+ meterPerSec[ZAXIS] = readReverseShortI2C() * accelScaleFactor[ZAXIS] + runTimeAccelBias[ZAXIS];
+}
+
+void measureAccelSum() {
+
+ sendByteI2C(ACCEL_ADDRESS, 0x32);
+ Wire.requestFrom(ACCEL_ADDRESS, 6);
+
+ accelSample[YAXIS] += readReverseShortI2C() ;
+ accelSample[XAXIS] += readReverseShortI2C() ;
+ accelSample[ZAXIS] += readReverseShortI2C() ;
+ accelSampleCount++;
+}
+
+void evaluateMetersPerSec() {
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ meterPerSec[axis] = (accelSample[axis] / accelSampleCount) * accelScaleFactor[axis] + runTimeAccelBias[axis];
+ accelSample[axis] = 0;
+ }
+ accelSampleCount = 0;
+}
+
+void computeAccelBias() {
+
+ for (int samples = 0; samples < SAMPLECOUNT; samples++) {
+ measureAccelSum();
+ delayMicroseconds(2500);
+ }
+
+ for (byte axis = 0; axis < 3; axis++) {
+ meterPerSec[axis] = (float(accelSample[axis])/SAMPLECOUNT) * accelScaleFactor[axis];
+ accelSample[axis] = 0;
+ }
+ accelSampleCount = 0;
+
+ runTimeAccelBias[XAXIS] = -meterPerSec[XAXIS];
+ runTimeAccelBias[YAXIS] = -meterPerSec[YAXIS];
+ runTimeAccelBias[ZAXIS] = -9.8065 - meterPerSec[ZAXIS];
+
+ accelOneG = abs(meterPerSec[ZAXIS] + runTimeAccelBias[ZAXIS]);
+}
+
+
+
+#endif
diff --git a/Libraries/AQ_Accelerometer/Accelerometer_ADXL500.h b/Libraries/AQ_Accelerometer/Accelerometer_ADXL500.h
new file mode 100644
index 00000000..6d36adf7
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Accelerometer_ADXL500.h
@@ -0,0 +1,69 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_ACCELEROMETER_IDG500_H_
+#define _AEROQUAD_ACCELEROMETER_IDG500_H_
+
+#include
+
+void initializeAccel() {
+ vehicleState |= ACCEL_DETECTED;
+}
+
+void measureAccel() {
+
+ meterPerSec[XAXIS] = analogRead(1) * accelScaleFactor[XAXIS] + runTimeAccelBias[XAXIS];
+ meterPerSec[YAXIS] = analogRead(0) * accelScaleFactor[YAXIS] + runTimeAccelBias[YAXIS];
+ meterPerSec[ZAXIS] = analogRead(2) * accelScaleFactor[ZAXIS] + runTimeAccelBias[ZAXIS];
+}
+
+void measureAccelSum() {
+
+ accelSample[XAXIS] += analogRead(1);
+ accelSample[YAXIS] += analogRead(0);
+ accelSample[ZAXIS] += analogRead(2);
+ accelSampleCount++;
+}
+
+void evaluateMetersPerSec() {
+ // do nothing here
+}
+
+void computeAccelBias() {
+
+ for (int samples = 0; samples < SAMPLECOUNT; samples++) {
+ measureAccelSum();
+ delayMicroseconds(2500);
+ }
+
+ for (byte axis = 0; axis < 3; axis++) {
+ meterPerSec[axis] = (float(accelSample[axis])/SAMPLECOUNT) * accelScaleFactor[axis];
+ accelSample[axis] = 0;
+ }
+ accelSampleCount = 0;
+
+ runTimeAccelBias[XAXIS] = -meterPerSec[XAXIS];
+ runTimeAccelBias[YAXIS] = -meterPerSec[YAXIS];
+ runTimeAccelBias[ZAXIS] = -9.8065 - meterPerSec[ZAXIS];
+
+ accelOneG = abs(meterPerSec[ZAXIS] + runTimeAccelBias[ZAXIS]);
+}
+
+#endif
diff --git a/Libraries/AQ_Accelerometer/Accelerometer_APM.h b/Libraries/AQ_Accelerometer/Accelerometer_APM.h
new file mode 100644
index 00000000..60191a9c
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Accelerometer_APM.h
@@ -0,0 +1,75 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_ACCELEROMETER_APM_H_
+#define _AEROQUAD_ACCELEROMETER_APM_H_
+
+#include
+
+void initializeAccel() {
+ vehicleState |= ACCEL_DETECTED;
+}
+
+void measureAccel() {
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ const float rawADC = readADC(axis+3);
+ if (rawADC > 500) { // Check if measurement good
+ meterPerSec[axis] = rawADC * accelScaleFactor[axis] + runTimeAccelBias[axis];
+ }
+ }
+}
+
+void measureAccelSum() {
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ const float rawADC = readADC(axis+3);
+ if (rawADC > 500) { // Check if measurement good
+ accelSample[axis] += rawADC;
+ }
+ }
+ accelSampleCount++;
+}
+
+void evaluateMetersPerSec() {
+ // do nothing here
+}
+
+void computeAccelBias() {
+
+ for (int samples = 0; samples < SAMPLECOUNT; samples++) {
+ measureAccelSum();
+ delay(10);
+ }
+
+ for (byte axis = 0; axis < 3; axis++) {
+ meterPerSec[axis] = (float(accelSample[axis])/SAMPLECOUNT) * accelScaleFactor[axis];
+ accelSample[axis] = 0;
+ }
+ accelSampleCount = 0;
+
+ runTimeAccelBias[XAXIS] = -meterPerSec[XAXIS];
+ runTimeAccelBias[YAXIS] = -meterPerSec[YAXIS];
+ runTimeAccelBias[ZAXIS] = -9.8065 - meterPerSec[ZAXIS];
+
+ accelOneG = abs(meterPerSec[ZAXIS] + runTimeAccelBias[ZAXIS]);
+}
+
+#endif
diff --git a/Libraries/AQ_Accelerometer/Accelerometer_BMA180.h b/Libraries/AQ_Accelerometer/Accelerometer_BMA180.h
new file mode 100644
index 00000000..1b9b9571
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Accelerometer_BMA180.h
@@ -0,0 +1,132 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_ACCELEROMETER_BMA180_H_
+#define _AEROQUAD_ACCELEROMETER_BMA180_H_
+
+#include
+#include
+#include
+
+#define ACCEL_ADDRESS 0x40
+#define ACCEL_IDENTITY 0x03
+#define ACCEL_RESET_REGISTER 0x10
+#define ACCEL_TRIGER_RESET_VALUE 0xB6
+#define ACCEL_ENABLE_WRITE_CONTROL_REGISTER 0x0D
+#define ACCEL_CONTROL_REGISTER 0x10
+#define ACCEL_BW_TCS 0x20
+#define ACCEL_LOW_PASS_FILTER_REGISTER 0x20
+#define ACCEL_10HZ_LOW_PASS_FILTER_VALUE 0x0F
+#define ACCEL_1200HZ_LOW_PASS_FILTER_VALUE 0X7F
+#define ACCEL_OFFSET_REGISTER 0x35
+#define ACCEL_READ_ROLL_ADDRESS 0x02
+#define ACCEL_READ_PITCH_ADDRESS 0x04
+#define ACCEL_READ_YAW_ADDRESS 0x06
+
+void initializeAccel() {
+
+ //accelScale = G_2_MPS2(1.0/4096.0); // g per LSB @ +/- 2g range - checking with John if we can remove this
+
+ if (readWhoI2C(ACCEL_ADDRESS) != ACCEL_IDENTITY) {// page 52 of datasheet
+ vehicleState |= ACCEL_DETECTED;
+ }
+
+ updateRegisterI2C(ACCEL_ADDRESS, ACCEL_RESET_REGISTER, ACCEL_TRIGER_RESET_VALUE); //reset device
+ delay(10); //sleep 10 ms after reset (page 25)
+
+ // In datasheet, summary register map is page 21
+ // Low pass filter settings is page 27
+ // Range settings is page 28
+ updateRegisterI2C(ACCEL_ADDRESS, ACCEL_ENABLE_WRITE_CONTROL_REGISTER, ACCEL_CONTROL_REGISTER); //enable writing to control registers
+ sendByteI2C(ACCEL_ADDRESS, ACCEL_BW_TCS); // register bw_tcs (bits 4-7)
+ byte data = readByteI2C(ACCEL_ADDRESS); // get current register value
+ updateRegisterI2C(ACCEL_ADDRESS, ACCEL_LOW_PASS_FILTER_REGISTER, data & ACCEL_1200HZ_LOW_PASS_FILTER_VALUE); // set low pass filter to 10Hz (value = 0000xxxx)
+
+ // From page 27 of BMA180 Datasheet
+ // 1.0g = 0.13 mg/LSB
+ // 1.5g = 0.19 mg/LSB
+ // 2.0g = 0.25 mg/LSB
+ // 3.0g = 0.38 mg/LSB
+ // 4.0g = 0.50 mg/LSB
+ // 8.0g = 0.99 mg/LSB
+ // 16.0g = 1.98 mg/LSB
+ sendByteI2C(ACCEL_ADDRESS, ACCEL_OFFSET_REGISTER); // register offset_lsb1 (bits 1-3)
+ data = readByteI2C(ACCEL_ADDRESS);
+ data &= 0xF1;
+ //data |= 0x04; // Set range select bits for +/-2g
+ data |= 0x08;
+ updateRegisterI2C(ACCEL_ADDRESS, ACCEL_OFFSET_REGISTER, data);
+}
+
+void measureAccel() {
+
+ Wire.beginTransmission(ACCEL_ADDRESS);
+ Wire.write(ACCEL_READ_ROLL_ADDRESS);
+ Wire.endTransmission();
+ Wire.requestFrom(ACCEL_ADDRESS, 6);
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ meterPerSec[axis] = (readReverseShortI2C() >> 2) * accelScaleFactor[axis] + runTimeAccelBias[axis];
+ }
+}
+
+void measureAccelSum() {
+
+ Wire.beginTransmission(ACCEL_ADDRESS);
+ Wire.write(ACCEL_READ_ROLL_ADDRESS);
+ Wire.endTransmission();
+ Wire.requestFrom(ACCEL_ADDRESS, 6);
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ accelSample[axis] += (readReverseShortI2C() >> 2);
+ }
+ accelSampleCount++;
+}
+
+void evaluateMetersPerSec() {
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ meterPerSec[axis] = (accelSample[axis] / accelSampleCount) * accelScaleFactor[axis] + runTimeAccelBias[axis];
+ accelSample[axis] = 0;
+ }
+ accelSampleCount = 0;
+}
+
+void computeAccelBias() {
+
+ for (int samples = 0; samples < SAMPLECOUNT; samples++) {
+ measureAccelSum();
+ delayMicroseconds(2500);
+ }
+
+ for (byte axis = 0; axis < 3; axis++) {
+ meterPerSec[axis] = (float(accelSample[axis])/SAMPLECOUNT) * accelScaleFactor[axis];
+ accelSample[axis] = 0;
+ }
+ accelSampleCount = 0;
+
+ runTimeAccelBias[XAXIS] = -meterPerSec[XAXIS];
+ runTimeAccelBias[YAXIS] = -meterPerSec[YAXIS];
+ runTimeAccelBias[ZAXIS] = -9.8065 - meterPerSec[ZAXIS];
+
+ accelOneG = abs(meterPerSec[ZAXIS] + runTimeAccelBias[ZAXIS]);
+}
+
+#endif
diff --git a/Libraries/AQ_Accelerometer/Accelerometer_CHR6DM.h b/Libraries/AQ_Accelerometer/Accelerometer_CHR6DM.h
new file mode 100644
index 00000000..b8e02675
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Accelerometer_CHR6DM.h
@@ -0,0 +1,90 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_ACCELEROMETER_CHR6DM_H_
+#define _AEROQUAD_ACCELEROMETER_CHR6DM_H_
+
+//#include
+#include
+
+#define SAMPLECOUNT 400.0
+
+float accelScaleFactor[3] = {0.0,0.0,0.0};
+float runTimeAccelBias[3] = {0, 0, 0};
+float accelSmoothFactor = 1.0; // can we remove if we go with 4th order filter?
+float accelOneG = 0.0;
+float meterPerSec[3] = {0.0,0.0,0.0};
+
+float accelSample[3] = {0,0,0};
+byte accelSampleCount = 0;
+
+void initializeAccel();
+void measureAccel();
+void measureAccelSum();
+void evaluateMetersPerSec();
+void computeAccelBias();
+
+
+CHR6DM *accelChr6dm;
+
+void initializeAccel() {
+ vehicleState |= ACCEL_DETECTED;
+}
+
+void measureAccel() {
+
+ meterPerSec[XAXIS] = accelChr6dm->data.ax * accelScaleFactor[XAXIS] + runTimeAccelBias[XAXIS];
+ meterPerSec[YAXIS] = accelChr6dm->data.ay * accelScaleFactor[YAXIS] + runTimeAccelBias[YAXIS];
+ meterPerSec[ZAXIS] = accelChr6dm->data.az * accelScaleFactor[ZAXIS] + runTimeAccelBias[ZAXIS];
+}
+
+void measureAccelSum() {
+
+ accelSample[XAXIS] += accelChr6dm->data.ax;
+ accelSample[YAXIS] += accelChr6dm->data.ay;
+ accelSample[ZAXIS] += accelChr6dm->data.az;
+ accelSampleCount++;
+}
+
+void evaluateMetersPerSec() {
+ // do nothing here
+}
+
+void computeAccelBias() {
+
+ for (int samples = 0; samples < SAMPLECOUNT; samples++) {
+ measureAccelSum();
+ delay(6);
+ }
+
+ for (byte axis = 0; axis < 3; axis++) {
+ meterPerSec[axis] = (float(accelSample[axis])/SAMPLECOUNT) * accelScaleFactor[axis];
+ accelSample[axis] = 0;
+ }
+ accelSampleCount = 0;
+
+ runTimeAccelBias[XAXIS] = -meterPerSec[XAXIS];
+ runTimeAccelBias[YAXIS] = -meterPerSec[YAXIS];
+ runTimeAccelBias[ZAXIS] = -9.8065 - meterPerSec[ZAXIS];
+
+ accelOneG = abs(meterPerSec[ZAXIS] + runTimeAccelBias[ZAXIS]);
+}
+
+#endif
diff --git a/Libraries/AQ_Accelerometer/Accelerometer_WII.h b/Libraries/AQ_Accelerometer/Accelerometer_WII.h
new file mode 100644
index 00000000..5bc10297
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Accelerometer_WII.h
@@ -0,0 +1,70 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_ACCELEROMETER_WII_H_
+#define _AEROQUAD_ACCELEROMETER_WII_H_
+
+#include
+#include
+
+void initializeAccel() {
+ vehicleState |= ACCEL_DETECTED;
+}
+
+void measureAccel() {
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ meterPerSec[axis] = getWiiAccelADC(axis) * accelScaleFactor[axis] + runTimeAccelBias[axis];
+ }
+}
+
+void measureAccelSum() {
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ accelSample[axis] += getWiiAccelADC(axis);
+ }
+ accelSampleCount++;
+}
+
+void evaluateMetersPerSec() {
+ // do nothing here
+}
+
+void computeAccelBias() {
+
+ for (int samples = 0; samples < SAMPLECOUNT; samples++) {
+ readWiiSensors();
+ measureAccelSum();
+ }
+
+ for (byte axis = 0; axis <= ZAXIS; axis++) {
+ meterPerSec[axis] = (float(accelSample[axis])/SAMPLECOUNT) * accelScaleFactor[axis];
+ accelSample[axis] = 0;
+ }
+ accelSampleCount = 0;
+
+ runTimeAccelBias[XAXIS] = -meterPerSec[XAXIS];
+ runTimeAccelBias[YAXIS] = -meterPerSec[YAXIS];
+ runTimeAccelBias[ZAXIS] = -9.8065 - meterPerSec[ZAXIS];
+
+ accelOneG = abs(meterPerSec[ZAXIS] + runTimeAccelBias[ZAXIS]);
+}
+
+#endif
diff --git a/Libraries/AQ_Accelerometer/Examples/Test_ADXL345/Test_ADXL345.ino b/Libraries/AQ_Accelerometer/Examples/Test_ADXL345/Test_ADXL345.ino
new file mode 100644
index 00000000..71cfc693
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Examples/Test_ADXL345/Test_ADXL345.ino
@@ -0,0 +1,55 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include
+#include
+#include
+#include
+#include
+
+unsigned long timer;
+
+void setup() {
+
+ Serial.begin(115200);
+ Serial.println("Accelerometer library test (ADXL345)");
+
+ Wire.begin();
+
+ initializeAccel();
+ computeAccelBias();
+}
+
+void loop() {
+
+ if((millis() - timer) > 10) // 100Hz
+ {
+ timer = millis();
+ measureAccel();
+
+ Serial.print("Roll: ");
+ Serial.print(meterPerSec[XAXIS]);
+ Serial.print(" Pitch: ");
+ Serial.print(meterPerSec[YAXIS]);
+ Serial.print(" Yaw: ");
+ Serial.print(meterPerSec[ZAXIS]);
+ Serial.println();
+ }
+}
diff --git a/Libraries/AQ_Accelerometer/Examples/Test_ADXL500/Test_ADXL500.ino b/Libraries/AQ_Accelerometer/Examples/Test_ADXL500/Test_ADXL500.ino
new file mode 100644
index 00000000..f2141610
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Examples/Test_ADXL500/Test_ADXL500.ino
@@ -0,0 +1,57 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include // Arduino IDE bug, needed because that the ITG3200 use Wire!
+#include // Arduino IDE bug, needed because that the ITG3200 use Wire!
+#include // Arduino IDE bug, needed because that the CHR6DM use Wire!
+
+#include
+#include
+#include
+#include
+
+unsigned long timer;
+
+void setup() {
+
+ Serial.begin(115200);
+ Serial.println("Accelerometer library test (IDG500)");
+
+ initializeAccel();
+ computeAccelBias();
+}
+
+void loop() {
+
+ if((millis() - timer) > 10) // 100Hz
+ {
+ timer = millis();
+ //accel.measure();
+ measureAccel();
+
+ Serial.print("Roll: ");
+ Serial.print(meterPerSec[XAXIS]);
+ Serial.print(" Pitch: ");
+ Serial.print(meterPerSec[YAXIS]);
+ Serial.print(" Yaw: ");
+ Serial.print(meterPerSec[ZAXIS]);
+ Serial.println();
+ }
+}
diff --git a/Libraries/AQ_Accelerometer/Examples/Test_APM/Test_APM.ino b/Libraries/AQ_Accelerometer/Examples/Test_APM/Test_APM.ino
new file mode 100644
index 00000000..ae8da4aa
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Examples/Test_APM/Test_APM.ino
@@ -0,0 +1,58 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include // Arduino IDE bug, needed because that the ITG3200 use Wire!
+#include // Arduino IDE bug, needed because that the ITG3200 use Wire!
+
+#include
+#include
+#include
+#include
+
+unsigned long timer;
+
+void setup() {
+
+ Serial.begin(115200);
+ Serial.println("Accelerometer library test (APM)");
+
+ initializeADC();
+
+ initializeAccel();
+ computeAccelBias();
+
+}
+
+void loop() {
+
+ if((millis() - timer) > 10) // 100Hz
+ {
+ timer = millis();
+ measureAccel();
+
+ Serial.print("Roll: ");
+ Serial.print(meterPerSec[XAXIS]);
+ Serial.print(" Pitch: ");
+ Serial.print(meterPerSec[YAXIS]);
+ Serial.print(" Yaw: ");
+ Serial.print(meterPerSec[ZAXIS]);
+ Serial.println();
+ }
+}
diff --git a/Libraries/AQ_Accelerometer/Examples/Test_BMA180/Test_BMA180.ino b/Libraries/AQ_Accelerometer/Examples/Test_BMA180/Test_BMA180.ino
new file mode 100644
index 00000000..4d9528e7
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Examples/Test_BMA180/Test_BMA180.ino
@@ -0,0 +1,55 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include
+#include
+#include
+#include
+#include
+
+unsigned long timer;
+
+void setup() {
+
+ Serial.begin(115200);
+ Serial.println("Accelerometer library test (BMA180)");
+
+ Wire.begin();
+
+ initializeAccel();
+ computeAccelBias();
+}
+
+void loop() {
+
+ if((millis() - timer) > 10) // 100Hz
+ {
+ timer = millis();
+ measureAccel();
+
+ Serial.print("Roll: ");
+ Serial.print(meterPerSec[XAXIS]);
+ Serial.print(" Pitch: ");
+ Serial.print(meterPerSec[YAXIS]);
+ Serial.print(" Yaw: ");
+ Serial.print(meterPerSec[ZAXIS]);
+ Serial.println();
+ }
+}
diff --git a/Libraries/AQ_Accelerometer/Examples/Test_WII/Test_WII.ino b/Libraries/AQ_Accelerometer/Examples/Test_WII/Test_WII.ino
new file mode 100644
index 00000000..6f211851
--- /dev/null
+++ b/Libraries/AQ_Accelerometer/Examples/Test_WII/Test_WII.ino
@@ -0,0 +1,59 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+unsigned long timer;
+
+void setup() {
+
+ Serial.begin(115200);
+ Serial.println("Accelerometer library test (WII)");
+
+ Wire.begin();
+
+ initializeWiiSensors(true);
+ initializeAccel();
+ computeAccelBias();
+
+ timer = millis();
+}
+
+void loop() {
+
+ if((millis() - timer) > 10) // 100Hz
+ {
+ timer = millis();
+ measureAccel();
+
+ Serial.print("Roll: ");
+ Serial.print(meterPerSec[XAXIS]);
+ Serial.print(" Pitch: ");
+ Serial.print(meterPerSec[YAXIS]);
+ Serial.print(" Yaw: ");
+ Serial.print(meterPerSec[ZAXIS]);
+ Serial.println();
+ }
+}
diff --git a/Libraries/AQ_BarometricSensor/BarometricSensor.h b/Libraries/AQ_BarometricSensor/BarometricSensor.h
new file mode 100644
index 00000000..01f184ba
--- /dev/null
+++ b/Libraries/AQ_BarometricSensor/BarometricSensor.h
@@ -0,0 +1,57 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_BAROMETRIC_SENSOR_
+#define _AQ_BAROMETRIC_SENSOR_
+
+#include "Arduino.h"
+#include "GlobalDefined.h"
+
+double baroAltitude = 0.0;
+double baroRawAltitude = 0.0;
+float baroGroundAltitude = 0.0;
+float baroSmoothFactor = 0.02;
+
+// **********************************************************************
+// The following function calls must be defined inside any new subclasses
+// **********************************************************************
+void initializeBaro();
+void measureBaro();
+
+// *********************************************************
+// The following functions are common between all subclasses
+// *********************************************************
+const float getBaroAltitude() {
+ return baroAltitude - baroGroundAltitude;
+}
+
+void measureGroundBaro() {
+ // measure initial ground pressure (multiple samples)
+ baroGroundAltitude = 0;
+ for (int i=0; i < 25; i++) {
+ measureBaro();
+ delay(26);
+ baroGroundAltitude += baroRawAltitude;
+ }
+ baroGroundAltitude = baroGroundAltitude / 25.0;
+}
+
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_BarometricSensor/BarometricSensor_BMP085.h b/Libraries/AQ_BarometricSensor/BarometricSensor_BMP085.h
new file mode 100644
index 00000000..413a880a
--- /dev/null
+++ b/Libraries/AQ_BarometricSensor/BarometricSensor_BMP085.h
@@ -0,0 +1,178 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_BAROMETRIC_SENSOR_BMP085_
+#define _AQ_BAROMETRIC_SENSOR_BMP085_
+
+#include "BarometricSensor.h"
+#include "Device_I2C.h"
+#include
+
+// This sets up the BMP085 from Sparkfun
+// Code from http://wiring.org.co/learning/libraries/bmp085.html
+// Also made bug fixes based on BMP085 library from Jordi Munoz and Jose Julio
+
+#define BMP085_I2C_ADDRESS 0x77
+
+#define TEMPERATURE 0
+#define PRESSURE 1
+
+
+byte overSamplingSetting = 3;
+int ac1 = 0, ac2 = 0, ac3 = 0;
+unsigned int ac4 = 0, ac5 = 0, ac6 = 0;
+int b1 = 0, b2 = 0, mb = 0, mc = 0, md = 0;
+long pressure = 0;
+long temperature = 0;
+long rawPressure = 0, rawTemperature = 0;
+byte select = 0, pressureCount = 0;
+float pressureFactor = 1/5.255;
+
+void requestRawPressure() {
+ updateRegisterI2C(BMP085_I2C_ADDRESS, 0xF4, 0x34+(overSamplingSetting<<6));
+}
+
+long readRawPressure(void) {
+
+ sendByteI2C(BMP085_I2C_ADDRESS, 0xF6);
+ Wire.requestFrom(BMP085_I2C_ADDRESS, 3); // request three bytes
+ return (((unsigned long)Wire.read() << 16) | ((unsigned long)Wire.read() << 8) | ((unsigned long)Wire.read())) >> (8-overSamplingSetting);
+}
+
+void requestRawTemperature() {
+ updateRegisterI2C(BMP085_I2C_ADDRESS, 0xF4, 0x2E);
+}
+
+unsigned int readRawTemperature() {
+ sendByteI2C(BMP085_I2C_ADDRESS, 0xF6);
+ return readWordWaitI2C(BMP085_I2C_ADDRESS);
+}
+
+// ***********************************************************
+// Define all the virtual functions declared in the main class
+// ***********************************************************
+void initializeBaro() {
+// float verifyGroundAltitude;
+
+ // oversampling setting
+ // 0 = ultra low power
+ // 1 = standard
+ // 2 = high
+ // 3 = ultra high resolution
+ overSamplingSetting = 3;
+ pressure = 0;
+ temperature = 0;
+ baroGroundAltitude = 0;
+ pressureFactor = 1/5.255;
+
+ if (readWhoI2C(BMP085_I2C_ADDRESS) != BMP085_I2C_ADDRESS) {
+ vehicleState |= BARO_DETECTED;
+ }
+
+ sendByteI2C(BMP085_I2C_ADDRESS, 0xAA);
+ Wire.requestFrom(BMP085_I2C_ADDRESS, 22);
+ ac1 = readShortI2C();
+ ac2 = readShortI2C();
+ ac3 = readShortI2C();
+ ac4 = readWordI2C();
+ ac5 = readWordI2C();
+ ac6 = readWordI2C();
+ b1 = readShortI2C();
+ b2 = readShortI2C();
+ mb = readShortI2C();
+ mc = readShortI2C();
+ md = readShortI2C();
+ requestRawTemperature(); // setup up next measure() for temperature
+ select = TEMPERATURE;
+ pressureCount = 0;
+ measureBaro();
+ delay(5); // delay for temperature
+ measureBaro();
+ delay(26); // delay for pressure
+ measureGroundBaro();
+ // check if measured ground altitude is valid
+ while (abs(baroRawAltitude - baroGroundAltitude) > 10) {
+ delay(26);
+ measureGroundBaro();
+ }
+ baroAltitude = baroGroundAltitude;
+}
+
+void measureBaro() {
+ long x1, x2, x3, b3, b5, b6, p;
+ unsigned long b4, b7;
+ int32_t tmp;
+
+ // switch between pressure and tempature measurements
+ // each loop, since it's slow to measure pressure
+ if (select == PRESSURE) {
+ rawPressure = readRawPressure();
+ if (pressureCount == 4) {
+ requestRawTemperature();
+ pressureCount = 0;
+ select = TEMPERATURE;
+ }
+ else
+ requestRawPressure();
+ pressureCount++;
+ }
+ else { // select must equal TEMPERATURE
+ rawTemperature = (long)readRawTemperature();
+ requestRawPressure();
+ select = PRESSURE;
+ }
+
+ //calculate true temperature
+ x1 = ((long)rawTemperature - ac6) * ac5 >> 15;
+ x2 = ((long) mc << 11) / (x1 + md);
+ b5 = x1 + x2;
+ temperature = ((b5 + 8) >> 4);
+
+ //calculate true pressure
+ b6 = b5 - 4000;
+ x1 = (b2 * (b6 * b6 >> 12)) >> 11;
+ x2 = ac2 * b6 >> 11;
+ x3 = x1 + x2;
+
+ // Real Bosch formula - b3 = ((((int32_t)ac1 * 4 + x3) << overSamplingSetting) + 2) >> 2;
+ // The version below is the same, but takes less program space
+ tmp = ac1;
+ tmp = (tmp * 4 + x3) << overSamplingSetting;
+ b3 = (tmp + 2) >> 2;
+
+ x1 = ac3 * b6 >> 13;
+ x2 = (b1 * (b6 * b6 >> 12)) >> 16;
+ x3 = ((x1 + x2) + 2) >> 2;
+ b4 = (ac4 * (uint32_t) (x3 + 32768)) >> 15;
+ b7 = ((uint32_t) rawPressure - b3) * (50000 >> overSamplingSetting);
+ p = b7 < 0x80000000 ? (b7 << 1) / b4 : (b7 / b4) << 1;
+
+ x1 = (p >> 8) * (p >> 8);
+ x1 = (x1 * 3038) >> 16;
+ x2 = (-7357 * p) >> 16;
+ pressure = (p + ((x1 + x2 + 3791) >> 4));
+
+ baroRawAltitude = 44330 * (1 - pow(pressure/101325.0, pressureFactor)); // returns absolute baroAltitude in meters
+ //baroRawAltitude = (101325.0-pressure)/4096*346;
+ baroAltitude = filterSmooth(baroRawAltitude, baroAltitude, baroSmoothFactor);
+}
+
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_BarometricSensor/Examples/Test_BMP085/Test_BMP085.ino b/Libraries/AQ_BarometricSensor/Examples/Test_BMP085/Test_BMP085.ino
new file mode 100644
index 00000000..a43d51ab
--- /dev/null
+++ b/Libraries/AQ_BarometricSensor/Examples/Test_BMP085/Test_BMP085.ino
@@ -0,0 +1,51 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include
+#include
+#include
+
+#include
+#include
+
+unsigned long timer = 0;
+
+void setup() {
+
+ Serial.begin(115200);
+ Serial.println("Barometric sensor library test (BMP085)");
+
+ Wire.begin();
+
+ initializeBaro();
+}
+
+void loop() {
+
+ if((millis() - timer) > 50) // 20Hz
+ {
+ timer = millis();
+ measureBaro();
+
+ Serial.print("altitude : ");
+ Serial.print(getBaroAltitude());
+ Serial.println();
+ }
+}
diff --git a/Libraries/AQ_BatteryMonitor/BatteryMonitor.h b/Libraries/AQ_BatteryMonitor/BatteryMonitor.h
new file mode 100644
index 00000000..1a6514d2
--- /dev/null
+++ b/Libraries/AQ_BatteryMonitor/BatteryMonitor.h
@@ -0,0 +1,114 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_BATTERY_MONITOR_
+#define _AQ_BATTERY_MONITOR_
+
+#include
+
+#define BM_WARNING_RATIO 1.1
+
+byte numberOfBatteries = 0;
+boolean batteryAlarm = false;
+
+float batteryAlarmCellVoltage = 3.33; // 10.0V on 3S
+float batteryWarningCellVoltage = 3.66; // 11.0V on 3S
+
+void setBatteryCellVoltageThreshold(float alarmVoltage) {
+
+ batteryAlarmCellVoltage = alarmVoltage;
+ batteryWarningCellVoltage = alarmVoltage*BM_WARNING_RATIO;
+}
+
+// Reset Battery statistics
+void resetBattery(byte batno) {
+
+ if (batno < numberOfBatteries) {
+ batteryData[batno].voltage = 12.0;
+ batteryData[batno].minVoltage = 99.0;
+ batteryData[batno].current = 0.0;
+ batteryData[batno].maxCurrent = 0.0;
+ batteryData[batno].usedCapacity = 0.0;
+ }
+}
+
+void initializeBatteryMonitor(byte nb, float alarmVoltage) {
+
+ numberOfBatteries = nb;
+ setBatteryCellVoltageThreshold(alarmVoltage);
+ for (int i = 0; i < numberOfBatteries; i++) {
+ resetBattery(i);
+ }
+ measureBatteryVoltage(0.0); // Initial measurement
+}
+
+byte batteryGetCellCount(byte batNo) {
+ if (batteryData[batNo].cells) {
+ return batteryData[batNo].cells;
+ }
+ else if (batteryData[batNo].voltage<5.0) {
+ return 1;
+ }
+ else if (batteryData[batNo].voltage<8.6) {
+ return 2;
+ }
+ else {
+ return 3;
+ }
+}
+
+boolean batteryIsAlarm(byte batNo) {
+
+ if (batteryData[batNo].voltage < batteryGetCellCount(batNo) * batteryAlarmCellVoltage) {
+ return true;
+ }
+ return false;
+}
+
+boolean batteryIsWarning(byte batNo) {
+
+ if (batteryData[batNo].voltage < batteryGetCellCount(batNo) * batteryWarningCellVoltage) {
+ return true;
+ }
+ return false;
+}
+
+
+void measureBatteryVoltage(float deltaTime) {
+
+ batteryAlarm = false;
+ for (int i = 0; i < numberOfBatteries; i++) {
+ batteryData[i].voltage = (float)analogRead(batteryData[i].vPin) * batteryData[i].vScale + batteryData[i].vBias;
+ if (batteryData[i].voltage < batteryData[i].minVoltage) {
+ batteryData[i].minVoltage = batteryData[i].voltage;
+ }
+ if (batteryData[i].cPin != BM_NOPIN) {
+ batteryData[i].current = (float)analogRead(batteryData[i].cPin) * batteryData[i].cScale + batteryData[i].cBias;
+ if (batteryData[i].current > batteryData[i].maxCurrent) {
+ batteryData[i].maxCurrent = batteryData[i].current;
+ }
+ batteryData[i].usedCapacity += batteryData[i].current * deltaTime / 3.6; // current(A) * 1000 * time(s) / 3600 -> mAh
+ }
+ if (batteryIsAlarm(i)) {
+ batteryAlarm = true;
+ }
+ }
+}
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_BatteryMonitor/BatteryMonitorTypes.h b/Libraries/AQ_BatteryMonitor/BatteryMonitorTypes.h
new file mode 100644
index 00000000..6069a138
--- /dev/null
+++ b/Libraries/AQ_BatteryMonitor/BatteryMonitorTypes.h
@@ -0,0 +1,58 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_BATTERY_MONITOR_TYPES
+#define _AQ_BATTERY_MONITOR_TYPES
+
+#define BM_NOPIN 255
+
+struct BatteryData {
+ byte vPin,cPin; // A/D pins for voltage and current sensors (255 = BM_NOPIN <=> no sensor)
+ byte cells; // Number of Cells (used for alarm/warning voltage
+ float vScale,vBias; // voltage polynom V = vbias + AnalogIn(vpin)*vscale
+ float cScale,cBias; // current polynom C = cbias + AnalogIn(cpin)*cscale
+ float voltage; // Current battery voltage
+ float current; // Current battery current
+ float minVoltage; // Minimum voltage since reset
+ float maxCurrent; // Maximum current since reset
+ float usedCapacity; // Capacity used since reset (in mAh)
+};
+
+extern struct BatteryData batteryData[]; // BatteryMonitor config, !! MUST BE DEFINED BY MAIN SKETCH !!
+extern byte numberOfBatteries; // number of batteries monitored, defined by BatteryMonitor
+extern boolean batteryAlarm; // any battery in alarm state used for e.g. autodescent
+
+// Helper macros to make battery definitions cleaner
+
+// for defining battery with just voltage sensing
+#define BM_DEFINE_BATTERY_V(CELLS,VPIN,VSCALE,VBIAS) {VPIN,BM_NOPIN,CELLS,VSCALE,VBIAS, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0},
+
+// for defining battery with voltage and current sensors
+#define BM_DEFINE_BATTERY_VC(CELLS,VPIN,VSCALE,VBIAS,CPIN,CSCALE,CBIAS) {VPIN,CPIN,CELLS,VSCALE,VBIAS, CSCALE, CBIAS, 0.0, 0.0, 0.0, 0.0, 0.0},
+
+// Function declarations
+
+boolean batteryIsAlarm(byte batteryNo);
+boolean batteryIsWarning(byte batteryNo);
+void resetBattery(byte batteryNo);
+void initializeBatteryMonitor(byte numberOfMonitoredBatteries, float alarmVoltage);
+void setBatteryCellVoltageThreshold(float alarmVoltage);
+void measureBatteryVoltage(float deltaTime);
+#endif
diff --git a/Libraries/AQ_CameraStabilizer/CameraStabilizer.h b/Libraries/AQ_CameraStabilizer/CameraStabilizer.h
new file mode 100644
index 00000000..830f54b2
--- /dev/null
+++ b/Libraries/AQ_CameraStabilizer/CameraStabilizer.h
@@ -0,0 +1,242 @@
+/*
+ AeroQuad v3.0 - June 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_CAMERA_STABILIZER_H_
+#define _AEROQUAD_CAMERA_STABILIZER_H_
+
+
+#if defined(CameraControl)
+
+// Written by CupOfTea:
+// http://aeroquad.com/showthread.php?1484-Camera-Stablisation
+// http://aeroquad.com/showthread.php?1491-Camera-Stablisation-continued
+
+// ***********************************************************************
+// *********************** Camera Control ***************************
+// ***********************************************************************
+/*Some basics about the 16 bit timer:
+- The timer counts clock ticks derived from the CPU clock. Using 16MHz CPU clock
+ and a prescaler of 8 gives a timer clock of 2MHz, one tick every 0.5?s. This
+ is also called timer resolution.
+- The timer is used as cyclic upwards counter, the counter periode is set in the
+ ICRx register. IIRC periode-1 has to be set in the ICRx register.
+- When the counter reaches 0, the outputs are set
+- When the counter reaches OCRxy, the corresponding output is cleared.
+In the code below, the periode shall be 20ms, so the ICRx register is set to
+ 40000 ticks of 0.5?s/tick. It probably should be 39999, but who cares about
+ this 0.5?s for the periode.
+The high time shall be 1500?s, so the OCRxy register is set to 3000. A change of
+ the timer periode does not change this setting, as the clock rate is still one
+ tick every 0.5?s. If the prescaler was changed, the OCRxy register value would
+ be different.
+*/
+int mode = 0;
+float mCameraPitch = 0.0;
+float mCameraRoll = 0.0;
+float mCameraYaw = 0.0;
+int centerPitch = 0;
+int centerRoll = 0;
+int centerYaw = 0;
+int servoMinPitch = 0;
+int servoMinRoll = 0;
+int servoMinYaw = 0;
+int servoMaxPitch = 0;
+int servoMaxRoll = 0;
+int servoMaxYaw = 0;
+int servoPitch = 0; // 1000 - 2000 where we are or will move to next
+int servoRoll = 0;
+int servoYaw = 0;
+
+void initializeCameraControl();
+void cameraControlMove ();
+
+
+
+void cameraControlSetPitch (float angle) {
+
+ if (mode == 1) {
+ servoPitch = constrain((mCameraPitch * angle) + centerPitch , servoMinPitch , servoMaxPitch);
+ }
+ else {
+ servoPitch = constrain(centerPitch , servoMinPitch , servoMaxPitch);
+ }
+}
+
+void cameraControlSetRoll (float angle) {
+
+ if (mode == 1) {
+ servoRoll = constrain((mCameraRoll * angle) + centerRoll , servoMinRoll , servoMaxRoll);
+ }
+ else {
+ servoRoll = constrain(centerRoll , servoMinRoll , servoMaxRoll);
+ }
+}
+
+void cameraControlSetYaw (float angle) {
+
+ if (mode == 1) {
+ servoYaw = constrain((mCameraYaw * angle) + centerYaw , servoMinYaw , servoMaxYaw);
+ }
+ else {
+ servoYaw = constrain(centerYaw , servoMinYaw , servoMaxYaw);
+ }
+}
+
+void setmCameraPitch(float gear) {
+ mCameraPitch = gear;
+}
+
+void setmCameraRoll(float gear) {
+ mCameraRoll = gear;
+}
+
+void setmCameraYaw(float gear) {
+ mCameraYaw = gear;
+}
+
+void setCenterPitch(int servoCenter) {
+ centerPitch = servoCenter;
+}
+
+void setCenterRoll(int servoCenter) {
+ centerRoll = servoCenter;
+}
+
+void setCenterYaw(int servoCenter) {
+ centerYaw = servoCenter;
+}
+
+void setServoMinPitch (int servoMin) {
+ servoMinPitch = servoMin;
+}
+
+void setServoMinRoll (int servoMin) {
+ servoMinRoll = servoMin;
+}
+
+void setServoMinYaw (int servoMin) {
+ servoMinYaw = servoMin;
+}
+
+void setServoMaxPitch (int servoMax) {
+ servoMaxPitch = servoMax;
+}
+
+void setServoMaxRoll (int servoMax) {
+ servoMaxRoll = servoMax;
+}
+
+void setServoMaxYaw (int servoMax) {
+ servoMaxYaw = servoMax;
+}
+
+void setMode (int camMode) {
+ mode = camMode;
+}
+
+int getMode (void) {
+ return mode;
+}
+
+int getPitch (void) {
+ return servoPitch;
+}
+
+int getRoll (void) {
+ return servoRoll;
+}
+
+int getYaw (void) {
+ return servoYaw;
+}
+
+float getmCameraPitch(void) {
+ return mCameraPitch;
+}
+
+float getmCameraRoll(void) {
+ return mCameraRoll;
+}
+
+float getmCameraYaw(void) {
+ return mCameraYaw;
+}
+
+int getCenterPitch(void) {
+ return centerPitch;
+}
+
+int getCenterRoll(void) {
+ return centerRoll;
+}
+
+int getCenterYaw(void) {
+ return centerYaw;
+}
+
+int getServoMinPitch(void) {
+ return servoMinPitch;
+}
+
+int getServoMinRoll(void) {
+ return servoMinRoll;
+}
+
+int getServoMinYaw(void) {
+ return servoMinYaw;
+}
+
+int getServoMaxPitch(void) {
+ return servoMaxPitch;
+}
+
+int getServoMaxRoll(void) {
+ return servoMaxRoll;
+}
+
+int getServoMaxYaw(void) {
+ return servoMaxYaw;
+}
+
+void initializeCameraStabilization() {
+ mode = 1; // 0 = off, 1 = onboard stabilisation, 2 = serialCom/debug/adjust center
+ mCameraPitch = 318.3; // scale angle to servo.... caculated as +/- 90 (ie 180) degrees maped to 1000-2000
+ mCameraRoll = 318.3;
+ mCameraYaw = 318.3;
+ centerPitch = 1500; // (bCamera) Center of stabilisation in mode 1, point here in mode 2
+ centerRoll = 1500; // 1000 - 2000 nornaly centered 1500
+ centerYaw = 1500;
+ servoMinPitch = 1000; // don't drive the servo past here
+ servoMinRoll = 1000;
+ servoMinYaw = 1000;
+ servoMaxPitch = 2000;
+ servoMaxRoll = 2000;
+ servoMaxYaw = 2000;
+
+ initializeCameraControl(); // specific init for timer chosen
+ cameraControlSetPitch(0);
+ cameraControlSetRoll(0);
+ cameraControlSetYaw(0);
+ cameraControlMove();
+}
+
+#endif // #if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+
+#endif // #define _AEROQUAD_CAMERA_STABILIZER_H_
diff --git a/Libraries/AQ_CameraStabilizer/CameraStabilizer_Aeroquad.h b/Libraries/AQ_CameraStabilizer/CameraStabilizer_Aeroquad.h
new file mode 100644
index 00000000..4a9fcf86
--- /dev/null
+++ b/Libraries/AQ_CameraStabilizer/CameraStabilizer_Aeroquad.h
@@ -0,0 +1,52 @@
+/*
+ AeroQuad v3.0 - June 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_CAMERA_STABILIZER_AEROQUAD_H_
+#define _AEROQUAD_CAMERA_STABILIZER_AEROQUAD_H_
+
+
+#if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) // used only on mega for now
+
+#include "CameraStabilizer.h"
+
+// Written by CupOfTea:
+// http://aeroquad.com/showthread.php?1484-Camera-Stablisation
+// http://aeroquad.com/showthread.php?1491-Camera-Stablisation-continued
+
+void initializeCameraControl() {
+ // Init PWM Timer 1 Probable conflict with Arducopter Motor
+ DDRB = DDRB | B11100000; //Set to Output Mega Port-Pin PB5-11, PB6-12, PB7-13
+ //WGMn1 WGMn2 WGMn3 = Mode 14 Fast PWM, TOP = ICRn ,Update of OCRnx at BOTTOM
+ TCCR1A =((1< 0) {
+ OCR1A = servoPitch * 2;
+ OCR1B = servoRoll * 2;
+ OCR1C = servoYaw * 2;
+ }
+}
+
+#endif // #if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+
+#endif // #define _AEROQUAD_CAMERA_STABILIZER_H_
diff --git a/Libraries/AQ_CameraStabilizer/CameraStabilizer_Pins_2_3_5.h b/Libraries/AQ_CameraStabilizer/CameraStabilizer_Pins_2_3_5.h
new file mode 100644
index 00000000..ea79c805
--- /dev/null
+++ b/Libraries/AQ_CameraStabilizer/CameraStabilizer_Pins_2_3_5.h
@@ -0,0 +1,53 @@
+/*
+ AeroQuad v3.0 - June 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_CAMERA_STABILIZER_2_3_5_H_
+#define _AEROQUAD_CAMERA_STABILIZER_2_3_5_H_
+
+
+#if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) // used only on mega for now
+
+// Written by CupOfTea:
+// http://aeroquad.com/showthread.php?1484-Camera-Stablisation
+// http://aeroquad.com/showthread.php?1491-Camera-Stablisation-continued
+
+#include "CameraStabilizer.h"
+
+void initializeCameraControl() {
+ // Init PWM Timer 3 Probable conflict with AeroQuad Motor
+ DDRE = DDRE | B00111000; //Set to Output Mega Port-Pin PE4-2, PE5-3, PE3-5
+ TCCR3A =((1< 0) {
+ OCR3A = servoPitch * 2;
+ OCR3B = servoRoll * 2;
+ OCR3C = servoYaw * 2;
+ }
+}
+
+
+
+#endif // #if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+
+#endif // #define _AEROQUAD_CAMERA_STABILIZER_H_
diff --git a/Libraries/AQ_CameraStabilizer/CameraStabilizer_Pins_44_45_46.h b/Libraries/AQ_CameraStabilizer/CameraStabilizer_Pins_44_45_46.h
new file mode 100644
index 00000000..bc4651be
--- /dev/null
+++ b/Libraries/AQ_CameraStabilizer/CameraStabilizer_Pins_44_45_46.h
@@ -0,0 +1,53 @@
+/*
+ AeroQuad v3.0 - June 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_CAMERA_STABILIZER_44_45_46_H_
+#define _AEROQUAD_CAMERA_STABILIZER_44_45_46_H_
+
+
+#if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) // used only on mega for now
+
+// Written by CupOfTea:
+// http://aeroquad.com/showthread.php?1484-Camera-Stablisation
+// http://aeroquad.com/showthread.php?1491-Camera-Stablisation-continued
+
+#include "CameraStabilizer.h"
+
+void initializeCameraControl() {
+ // Init PWM Timer 5 Probable conflict with Arducopter Motor
+ DDRL = DDRL | B00111000; //Set to Output Mega Port-Pin PL3-46, PE4-45, PE5-44
+ TCCR5A =((1< 0) {
+ OCR5A = servoPitch * 2;
+ OCR5B = servoRoll * 2;
+ OCR5C = servoYaw * 2;
+ }
+}
+
+
+
+#endif // #if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+
+#endif // #define _AEROQUAD_CAMERA_STABILIZER_H_
diff --git a/Libraries/AQ_CameraStabilizer/CameraStabilizer_Pins_6_7_8.h b/Libraries/AQ_CameraStabilizer/CameraStabilizer_Pins_6_7_8.h
new file mode 100644
index 00000000..4a38b5cd
--- /dev/null
+++ b/Libraries/AQ_CameraStabilizer/CameraStabilizer_Pins_6_7_8.h
@@ -0,0 +1,52 @@
+/*
+ AeroQuad v3.0 - June 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_CAMERA_STABILIZER6_7_8_H_
+#define _AEROQUAD_CAMERA_STABILIZER6_7_8_H_
+
+
+#if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) // used only on mega for now
+
+// Written by CupOfTea:
+// http://aeroquad.com/showthread.php?1484-Camera-Stablisation
+// http://aeroquad.com/showthread.php?1491-Camera-Stablisation-continued
+
+#include "CameraStabilizer.h"
+
+void initializeCameraControl() {
+ // Init PWM Timer 4 Probable conflict with AeroQuad Motor or Arducopter PPM
+ DDRH = DDRH | B00111000; //Set to Output Mega Port-Pin PH3-8, PE4-7, PE5-6
+ TCCR4A =((1< 0) {
+ OCR4A = servoPitch * 2;
+ OCR4B = servoRoll * 2;
+ OCR4C = servoYaw * 2;
+ }
+}
+
+
+#endif // #if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+
+#endif // #define _AEROQUAD_CAMERA_STABILIZER_H_
diff --git a/Libraries/AQ_Compass/Compass.h b/Libraries/AQ_Compass/Compass.h
new file mode 100644
index 00000000..b0e582bd
--- /dev/null
+++ b/Libraries/AQ_Compass/Compass.h
@@ -0,0 +1,71 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+
+#ifndef _AEROQUAD_COMPASS_H_
+#define _AEROQUAD_COMPASS_H_
+
+#include "Arduino.h"
+
+float hdgX = 0.0;
+float hdgY = 0.0;
+
+float measuredMagX = 0.0;
+float measuredMagY = 0.0;
+float measuredMagZ = 0.0;
+
+float rawMag[3] = {0.0,0.0,0.0};
+float magBias[3] = {0.0,0.0,0.0};
+
+//float magMax[3] = {0.0,0.0,0.0};
+//float magMin[3] = {0.0,0.0,0.0};
+//float magScale[3] = {0.0,0.0,0.0};
+//float magOffset[3] = {0.0,0.0,0.0};
+//float magBias[3] = {0.0, 0.0, 0.0};
+
+void initializeMagnetometer();
+void measureMagnetometer(float roll, float pitch);
+
+const float getHdgXY(byte axis) {
+ if (axis == XAXIS) {
+ return hdgX;
+ } else {
+ return hdgY;
+ }
+}
+
+const int getMagnetometerRawData(byte axis) {
+ return rawMag[axis];
+}
+
+/*
+void setMagCal(byte axis, float maxValue, float minValue) {
+ magMax[axis] = maxValue;
+ magMin[axis] = minValue;
+ // Assume max/min is scaled to +1 and -1
+ // y2 = 1, x2 = max; y1 = -1, x1 = min
+ // m = (y2 - y1) / (x2 - x1)
+ // m = 2 / (max - min)
+ magScale[axis] = 2.0 / (magMax[axis] - magMin[axis]);
+ // b = y1 - mx1; b = -1 - (m * min)
+ magOffset[axis] = -(magScale[axis] * magMin[axis]) - 1;
+}
+*/
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_Compass/Examples/Test_HMC5843/Test_HMC5843.ino b/Libraries/AQ_Compass/Examples/Test_HMC5843/Test_HMC5843.ino
new file mode 100644
index 00000000..14ae5605
--- /dev/null
+++ b/Libraries/AQ_Compass/Examples/Test_HMC5843/Test_HMC5843.ino
@@ -0,0 +1,55 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include // Arduino IDE bug, needed because that the ITG3200 use Wire!
+#include // Arduino IDE bug, needed because that the ITG3200 use Wire!
+
+#include
+#include
+#include
+
+unsigned long timer;
+
+void setup() {
+
+ Serial.begin(115200);
+ Serial.println("Magnetometer library test (HMC5843)");
+
+ Wire.begin();
+ initializeMagnetometer();
+}
+
+void loop() {
+
+ if((millis() - timer) > 10) // 100Hz
+ {
+ timer = millis();
+ //accel.measure();
+ measureMagnetometer(0.0,0.0);
+
+ Serial.print("Roll: ");
+ Serial.print(getMagnetometerRawData(XAXIS));
+ Serial.print(" Pitch: ");
+ Serial.print(getMagnetometerRawData(YAXIS));
+ Serial.print(" Yaw: ");
+ Serial.print(getMagnetometerRawData(ZAXIS));
+ Serial.println();
+ }
+}
diff --git a/Libraries/AQ_Compass/Magnetometer_CHR6DM.h b/Libraries/AQ_Compass/Magnetometer_CHR6DM.h
new file mode 100644
index 00000000..ec54303c
--- /dev/null
+++ b/Libraries/AQ_Compass/Magnetometer_CHR6DM.h
@@ -0,0 +1,44 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+
+#ifndef _AEROQUAD_MAGNETOMETER_CHR6DM_H_
+#define _AEROQUAD_MAGNETOMETER_CHR6DM_H_
+
+#include "Compass.h"
+#include "Arduino.h"
+#include
+
+CHR6DM *compassChr6dm;
+float absoluteHeading = 0.0;
+
+void initializeMagnetometer() {
+ vehicleState |= MAG_DETECTED;
+}
+
+void measureMagnetometer(float roll, float pitch) {
+ heading = compassChr6dm->data.yaw; //this hardly needs any filtering :)
+ // Change from +/-180 to 0-360
+ if (heading < 0) absoluteHeading = 360 + heading;
+ else absoluteHeading = heading;
+}
+
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_Compass/Magnetometer_HMC5843.h b/Libraries/AQ_Compass/Magnetometer_HMC5843.h
new file mode 100644
index 00000000..d00e85d3
--- /dev/null
+++ b/Libraries/AQ_Compass/Magnetometer_HMC5843.h
@@ -0,0 +1,91 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+
+#ifndef _AEROQUAD_MAGNETOMETER_HMC5843_H_
+#define _AEROQUAD_MAGNETOMETER_HMC5843_H_
+
+#include "Compass.h"
+
+#include "Arduino.h"
+
+#define COMPASS_ADDRESS 0x1E
+//#define SENSOR_GAIN 0x00 // +/- 0.7 Ga
+#define SENSOR_GAIN 0x20 // +/- 1.0 Ga (default)
+//#define SENSOR_GAIN 0x40 // +/- 1.5 Ga
+//#define SENSOR_GAIN 0x60 // +/- 2.0 Ga
+//#define SENSOR_GAIN 0x80 // +/- 3.2 Ga
+//#define SENSOR_GAIN 0xA0 // +/- 3.8 Ga
+//#define SENSOR_GAIN 0xC0 // +/- 4.5 Ga
+//#define SENSOR_GAIN 0xE0 // +/- 6.5 Ga (not recommended)
+
+void initializeMagnetometer() {
+
+ delay(10); // Power up delay **
+
+ if (readWhoI2C(COMPASS_ADDRESS) != COMPASS_ADDRESS) {
+ vehicleState |= MAG_DETECTED;
+ }
+
+ updateRegisterI2C(COMPASS_ADDRESS, 0x01, SENSOR_GAIN); // Gain as defined above
+ delay(20);
+ updateRegisterI2C(COMPASS_ADDRESS, 0x02, 0x01); // start single conversion
+ delay(20);
+
+ measureMagnetometer(0.0, 0.0); // Assume 1st measurement at 0 degrees roll and 0 degrees pitch
+}
+
+void measureMagnetometer(float roll, float pitch) {
+ float magX;
+ float magY;
+ float tmp;
+
+ sendByteI2C(COMPASS_ADDRESS, 0x03);
+ Wire.requestFrom(COMPASS_ADDRESS, 6);
+
+ rawMag[XAXIS] = readShortI2C();
+ rawMag[YAXIS] = -readShortI2C();
+ rawMag[ZAXIS] = -readShortI2C();
+
+ updateRegisterI2C(COMPASS_ADDRESS, 0x02, 0x01); // start single conversion
+
+ measuredMagX = rawMag[XAXIS] + magBias[XAXIS];
+ measuredMagY = rawMag[YAXIS] + magBias[YAXIS];
+ measuredMagZ = rawMag[ZAXIS] + magBias[ZAXIS];
+
+ float cosRoll = cos(roll);
+ float sinRoll = sin(roll);
+ float cosPitch = cos(pitch);
+ float sinPitch = sin(pitch);
+
+ magX = (float)measuredMagX * cosPitch +
+ (float)measuredMagY * sinRoll * sinPitch +
+ (float)measuredMagZ * cosRoll * sinPitch;
+
+ magY = (float)measuredMagY * cosRoll -
+ (float)measuredMagZ * sinRoll;
+
+ tmp = sqrt(magX * magX + magY * magY);
+
+ hdgX = magX / tmp;
+ hdgY = -magY / tmp;
+}
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_Compass/Magnetometer_HMC5883L.h b/Libraries/AQ_Compass/Magnetometer_HMC5883L.h
new file mode 100644
index 00000000..c46d596b
--- /dev/null
+++ b/Libraries/AQ_Compass/Magnetometer_HMC5883L.h
@@ -0,0 +1,134 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+
+#ifndef _AEROQUAD_MAGNETOMETER_HMC5883L_H_
+#define _AEROQUAD_MAGNETOMETER_HMC5883L_H_
+
+#include "Compass.h"
+
+#include "Arduino.h"
+
+#define COMPASS_ADDRESS 0x1E
+
+// See HMC58x3 datasheet for more information on these values
+#define NormalOperation 0x10
+// Default DataOutputRate is 10hz on HMC5843 , 15hz on HMC5883L
+#define DataOutputRate_Default ( 0x04 << 2 )
+#define HMC5883L_SampleAveraging_8 ( 0x03 << 5 )
+
+
+float magCalibration[3] = {0.0,0.0,0.0};
+
+void initializeMagnetometer() {
+
+ byte numAttempts = 0;
+ bool success = false;
+ delay(10); // Power up delay **
+
+ magCalibration[XAXIS] = 1.0;
+ magCalibration[YAXIS] = 1.0;
+ magCalibration[ZAXIS] = 1.0;
+
+ if (readWhoI2C(COMPASS_ADDRESS) != COMPASS_ADDRESS) {
+ vehicleState |= MAG_DETECTED;
+ }
+
+ while (success == false && numAttempts < 5 ) {
+
+ numAttempts++;
+
+ updateRegisterI2C(COMPASS_ADDRESS, 0x00, 0x11); // Set positive bias configuration for sensor calibraiton
+ delay(50);
+ updateRegisterI2C(COMPASS_ADDRESS, 0x01, 0x20); // Set +/- 1G gain
+ delay(10);
+ updateRegisterI2C(COMPASS_ADDRESS, 0x02, 0x01); // Perform single conversion
+ delay(10);
+
+ measureMagnetometer(0.0, 0.0); // Read calibration data
+ delay(10);
+
+ if ( fabs(measuredMagX) > 500.0 && fabs(measuredMagX) < 1564.4f
+ && fabs(measuredMagY) > 500.0 && fabs(measuredMagY) < 1564.4f
+ && fabs(measuredMagZ) > 500.0 && fabs(measuredMagZ) < 1477.2f) {
+ magCalibration[XAXIS] = fabs(1264.4f / measuredMagX);
+ magCalibration[YAXIS] = fabs(1264.4f / measuredMagY);
+ magCalibration[ZAXIS] = fabs(1177.2f / measuredMagZ);
+ success = true;
+ }
+
+ updateRegisterI2C(COMPASS_ADDRESS, 0x00, HMC5883L_SampleAveraging_8 | DataOutputRate_Default | NormalOperation);
+ delay(50);
+
+ updateRegisterI2C(COMPASS_ADDRESS, 0x02, 0x00); // Continuous Update mode
+ delay(50); // Mode change delay (1/Update Rate) **
+ }
+
+ measureMagnetometer(0.0, 0.0); // Assume 1st measurement at 0 degrees roll and 0 degrees pitch
+
+}
+
+void measureMagnetometer(float roll, float pitch) {
+
+ sendByteI2C(COMPASS_ADDRESS, 0x03);
+ Wire.requestFrom(COMPASS_ADDRESS, 6);
+
+ #if defined(SPARKFUN_9DOF)
+ // JI - 11/24/11 - SparkFun DOF on v2p1 Shield Configuration
+ // JI - 11/24/11 - 5883L X axis points aft
+ // JI - 11/24/11 - 5883L Sensor Orientation 3
+ rawMag[XAXIS] = -readShortI2C();
+ rawMag[ZAXIS] = -readShortI2C();
+ rawMag[YAXIS] = readShortI2C();
+ #elif defined(SPARKFUN_5883L_BOB)
+ // JI - 11/24/11 - Sparkfun 5883L Breakout Board Upside Down on v2p0 shield
+ // JI - 11/24/11 - 5883L is upside down, X axis points forward
+ // JI - 11/24/11 - 5883L Sensor Orientation 5
+ rawMag[XAXIS] = readShortI2C();
+ rawMag[ZAXIS] = readShortI2C();
+ rawMag[YAXIS] = readShortI2C();
+ #else
+ //!! Define 5883L Orientation !!
+ #endif
+
+ measuredMagX = rawMag[XAXIS] + magBias[XAXIS];
+ measuredMagY = rawMag[YAXIS] + magBias[YAXIS];
+ measuredMagZ = rawMag[ZAXIS] + magBias[ZAXIS];
+
+
+ float cosRoll = cos(roll);
+ float sinRoll = sin(roll);
+ float cosPitch = cos(pitch);
+ float sinPitch = sin(pitch);
+
+ float magX = (float)measuredMagX * cosPitch +
+ (float)measuredMagY * sinRoll * sinPitch +
+ (float)measuredMagZ * cosRoll * sinPitch;
+
+ float magY = (float)measuredMagY * cosRoll -
+ (float)measuredMagZ * sinRoll;
+
+ float tmp = sqrt(magX * magX + magY * magY);
+
+ hdgX = magX / tmp;
+ hdgY = -magY / tmp;
+}
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_Defines/GlobalDefined.h b/Libraries/AQ_Defines/GlobalDefined.h
new file mode 100644
index 00000000..aebde339
--- /dev/null
+++ b/Libraries/AQ_Defines/GlobalDefined.h
@@ -0,0 +1,43 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_GLOBAL_DEFINES_H_
+#define _AEROQUAD_GLOBAL_DEFINES_H_
+
+
+// More AQ relative than generic... have to be think again
+// Basic axis definitions
+#define XAXIS 0
+#define YAXIS 1
+#define ZAXIS 2
+#define THROTTLE 3
+#define MODE 4
+#define AUX 5
+#define AUX2 6
+#define AUX3 7
+
+#define ON 1
+#define OFF 0
+
+#define ALTPANIC 2
+#define INVALID_ALTITUDE -1000.0
+
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_Defines/SensorsStatus.h b/Libraries/AQ_Defines/SensorsStatus.h
new file mode 100644
index 00000000..add8b8cb
--- /dev/null
+++ b/Libraries/AQ_Defines/SensorsStatus.h
@@ -0,0 +1,36 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_SENSORS_STATE_H_
+#define _AQ_SENSORS_STATE_H_
+
+unsigned long vehicleState = 0;
+
+#define GYRO_DETECTED 0x001
+#define ACCEL_DETECTED 0x002
+#define MAG_DETECTED 0x004
+#define BARO_DETECTED 0x008
+#define HEADINGHOLD_ENABLED 0x010
+#define ALTITUDEHOLD_ENABLED 0x020
+#define BATTMONITOR_ENABLED 0x040
+#define CAMERASTABLE_ENABLED 0x080
+#define RANGE_ENABLED 0x100
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_FlightControlProcessor/FlightControlHexPlus.h b/Libraries/AQ_FlightControlProcessor/FlightControlHexPlus.h
new file mode 100644
index 00000000..46d8e8e6
--- /dev/null
+++ b/Libraries/AQ_FlightControlProcessor/FlightControlHexPlus.h
@@ -0,0 +1,63 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_PROCESS_FLIGHT_CONTROL_HEX_PLUS_MODE_H_
+#define _AQ_PROCESS_FLIGHT_CONTROL_HEX_PLUS_MODE_H_
+
+#include "FlightControlVariable.h"
+
+/*
+
+ CCW
+
+ CW 0....Front....0 CW
+ ......***......
+ ......***......
+ ......***......
+ CCW 0....Back.....0 CCW
+
+ CW
+*/
+
+
+#define FRONT MOTOR1
+#define FRONT_RIGHT MOTOR2
+#define REAR_RIGHT MOTOR3
+#define REAR MOTOR4
+#define REAR_LEFT MOTOR5
+#define FRONT_LEFT MOTOR6
+#define LASTMOTOR MOTOR6+1
+
+int motorMaxCommand[6] = {0,0,0,0,0,0};
+int motorMinCommand[6] = {0,0,0,0,0,0};
+int motorConfiguratorCommand[6] = {0,0,0,0,0,0};
+
+void applyMotorCommand() {
+ const int throttleCorrection = abs(motorAxisCommandYaw*3/6);
+ motorCommand[FRONT_LEFT] = (throttle - throttleCorrection) + motorAxisCommandRoll/2 - motorAxisCommandPitch/2 - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_RIGHT] = (throttle - throttleCorrection) - motorAxisCommandRoll/2 + motorAxisCommandPitch/2 + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[FRONT_RIGHT] = (throttle - throttleCorrection) - motorAxisCommandRoll/2 - motorAxisCommandPitch/2 - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_LEFT] = (throttle - throttleCorrection) + motorAxisCommandRoll/2 + motorAxisCommandPitch/2 + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[FRONT] = (throttle - throttleCorrection) - motorAxisCommandPitch + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR] = (throttle - throttleCorrection) + motorAxisCommandPitch - (YAW_DIRECTION * motorAxisCommandYaw);
+}
+
+#endif // #define _AQ_PROCESS_FLIGHT_CONTROL_HEX_PLUS_MODE_H_
+
diff --git a/Libraries/AQ_FlightControlProcessor/FlightControlHexX.h b/Libraries/AQ_FlightControlProcessor/FlightControlHexX.h
new file mode 100644
index 00000000..81c4f7f8
--- /dev/null
+++ b/Libraries/AQ_FlightControlProcessor/FlightControlHexX.h
@@ -0,0 +1,60 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_PROCESS_FLIGHT_CONTROL_HEX_X_MODE_H_
+#define _AQ_PROCESS_FLIGHT_CONTROL_HEX_X_MODE_H_
+
+/*
+ CW CCW
+
+ 0....Front....0
+ ......***......
+ CCW ......***...... CW
+ ......***......
+ 0....Back.....0
+
+ CW CCW
+*/
+
+#include "FlightControlVariable.h"
+
+#define FRONT_LEFT MOTOR1
+#define FRONT_RIGHT MOTOR2
+#define RIGHT MOTOR3
+#define REAR_RIGHT MOTOR4
+#define REAR_LEFT MOTOR5
+#define LEFT MOTOR6
+#define LASTMOTOR MOTOR6+1
+
+int motorMaxCommand[6] = {0,0,0,0,0,0};
+int motorMinCommand[6] = {0,0,0,0,0,0};
+int motorConfiguratorCommand[6] = {0,0,0,0,0,0};
+
+void applyMotorCommand() {
+ const int throttleCorrection = abs(motorAxisCommandYaw*3/6);
+ motorCommand[FRONT_LEFT] = (throttle - throttleCorrection) + motorAxisCommandRoll/2 - motorAxisCommandPitch/2 - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_RIGHT] = (throttle - throttleCorrection) - motorAxisCommandRoll/2 + motorAxisCommandPitch/2 + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[FRONT_RIGHT] = (throttle - throttleCorrection) - motorAxisCommandRoll/2 - motorAxisCommandPitch/2 + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_LEFT] = (throttle - throttleCorrection) + motorAxisCommandRoll/2 + motorAxisCommandPitch/2 - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[RIGHT] = (throttle - throttleCorrection) - motorAxisCommandRoll - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[LEFT] = (throttle - throttleCorrection) + motorAxisCommandRoll + (YAW_DIRECTION * motorAxisCommandYaw);
+}
+
+#endif // #define _AQ_PROCESS_FLIGHT_CONTROL_HEX_X_MODE_H_
diff --git a/Libraries/AQ_FlightControlProcessor/FlightControlHexY6.h b/Libraries/AQ_FlightControlProcessor/FlightControlHexY6.h
new file mode 100644
index 00000000..bc4678fd
--- /dev/null
+++ b/Libraries/AQ_FlightControlProcessor/FlightControlHexY6.h
@@ -0,0 +1,65 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_PROCESS_FLIGHT_CONTROL_HEX_Y6_MODE_H_
+#define _AQ_PROCESS_FLIGHT_CONTROL_HEX_Y6_MODE_H_
+
+/*
+ UPPER/LOWER
+
+
+ CW/CCW CCW/CW
+
+ 0....Front....0
+ ......***......
+ ......***......
+ ......***......
+ 0....Back.....0
+
+ CW/CCW
+*/
+
+#include "FlightControlVariable.h"
+
+#define LEFT MOTOR1
+#define RIGHT MOTOR2
+#define REAR MOTOR3
+#define LEFT_UNDER MOTOR4
+#define RIGHT_UNDER MOTOR5
+#define REAR_UNDER MOTOR6
+#define LASTMOTOR MOTOR6+1
+
+int motorMaxCommand[6] = {0,0,0,0,0,0};
+int motorMinCommand[6] = {0,0,0,0,0,0};
+int motorConfiguratorCommand[6] = {0,0,0,0,0,0};
+
+
+void applyMotorCommand() {
+ // Front = Front/Right, Back = Left/Rear, Left = Front/Left, Right = Right/Rear
+ const int throttleCorrection = abs(motorAxisCommandYaw*3/6);
+ motorCommand[REAR] = (throttle - throttleCorrection) + (motorAxisCommandPitch*4/3) - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[RIGHT] = (throttle - throttleCorrection) - motorAxisCommandRoll - (motorAxisCommandPitch*2/3) + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[LEFT] = (throttle - throttleCorrection) + motorAxisCommandRoll - (motorAxisCommandPitch*2/3) - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_UNDER] = (throttle - throttleCorrection) + (motorAxisCommandPitch*4/3) + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[RIGHT_UNDER] = (throttle - throttleCorrection) - motorAxisCommandRoll - (motorAxisCommandPitch*2/3) - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[LEFT_UNDER] = (throttle - throttleCorrection) + motorAxisCommandRoll - (motorAxisCommandPitch*2/3) + (YAW_DIRECTION * motorAxisCommandYaw);
+}
+
+#endif // #define _AQ_PROCESS_FLIGHT_CONTROL_HEX_Y6_MODE_H_
diff --git a/Libraries/AQ_FlightControlProcessor/FlightControlOctoPlus.h b/Libraries/AQ_FlightControlProcessor/FlightControlOctoPlus.h
new file mode 100644
index 00000000..3b778953
--- /dev/null
+++ b/Libraries/AQ_FlightControlProcessor/FlightControlOctoPlus.h
@@ -0,0 +1,70 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_PROCESS_FLIGHT_CONTROL_OCTO_PLUS_MODE_H_
+#define _AQ_PROCESS_FLIGHT_CONTROL_OCTO_PLUS_MODE_H_
+
+
+/*
+ UPPER/LOWER
+
+
+ CW
+ CCW CCW
+ 0....Front....0
+ ......***......
+ CW ......***...... CW
+ ......***......
+ 0....Back.....0
+ CCW CCW
+ CW
+*/
+
+#include "FlightControlVariable.h"
+
+#define FRONT MOTOR1
+#define FRONT_RIGHT MOTOR2
+#define RIGHT MOTOR3
+#define REAR_RIGHT MOTOR5
+#define REAR MOTOR4
+#define REAR_LEFT MOTOR6
+#define LEFT MOTOR7
+#define FRONT_LEFT MOTOR8
+#define LASTMOTOR MOTOR8+1
+
+int motorMaxCommand[8] = {0,0,0,0,0,0,0,0};
+int motorMinCommand[8] = {0,0,0,0,0,0,0,0};
+int motorConfiguratorCommand[8] = {0,0,0,0,0,0,0,0};
+
+void applyMotorCommand() {
+ // Front = Front/Right, Back = Left/Rear, Left = Front/Left, Right = Right/Rear
+ const int throttleCorrection = abs(motorAxisCommandYaw*4/8);
+ motorCommand[FRONT] = (throttle-throttleCorrection) - motorAxisCommandPitch - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[FRONT_RIGHT] = (throttle-throttleCorrection) - motorAxisCommandPitch*7/10 - motorAxisCommandRoll*7/10 + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[RIGHT] = (throttle-throttleCorrection) - motorAxisCommandRoll - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_RIGHT] = (throttle-throttleCorrection) + motorAxisCommandPitch*7/10 - motorAxisCommandRoll*7/10 + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR] = (throttle-throttleCorrection) + motorAxisCommandPitch - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_LEFT] = (throttle-throttleCorrection) + motorAxisCommandPitch*7/10 + motorAxisCommandRoll*7/10 + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[LEFT] = (throttle-throttleCorrection) + motorAxisCommandRoll - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[FRONT_LEFT] = (throttle-throttleCorrection) - motorAxisCommandPitch*7/10 + motorAxisCommandRoll*7/10 + (YAW_DIRECTION * motorAxisCommandYaw);
+}
+
+#endif // #define _AQ_PROCESS_FLIGHT_CONTROL_OCTO_PLUS_MODE_H_
+
diff --git a/Libraries/AQ_FlightControlProcessor/FlightControlOctoX.h b/Libraries/AQ_FlightControlProcessor/FlightControlOctoX.h
new file mode 100644
index 00000000..0ea537c1
--- /dev/null
+++ b/Libraries/AQ_FlightControlProcessor/FlightControlOctoX.h
@@ -0,0 +1,67 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_PROCESS_FLIGHT_CONTROL_OCTO_X_MODE_H_
+#define _AQ_PROCESS_FLIGHT_CONTROL_OCTO_X_MODE_H_
+
+
+/*
+
+ CW CCW
+
+ CCW 0....Front....0 CW
+ ......***......
+ ......***......
+ ......***......
+ CW 0....Back.....0 CCW
+
+ CCW CW
+*/
+
+#include "FlightControlVariable.h"
+
+#define FRONT_LEFT MOTOR1
+#define FRONT_RIGHT MOTOR2
+#define MID_FRONT_RIGHT MOTOR3
+#define MID_REAR_RIGHT MOTOR4
+#define REAR_RIGHT MOTOR5
+#define REAR_LEFT MOTOR6
+#define MID_REAR_LEFT MOTOR7
+#define MID_FRONT_LEFT MOTOR8
+#define LASTMOTOR MOTOR8+1
+
+int motorMaxCommand[8] = {0,0,0,0,0,0,0,0};
+int motorMinCommand[8] = {0,0,0,0,0,0,0,0};
+int motorConfiguratorCommand[8] = {0,0,0,0,0,0,0,0};
+
+void applyMotorCommand() {
+ // Front = Front/Right, Back = Left/Rear, Left = Front/Left, Right = Right/Rear
+ const int throttleCorrection = abs(motorAxisCommandYaw*4/8);
+ motorCommand[FRONT_LEFT] = (throttle-throttleCorrection) - motorAxisCommandPitch + motorAxisCommandRoll*0.5 - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[FRONT_RIGHT] = (throttle-throttleCorrection) - motorAxisCommandPitch - motorAxisCommandRoll*0.5 + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[MID_FRONT_RIGHT] = (throttle-throttleCorrection) - motorAxisCommandPitch*0.5 - motorAxisCommandRoll - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[MID_REAR_RIGHT] = (throttle-throttleCorrection) + motorAxisCommandPitch*0.5 - motorAxisCommandRoll + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_RIGHT] = (throttle-throttleCorrection) + motorAxisCommandPitch - motorAxisCommandRoll*0.5 - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_LEFT] = (throttle-throttleCorrection) + motorAxisCommandPitch + motorAxisCommandRoll*0.5 + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[MID_REAR_LEFT] = (throttle-throttleCorrection) + motorAxisCommandPitch*0.5 + motorAxisCommandRoll - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[MID_FRONT_LEFT] = (throttle-throttleCorrection) - motorAxisCommandPitch*0.5 + motorAxisCommandRoll + (YAW_DIRECTION * motorAxisCommandYaw);
+}
+
+#endif // #define _AQ_PROCESS_FLIGHT_CONTROL_OCTO_X_MODE_H_
diff --git a/Libraries/AQ_FlightControlProcessor/FlightControlOctoX8.h b/Libraries/AQ_FlightControlProcessor/FlightControlOctoX8.h
new file mode 100644
index 00000000..6e3421bf
--- /dev/null
+++ b/Libraries/AQ_FlightControlProcessor/FlightControlOctoX8.h
@@ -0,0 +1,70 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_PROCESS_FLIGHT_CONTROL_OCTO_X8_MODE_H_
+#define _AQ_PROCESS_FLIGHT_CONTROL_OCTO_X8_MODE_H_
+
+
+/*
+ UPPER/LOWER
+
+
+ CW/CCW CCW/CW
+
+ 0....Front....0
+ ......***......
+ ......***......
+ ......***......
+ 0....Back.....0
+
+ CCW/CW CW/CCW
+*/
+
+#include "FlightControlVariable.h"
+
+#define FRONT_LEFT MOTOR1
+#define FRONT_RIGHT MOTOR2
+#define REAR_RIGHT MOTOR3
+#define REAR_LEFT MOTOR4
+#define FRONT_LEFT_2 MOTOR5
+#define FRONT_RIGHT_2 MOTOR6
+#define REAR_RIGHT_2 MOTOR7
+#define REAR_LEFT_2 MOTOR8
+#define LASTMOTOR MOTOR8+1
+
+int motorMaxCommand[8] = {0,0,0,0,0,0,0,0};
+int motorMinCommand[8] = {0,0,0,0,0,0,0,0};
+int motorConfiguratorCommand[8] = {0,0,0,0,0,0,0,0};
+
+void applyMotorCommand() {
+ // Front = Front/Right, Back = Left/Rear, Left = Front/Left, Right = Right/Rear
+ const int throttleCorrection = abs(motorAxisCommandYaw*4/8);
+ motorCommand[FRONT_LEFT] = (throttle-throttleCorrection) - motorAxisCommandPitch + motorAxisCommandRoll - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[FRONT_RIGHT] = (throttle-throttleCorrection) - motorAxisCommandPitch - motorAxisCommandRoll + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_LEFT] = (throttle-throttleCorrection) + motorAxisCommandPitch + motorAxisCommandRoll + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_RIGHT] = (throttle-throttleCorrection) + motorAxisCommandPitch - motorAxisCommandRoll - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[FRONT_LEFT_2] = (throttle-throttleCorrection) - motorAxisCommandPitch + motorAxisCommandRoll + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[FRONT_RIGHT_2] = (throttle-throttleCorrection) - motorAxisCommandPitch - motorAxisCommandRoll - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_LEFT_2] = (throttle-throttleCorrection) + motorAxisCommandPitch + motorAxisCommandRoll - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_RIGHT_2] = (throttle-throttleCorrection) + motorAxisCommandPitch - motorAxisCommandRoll + (YAW_DIRECTION * motorAxisCommandYaw);
+}
+
+#endif // #define _AQ_PROCESS_FLIGHT_CONTROL_OCTO_X8_MODE_H_
+
diff --git a/Libraries/AQ_FlightControlProcessor/FlightControlQuadPlus.h b/Libraries/AQ_FlightControlProcessor/FlightControlQuadPlus.h
new file mode 100644
index 00000000..1752b490
--- /dev/null
+++ b/Libraries/AQ_FlightControlProcessor/FlightControlQuadPlus.h
@@ -0,0 +1,63 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_PROCESS_FLIGHT_CONTROL_PLUS_MODE_H_
+#define _AQ_PROCESS_FLIGHT_CONTROL_PLUS_MODE_H_
+
+/*
+ CW
+
+ 0....Front....0
+ ......***......
+ CCW ......***...... CCW
+ ......***......
+ 0....Back.....0
+
+ CW
+*/
+
+#include "FlightControlVariable.h"
+
+#ifdef OLD_MOTOR_NUMBERING
+ #define FRONT MOTOR1
+ #define REAR MOTOR2
+ #define RIGHT MOTOR3
+ #define LEFT MOTOR4
+#else
+ #define FRONT MOTOR1
+ #define RIGHT MOTOR2
+ #define REAR MOTOR3
+ #define LEFT MOTOR4
+#endif
+#define LASTMOTOR MOTOR4+1
+
+int motorMaxCommand[4] = {0,0,0,0};
+int motorMinCommand[4] = {0,0,0,0};
+int motorConfiguratorCommand[4] = {0,0,0,0};
+
+void applyMotorCommand() {
+ const int throttleCorrection = abs(motorAxisCommandYaw*2/4);
+ motorCommand[FRONT] = (throttle - throttleCorrection) - motorAxisCommandPitch - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR] = (throttle - throttleCorrection) + motorAxisCommandPitch - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[RIGHT] = (throttle - throttleCorrection) - motorAxisCommandRoll + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[LEFT] = (throttle - throttleCorrection) + motorAxisCommandRoll + (YAW_DIRECTION * motorAxisCommandYaw);
+}
+
+#endif // #define _AQ_PROCESS_FLIGHT_CONTROL_PLUS_MODE_H_
diff --git a/Libraries/AQ_FlightControlProcessor/FlightControlQuadX.h b/Libraries/AQ_FlightControlProcessor/FlightControlQuadX.h
new file mode 100644
index 00000000..27f98e2b
--- /dev/null
+++ b/Libraries/AQ_FlightControlProcessor/FlightControlQuadX.h
@@ -0,0 +1,61 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_PROCESS_FLIGHT_CONTROL_X_MODE_H_
+#define _AQ_PROCESS_FLIGHT_CONTROL_X_MODE_H_
+
+/*
+ CW 0....Front....0 CCW
+ ......***......
+ ......***......
+ ......***......
+ CCW 0....Back.....0 CW
+*/
+
+#include "FlightControlVariable.h"
+
+#ifdef OLD_MOTOR_NUMBERING
+ #define FRONT_LEFT MOTOR1
+ #define REAR_RIGHT MOTOR2
+ #define FRONT_RIGHT MOTOR3
+ #define REAR_LEFT MOTOR4
+#else
+ #define FRONT_LEFT MOTOR1
+ #define FRONT_RIGHT MOTOR2
+ #define REAR_RIGHT MOTOR3
+ #define REAR_LEFT MOTOR4
+#endif
+#define LASTMOTOR MOTOR4+1
+
+int motorMaxCommand[4] = {0,0,0,0};
+int motorMinCommand[4] = {0,0,0,0};
+int motorConfiguratorCommand[4] = {0,0,0,0};
+
+void applyMotorCommand() {
+ // Front = Front/Right, Back = Left/Rear, Left = Front/Left, Right = Right/Rear
+ const int throttleCorrection = abs(motorAxisCommandYaw*2/4);
+ motorCommand[FRONT_LEFT] = (throttle-throttleCorrection) - motorAxisCommandPitch + motorAxisCommandRoll - (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[FRONT_RIGHT] = (throttle-throttleCorrection) - motorAxisCommandPitch - motorAxisCommandRoll + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_LEFT] = (throttle-throttleCorrection) + motorAxisCommandPitch + motorAxisCommandRoll + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR_RIGHT] = (throttle-throttleCorrection) + motorAxisCommandPitch - motorAxisCommandRoll - (YAW_DIRECTION * motorAxisCommandYaw);
+}
+
+#endif // #define _AQ_PROCESS_FLIGHT_CONTROL_X_MODE_H_
+
diff --git a/Libraries/AQ_FlightControlProcessor/FlightControlQuadY4.h b/Libraries/AQ_FlightControlProcessor/FlightControlQuadY4.h
new file mode 100644
index 00000000..ec7edf29
--- /dev/null
+++ b/Libraries/AQ_FlightControlProcessor/FlightControlQuadY4.h
@@ -0,0 +1,61 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_PROCESS_FLIGHT_CONTROL_Y4_MODE_H_
+#define _AQ_PROCESS_FLIGHT_CONTROL_Y4_MODE_H_
+
+/*
+ UPPER/LOWER
+
+
+ CW CCW
+
+ 0....Front....0
+ ......***......
+ ......***......
+ ......***......
+ 0....Back.....0
+
+ CW/CCW
+*/
+
+
+#include "FlightControlVariable.h"
+
+#define LEFT MOTOR1
+#define RIGHT MOTOR2
+#define REAR MOTOR3
+#define REAR_UNDER MOTOR4
+#define LASTMOTOR MOTOR4+1
+
+int motorMaxCommand[4] = {0,0,0,0};
+int motorMinCommand[4] = {0,0,0,0};
+int motorConfiguratorCommand[4] = {0,0,0,0};
+
+void applyMotorCommand() {
+ // Front = Front/Right, Back = Left/Rear, Left = Front/Left, Right = Right/Rear
+ const int throttleCorrection = abs(motorAxisCommandYaw*2/4);
+ motorCommand[LEFT] = (throttle) - motorAxisCommandPitch + motorAxisCommandRoll;
+ motorCommand[RIGHT] = (throttle) - motorAxisCommandPitch - motorAxisCommandRoll;
+ motorCommand[REAR_UNDER] = (throttle-throttleCorrection) + motorAxisCommandPitch + (YAW_DIRECTION * motorAxisCommandYaw);
+ motorCommand[REAR] = (throttle-throttleCorrection) + motorAxisCommandPitch - (YAW_DIRECTION * motorAxisCommandYaw);
+}
+
+#endif // #define _AQ_PROCESS_FLIGHT_CONTROL_Y4_MODE_H_
diff --git a/Libraries/AQ_FlightControlProcessor/FlightControlTri.h b/Libraries/AQ_FlightControlProcessor/FlightControlTri.h
new file mode 100644
index 00000000..950aa9f3
--- /dev/null
+++ b/Libraries/AQ_FlightControlProcessor/FlightControlTri.h
@@ -0,0 +1,63 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_PROCESS_FLIGHT_CONTROL_TRI_MODE_H_
+#define _AQ_PROCESS_FLIGHT_CONTROL_TRI_MODE_H_
+
+
+/*
+ CW CCW
+
+ 0....Front....0
+ ......***......
+ ......***......
+ ......***......
+ 0....Back.....0
+
+ CW
+*/
+
+#include "FlightControlVariable.h"
+
+#define SERVO MOTOR1
+#define FRONT_LEFT MOTOR2
+#define FRONT_RIGHT MOTOR3
+#define REAR MOTOR4
+#define LASTMOTOR MOTOR4+1
+
+#define TRI_YAW_CONSTRAINT_MIN 1100
+#define TRI_YAW_CONSTRAINT_MAX 1900
+#define TRI_YAW_MIDDLE 1500
+
+#define MAX_RECEIVER_OFFSET 50
+
+int motorMaxCommand[4] = {0,0,0,0};
+int motorMinCommand[4] = {0,0,0,0};
+int motorConfiguratorCommand[4] = {0,0,0,0};
+
+void applyMotorCommand() {
+ motorCommand[FRONT_LEFT] = throttle + motorAxisCommandRoll - motorAxisCommandPitch*2/3;
+ motorCommand[FRONT_RIGHT] = throttle - motorAxisCommandRoll - motorAxisCommandPitch*2/3;
+ motorCommand[REAR] = throttle + motorAxisCommandPitch*4/3;
+ const float yawMotorCommand = constrain(motorAxisCommandYaw,-MAX_RECEIVER_OFFSET-abs(receiverCommand[ZAXIS]),+MAX_RECEIVER_OFFSET+abs(receiverCommand[ZAXIS]));
+ motorCommand[SERVO] = constrain(TRI_YAW_MIDDLE + YAW_DIRECTION * yawMotorCommand, TRI_YAW_CONSTRAINT_MIN, TRI_YAW_CONSTRAINT_MAX);
+}
+
+#endif // #define _AQ_PROCESS_FLIGHT_CONTROL_X_MODE_H_
diff --git a/Libraries/AQ_FlightControlProcessor/FlightControlVariable.h b/Libraries/AQ_FlightControlProcessor/FlightControlVariable.h
new file mode 100644
index 00000000..2b8105b8
--- /dev/null
+++ b/Libraries/AQ_FlightControlProcessor/FlightControlVariable.h
@@ -0,0 +1,30 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_PROCESS_FLIGHT_CONTROL_VARIABLE_H_
+#define _AQ_PROCESS_FLIGHT_CONTROL_VARIABLE_H_
+
+byte YAW_DIRECTION = 1;
+int motorAxisCommandRoll = 0;
+int motorAxisCommandPitch = 0;
+int motorAxisCommandYaw = 0;
+
+#endif // #define _AQ_PROCESS_FLIGHT_CONTROL_VARIABLE_H_
+
diff --git a/Libraries/AQ_Gps/Examples/static_test/static_test.pde b/Libraries/AQ_Gps/Examples/static_test/static_test.pde
new file mode 100644
index 00000000..7242c94e
--- /dev/null
+++ b/Libraries/AQ_Gps/Examples/static_test/static_test.pde
@@ -0,0 +1,124 @@
+#include
+#include
+
+/* This sample code demonstrates the basic use of a TinyGPS object.
+ Typically, you would feed it characters from a serial GPS device, but
+ this example uses static strings for simplicity.
+*/
+prog_char str1[] PROGMEM = "$GPRMC,201547.000,A,3014.5527,N,09749.5808,W,0.24,163.05,040109,,*1A";
+prog_char str2[] PROGMEM = "$GPGGA,201548.000,3014.5529,N,09749.5808,W,1,07,1.5,225.6,M,-22.5,M,18.8,0000*78";
+prog_char str3[] PROGMEM = "$GPRMC,201548.000,A,3014.5529,N,09749.5808,W,0.17,53.25,040109,,*2B";
+prog_char str4[] PROGMEM = "$GPGGA,201549.000,3014.5533,N,09749.5812,W,1,07,1.5,223.5,M,-22.5,M,18.8,0000*7C";
+prog_char *teststrs[4] = {str1, str2, str3, str4};
+
+void sendstring(TinyGPS &gps, const PROGMEM char *str);
+void gpsdump(TinyGPS &gps);
+
+void setup()
+{
+ Serial.begin(115200);
+
+ Serial.print("Testing TinyGPS library v. "); Serial.println(TinyGPS::library_version());
+ Serial.println("by Mikal Hart");
+ Serial.println();
+ Serial.print("Sizeof(gpsobject) = "); Serial.println(sizeof(TinyGPS));
+ Serial.println();
+
+ for (int i=0; i<4; ++i)
+ {
+ TinyGPS test_gps;
+ Serial.print("Test string #"); Serial.println(i+1);
+ Serial.println("--------------");
+ sendstring(test_gps, teststrs[i]);
+ gpsdump(test_gps);
+ Serial.println();
+ }
+}
+
+void loop()
+{
+}
+
+void printFloat(double number, int digits=5)
+{
+ // Handle negative numbers
+ if (number < 0.0)
+ {
+ Serial.print('-');
+ number = -number;
+ }
+
+ // Round correctly so that print(1.999, 2) prints as "2.00"
+ double rounding = 0.5;
+ for (uint8_t i=0; i 0)
+ Serial.print(".");
+
+ // Extract digits from the remainder one at a time
+ while (digits-- > 0)
+ {
+ remainder *= 10.0;
+ int toPrint = int(remainder);
+ Serial.print(toPrint);
+ remainder -= toPrint;
+ }
+}
+
+void sendstring(TinyGPS &gps, const PROGMEM char *str)
+{
+ while (true)
+ {
+ char c = pgm_read_byte_near(str++);
+ if (!c) break;
+ Serial.print(c);
+ gps.encode(c);
+ }
+ Serial.println();
+ gps.encode('\r');
+ gps.encode('\n');
+}
+
+void gpsdump(TinyGPS &gps)
+{
+ long lat, lon;
+ float flat, flon;
+ unsigned long age, date, time, chars;
+ int year;
+ byte month, day, hour, minute, second, hundredths;
+ unsigned short sentences, failed;
+
+ gps.get_position(&lat, &lon, &age);
+ Serial.print("Lat/Long(10^-5 deg): "); Serial.print(lat); Serial.print(", "); Serial.print(lon);
+ Serial.print(" Fix age: "); Serial.print(age); Serial.println("ms.");
+
+ gps.f_get_position(&flat, &flon, &age);
+ Serial.print("Lat/Long(float): "); printFloat(flat); Serial.print(", "); printFloat(flon);
+ Serial.print(" Fix age: "); Serial.print(age); Serial.println("ms.");
+
+ gps.get_datetime(&date, &time, &age);
+ Serial.print("Date(ddmmyy): "); Serial.print(date); Serial.print(" Time(hhmmsscc): "); Serial.print(time);
+ Serial.print(" Fix age: "); Serial.print(age); Serial.println("ms.");
+
+ gps.crack_datetime(&year, &month, &day, &hour, &minute, &second, &hundredths, &age);
+ Serial.print("Date: "); Serial.print(static_cast(month)); Serial.print("/"); Serial.print(static_cast(day)); Serial.print("/"); Serial.print(year);
+ Serial.print(" Time: "); Serial.print(static_cast(hour)); Serial.print(":"); Serial.print(static_cast(minute)); Serial.print(":"); Serial.print(static_cast(second)); Serial.print("."); Serial.print(static_cast(hundredths));
+ Serial.print(" Fix age: "); Serial.print(age); Serial.println("ms.");
+
+ Serial.print("Alt(cm): "); Serial.print(gps.altitude()); Serial.print(" Course(10^-2 deg): "); Serial.print(gps.course()); Serial.print(" Speed(10^-2 knots): "); Serial.println(gps.speed());
+ Serial.print("Alt(float): "); printFloat(gps.f_altitude(), 2); Serial.print(" Course(float): "); printFloat(gps.f_course(), 2); Serial.println();
+ Serial.print("Speed (knots): "); printFloat(gps.f_speed_knots(), 2); Serial.print(" (mph): "); printFloat(gps.f_speed_mph(), 2);
+ Serial.print(" (mps): "); printFloat(gps.f_speed_mps(), 2); Serial.print(" (kmph): "); printFloat(gps.f_speed_kmph(), 2); Serial.println();
+ gps.stats(&chars, &sentences, &failed);
+ Serial.print("Stats: characters: "); Serial.print(chars); Serial.print(" sentences: "); Serial.print(sentences); Serial.print(" failed checksum: "); Serial.println(failed);
+}
+
diff --git a/Libraries/AQ_Gps/Examples/test_with_gps_device/test_with_gps_device.pde b/Libraries/AQ_Gps/Examples/test_with_gps_device/test_with_gps_device.pde
new file mode 100644
index 00000000..b77280df
--- /dev/null
+++ b/Libraries/AQ_Gps/Examples/test_with_gps_device/test_with_gps_device.pde
@@ -0,0 +1,141 @@
+#include
+#include
+
+/* This sample code demonstrates the normal use of a TinyGPS object.
+ It requires the use of NewSoftSerial, and assumes that you have a
+ 4800-baud serial GPS device hooked up on pins 2(rx) and 3(tx).
+*/
+
+TinyGPS gps;
+NewSoftSerial nss(19, 18);
+
+void gpsdump(TinyGPS &gps);
+bool feedgps();
+void printFloat(double f, int digits = 2);
+
+void setup()
+{
+ Serial.begin(115200);
+ nss.begin(38400);
+
+ Serial.print("Testing TinyGPS library v. "); Serial.println(TinyGPS::library_version());
+ Serial.println("by Mikal Hart");
+ Serial.println();
+ Serial.print("Sizeof(gpsobject) = "); Serial.println(sizeof(TinyGPS));
+ Serial.println();
+}
+
+void loop()
+{
+ bool newdata = false;
+ unsigned long start = millis();
+
+ // Every 5 seconds we print an update
+ while (millis() - start < 5000)
+ {
+ if (feedgps())
+ newdata = true;
+ }
+
+ if (newdata)
+ {
+ Serial.println("Acquired Data");
+ Serial.println("-------------");
+ gpsdump(gps);
+ Serial.println("-------------");
+ Serial.println();
+ }
+ else {
+ Serial.println("No new data ");
+ }
+}
+
+void printFloat(double number, int digits)
+{
+ // Handle negative numbers
+ if (number < 0.0)
+ {
+ Serial.print('-');
+ number = -number;
+ }
+
+ // Round correctly so that print(1.999, 2) prints as "2.00"
+ double rounding = 0.5;
+ for (uint8_t i=0; i 0)
+ Serial.print(".");
+
+ // Extract digits from the remainder one at a time
+ while (digits-- > 0)
+ {
+ remainder *= 10.0;
+ int toPrint = int(remainder);
+ Serial.print(toPrint);
+ remainder -= toPrint;
+ }
+}
+
+void gpsdump(TinyGPS &gps)
+{
+ long lat, lon;
+ float flat, flon;
+ unsigned long age, date, time, chars;
+ int year;
+ byte month, day, hour, minute, second, hundredths;
+ unsigned short sentences, failed;
+
+ gps.get_position(&lat, &lon, &age);
+ Serial.print("Lat/Long(10^-5 deg): "); Serial.print(lat); Serial.print(", "); Serial.print(lon);
+ Serial.print(" Fix age: "); Serial.print(age); Serial.println("ms.");
+
+ feedgps(); // If we don't feed the gps during this long routine, we may drop characters and get checksum errors
+
+ gps.f_get_position(&flat, &flon, &age);
+ Serial.print("Lat/Long(float): "); printFloat(flat, 5); Serial.print(", "); printFloat(flon, 5);
+ Serial.print(" Fix age: "); Serial.print(age); Serial.println("ms.");
+
+ feedgps();
+
+ gps.get_datetime(&date, &time, &age);
+ Serial.print("Date(ddmmyy): "); Serial.print(date); Serial.print(" Time(hhmmsscc): "); Serial.print(time);
+ Serial.print(" Fix age: "); Serial.print(age); Serial.println("ms.");
+
+ feedgps();
+
+ gps.crack_datetime(&year, &month, &day, &hour, &minute, &second, &hundredths, &age);
+ Serial.print("Date: "); Serial.print(static_cast(month)); Serial.print("/"); Serial.print(static_cast(day)); Serial.print("/"); Serial.print(year);
+ Serial.print(" Time: "); Serial.print(static_cast(hour)); Serial.print(":"); Serial.print(static_cast(minute)); Serial.print(":"); Serial.print(static_cast(second)); Serial.print("."); Serial.print(static_cast(hundredths));
+ Serial.print(" Fix age: "); Serial.print(age); Serial.println("ms.");
+
+ feedgps();
+
+ Serial.print("Alt(cm): "); Serial.print(gps.altitude()); Serial.print(" Course(10^-2 deg): "); Serial.print(gps.course()); Serial.print(" Speed(10^-2 knots): "); Serial.println(gps.speed());
+ Serial.print("Alt(float): "); printFloat(gps.f_altitude()); Serial.print(" Course(float): "); printFloat(gps.f_course()); Serial.println();
+ Serial.print("Speed(knots): "); printFloat(gps.f_speed_knots()); Serial.print(" (mph): "); printFloat(gps.f_speed_mph());
+ Serial.print(" (mps): "); printFloat(gps.f_speed_mps()); Serial.print(" (kmph): "); printFloat(gps.f_speed_kmph()); Serial.println();
+
+ feedgps();
+
+ gps.stats(&chars, &sentences, &failed);
+ Serial.print("Stats: characters: "); Serial.print(chars); Serial.print(" sentences: "); Serial.print(sentences); Serial.print(" failed checksum: "); Serial.println(failed);
+}
+
+bool feedgps()
+{
+ while (nss.available())
+ {
+ if (gps.encode(nss.read()))
+ return true;
+ }
+ return false;
+}
diff --git a/Libraries/AQ_Gps/README.markdown b/Libraries/AQ_Gps/README.markdown
new file mode 100644
index 00000000..3690872a
--- /dev/null
+++ b/Libraries/AQ_Gps/README.markdown
@@ -0,0 +1,6 @@
+TinyGPS-AQ AeroQuad GPS libary - Arduino
+========================================
+
+Version 1.0 Release Notes (5/16/2011)
+----------------------------------------
+ * initial checkin and creation of repo
diff --git a/Libraries/AQ_Gps/TinyGPS.cpp b/Libraries/AQ_Gps/TinyGPS.cpp
new file mode 100644
index 00000000..06a17207
--- /dev/null
+++ b/Libraries/AQ_Gps/TinyGPS.cpp
@@ -0,0 +1,303 @@
+/*
+ TinyGPS - a small GPS library for Arduino providing basic NMEA parsing
+ Based on work by and "distance_to" courtesy of Maarten Lamers.
+ Copyright (C) 2008-2011 Mikal Hart
+ All rights reserved.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+
+#include "Arduino.h"
+#include "TinyGPS.h"
+
+#define _GPRMC_TERM "GPRMC"
+#define _GPGGA_TERM "GPGGA"
+
+TinyGPS::TinyGPS()
+: _time(GPS_INVALID_TIME)
+, _date(GPS_INVALID_DATE)
+, _latitude(GPS_INVALID_ANGLE)
+, _longitude(GPS_INVALID_ANGLE)
+, _altitude(GPS_INVALID_ALTITUDE)
+, _speed(GPS_INVALID_SPEED)
+, _course(GPS_INVALID_ANGLE)
+, _last_time_fix(GPS_INVALID_FIX_TIME)
+, _last_position_fix(GPS_INVALID_FIX_TIME)
+, _parity(0)
+, _is_checksum_term(false)
+, _sentence_type(_GPS_SENTENCE_OTHER)
+, _term_number(0)
+, _term_offset(0)
+, _gps_data_good(false)
+#ifndef _GPS_NO_STATS
+, _encoded_characters(0)
+, _good_sentences(0)
+, _failed_checksum(0)
+#endif
+{
+ _term[0] = '\0';
+}
+
+//
+// public methods
+//
+
+bool TinyGPS::encode(char c)
+{
+ bool valid_sentence = false;
+
+ ++_encoded_characters;
+ switch(c)
+ {
+ case ',': // term terminators
+ _parity ^= c;
+ case '\r':
+ case '\n':
+ case '*':
+ if (_term_offset < sizeof(_term))
+ {
+ _term[_term_offset] = 0;
+ valid_sentence = term_complete();
+ }
+ ++_term_number;
+ _term_offset = 0;
+ _is_checksum_term = c == '*';
+ return valid_sentence;
+
+ case '$': // sentence begin
+ _term_number = _term_offset = 0;
+ _parity = 0;
+ _sentence_type = _GPS_SENTENCE_OTHER;
+ _is_checksum_term = false;
+ _gps_data_good = false;
+ return valid_sentence;
+ }
+
+ // ordinary characters
+ if (_term_offset < sizeof(_term) - 1)
+ _term[_term_offset++] = c;
+ if (!_is_checksum_term)
+ _parity ^= c;
+
+ return valid_sentence;
+}
+
+#ifndef _GPS_NO_STATS
+void TinyGPS::stats(unsigned long *chars, unsigned short *sentences, unsigned short *failed_cs)
+{
+ if (chars) *chars = _encoded_characters;
+ if (sentences) *sentences = _good_sentences;
+ if (failed_cs) *failed_cs = _failed_checksum;
+}
+#endif
+
+//
+// internal utilities
+//
+int TinyGPS::from_hex(char a)
+{
+ if (a >= 'A' && a <= 'F')
+ return a - 'A' + 10;
+ else if (a >= 'a' && a <= 'f')
+ return a - 'a' + 10;
+ else
+ return a - '0';
+}
+
+unsigned long TinyGPS::parse_decimal()
+{
+ char *p = _term;
+ bool isneg = *p == '-';
+ if (isneg) ++p;
+ unsigned long ret = 100UL * gpsatol(p);
+ while (gpsisdigit(*p)) ++p;
+ if (*p == '.')
+ {
+ if (gpsisdigit(p[1]))
+ {
+ ret += 10 * (p[1] - '0');
+ if (gpsisdigit(p[2]))
+ ret += p[2] - '0';
+ }
+ }
+ return isneg ? -ret : ret;
+}
+
+unsigned long TinyGPS::parse_degrees()
+{
+ char *p;
+ unsigned long left = gpsatol(_term);
+ unsigned long tenk_minutes = (left % 100UL) * 10000UL;
+ for (p=_term; gpsisdigit(*p); ++p);
+ if (*p == '.')
+ {
+ unsigned long mult = 1000;
+ while (gpsisdigit(*++p))
+ {
+ tenk_minutes += mult * (*p - '0');
+ mult /= 10;
+ }
+ }
+ return (left / 100) * 100000 + tenk_minutes / 6;
+}
+
+// Processes a just-completed term
+// Returns true if new sentence has just passed checksum test and is validated
+bool TinyGPS::term_complete()
+{
+ if (_is_checksum_term)
+ {
+ byte checksum = 16 * from_hex(_term[0]) + from_hex(_term[1]);
+ if (checksum == _parity)
+ {
+ if (_gps_data_good)
+ {
+#ifndef _GPS_NO_STATS
+ ++_good_sentences;
+#endif
+ _last_time_fix = _new_time_fix;
+ _last_position_fix = _new_position_fix;
+
+ switch(_sentence_type)
+ {
+ case _GPS_SENTENCE_GPRMC:
+ _time = _new_time;
+ _date = _new_date;
+ _latitude = _new_latitude;
+ _longitude = _new_longitude;
+ _speed = _new_speed;
+ _course = _new_course;
+ break;
+ case _GPS_SENTENCE_GPGGA:
+ _altitude = _new_altitude;
+ _time = _new_time;
+ _latitude = _new_latitude;
+ _longitude = _new_longitude;
+ break;
+ }
+
+ return true;
+ }
+ }
+
+#ifndef _GPS_NO_STATS
+ else
+ ++_failed_checksum;
+#endif
+ return false;
+ }
+
+ // the first term determines the sentence type
+ if (_term_number == 0)
+ {
+ if (!gpsstrcmp(_term, _GPRMC_TERM))
+ _sentence_type = _GPS_SENTENCE_GPRMC;
+ else if (!gpsstrcmp(_term, _GPGGA_TERM))
+ _sentence_type = _GPS_SENTENCE_GPGGA;
+ else
+ _sentence_type = _GPS_SENTENCE_OTHER;
+ return false;
+ }
+
+ if (_sentence_type != _GPS_SENTENCE_OTHER && _term[0])
+ switch((_sentence_type == _GPS_SENTENCE_GPGGA ? 200 : 100) + _term_number)
+ {
+ case 101: // Time in both sentences
+ case 201:
+ _new_time = parse_decimal();
+ _new_time_fix = millis();
+ break;
+ case 102: // GPRMC validity
+ _gps_data_good = _term[0] == 'A';
+ break;
+ case 103: // Latitude
+ case 202:
+ _new_latitude = parse_degrees();
+ _new_position_fix = millis();
+ break;
+ case 104: // N/S
+ case 203:
+ if (_term[0] == 'S')
+ _new_latitude = -_new_latitude;
+ break;
+ case 105: // Longitude
+ case 204:
+ _new_longitude = parse_degrees();
+ break;
+ case 106: // E/W
+ case 205:
+ if (_term[0] == 'W')
+ _new_longitude = -_new_longitude;
+ break;
+ case 107: // Speed (GPRMC)
+ _new_speed = parse_decimal();
+ break;
+ case 108: // Course (GPRMC)
+ _new_course = parse_decimal();
+ break;
+ case 109: // Date (GPRMC)
+ _new_date = gpsatol(_term);
+ break;
+ case 206: // Fix data (GPGGA)
+ _gps_data_good = _term[0] > '0';
+ break;
+ case 209: // Altitude (GPGGA)
+ _new_altitude = parse_decimal();
+ break;
+ }
+
+ return false;
+}
+
+long TinyGPS::gpsatol(const char *str)
+{
+ long ret = 0;
+ while (gpsisdigit(*str))
+ ret = 10 * ret + *str++ - '0';
+ return ret;
+}
+
+int TinyGPS::gpsstrcmp(const char *str1, const char *str2)
+{
+ while (*str1 && *str1 == *str2)
+ ++str1, ++str2;
+ return *str1;
+}
+
+/* static */
+float TinyGPS::distance_between (float lat1, float long1, float lat2, float long2)
+{
+ // returns distance in meters between two positions, both specified
+ // as signed decimal-degrees latitude and longitude. Uses great-circle
+ // distance computation for hypothetical sphere of radius 6372795 meters.
+ // Because Earth is no exact sphere, rounding errors may be up to 0.5%.
+ // Courtesy of Maarten Lamers
+ float delta = radians(long1-long2);
+ float sdlong = sin(delta);
+ float cdlong = cos(delta);
+ lat1 = radians(lat1);
+ lat2 = radians(lat2);
+ float slat1 = sin(lat1);
+ float clat1 = cos(lat1);
+ float slat2 = sin(lat2);
+ float clat2 = cos(lat2);
+ delta = (clat1 * slat2) - (slat1 * clat2 * cdlong);
+ delta = sq(delta);
+ delta += sq(clat2 * sdlong);
+ delta = sqrt(delta);
+ float denom = (slat1 * slat2) + (clat1 * clat2 * cdlong);
+ delta = atan2(delta, denom);
+ return delta * 6372795;
+}
diff --git a/Libraries/AQ_Gps/TinyGPS.h b/Libraries/AQ_Gps/TinyGPS.h
new file mode 100644
index 00000000..4c506f82
--- /dev/null
+++ b/Libraries/AQ_Gps/TinyGPS.h
@@ -0,0 +1,165 @@
+/*
+ TinyGPS - a small GPS library for Arduino providing basic NMEA parsing
+ Based on work by and "distance_to" courtesy of Maarten Lamers.
+ Copyright (C) 2008-2011 Mikal Hart
+ All rights reserved.
+
+ This library is free software; you can redistribute it and/or
+ modify it under the terms of the GNU Lesser General Public
+ License as published by the Free Software Foundation; either
+ version 2.1 of the License, or (at your option) any later version.
+
+ This library is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with this library; if not, write to the Free Software
+ Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
+*/
+
+#ifndef TinyGPS_h
+#define TinyGPS_h
+
+#include "Arduino.h"
+
+#define _GPS_VERSION 10 // software version of this library
+#define _GPS_MPH_PER_KNOT 1.15077945
+#define _GPS_MPS_PER_KNOT 0.51444444
+#define _GPS_KMPH_PER_KNOT 1.852
+#define _GPS_MILES_PER_METER 0.00062137112
+#define _GPS_KM_PER_METER 0.001
+//#define _GPS_NO_STATS
+
+class TinyGPS
+{
+ public:
+ TinyGPS();
+ bool encode(char c); // process one character received from GPS
+ TinyGPS &operator << (char c) {encode(c); return *this;}
+
+ // lat/long in hundred thousandths of a degree and age of fix in milliseconds
+ inline void get_position(long *latitude, long *longitude, unsigned long *fix_age = 0)
+ {
+ if (latitude) *latitude = _latitude;
+ if (longitude) *longitude = _longitude;
+ if (fix_age) *fix_age = _last_position_fix == GPS_INVALID_FIX_TIME ?
+ GPS_INVALID_AGE : millis() - _last_position_fix;
+ }
+
+ // date as ddmmyy, time as hhmmsscc, and age in milliseconds
+ inline void get_datetime(unsigned long *date, unsigned long *time, unsigned long *fix_age = 0)
+ {
+ if (date) *date = _date;
+ if (time) *time = _time;
+ if (fix_age) *fix_age = _last_time_fix == GPS_INVALID_FIX_TIME ?
+ GPS_INVALID_AGE : millis() - _last_time_fix;
+ }
+
+ // signed altitude in centimeters (from GPGGA sentence)
+ inline long altitude() { return _altitude; }
+
+ // course in last full GPRMC sentence in 100th of a degree
+ inline unsigned long course() { return _course; }
+
+ // speed in last full GPRMC sentence in 100ths of a knot
+ unsigned long speed() { return _speed; }
+
+#ifndef _GPS_NO_STATS
+ void stats(unsigned long *chars, unsigned short *good_sentences, unsigned short *failed_cs);
+#endif
+
+ inline void f_get_position(float *latitude, float *longitude, unsigned long *fix_age = 0)
+ {
+ long lat, lon;
+ get_position(&lat, &lon, fix_age);
+ *latitude = lat / 100000.0;
+ *longitude = lon / 100000.0;
+ }
+
+ inline void crack_datetime(int *year, byte *month, byte *day,
+ byte *hour, byte *minute, byte *second, byte *hundredths = 0, unsigned long *fix_age = 0)
+ {
+ unsigned long date, time;
+ get_datetime(&date, &time, fix_age);
+ if (year)
+ {
+ *year = date % 100;
+ *year += *year > 80 ? 1900 : 2000;
+ }
+ if (month) *month = (date / 100) % 100;
+ if (day) *day = date / 10000;
+ if (hour) *hour = time / 1000000;
+ if (minute) *minute = (time / 10000) % 100;
+ if (second) *second = (time / 100) % 100;
+ if (hundredths) *hundredths = time % 100;
+ }
+
+ inline float f_altitude() { return altitude() / 100.0; }
+ inline float f_course() { return course() / 100.0; }
+ inline float f_speed_knots() { return speed() / 100.0; }
+ inline float f_speed_mph() { return _GPS_MPH_PER_KNOT * f_speed_knots(); }
+ inline float f_speed_mps() { return _GPS_MPS_PER_KNOT * f_speed_knots(); }
+ inline float f_speed_kmph() { return _GPS_KMPH_PER_KNOT * f_speed_knots(); }
+
+ static int library_version() { return _GPS_VERSION; }
+
+ enum {GPS_INVALID_AGE = 0xFFFFFFFF, GPS_INVALID_ANGLE = 999999999, GPS_INVALID_ALTITUDE = 999999999, GPS_INVALID_DATE = 0,
+ GPS_INVALID_TIME = 0xFFFFFFFF, GPS_INVALID_SPEED = 999999999, GPS_INVALID_FIX_TIME = 0xFFFFFFFF};
+
+
+ static float distance_between (float lat1, float long1, float lat2, float long2);
+
+private:
+ enum {_GPS_SENTENCE_GPGGA, _GPS_SENTENCE_GPRMC, _GPS_SENTENCE_OTHER};
+
+ // properties
+ unsigned long _time, _new_time;
+ unsigned long _date, _new_date;
+ long _latitude, _new_latitude;
+ long _longitude, _new_longitude;
+ long _altitude, _new_altitude;
+ unsigned long _speed, _new_speed;
+ unsigned long _course, _new_course;
+
+ unsigned long _last_time_fix, _new_time_fix;
+ unsigned long _last_position_fix, _new_position_fix;
+
+ // parsing state variables
+ byte _parity;
+ bool _is_checksum_term;
+ char _term[15];
+ byte _sentence_type;
+ byte _term_number;
+ byte _term_offset;
+ bool _gps_data_good;
+
+#ifndef _GPS_NO_STATS
+ // statistics
+ unsigned long _encoded_characters;
+ unsigned short _good_sentences;
+ unsigned short _failed_checksum;
+ unsigned short _passed_checksum;
+#endif
+
+ // internal utilities
+ int from_hex(char a);
+ unsigned long parse_decimal();
+ unsigned long parse_degrees();
+ bool term_complete();
+ bool gpsisdigit(char c) { return c >= '0' && c <= '9'; }
+ long gpsatol(const char *str);
+ int gpsstrcmp(const char *str1, const char *str2);
+};
+
+// Arduino 0012 workaround
+#undef int
+#undef char
+#undef long
+#undef byte
+#undef float
+#undef abs
+#undef round
+
+#endif
diff --git a/Libraries/AQ_Gps/keywords.txt b/Libraries/AQ_Gps/keywords.txt
new file mode 100644
index 00000000..fc4989d3
--- /dev/null
+++ b/Libraries/AQ_Gps/keywords.txt
@@ -0,0 +1,41 @@
+#######################################
+# Syntax Coloring Map for TinyGPS
+#######################################
+
+#######################################
+# Datatypes (KEYWORD1)
+#######################################
+
+TinyGPS KEYWORD1
+
+#######################################
+# Methods and Functions (KEYWORD2)
+#######################################
+
+encode KEYWORD2
+get_position KEYWORD2
+get_datetime KEYWORD2
+altitude KEYWORD2
+speed KEYWORD2
+course KEYWORD2
+stats KEYWORD2
+f_get_position KEYWORD2
+crack_datetime KEYWORD2
+f_altitude KEYWORD2
+f_course KEYWORD2
+f_speed_knots KEYWORD2
+f_speed_mph KEYWORD2
+f_speed_mps KEYWORD2
+f_speed_kmph KEYWORD2
+library_version KEYWORD2
+distance_between KEYWORD2
+
+#######################################
+# Constants (LITERAL1)
+#######################################
+
+GPS_INVALID_AGE LITERAL1
+GPS_INVALID_ANGLE LITERAL1
+GPS_INVALID_ALTITUDE LITERAL1
+GPS_INVALID_DATE LITERAL1
+GPS_INVALID_TIME LITERAL1
diff --git a/Libraries/AQ_Gyroscope/Examples/Test_APM/Test_APM.ino b/Libraries/AQ_Gyroscope/Examples/Test_APM/Test_APM.ino
new file mode 100644
index 00000000..5eaf88f7
--- /dev/null
+++ b/Libraries/AQ_Gyroscope/Examples/Test_APM/Test_APM.ino
@@ -0,0 +1,58 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include // Arduino IDE bug, needed because that the ITG3200 use Wire!
+#include // Arduino IDE bug, needed because that the ITG3200 use Wire!
+
+#include
+#include
+#include
+#include
+
+unsigned long timer;
+
+void setup() {
+
+ Serial.begin(115200);
+ Serial.println("Gyroscope library test (APM)");
+
+ initializeADC();
+ initializeGyro();
+}
+
+void loop() {
+
+ if((millis() - timer) > 10) // 100Hz
+ {
+ timer = millis();
+ measureGyro();
+
+ Serial.print("Roll: ");
+ Serial.print(degrees(gyroRate[XAXIS]));
+ Serial.print(" Pitch: ");
+ Serial.print(degrees(gyroRate[YAXIS]));
+ Serial.print(" Yaw: ");
+ Serial.print(degrees(gyroRate[ZAXIS]));
+ Serial.print(" Heading: ");
+ Serial.print(degrees(gyroHeading));
+ Serial.println();
+ }
+
+}
diff --git a/Libraries/AQ_Gyroscope/Examples/Test_CHR6DM/Test_CHR6DM.ino b/Libraries/AQ_Gyroscope/Examples/Test_CHR6DM/Test_CHR6DM.ino
new file mode 100644
index 00000000..a7ba6956
--- /dev/null
+++ b/Libraries/AQ_Gyroscope/Examples/Test_CHR6DM/Test_CHR6DM.ino
@@ -0,0 +1,59 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+unsigned long timer;
+
+
+void setup()
+{
+ Serial.begin(115200);
+ Serial.println("Gyroscope library test (CHR6DM)");
+
+ calibrateGyro();
+
+ timer = millis();
+}
+
+void loop(void)
+{
+ if((millis() - timer) > 10) // 100Hz
+ {
+ timer = millis();
+ measureGyro();
+
+ Serial.print("Roll: ");
+ Serial.print(degrees(gyroRate[XAXIS]));
+ Serial.print(" Pitch: ");
+ Serial.print(degrees(gyroRate[YAXIS]));
+ Serial.print(" Yaw: ");
+ Serial.print(degrees(gyroRate[ZAXIS]));
+ Serial.print(" Heading: ");
+ Serial.print(degrees(gyroHeading));
+ Serial.println();
+ }
+}
+
diff --git a/Libraries/AQ_Gyroscope/Examples/Test_IDG_IDZ500/Test_IDG_IDZ500.ino b/Libraries/AQ_Gyroscope/Examples/Test_IDG_IDZ500/Test_IDG_IDZ500.ino
new file mode 100644
index 00000000..03aba003
--- /dev/null
+++ b/Libraries/AQ_Gyroscope/Examples/Test_IDG_IDZ500/Test_IDG_IDZ500.ino
@@ -0,0 +1,59 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include // @see Kenny, Arduino IDE compiliation bug
+
+#include
+#include
+#include
+#include
+
+unsigned long timer;
+
+void setup()
+{
+ Serial.begin(115200);
+ Serial.println("Gyroscope library test (IDG_IDZ500)");
+
+ setGyroAref(3.3);
+ initializeGyro();
+ calibrateGyro();
+ timer = millis();
+}
+
+void loop(void)
+{
+ if((millis() - timer) > 10) // 100Hz
+ {
+ timer = millis();
+ measureGyro();
+
+ Serial.print("Roll: ");
+ Serial.print(degrees(gyroRate[XAXIS]));
+ Serial.print(" Pitch: ");
+ Serial.print(degrees(gyroRate[YAXIS]));
+ Serial.print(" Yaw: ");
+ Serial.print(degrees(gyroRate[ZAXIS]));
+ Serial.print(" Heading: ");
+ Serial.print(degrees(gyroHeading));
+ Serial.println();
+ }
+}
+
diff --git a/Libraries/AQ_Gyroscope/Examples/Test_ITG3200/Test_ITG3200.ino b/Libraries/AQ_Gyroscope/Examples/Test_ITG3200/Test_ITG3200.ino
new file mode 100644
index 00000000..3f6f2aef
--- /dev/null
+++ b/Libraries/AQ_Gyroscope/Examples/Test_ITG3200/Test_ITG3200.ino
@@ -0,0 +1,60 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include
+
+#include
+#include
+#include
+#include
+
+unsigned long timer;
+
+void setup()
+{
+ Serial.begin(115200);
+ Serial.println("Gyroscope library test (ITG3200)");
+
+ Wire.begin();
+
+ initializeGyro();
+ calibrateGyro();
+ timer = millis();
+}
+
+void loop(void)
+{
+ if((millis() - timer) > 10) // 100Hz
+ {
+ timer = millis();
+ measureGyro();
+
+ Serial.print("Roll: ");
+ Serial.print(degrees(gyroRate[XAXIS]));
+ Serial.print(" Pitch: ");
+ Serial.print(degrees(gyroRate[YAXIS]));
+ Serial.print(" Yaw: ");
+ Serial.print(degrees(gyroRate[ZAXIS]));
+ Serial.print(" Heading: ");
+ Serial.print(degrees(gyroHeading));
+ Serial.println();
+ }
+}
+
diff --git a/Libraries/AQ_Gyroscope/Examples/Test_WII/Test_WII.ino b/Libraries/AQ_Gyroscope/Examples/Test_WII/Test_WII.ino
new file mode 100644
index 00000000..a7e1acda
--- /dev/null
+++ b/Libraries/AQ_Gyroscope/Examples/Test_WII/Test_WII.ino
@@ -0,0 +1,64 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include
+
+#include
+#include
+#include
+#include
+#include
+
+
+unsigned long timer;
+
+void setup()
+{
+ Serial.begin(115200);
+ Serial.println("Gyroscope library test (WII)");
+
+ Wire.begin();
+
+ initializeWiiSensors(true);
+ initializeGyro();
+ calibrateGyro();
+ timer = millis();
+}
+
+void loop(void)
+{
+ if((millis() - timer) > 10) // 100Hz
+ {
+ timer = millis();
+ readWiiSensors();
+ measureGyro();
+
+ Serial.print("Roll: ");
+ Serial.print(degrees(gyroRate[XAXIS]));
+ Serial.print(" Pitch: ");
+ Serial.print(degrees(gyroRate[YAXIS]));
+ Serial.print(" Yaw: ");
+ Serial.print(degrees(gyroRate[ZAXIS]));
+ Serial.print(" Heading: ");
+ Serial.print(degrees(gyroHeading));
+ Serial.println();
+ }
+}
+
diff --git a/Libraries/AQ_Gyroscope/Gyroscope.h b/Libraries/AQ_Gyroscope/Gyroscope.h
new file mode 100644
index 00000000..7b4ca1f3
--- /dev/null
+++ b/Libraries/AQ_Gyroscope/Gyroscope.h
@@ -0,0 +1,47 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_GYROSCOPE_H_
+#define _AEROQUAD_GYROSCOPE_H_
+
+#include "Arduino.h"
+#include "GlobalDefined.h"
+
+#define FINDZERO 49
+
+float gyroRate[3] = {0.0,0.0,0.0};
+int gyroZero[3] = {0,0,0};
+long gyroSample[3] = {0,0,0};
+float gyroSmoothFactor = 1.0;
+float gyroScaleFactor = 0.0;
+float gyroHeading = 0.0;
+unsigned long gyroLastMesuredTime = 0;
+
+void measureGyroSum();
+void evaluateGyroRate();
+
+byte gyroSampleCount = 0;
+
+
+void initializeGyro();
+void measureGyro();
+void calibrateGyro();
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_Gyroscope/Gyroscope_APM.h b/Libraries/AQ_Gyroscope/Gyroscope_APM.h
new file mode 100644
index 00000000..97bbe95e
--- /dev/null
+++ b/Libraries/AQ_Gyroscope/Gyroscope_APM.h
@@ -0,0 +1,74 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_GYROSCOPE_APM_H_
+#define _AEROQUAD_GYROSCOPE_APM_H_
+
+#include
+#include
+
+//#define APM_SCALE_TO_RADIANS radians((3.3/4096) / 0.002); // IDG/IXZ500 sensitivity = 2mV/(deg/sec)
+
+void initializeGyro() {
+ gyroScaleFactor = radians((3.3/4096) / 0.002); // IDG/IXZ500 sensitivity = 2mV/(deg/sec)
+ vehicleState |= GYRO_DETECTED;
+}
+
+void measureGyro() {
+ int gyroADC;
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ float rawADC = readADC(axis);
+ if (rawADC > 500) // Check if good measurement
+ if (axis == XAXIS)
+ gyroADC = rawADC - gyroZero[axis];
+ else
+ gyroADC = gyroZero[axis] - rawADC;
+ gyroRate[axis] = filterSmooth(gyroADC * gyroScaleFactor, gyroRate[axis], gyroSmoothFactor);
+ }
+
+ // Measure gyro heading
+ long int currentTime = micros();
+ if (gyroRate[ZAXIS] > radians(1.0) || gyroRate[ZAXIS] < radians(-1.0)) {
+ gyroHeading += gyroRate[ZAXIS] * ((currentTime - gyroLastMesuredTime) / 1000000.0);
+ }
+ gyroLastMesuredTime = currentTime;
+}
+
+void measureGyroSum() {
+ // do nothing here since it's already oversample in the APM_ADC class
+}
+
+void evaluateGyroRate() {
+ // do nothing here since it's already oversample in the APM_ADC class
+}
+
+void calibrateGyro() {
+ int findZero[FINDZERO];
+
+ for (byte axis = 0; axis < 3; axis++) {
+ for (int i=0; i.
+*/
+
+#ifndef _AEROQUAD_GYROSCOPE_CHR6DM_H_
+#define _AEROQUAD_GYROSCOPE_CHR6DM_H_
+
+#include
+#include
+#include
+
+#define FINDZERO 49
+
+float gyroRate[3] = {0.0,0.0,0.0};
+float gyroZero[3] = {0,0,0};
+float gyroSample[3] = {0,0,0};
+float gyroSmoothFactor = 1.0;
+float gyroScaleFactor = 0.0;
+float gyroHeading = 0.0;
+unsigned long gyroLastMesuredTime = 0;
+
+void measureGyroSum();
+void evaluateGyroRate();
+
+byte gyroSampleCount = 0;
+
+
+void initializeGyro();
+void measureGyro();
+void calibrateGyro();
+
+CHR6DM *gyroChr6dm;
+
+void initializeGyro() {
+ vehicleState |= GYRO_DETECTED;
+}
+
+void measureGyro() {
+
+ int gyroADC[3];
+ gyroADC[XAXIS] = gyroChr6dm->data.rollRate - gyroZero[XAXIS]; //gx yawRate
+ gyroADC[YAXIS] = gyroZero[YAXIS] - gyroChr6dm->data.pitchRate; //gy pitchRate
+ gyroADC[ZAXIS] = gyroChr6dm->data.yawRate - gyroZero[ZAXIS]; //gz rollRate
+
+ gyroRate[XAXIS] = filterSmooth(gyroADC[XAXIS], gyroRate[XAXIS], gyroSmoothFactor); //expect 5ms = 5000µs = (current-previous) / 5000.0 to get around 1
+ gyroRate[YAXIS] = filterSmooth(gyroADC[YAXIS], gyroRate[YAXIS], gyroSmoothFactor); //expect 5ms = 5000µs = (current-previous) / 5000.0 to get around 1
+ gyroRate[ZAXIS] = filterSmooth(gyroADC[ZAXIS], gyroRate[ZAXIS], gyroSmoothFactor); //expect 5ms = 5000µs = (current-previous) / 5000.0 to get around 1
+
+ // Measure gyro heading
+ long int currentTime = micros();
+ if (gyroRate[ZAXIS] > radians(1.0) || gyroRate[ZAXIS] < radians(-1.0)) {
+ gyroHeading += gyroRate[ZAXIS] * ((currentTime - gyroLastMesuredTime) / 1000000.0);
+ }
+ gyroLastMesuredTime = currentTime;
+}
+
+void measureGyroSum() {
+ // do nothing here since it's already oversample in the APM_ADC class
+}
+
+void evaluateGyroRate() {
+ // do nothing here since it's already oversample in the APM_ADC class
+}
+
+void calibrateGyro() {
+ float zeroXreads[FINDZERO];
+ float zeroYreads[FINDZERO];
+ float zeroZreads[FINDZERO];
+
+ for (int i=0; iread();
+ zeroXreads[i] = gyroChr6dm->data.rollRate;
+ zeroYreads[i] = gyroChr6dm->data.pitchRate;
+ zeroZreads[i] = gyroChr6dm->data.yawRate;
+ }
+
+ gyroZero[XAXIS] = findMedianFloat(zeroXreads, FINDZERO);
+ gyroZero[YAXIS] = findMedianFloat(zeroYreads, FINDZERO);
+ gyroZero[ZAXIS] = findMedianFloat(zeroZreads, FINDZERO);
+}
+
+
+#endif // #ifndef _AEROQUAD_GYROSCOPE_CHR6DM_H_
+
diff --git a/Libraries/AQ_Gyroscope/Gyroscope_IDG_IDZ500.h b/Libraries/AQ_Gyroscope/Gyroscope_IDG_IDZ500.h
new file mode 100644
index 00000000..aeaa11c0
--- /dev/null
+++ b/Libraries/AQ_Gyroscope/Gyroscope_IDG_IDZ500.h
@@ -0,0 +1,94 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_GYROSCOPE_IDG_IDZ500_H_
+#define _AEROQUAD_GYROSCOPE_IDG_IDZ500_H_
+
+#include
+#include
+
+#define AZPIN 12 // Auto zero pin for IDG500 gyros
+
+int gyroChannel[3] = {0.0,0.0,0.0};
+float gyroAref = 0.0;
+
+
+void setGyroAref(float _aref) {
+ gyroAref = _aref;
+ gyroScaleFactor = radians((gyroAref/1024.0) / 0.002); // IDG/IXZ500 sensitivity = 2mV/(deg/sec)
+}
+
+void initializeGyro() {
+ vehicleState |= GYRO_DETECTED;
+ analogReference(EXTERNAL);
+ // Configure gyro auto zero pins
+ pinMode (AZPIN, OUTPUT);
+ digitalWrite(AZPIN, LOW);
+ delay(1);
+
+ // rollChannel = 4
+ // pitchChannel = 3
+ // yawChannel = 5
+ gyroChannel[0] = 4;
+ gyroChannel[1] = 3;
+ gyroChannel[2] = 5;
+}
+
+void measureGyro() {
+ int gyroADC;
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ if (axis == YAXIS)
+ gyroADC = analogRead(gyroChannel[axis]) - gyroZero[axis];
+ else
+ gyroADC = gyroZero[axis] - analogRead(gyroChannel[axis]);
+ gyroRate[axis] = filterSmooth(gyroADC * gyroScaleFactor, gyroRate[axis], gyroSmoothFactor);
+ }
+
+ // Measure gyro heading
+ long int currentTime = micros();
+ if (gyroRate[ZAXIS] > radians(1.0) || gyroRate[ZAXIS] < radians(-1.0)) {
+ gyroHeading += gyroRate[ZAXIS] * ((currentTime - gyroLastMesuredTime) / 1000000.0);
+ }
+ gyroLastMesuredTime = currentTime;
+}
+
+void measureGyroSum() {
+ // do nothing here since it's already oversample in the APM_ADC class
+}
+
+void evaluateGyroRate() {
+ // do nothing here since it's already oversample in the APM_ADC class
+}
+
+void calibrateGyro() {
+ int findZero[FINDZERO];
+ digitalWrite(AZPIN, HIGH);
+ delayMicroseconds(750);
+ digitalWrite(AZPIN, LOW);
+ delay(8);
+
+ for (byte calAxis = XAXIS; calAxis <= ZAXIS; calAxis++) {
+ for (int i=0; i.
+*/
+
+#ifndef _AEROQUAD_GYROSCOPE_ITG3200_H_
+#define _AEROQUAD_GYROSCOPE_ITG3200_H_
+
+#include
+#include
+#include
+
+#define ITG3200_ADDRESS 0x69
+
+int gyroAddress = ITG3200_ADDRESS;
+
+void initializeGyro() {
+
+ if (readWhoI2C(gyroAddress) != gyroAddress) {
+ vehicleState |= GYRO_DETECTED;
+ }
+
+ gyroScaleFactor = radians(1.0 / 14.375); // ITG3200 14.375 LSBs per °/sec
+ updateRegisterI2C(gyroAddress, ITG3200_RESET_ADDRESS, ITG3200_RESET_VALUE); // send a reset to the device
+ updateRegisterI2C(gyroAddress, ITG3200_LOW_PASS_FILTER_ADDR, ITG3200_MEMORY_ADDRESS); // 10Hz low pass filter
+ updateRegisterI2C(gyroAddress, ITG3200_RESET_ADDRESS, ITG3200_OSCILLATOR_VALUE); // use internal oscillator
+}
+
+void measureGyro() {
+ sendByteI2C(gyroAddress, ITG3200_MEMORY_ADDRESS);
+ Wire.requestFrom(gyroAddress, ITG3200_BUFFER_SIZE);
+
+ // The following 3 lines read the gyro and assign it's data to gyroADC
+ // in the correct order and phase to suit the standard shield installation
+ // orientation. See TBD for details. If your shield is not installed in this
+ // orientation, this is where you make the changes.
+ int gyroADC[3];
+ gyroADC[XAXIS] = readShortI2C() - gyroZero[XAXIS];
+ gyroADC[YAXIS] = gyroZero[YAXIS] - readShortI2C();
+ gyroADC[ZAXIS] = gyroZero[ZAXIS] - readShortI2C();
+
+ for (byte axis = 0; axis <= ZAXIS; axis++) {
+ gyroRate[axis] = filterSmooth(gyroADC[axis] * gyroScaleFactor, gyroRate[axis], gyroSmoothFactor);
+ }
+
+ // Measure gyro heading
+ long int currentTime = micros();
+ if (gyroRate[ZAXIS] > radians(1.0) || gyroRate[ZAXIS] < radians(-1.0)) {
+ gyroHeading += gyroRate[ZAXIS] * ((currentTime - gyroLastMesuredTime) / 1000000.0);
+ }
+ gyroLastMesuredTime = currentTime;
+}
+
+void measureGyroSum() {
+ sendByteI2C(gyroAddress, ITG3200_MEMORY_ADDRESS);
+ Wire.requestFrom(gyroAddress, ITG3200_BUFFER_SIZE);
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ gyroSample[axis] += readShortI2C();
+ }
+ gyroSampleCount++;
+}
+
+void evaluateGyroRate() {
+ int gyroADC[3];
+ gyroADC[XAXIS] = (gyroSample[XAXIS] / gyroSampleCount) - gyroZero[XAXIS];
+ gyroADC[YAXIS] = gyroZero[YAXIS] - (gyroSample[YAXIS] / gyroSampleCount);
+ gyroADC[ZAXIS] = gyroZero[ZAXIS] - (gyroSample[ZAXIS] / gyroSampleCount);
+ gyroSample[0] = 0;
+ gyroSample[1] = 0;
+ gyroSample[2] = 0;
+ gyroSampleCount = 0;
+
+ for (byte axis = 0; axis <= ZAXIS; axis++) {
+ gyroRate[axis] = filterSmooth(gyroADC[axis] * gyroScaleFactor, gyroRate[axis], gyroSmoothFactor);
+ }
+
+ // Measure gyro heading
+ long int currentTime = micros();
+ if (gyroRate[ZAXIS] > radians(1.0) || gyroRate[ZAXIS] < radians(-1.0)) {
+ gyroHeading += gyroRate[ZAXIS] * ((currentTime - gyroLastMesuredTime) / 1000000.0);
+ }
+ gyroLastMesuredTime = currentTime;
+}
+
+void calibrateGyro() {
+ int findZero[FINDZERO];
+
+ for (byte axis = 0; axis < 3; axis++) {
+ for (int i=0; i.
+*/
+
+#ifndef _AEROQUAD_GYROSCOPE_ITG3200_DEFINES_H_
+#define _AEROQUAD_GYROSCOPE_ITG3200_DEFINES_H_
+
+#define ITG3200_MEMORY_ADDRESS 0x1D
+#define ITG3200_BUFFER_SIZE 6
+#define ITG3200_RESET_ADDRESS 0x3E
+#define ITG3200_RESET_VALUE 0x80
+#define ITG3200_LOW_PASS_FILTER_ADDR 0x16
+#define ITG3200_LOW_PASS_FILTER_VALUE 0x1D // 10Hz low pass filter
+#define ITG3200_OSCILLATOR_ADDR 0x3E
+#define ITG3200_OSCILLATOR_VALUE 0x01 // use X gyro oscillator
+#define ITG3200_SCALE_TO_RADIANS 823.626831 // 14.375 LSBs per °/sec, / Pi / 180
+
+#endif
diff --git a/Libraries/AQ_Gyroscope/Gyroscope_ITG3200_9DOF.h b/Libraries/AQ_Gyroscope/Gyroscope_ITG3200_9DOF.h
new file mode 100644
index 00000000..1e45966b
--- /dev/null
+++ b/Libraries/AQ_Gyroscope/Gyroscope_ITG3200_9DOF.h
@@ -0,0 +1,123 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_GYROSCOPE_ITG3200_9DOF_H_
+#define _AEROQUAD_GYROSCOPE_ITG3200_9DOF_H_
+
+#include
+#include
+#include
+
+#define ITG3200_ADDRESS 0x68
+
+int gyroAddress = ITG3200_ADDRESS;
+
+void initializeGyro() {
+
+ if (readWhoI2C(gyroAddress) != gyroAddress) {
+ vehicleState |= GYRO_DETECTED;
+ }
+
+ gyroScaleFactor = radians(1.0 / 14.375); // ITG3200 14.375 LSBs per °/sec
+ updateRegisterI2C(gyroAddress, ITG3200_RESET_ADDRESS, ITG3200_RESET_VALUE); // send a reset to the device
+ updateRegisterI2C(gyroAddress, ITG3200_LOW_PASS_FILTER_ADDR, ITG3200_MEMORY_ADDRESS); // 10Hz low pass filter
+ updateRegisterI2C(gyroAddress, ITG3200_RESET_ADDRESS, ITG3200_OSCILLATOR_VALUE); // use internal oscillator
+}
+
+void measureGyro() {
+ sendByteI2C(gyroAddress, ITG3200_MEMORY_ADDRESS);
+ Wire.requestFrom(gyroAddress, ITG3200_BUFFER_SIZE);
+
+ // The following 3 lines read the gyro and assign it's data to gyroADC
+ // in the correct order and phase to suit the standard shield installation
+ // orientation. See TBD for details. If your shield is not installed in this
+ // orientation, this is where you make the changes.
+ int gyroADC[3];
+ gyroADC[YAXIS] = readShortI2C() - gyroZero[YAXIS];
+ gyroADC[XAXIS] = readShortI2C() - gyroZero[XAXIS];
+ gyroADC[ZAXIS] = gyroZero[ZAXIS] - readShortI2C();
+
+ for (byte axis = 0; axis <= ZAXIS; axis++) {
+ gyroRate[axis] = filterSmooth(gyroADC[axis] * gyroScaleFactor, gyroRate[axis], gyroSmoothFactor);
+ }
+
+ // Measure gyro heading
+ long int currentTime = micros();
+ if (gyroRate[ZAXIS] > radians(1.0) || gyroRate[ZAXIS] < radians(-1.0)) {
+ gyroHeading += gyroRate[ZAXIS] * ((currentTime - gyroLastMesuredTime) / 1000000.0);
+ }
+ gyroLastMesuredTime = currentTime;
+}
+
+void measureGyroSum() {
+ sendByteI2C(gyroAddress, ITG3200_MEMORY_ADDRESS);
+ Wire.requestFrom(gyroAddress, ITG3200_BUFFER_SIZE);
+
+ gyroSample[YAXIS] += readShortI2C();
+ gyroSample[XAXIS] += readShortI2C();
+ gyroSample[ZAXIS] += readShortI2C();
+
+ gyroSampleCount++;
+}
+
+void evaluateGyroRate() {
+
+ int gyroADC[3];
+ gyroADC[XAXIS] = (gyroSample[XAXIS] / gyroSampleCount) - gyroZero[XAXIS];
+ gyroADC[YAXIS] = (gyroSample[YAXIS] / gyroSampleCount) - gyroZero[YAXIS];
+ gyroADC[ZAXIS] = gyroZero[ZAXIS] - (gyroSample[ZAXIS] / gyroSampleCount);
+ gyroSample[0] = 0;
+ gyroSample[1] = 0;
+ gyroSample[2] = 0;
+ gyroSampleCount = 0;
+
+ for (byte axis = 0; axis <= ZAXIS; axis++) {
+ gyroRate[axis] = filterSmooth(gyroADC[axis] * gyroScaleFactor, gyroRate[axis], gyroSmoothFactor);
+ }
+
+ // Measure gyro heading
+ long int currentTime = micros();
+ if (gyroRate[ZAXIS] > radians(1.0) || gyroRate[ZAXIS] < radians(-1.0)) {
+ gyroHeading += gyroRate[ZAXIS] * ((currentTime - gyroLastMesuredTime) / 1000000.0);
+ }
+ gyroLastMesuredTime = currentTime;
+}
+
+void calibrateGyro() {
+ int findZero[FINDZERO];
+ for (byte calAxis = XAXIS; calAxis <= ZAXIS; calAxis++) {
+ for (int i=0; i.
+*/
+
+#ifndef _AEROQUAD_GYROSCOPE_WII_H_
+#define _AEROQUAD_GYROSCOPE_WII_H_
+
+#include
+#include
+#include "../AQ_Platform_Wii/Platform_Wii.h"
+
+
+// Wii Motion+ has a low range and high range. Scaling is thought to be as follows:
+//
+// Vref = 1.35 volts
+// At 0 rate, reading is approximately 8063 bits
+// Scaling is then 1.35/8063, or 0.00016743 volts/bit
+//
+// Low Range
+// 440 degrees per second at 2.7 millivolts/degree (from datasheet)
+// degrees per bit = 0.00016743 / 2.7 mVolts = 0.06201166 degrees per second per bit
+// = 0.00108231 radians per second per bit
+// High Range
+// 2000 degrees per second at 0.5 millivolts/degree (from datasheet)
+// degrees per bit = 0.00016743 / 0.5 mVolts = 0.33486295 degrees per second per bit
+// = 0.00584446 radians per second per bit
+
+float wmpLowRangeToRadPerSec = 0.001082308;
+float wmpHighRangeToRadPerSec = 0.005844461;
+
+void initializeGyro() {
+ vehicleState |= GYRO_DETECTED;
+}
+
+void measureGyro() {
+ int gyroADC[3];
+ gyroADC[XAXIS] = gyroZero[XAXIS] - getWiiGyroADC(XAXIS);
+ gyroADC[YAXIS] = getWiiGyroADC(YAXIS) - gyroZero[YAXIS];
+ gyroADC[ZAXIS] = gyroZero[ZAXIS] - getWiiGyroADC(ZAXIS);
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ float gyroScaleFactor = getWmpSlow(axis) ? wmpLowRangeToRadPerSec : wmpHighRangeToRadPerSec ; // if wmpSlow == 1, use low range conversion,
+ gyroRate[axis] = filterSmooth(gyroADC[axis] * gyroScaleFactor, gyroRate[axis], gyroSmoothFactor);
+ }
+
+ // Measure gyro heading
+ long int currentTime = micros();
+ if (gyroRate[ZAXIS] > radians(1.0) || gyroRate[ZAXIS] < radians(-1.0)) {
+ gyroHeading += gyroRate[ZAXIS] * ((currentTime - gyroLastMesuredTime) / 1000000.0);
+ }
+ gyroLastMesuredTime = currentTime;
+}
+
+void measureGyroSum() {
+/**
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ gyroSample[axis] += getWiiGyroADC(axis);
+ }
+ gyroSampleCount++;
+*/
+}
+
+void evaluateGyroRate() {
+/**
+ int gyroADC[3];
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ if (axis == YAXIS)
+ gyroADC[axis] = gyroSample[axis]/gyroSampleCount - gyroZero[axis];
+ else
+ gyroADC[axis] = gyroZero[axis] - gyroSample[axis]/gyroSampleCount;
+ gyroSample[axis] = 0.0;
+ }
+ gyroSampleCount = 0;
+
+ for (byte axis = XAXIS; axis < LASTAXIS; axis++) {
+ float gyroScaleFactor = getWmpSlow(axis) ? wmpLowRangeToRadPerSec : wmpHighRangeToRadPerSec ; // if wmpSlow == 1, use low range conversion,
+ gyroRate[axis] = filterSmooth(gyroADC[axis] * gyroScaleFactor, gyroRate[axis], gyroSmoothFactor);
+ }
+
+ // Measure gyro heading
+ long int currentTime = micros();
+ if (gyroRate[ZAXIS] > radians(1.0) || gyroRate[ZAXIS] < radians(-1.0)) {
+ heading += gyroRate[ZAXIS] * ((currentTime - gyroLastMesuredTime) / 1000000.0);
+ }
+ gyroLastMesuredTime = currentTime;
+*/
+}
+
+void calibrateGyro() {
+ int findZero[FINDZERO];
+
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++) {
+ for (int i=0; i.
+*/
+
+// I2C functions
+#include "Device_I2C.h"
+
+void sendByteI2C(int deviceAddress, byte dataValue) {
+
+ Wire.beginTransmission(deviceAddress);
+ Wire.write(dataValue);
+ Wire.endTransmission();
+}
+
+byte readByteI2C(int deviceAddress) {
+
+ Wire.requestFrom(deviceAddress, 1);
+ return Wire.read();
+}
+
+int readWordI2C(int deviceAddress) {
+
+ Wire.requestFrom(deviceAddress, 2);
+ return (Wire.read() << 8) | Wire.read();
+}
+
+int readWordI2C() {
+
+ return (Wire.read() << 8) | Wire.read();
+}
+
+int readShortI2C(int deviceAddress) {
+
+ Wire.requestFrom(deviceAddress, 2);
+ return readShortI2C();
+}
+
+int readShortI2C() {
+
+ return (signed short)readWordI2C();
+}
+
+int readReverseShortI2C() {
+
+ return (signed short)( Wire.read() | (Wire.read() << 8));
+}
+
+int readWordWaitI2C(int deviceAddress) {
+
+ Wire.requestFrom(deviceAddress, 2); // request two bytes
+ while(!Wire.available()); // wait until data available
+ unsigned char msb = Wire.read();
+ while(!Wire.available()); // wait until data available
+ unsigned char lsb = Wire.read();
+ return (((int)msb<<8) | ((int)lsb));
+}
+
+int readReverseWordI2C(int deviceAddress) {
+
+ Wire.requestFrom(deviceAddress, 2);
+ byte lowerByte = Wire.read();
+ return (Wire.read() << 8) | lowerByte;
+}
+
+byte readWhoI2C(int deviceAddress) {
+
+ // read the ID of the I2C device
+ Wire.beginTransmission(deviceAddress);
+ Wire.write((byte)0);
+ Wire.endTransmission();
+ delay(100);
+ Wire.requestFrom(deviceAddress, 1);
+ return Wire.read();
+}
+
+void updateRegisterI2C(int deviceAddress, byte dataAddress, byte dataValue) {
+
+ Wire.beginTransmission(deviceAddress);
+ Wire.write(dataAddress);
+ Wire.write(dataValue);
+ Wire.endTransmission();
+}
+
+
+
diff --git a/Libraries/AQ_I2C/Device_I2C.h b/Libraries/AQ_I2C/Device_I2C.h
new file mode 100644
index 00000000..c200ef5d
--- /dev/null
+++ b/Libraries/AQ_I2C/Device_I2C.h
@@ -0,0 +1,45 @@
+/*
+ AeroQuad v2.2 - Feburary 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_DEVICE_I2C_H_
+#define _AEROQUAD_DEVICE_I2C_H_
+
+// I2C functions
+#include "Arduino.h"
+#include
+
+void sendByteI2C(int deviceAddress, byte dataValue);
+byte readByteI2C(int deviceAddress);
+int readWordI2C(int deviceAddress);
+int readWordI2C();
+int readShortI2C(int deviceAddress);
+int readShortI2C();
+int readReverseShortI2C();
+int readWordWaitI2C(int deviceAddress);
+int readReverseWordI2C(int deviceAddress);
+byte readWhoI2C(int deviceAddress);
+void updateRegisterI2C(int deviceAddress, byte dataAddress, byte dataValue);
+
+#endif
+
+
+
+
+
diff --git a/Libraries/AQ_Kinematics/Kinematics.h b/Libraries/AQ_Kinematics/Kinematics.h
new file mode 100644
index 00000000..0275b2b3
--- /dev/null
+++ b/Libraries/AQ_Kinematics/Kinematics.h
@@ -0,0 +1,85 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_KINEMATICS_
+#define _AQ_KINEMATICS_
+
+#include "GlobalDefined.h"
+
+#define CF 0
+#define KF 1
+#define DCM 2
+#define ARG 3
+#define MARG 4
+
+// This class is responsible for calculating vehicle attitude
+byte kinematicsType = 0;
+float kinematicsAngle[3] = {0.0,0.0,0.0};
+float gyroAngle[2] = {0.0,0.0};
+float correctedRateVector[3] = {0.0,0.0,0.0};
+float earthAccel[3] = {0.0,0.0,0.0};
+
+float accelCutoff = 0.0;
+
+void initializeBaseKinematicsParam(float hdgX, float hdgY) {
+ for (byte axis = XAXIS; axis <= ZAXIS; axis++)
+ kinematicsAngle[axis] = 0.0;
+ gyroAngle[XAXIS] = 0;
+ gyroAngle[YAXIS] = 0;
+}
+
+void initializeKinematics(float hdgX, float hdgY);
+void calculateKinematics(float rollRate, float pitchRate, float yawRate,
+ float longitudinalAccel, float lateralAccel, float verticalAccel,
+ float oneG, float magX, float magY,
+ float G_Dt);
+float getGyroUnbias(byte axis);
+void calibrateKinematics();
+
+ // returns the kinematicsAngle of a specific axis in SI units (radians)
+// const float getData(byte axis) {
+// return kinematicsAngle[axis];
+// }
+ // return heading as +PI/-PI
+// const float getHeading(byte axis) {
+// return(kinematicsAngle[axis]);
+// }
+
+ // This really needs to be in Radians to be consistent
+ // I'll fix later - AKA
+ // returns heading in degrees as 0-360
+const float kinematicsGetDegreesHeading(byte axis) {
+ float tDegrees;
+
+ tDegrees = degrees(kinematicsAngle[axis]);
+ if (tDegrees < 0.0)
+ return (tDegrees + 360.0);
+ else
+ return (tDegrees);
+}
+
+// const byte getType(void) {
+ // This is set in each subclass to identify which algorithm used
+// return kinematicsType;
+// }
+
+
+#endif
+
diff --git a/Libraries/AQ_Kinematics/Kinematics_ARG.h b/Libraries/AQ_Kinematics/Kinematics_ARG.h
new file mode 100644
index 00000000..463730e5
--- /dev/null
+++ b/Libraries/AQ_Kinematics/Kinematics_ARG.h
@@ -0,0 +1,192 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_KINEMATICS_MARG_
+#define _AQ_KINEMATICS_MARG_
+
+//=====================================================================================================
+// IMU.c
+// S.O.H. Madgwick
+// 25th September 2010
+//=====================================================================================================
+// Description:
+//
+// Quaternion implementation of the 'DCM filter' [Mayhony et al].
+//
+// User must define 'halfT' as the (sample period / 2), and the filter gains 'Kp' and 'Ki'.
+//
+// Global variables 'q0', 'q1', 'q2', 'q3' are the quaternion elements representing the estimated
+// orientation. See my report for an overview of the use of quaternions in this application.
+//
+// User must call 'IMUupdate()' every sample period and parse calibrated gyroscope ('gx', 'gy', 'gz')
+// and accelerometer ('ax', 'ay', 'ay') data. Gyroscope units are radians/second, accelerometer
+// units are irrelevant as the vector is normalised.
+//
+//=====================================================================================================
+
+
+////////////////////////////////////////////////////////////////////////////////
+// ARG - Accelerometer, Rate Gyro
+////////////////////////////////////////////////////////////////////////////////
+
+
+#include "Kinematics.h"
+
+#include
+
+float Kp = 0.0; // proportional gain governs rate of convergence to accelerometer/magnetometer
+float Ki = 0.0; // integral gain governs rate of convergence of gyroscope biases
+float halfT = 0.0; // half the sample period
+float q0 = 0.0, q1 = 0.0, q2 = 0.0, q3 = 0.0; // quaternion elements representing the estimated orientation
+float exInt = 0.0, eyInt = 0.0, ezInt = 0.0; // scaled integral error
+
+float previousEx = 0.0;
+float previousEy = 0.0;
+float previousEz = 0.0;
+
+////////////////////////////////////////////////////////////////////////////////
+// argUpdate
+////////////////////////////////////////////////////////////////////////////////
+void argUpdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float G_Dt) {
+
+ float norm;
+ float vx, vy, vz;
+ float q0i, q1i, q2i, q3i;
+ float ex, ey, ez;
+
+ halfT = G_Dt/2;
+
+ // normalise the measurements
+ norm = sqrt(ax*ax + ay*ay + az*az);
+ ax = ax / norm;
+ ay = ay / norm;
+ az = az / norm;
+
+ // estimated direction of gravity and flux (v and w)
+ vx = 2*(q1*q3 - q0*q2);
+ vy = 2*(q0*q1 + q2*q3);
+ vz = q0*q0 - q1*q1 - q2*q2 + q3*q3;
+
+ // error is sum of cross product between reference direction of fields and direction measured by sensors
+ ex = (vy*az - vz*ay);
+ ey = (vz*ax - vx*az);
+ ez = (vx*ay - vy*ax);
+
+ // integral error scaled integral gain
+ exInt = exInt + ex*Ki;
+ if (isSwitched(previousEx,ex)) {
+ exInt = 0.0;
+ }
+ previousEx = ex;
+
+ eyInt = eyInt + ey*Ki;
+ if (isSwitched(previousEy,ey)) {
+ eyInt = 0.0;
+ }
+ previousEy = ey;
+
+ ezInt = ezInt + ez*Ki;
+ if (isSwitched(previousEz,ez)) {
+ ezInt = 0.0;
+ }
+ previousEz = ez;
+
+ // adjusted gyroscope measurements
+ correctedRateVector[XAXIS] = gx = gx + Kp*ex + exInt;
+ correctedRateVector[YAXIS] = gy = gy + Kp*ey + eyInt;
+ correctedRateVector[ZAXIS] = gz = gz + Kp*ez + ezInt;
+
+ // integrate quaternion rate and normalise
+ q0i = (-q1*gx - q2*gy - q3*gz) * halfT;
+ q1i = ( q0*gx + q2*gz - q3*gy) * halfT;
+ q2i = ( q0*gy - q1*gz + q3*gx) * halfT;
+ q3i = ( q0*gz + q1*gy - q2*gx) * halfT;
+ q0 += q0i;
+ q1 += q1i;
+ q2 += q2i;
+ q3 += q3i;
+
+ // normalise quaternion
+ norm = sqrt(q0*q0 + q1*q1 + q2*q2 + q3*q3);
+ q0 = q0 / norm;
+ q1 = q1 / norm;
+ q2 = q2 / norm;
+ q3 = q3 / norm;
+
+ // save the adjusted gyroscope measurements
+ correctedRateVector[XAXIS] = gx;
+ correctedRateVector[YAXIS] = gy;
+ correctedRateVector[ZAXIS] = gz;
+}
+
+void eulerAngles()
+{
+ kinematicsAngle[XAXIS] = atan2(2 * (q0*q1 + q2*q3), 1 - 2 *(q1*q1 + q2*q2));
+ kinematicsAngle[YAXIS] = asin(2 * (q0*q2 - q1*q3));
+ kinematicsAngle[ZAXIS] = atan2(2 * (q0*q3 + q1*q2), 1 - 2 *(q2*q2 + q3*q3));
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Initialize ARG
+////////////////////////////////////////////////////////////////////////////////
+
+void initializeKinematics(float hdgX, float hdgY)
+{
+ initializeBaseKinematicsParam(hdgX,hdgY);
+ q0 = 1.0;
+ q1 = 0.0;
+ q2 = 0.0;
+ q3 = 0.0;
+ exInt = 0.0;
+ eyInt = 0.0;
+ ezInt = 0.0;
+
+ previousEx = 0;
+ previousEy = 0;
+ previousEz = 0;
+
+ Kp = 0.2; // 2.0;
+ Ki = 0.0005; //0.005;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Calculate ARG
+////////////////////////////////////////////////////////////////////////////////
+void calculateKinematics(float rollRate, float pitchRate, float yawRate,
+ float longitudinalAccel, float lateralAccel, float verticalAccel,
+ float measuredMagX, float measuredMagY, float measuredMagZ,
+ float G_DT) {
+
+ argUpdate(rollRate, pitchRate, yawRate,
+ longitudinalAccel, lateralAccel, verticalAccel,
+ measuredMagX, measuredMagY, measuredMagZ,
+ G_Dt);
+ eulerAngles();
+}
+
+float getGyroUnbias(byte axis) {
+ return correctedRateVector[axis];
+}
+
+void calibrateKinematics() {}
+
+
+#endif
+
diff --git a/Libraries/AQ_Kinematics/Kinematics_CHR6DM.h b/Libraries/AQ_Kinematics/Kinematics_CHR6DM.h
new file mode 100644
index 00000000..c28496b5
--- /dev/null
+++ b/Libraries/AQ_Kinematics/Kinematics_CHR6DM.h
@@ -0,0 +1,61 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_KINEMATICS_CHR6DM_
+#define _AQ_KINEMATICS_CHR6DM_
+
+#include "Kinematics.h"
+#include
+#include
+
+float zeroRoll = 0.0;
+float zeroPitch = 0.0;
+float CHR_RollAngle = 0.0;
+float CHR_PitchAngle = 0.0;
+
+CHR6DM *kinematicsChr6dm;
+
+void initializeKinematics(float hdgX, float hdgY) {
+ initializeBaseKinematicsParam(hdgX,hdgY);
+ calibrateKinematics();
+}
+
+void calculateKinematics(float rollRate, float pitchRate, float yawRate,
+ float longitudinalAccel, float lateralAccel, float verticalAccel,
+ float oneG, float magX, float magY,
+ float G_Dt) {
+
+ kinematicsAngle[XAXIS] = kinematicsChr6dm->data.roll - zeroRoll;
+ kinematicsAngle[YAXIS] = kinematicsChr6dm->data.pitch - zeroPitch;
+ CHR_RollAngle = kinematicsAngle[XAXIS]; //ugly since gotta access through accel class
+ CHR_PitchAngle = kinematicsAngle[YAXIS];
+}
+
+ void calibrateKinematics() {
+ zeroRoll = kinematicsChr6dm->data.roll;
+ zeroPitch = kinematicsChr6dm->data.pitch;
+}
+
+float getGyroUnbias(byte axis) {
+ return gyroRate[axis];
+}
+
+
+#endif
diff --git a/Libraries/AQ_Kinematics/Kinematics_DCM.h b/Libraries/AQ_Kinematics/Kinematics_DCM.h
new file mode 100644
index 00000000..aa6259d0
--- /dev/null
+++ b/Libraries/AQ_Kinematics/Kinematics_DCM.h
@@ -0,0 +1,248 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_KINEMATICS_DCM_
+#define _AQ_KINEMATICS_DCM_
+
+// Written by William Premerlani
+// Modified by Jose Julio for multicopters
+// http://diydrones.com/profiles/blogs/dcm-imu-theory-first-draft
+// Optimizations done by Jihlein
+// http://aeroquad.com/showthread.php?991-AeroQuad-Flight-Software-v2.0&p=12286&viewfull=1#post12286
+
+#include "Kinematics.h"
+
+float dcmMatrix[9] = {0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
+float omegaP[3] = {0.0,0.0,0.0};
+float omegaI[3] = {0.0,0.0,0.0};
+float omega[3] = {0.0,0.0,0.0};
+float errorCourse = 0.0;
+float kpRollPitch = 0.0;
+float kiRollPitch = 0.0;
+float kpYaw = 0.0;
+float kiYaw = 0.0;
+
+////////////////////////////////////////////////////////////////////////////////
+// Matrix Update
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixUpdate(float p, float q, float r, float G_Dt)
+{
+ float rateGyroVector[3];
+ float temporaryMatrix[9];
+ float updateMatrix[9];
+
+ rateGyroVector[XAXIS] = p;
+ rateGyroVector[YAXIS] = q;
+ rateGyroVector[ZAXIS] = r;
+
+ vectorSubtract(3, &omega[XAXIS], &rateGyroVector[XAXIS], &omegaI[XAXIS]);
+ vectorSubtract(3, &correctedRateVector[XAXIS], &omega[XAXIS], &omegaP[XAXIS]);
+
+ //Accel_adjust();//adjusting centrifugal acceleration. // Not used for quadcopter
+
+ updateMatrix[0] = 0;
+ updateMatrix[1] = -G_Dt * correctedRateVector[ZAXIS]; // -r
+ updateMatrix[2] = G_Dt * correctedRateVector[YAXIS]; // q
+ updateMatrix[3] = G_Dt * correctedRateVector[ZAXIS]; // r
+ updateMatrix[4] = 0;
+ updateMatrix[5] = -G_Dt * correctedRateVector[XAXIS]; // -p
+ updateMatrix[6] = -G_Dt * correctedRateVector[YAXIS]; // -q
+ updateMatrix[7] = G_Dt * correctedRateVector[XAXIS]; // p
+ updateMatrix[8] = 0;
+
+ matrixMultiply(3, 3, 3, temporaryMatrix, dcmMatrix, updateMatrix);
+ matrixAdd(3, 3, dcmMatrix, dcmMatrix, temporaryMatrix);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Normalize
+////////////////////////////////////////////////////////////////////////////////
+void normalize()
+{
+ float error=0;
+ float temporary[9];
+ float renorm=0;
+
+ error= -vectorDotProduct(3, &dcmMatrix[0], &dcmMatrix[3]) * 0.5; // eq.18
+
+ vectorScale(3, &temporary[0], &dcmMatrix[3], error); // eq.19
+ vectorScale(3, &temporary[3], &dcmMatrix[0], error); // eq.19
+
+ vectorAdd(6, &temporary[0], &temporary[0], &dcmMatrix[0]); // eq.19
+
+ vectorCrossProduct(&temporary[6],&temporary[0],&temporary[3]); // eq.20
+
+ for(byte v=0; v<9; v+=3) {
+ renorm = 0.5 *(3 - vectorDotProduct(3, &temporary[v],&temporary[v])); // eq.21
+ vectorScale(3, &dcmMatrix[v], &temporary[v], renorm);
+ }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Drift Correction
+////////////////////////////////////////////////////////////////////////////////
+
+void driftCorrection(float ax, float ay, float az, float oneG, float magX, float magY)
+{
+ // Compensation of the Roll, Pitch and Yaw drift.
+ float accelMagnitude;
+ float accelVector[3];
+ float accelWeight;
+ float errorRollPitch[3];
+ #ifdef HeadingMagHold
+ float errorCourse;
+ float errorYaw[3];
+ float scaledOmegaP[3];
+ #endif
+ float scaledOmegaI[3];
+
+ // Roll and Pitch Compensation
+ accelVector[XAXIS] = ax;
+ accelVector[YAXIS] = ay;
+ accelVector[ZAXIS] = az;
+
+ // Calculate the magnitude of the accelerometer vector
+ accelMagnitude = (sqrt(accelVector[XAXIS] * accelVector[XAXIS] +
+ accelVector[YAXIS] * accelVector[YAXIS] +
+ accelVector[ZAXIS] * accelVector[ZAXIS])) / oneG;
+
+ // Weight for accelerometer info (<0.75G = 0.0, 1G = 1.0 , >1.25G = 0.0)
+ // accelWeight = constrain(1 - 4*abs(1 - accelMagnitude),0,1);
+
+ // Weight for accelerometer info (<0.5G = 0.0, 1G = 1.0 , >1.5G = 0.0)
+ accelWeight = constrain(1 - 2 * abs(1 - accelMagnitude), 0, 1);
+
+ vectorCrossProduct(&errorRollPitch[0], &accelVector[0], &dcmMatrix[6]);
+ vectorScale(3, &omegaP[0], &errorRollPitch[0], kpRollPitch * accelWeight);
+
+ vectorScale(3, &scaledOmegaI[0], &errorRollPitch[0], kiRollPitch * accelWeight);
+ vectorAdd(3, omegaI, omegaI, scaledOmegaI);
+
+ // Yaw Compensation
+ #ifdef HeadingMagHold
+ errorCourse = (dcmMatrix[0] * magY) - (dcmMatrix[3] * magX);
+ vectorScale(3, errorYaw, &dcmMatrix[6], errorCourse);
+
+ vectorScale(3, &scaledOmegaP[0], &errorYaw[0], kpYaw);
+ vectorAdd(3, omegaP, omegaP, scaledOmegaP);
+
+ vectorScale(3, &scaledOmegaI[0] ,&errorYaw[0], kiYaw);
+ vectorAdd(3, omegaI, omegaI, scaledOmegaI);
+ #else
+ omegaP[ZAXIS] = 0.0;
+ omegaI[ZAXIS] = 0.0;
+ #endif
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Accel Adjust
+////////////////////////////////////////////////////////////////////////////////
+
+/*void Accel_adjust(void) {
+ // ADC : Voltage reference 3.0V / 10bits(1024 steps) => 2.93mV/ADC step
+ // ADXL335 Sensitivity(from datasheet) => 330mV/g, 2.93mV/ADC step => 330/0.8 = 102
+ #define GRAVITY 102 //this equivalent to 1G in the raw data coming from the accelerometer
+ #define Accel_Scale(x) x*(GRAVITY/9.81)//Scaling the raw data of the accel to actual acceleration in meters for seconds square
+
+ accelVector[1] += Accel_Scale(speed_3d*omega[2]); // Centrifugal force on Acc_y = GPS_speed*GyroZ
+ accelVector[2] -= Accel_Scale(speed_3d*omega[1]); // Centrifugal force on Acc_z = GPS_speed*GyroY
+}*/
+
+////////////////////////////////////////////////////////////////////////////////
+// Euler Angles
+////////////////////////////////////////////////////////////////////////////////
+
+void eulerAngles(void)
+{
+ kinematicsAngle[XAXIS] = atan2(dcmMatrix[7], dcmMatrix[8]);
+ kinematicsAngle[YAXIS] = -asin(dcmMatrix[6]);
+ kinematicsAngle[ZAXIS] = atan2(dcmMatrix[3], dcmMatrix[0]);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Earth Axis Accels
+////////////////////////////////////////////////////////////////////////////////
+
+void earthAxisAccels(float ax, float ay, float az, float oneG)
+{
+ float accelVector[3];
+
+ accelVector[XAXIS] = ax;
+ accelVector[YAXIS] = ay;
+ accelVector[ZAXIS] = az;
+
+ earthAccel[XAXIS] = vectorDotProduct(3, &dcmMatrix[0], &accelVector[0]);
+ earthAccel[YAXIS] = vectorDotProduct(3, &dcmMatrix[3], &accelVector[0]);
+ earthAccel[ZAXIS] = vectorDotProduct(3, &dcmMatrix[6], &accelVector[0]) + oneG;
+}
+
+
+////////////////////////////////////////////////////////////////////////////////
+// Initialize DCM
+////////////////////////////////////////////////////////////////////////////////
+
+void initializeKinematics(float hdgX, float hdgY)
+{
+ initializeBaseKinematicsParam(hdgX,hdgY);
+ for (byte i=0; i<3; i++) {
+ omegaP[i] = 0;
+ omegaI[i] = 0;
+ }
+ dcmMatrix[0] = hdgX;
+ dcmMatrix[1] = -hdgY;
+ dcmMatrix[2] = 0;
+ dcmMatrix[3] = hdgY;
+ dcmMatrix[4] = hdgX;
+ dcmMatrix[5] = 0;
+ dcmMatrix[6] = 0;
+ dcmMatrix[7] = 0;
+ dcmMatrix[8] = 1;
+
+ kpRollPitch = 0.1; // alternate 0.05;
+ kiRollPitch = 0.0002; // alternate 0.0001;
+
+ kpYaw = -0.1; // alternate -0.05;
+ kiYaw = -0.0002; // alternate -0.0001;
+
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Calculate DCM
+////////////////////////////////////////////////////////////////////////////////
+
+void calculateKinematics(float rollRate, float pitchRate, float yawRate,
+ float longitudinalAccel, float lateralAccel, float verticalAccel,
+ float oneG, float magX, float magY,
+ float G_Dt) {
+
+ matrixUpdate(rollRate, pitchRate, yawRate, G_Dt);
+ normalize();
+ driftCorrection(longitudinalAccel, lateralAccel, verticalAccel, oneG, magX, magY);
+ eulerAngles();
+ earthAxisAccels(longitudinalAccel, lateralAccel, verticalAccel, oneG);
+}
+
+void calibrateKinematics() {};
+
+
+
+#endif
+
diff --git a/Libraries/AQ_Kinematics/Kinematics_MARG.h b/Libraries/AQ_Kinematics/Kinematics_MARG.h
new file mode 100644
index 00000000..87154e2a
--- /dev/null
+++ b/Libraries/AQ_Kinematics/Kinematics_MARG.h
@@ -0,0 +1,211 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_KINEMATICS_MARG_
+#define _AQ_KINEMATICS_MARG_
+
+//=====================================================================================================
+// AHRS.c
+// S.O.H. Madgwick
+// 25th August 2010
+//=====================================================================================================
+// Description:
+//
+// Quaternion implementation of the 'DCM filter' [Mayhony et al]. Incorporates the magnetic distortion
+// compensation algorithms from my filter [Madgwick] which eliminates the need for a reference
+// direction of flux (bx bz) to be predefined and limits the effect of magnetic distortions to yaw
+// axis only.
+//
+// User must define 'halfT' as the (sample period / 2), and the filter gains 'Kp' and 'Ki'.
+//
+// Global variables 'q0', 'q1', 'q2', 'q3' are the quaternion elements representing the estimated
+// orientation. See my report for an overview of the use of quaternions in this application.
+//
+// User must call 'AHRSupdate()' every sample period and parse calibrated gyroscope ('gx', 'gy', 'gz'),
+// accelerometer ('ax', 'ay', 'ay') and magnetometer ('mx', 'my', 'mz') data. Gyroscope units are
+// radians/second, accelerometer and magnetometer units are irrelevant as the vector is normalised.
+//
+//=====================================================================================================
+
+////////////////////////////////////////////////////////////////////////////////
+// MARG - Magntometer, Accelerometer, Rate Gyro
+////////////////////////////////////////////////////////////////////////////////
+
+#include "Kinematics.h"
+
+float kpAcc = 0.0; // proportional gain governs rate of convergence to accelerometer
+float kiAcc = 0.0; // integral gain governs rate of convergence of gyroscope biases
+float kpMag = 0.0; // proportional gain governs rate of convergence to magnetometer
+float kiMag = 0.0; // integral gain governs rate of convergence of gyroscope biases
+float halfT = 0.0; // half the sample period
+float q0 = 0.0, q1 = 0.0, q2 = 0.0, q3 = 0.0; // quaternion elements representing the estimated orientation
+float exInt = 0.0, eyInt = 0.0, ezInt = 0.0; // scaled integral error
+
+////////////////////////////////////////////////////////////////////////////////
+// margUpdate
+////////////////////////////////////////////////////////////////////////////////
+
+void margUpdate(float gx, float gy, float gz, float ax, float ay, float az, float mx, float my, float mz, float G_Dt) {
+ float norm;
+ float hx, hy, hz, bx, bz;
+ float vx, vy, vz, wx, wy, wz;
+ float q0i, q1i, q2i, q3i;
+ float exAcc, eyAcc, ezAcc;
+ float exMag, eyMag, ezMag;
+
+ halfT = G_Dt/2;
+
+ // auxiliary variables to reduce number of repeated operations
+ float q0q0 = q0*q0;
+ float q0q1 = q0*q1;
+ float q0q2 = q0*q2;
+ float q0q3 = q0*q3;
+ float q1q1 = q1*q1;
+ float q1q2 = q1*q2;
+ float q1q3 = q1*q3;
+ float q2q2 = q2*q2;
+ float q2q3 = q2*q3;
+ float q3q3 = q3*q3;
+
+ // normalise the measurements
+ norm = sqrt(ax*ax + ay*ay + az*az);
+ ax = ax / norm;
+ ay = ay / norm;
+ az = az / norm;
+ norm = sqrt(mx*mx + my*my + mz*mz);
+ mx = mx / norm;
+ my = my / norm;
+ mz = mz / norm;
+
+ // compute reference direction of flux
+ hx = mx * 2*(0.5 - q2q2 - q3q3) + my * 2*(q1q2 - q0q3) + mz * 2*(q1q3 + q0q2);
+ hy = mx * 2*(q1q2 + q0q3) + my * 2*(0.5 - q1q1 - q3q3) + mz * 2*(q2q3 - q0q1);
+ hz = mx * 2*(q1q3 - q0q2) + my * 2*(q2q3 + q0q1) + mz * 2*(0.5 - q1q1 - q2q2);
+
+ bx = sqrt((hx*hx) + (hy*hy));
+ bz = hz;
+
+ // estimated direction of gravity and flux (v and w)
+ vx = 2*(q1q3 - q0q2);
+ vy = 2*(q0q1 + q2q3);
+ vz = q0q0 - q1q1 - q2q2 + q3q3;
+
+ wx = bx * 2*(0.5 - q2q2 - q3q3) + bz * 2*(q1q3 - q0q2);
+ wy = bx * 2*(q1q2 - q0q3) + bz * 2*(q0q1 + q2q3);
+ wz = bx * 2*(q0q2 + q1q3) + bz * 2*(0.5 - q1q1 - q2q2);
+
+ // error is sum of cross product between reference direction of fields and direction measured by sensors
+ exAcc = (vy*az - vz*ay);
+ eyAcc = (vz*ax - vx*az);
+ ezAcc = (vx*ay - vy*ax);
+
+ exMag = (my*wz - mz*wy);
+ eyMag = (mz*wx - mx*wz);
+ ezMag = (mx*wy - my*wx);
+
+ // integral error scaled integral gain
+ exInt = exInt + exAcc*kiAcc + exMag*kiMag;
+ eyInt = eyInt + eyAcc*kiAcc + eyMag*kiMag;
+ ezInt = ezInt + ezAcc*kiAcc + ezMag*kiMag;
+
+ // adjusted gyroscope measurements
+ correctedRateVector[XAXIS] = gx = gx + exAcc*kpAcc + exMag*kpMag + exInt;
+ correctedRateVector[YAXIS] = gy = gy + eyAcc*kpAcc + eyMag*kpMag + eyInt;
+ correctedRateVector[ZAXIS] = gz = gz + ezAcc*kpAcc + ezMag*kpMag + ezInt;
+
+ // integrate quaternion rate and normalise
+ q0i = (-q1*gx - q2*gy - q3*gz) * halfT;
+ q1i = ( q0*gx + q2*gz - q3*gy) * halfT;
+ q2i = ( q0*gy - q1*gz + q3*gx) * halfT;
+ q3i = ( q0*gz + q1*gy - q2*gx) * halfT;
+ q0 += q0i;
+ q1 += q1i;
+ q2 += q2i;
+ q3 += q3i;
+
+ // normalise quaternion
+ norm = sqrt(q0*q0 + q1*q1 + q2*q2 + q3*q3);
+ q0 = q0 / norm;
+ q1 = q1 / norm;
+ q2 = q2 / norm;
+ q3 = q3 / norm;
+
+ // save the adjusted gyroscope measurements
+ correctedRateVector[XAXIS] = gx;
+ correctedRateVector[YAXIS] = gy;
+ correctedRateVector[ZAXIS] = gz;
+}
+
+void eulerAngles(void)
+{
+ kinematicsAngle[XAXIS] = atan2(2 * (q0*q1 + q2*q3), 1 - 2 *(q1*q1 + q2*q2));
+ kinematicsAngle[YAXIS] = asin(2 * (q0*q2 - q1*q3));
+ kinematicsAngle[ZAXIS] = atan2(2 * (q0*q3 + q1*q2), 1 - 2 *(q2*q2 + q3*q3));
+}
+
+
+////////////////////////////////////////////////////////////////////////////////
+// Initialize MARG
+////////////////////////////////////////////////////////////////////////////////
+void initializeKinematics(float hdgX, float hdgY)
+{
+ initializeBaseKinematicsParam(hdgX,hdgY);
+ float hdg = atan2(hdgY, hdgX);
+
+ q0 = cos(hdg/2);
+ q1 = 0;
+ q2 = 0;
+ q3 = sin(hdg/2);
+ exInt = 0.0;
+ eyInt = 0.0;
+ ezInt = 0.0;
+
+ kpAcc = 0.2;
+ kiAcc = 0.0005;
+
+ kpMag = 2.0;
+ kiMag = 0.005;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Calculate MARG
+////////////////////////////////////////////////////////////////////////////////
+
+void calculateKinematics(float rollRate, float pitchRate, float yawRate,
+ float longitudinalAccel, float lateralAccel, float verticalAccel,
+ float measuredMagX, float measuredMagY, float measuredMagZ,
+ float G_Dt) {
+
+ margUpdate(rollRate, pitchRate, yawRate,
+ longitudinalAccel, lateralAccel, verticalAccel,
+ measuredMagX, measuredMagY, measuredMagZ,
+ G_Dt);
+ eulerAngles();
+}
+
+float getGyroUnbias(byte axis) {
+ return correctedRateVector[axis];
+}
+
+void calibrateKinematics() {}
+
+
+#endif
+
diff --git a/Libraries/AQ_Math/AQMath.cpp b/Libraries/AQ_Math/AQMath.cpp
new file mode 100644
index 00000000..364d5e96
--- /dev/null
+++ b/Libraries/AQ_Math/AQMath.cpp
@@ -0,0 +1,404 @@
+/*
+ AeroQuad v2.2 - Feburary 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include "AQMath.h"
+
+
+// Low pass filter, kept as regular C function for speed
+float filterSmooth(float currentData, float previousData, float smoothFactor)
+{
+ if (smoothFactor != 1.0) //only apply time compensated filter if smoothFactor is applied
+ {
+ return (previousData * (1.0 - smoothFactor) + (currentData * smoothFactor));
+ }
+ return currentData; //if smoothFactor == 1.0, do not calculate, just bypass!
+}
+
+float filterSmoothWithTime(float currentData, float previousData, float smoothFactor, float dT_scaledAroundOne)
+{ //time scale factor
+ if (smoothFactor != 1.0) //only apply time compensated filter if smoothFactor is applied
+ {
+ return (previousData * (1.0 - (smoothFactor * dT_scaledAroundOne)) + (currentData * (smoothFactor * dT_scaledAroundOne)));
+ }
+ return currentData; //if smoothFactor == 1.0, do not calculate, just bypass!
+}
+
+// ***********************************************************************
+// *********************** Median Filter Class ***************************
+// ***********************************************************************
+// Median filter currently not used, but kept if needed for the future
+// To declare use: MedianFilter filterSomething;
+
+MedianFilter::MedianFilter() {}
+
+void MedianFilter::initialize()
+{
+ for (int index = 0; index < DATASIZE; index++)
+ {
+ data[index] = 0;
+ sortData[index] = 0;
+ }
+ dataIndex = 0;
+}
+
+const float MedianFilter::filter(float newData)
+{
+ int temp, j; // used to sort array
+
+ // Insert new data into raw data array round robin style
+ data[dataIndex] = newData;
+ if (dataIndex < (DATASIZE-1))
+ {
+ dataIndex++;
+ }
+ else
+ {
+ dataIndex = 0;
+ }
+
+ // Copy raw data to sort data array
+ memcpy(sortData, data, sizeof(data));
+
+ // Insertion Sort
+ for(int i=1; i<=(DATASIZE-1); i++)
+ {
+ temp = sortData[i];
+ j = i-1;
+ while(temp=0)
+ {
+ sortData[j+1] = sortData[j];
+ j = j-1;
+ }
+ sortData[j+1] = temp;
+ }
+ return data[(DATASIZE)>>1]; // return data value in middle of sorted array
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Vector Dot Product
+// Return the Dot product of vectors a and b with length m
+//
+// Call as: vectorDotProduct(m, a, b)
+////////////////////////////////////////////////////////////////////////////////
+
+float vectorDotProduct(int length, float vector1[], float vector2[])
+{
+ float dotProduct = 0;
+ //int i;
+
+ for (int i = 0; i < length; i++)
+ {
+ dotProduct += vector1[i] * vector2[i];
+ }
+
+ return dotProduct;
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Vector Cross Product
+// Compute the cross product of vectors a and b with length 3
+// Place result in vector C
+//
+// Call as: vectorDotProduct(c, a, b)
+////////////////////////////////////////////////////////////////////////////////
+
+void vectorCrossProduct(float vectorC[3], float vectorA[3], float vectorB[3])
+{
+ vectorC[0] = (vectorA[1] * vectorB[2]) - (vectorA[2] * vectorB[1]);
+ vectorC[1] = (vectorA[2] * vectorB[0]) - (vectorA[0] * vectorB[2]);
+ vectorC[2] = (vectorA[0] * vectorB[1]) - (vectorA[1] * vectorB[0]);
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Multiply a vector by a scalar
+// Mulitply vector a with length m by a scalar
+// Place result in vector b
+//
+// Call as: vectorScale(m, b, a, scalar)
+////////////////////////////////////////////////////////////////////////////////
+
+void vectorScale(int length, float scaledVector[], float inputVector[], float scalar)
+{
+ for (int i = 0; i < length; i++)
+ {
+ scaledVector[i] = inputVector[i] * scalar;
+ }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Compute sum of 2 vectors
+// Add vector a to vector b, both of length m
+// Place result in vector c
+//
+// Call as: vectorAdd(m, c, b, a)
+////////////////////////////////////////////////////////////////////////////////
+
+void vectorAdd(int length, float vectorC[], float vectorA[], float vectorB[])
+{
+ for(int i = 0; i < length; i++)
+ {
+ vectorC[i] = vectorA[i] + vectorB[i];
+ }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Compute difference of 2 vectors
+// Subtract vector a from vector b, both of length m
+// Place result in vector c
+//
+// Call as: vectorSubtract(m, c, b, a)
+////////////////////////////////////////////////////////////////////////////////
+
+void vectorSubtract(int length, float vectorC[], float vectorA[], float vectorB[])
+{
+ for(int i = 0; i < length; i++)
+ {
+ vectorC[i] = vectorA[i] - vectorB[i];
+ }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Matrix Multiply
+// Multiply matrix A times matrix B, matrix A dimension m x n, matrix B dimension n x p
+// Result placed in matrix C, dimension m x p
+//
+// Call as: matrixMultiply(m, n, p, C, A, B)
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixMultiply(int aRows, int aCols_bRows, int bCols, float matrixC[], float matrixA[], float matrixB[])
+{
+ for (int i = 0; i < aRows * bCols; i++)
+ {
+ matrixC[i] = 0.0;
+ }
+
+ for (int i = 0; i < aRows; i++)
+ {
+ for(int j = 0; j < aCols_bRows; j++)
+ {
+ for(int k = 0; k < bCols; k++)
+ {
+ matrixC[i * bCols + k] += matrixA[i * aCols_bRows + j] * matrixB[j * bCols + k];
+ }
+ }
+ }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Matrix Addition
+// Add matrix A to matrix B, dimensions m x n
+// Result placed in matrix C, dimension m x n
+//
+// Call as: matrixAdd(m, n, C, A, B)
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixAdd(int rows, int cols, float matrixC[], float matrixA[], float matrixB[])
+{
+ for (int i = 0; i < rows * cols; i++)
+ {
+ matrixC[i] = matrixA[i] + matrixB[i];
+ }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// Matrix Subtraction
+// Subtract matrix A from matrix B, dimensions m x n
+// Result placed in matrix C, dimension m x n
+//
+// Call as: matrixSubtract(m, n, C, A, B)
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixSubtract(int rows, int cols, float matrixC[], float matrixA[], float matrixB[])
+{
+ for (int i = 0; i < rows * cols; i++)
+ {
+ matrixC[i] = matrixA[i] - matrixB[i];
+ }
+}
+
+
+////////////////////////////////////////////////////////////////////////////////
+// Matrix Scaling
+// Scale matrix A, dimensions m x n, by a scaler, S
+// Result placed in matrix C, dimension m x n
+//
+// Call as: matrixScale(m, n, C, S, B)
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixScale(int rows, int cols, float matrixC[], float scaler, float matrixA[])
+{
+ for (int i = 0; i < rows * cols; i++)
+ {
+ matrixC[i] = scaler * matrixA[i];
+ }
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// 3 x 3 Matrix Transpose
+// Compute 3 x 3 Transpose of A
+// Result placed in matrix C, dimension 3 x 3
+//
+// Call as: Transpose3x3(C, A)
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixTranspose3x3(float matrixC[9], float matrixA[9])
+{
+ matrixC[0] = matrixA[0];
+ matrixC[1] = matrixA[3];
+ matrixC[2] = matrixA[6];
+ matrixC[3] = matrixA[1];
+ matrixC[4] = matrixA[4];
+ matrixC[5] = matrixA[7];
+ matrixC[6] = matrixA[2];
+ matrixC[7] = matrixA[5];
+ matrixC[8] = matrixA[8];
+}
+
+////////////////////////////////////////////////////////////////////////////////
+// 3 x 3 Matrix Inverse
+// Compute 3 x 3 Inverse of A
+// Result placed in matrix C, dimension 3 x 3
+//
+// Call as: Inverse3x3(C, A)
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixInverse3x3(float matrixC[9], float matrixA[9])
+{
+
+ float det;
+ float transposeA[9];
+ float minors[9];
+ float transposeMinors[9];
+
+ det = matrixA[0] * (matrixA[4] * matrixA[8] - matrixA[5] * matrixA[7]) -
+ matrixA[1] * (matrixA[3] * matrixA[8] - matrixA[5] * matrixA[6]) +
+ matrixA[2] * (matrixA[3] * matrixA[7] - matrixA[4] * matrixA[6]);
+
+ matrixTranspose3x3(transposeA, matrixA);
+
+ minors[0] = matrixA[4] * matrixA[8] - matrixA[5] * matrixA[7];
+ minors[1] = matrixA[5] * matrixA[6] - matrixA[3] * matrixA[8];
+ minors[2] = matrixA[3] * matrixA[7] - matrixA[4] * matrixA[6];
+ minors[3] = matrixA[2] * matrixA[7] - matrixA[1] * matrixA[8];
+ minors[4] = matrixA[0] * matrixA[8] - matrixA[2] * matrixA[6];
+ minors[5] = matrixA[1] * matrixA[6] - matrixA[0] * matrixA[7];
+ minors[6] = matrixA[1] * matrixA[5] - matrixA[2] * matrixA[4];
+ minors[7] = matrixA[2] * matrixA[3] - matrixA[0] * matrixA[5];
+ minors[8] = matrixA[0] * matrixA[4] - matrixA[1] * matrixA[3];
+
+ matrixTranspose3x3(transposeMinors, minors);
+
+ det = 1/det;
+
+ matrixScale(3,3, matrixC, det, transposeMinors);
+}
+
+
+// Alternate method to calculate arctangent from: http://www.dspguru.com/comp.dsp/tricks/alg/fxdatan2.htm
+float arctan2(float y, float x)
+{
+ float coeff_1 = PI/4;
+ float coeff_2 = 3*coeff_1;
+ float abs_y = abs(y)+1e-10; // kludge to prevent 0/0 condition
+ float r, angle;
+
+ if (x >= 0)
+ {
+ r = (x - abs_y) / (x + abs_y);
+ angle = coeff_1 - coeff_1 * r;
+ }
+ else
+ {
+ r = (x + abs_y) / (abs_y - x);
+ angle = coeff_2 - coeff_1 * r;
+ }
+ if (y < 0)
+ {
+ return(-angle); // negate if in quad III or IV
+ }
+ else
+ {
+ return(angle);
+ }
+}
+
+// Used for sensor calibration
+// Takes the median of 50 results as zero
+// Thanks ala42! Post: http://aeroquad.com/showthread.php?1369-The-big-enhancement-addition-to-2.0-code/page5
+float findMedianFloat(float *data, int arraySize)
+{
+ float temp;
+ boolean done = 0;
+ byte i;
+
+ // Sorts numbers from lowest to highest
+ while (done != 1)
+ {
+ done = 1;
+ for (i=0; i<(arraySize-1); i++)
+ {
+ if (data[i] > data[i+1])
+ { // numbers are out of order - swap
+ temp = data[i+1];
+ data[i+1] = data[i];
+ data[i] = temp;
+ done = 0;
+ }
+ }
+ }
+
+ return data[arraySize/2]; // return the median value
+}
+
+
+int findMedianInt(int *data, int arraySize)
+{
+ int temp;
+ boolean done = 0;
+ byte i;
+
+ // Sorts numbers from lowest to highest
+ while (done != 1)
+ {
+ done = 1;
+ for (i=0; i<(arraySize-1); i++)
+ {
+ if (data[i] > data[i+1])
+ { // numbers are out of order - swap
+ temp = data[i+1];
+ data[i+1] = data[i];
+ data[i] = temp;
+ done = 0;
+ }
+ }
+ }
+
+ return data[arraySize/2]; // return the median value
+}
+
+
+
+boolean isSwitched(float previousError, float currentError) {
+ if ( (previousError > 0 && currentError < 0) ||
+ (previousError < 0 && currentError > 0)) {
+ return true;
+ }
+ return false;
+}
diff --git a/Libraries/AQ_Math/AQMath.h b/Libraries/AQ_Math/AQMath.h
new file mode 100644
index 00000000..45a28950
--- /dev/null
+++ b/Libraries/AQ_Math/AQMath.h
@@ -0,0 +1,174 @@
+/*
+ AeroQuad v2.2 - Feburary 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_MATH_H_
+#define _AQ_MATH_H_
+
+#define DATASIZE 25
+
+#include "Arduino.h"
+
+#define G_2_MPS2(g) (g * 9.80665)
+#define MPS2_2_G(m) (m * 0.10197162)
+
+// Low pass filter, kept as regular C function for speed
+float filterSmooth(float currentData, float previousData, float smoothFactor);
+float filterSmoothWithTime(float currentData, float previousData, float smoothFactor, float dT_scaledAroundOne);
+
+// ***********************************************************************
+// *********************** Median Filter Class ***************************
+// ***********************************************************************
+// Median filter currently not used, but kept if needed for the future
+// To declare use: MedianFilter filterSomething;
+
+class MedianFilter
+{
+public:
+ float data[DATASIZE], sortData[DATASIZE];
+ int dataIndex;
+ MedianFilter();
+
+ void initialize();
+
+ const float filter(float newData);
+};
+
+////////////////////////////////////////////////////////////////////////////////
+// Vector Dot Product
+// Return the Dot product of vectors a and b with length m
+//
+// Call as: vectorDotProduct(m, a, b)
+////////////////////////////////////////////////////////////////////////////////
+
+float vectorDotProduct(int length, float vector1[], float vector2[]);
+
+////////////////////////////////////////////////////////////////////////////////
+// Vector Cross Product
+// Compute the cross product of vectors a and b with length 3
+// Place result in vector C
+//
+// Call as: vectorDotProduct(c, a, b)
+////////////////////////////////////////////////////////////////////////////////
+
+void vectorCrossProduct(float vectorC[3], float vectorA[3], float vectorB[3]);
+
+////////////////////////////////////////////////////////////////////////////////
+// Multiply a vector by a scalar
+// Mulitply vector a with length m by a scalar
+// Place result in vector b
+//
+// Call as: vectorScale(m, b, a, scalar)
+////////////////////////////////////////////////////////////////////////////////
+
+void vectorScale(int length, float scaledVector[], float inputVector[], float scalar);
+
+////////////////////////////////////////////////////////////////////////////////
+// Compute sum of 2 vectors
+// Add vector a to vector b, both of length m
+// Place result in vector c
+//
+// Call as: vectorAdd(m, c, b, a)
+////////////////////////////////////////////////////////////////////////////////
+
+void vectorAdd(int length, float vectorC[], float vectorA[], float vectorB[]);
+
+////////////////////////////////////////////////////////////////////////////////
+// Compute difference of 2 vectors
+// Subtract vector a from vector b, both of length m
+// Place result in vector c
+//
+// Call as: vectorSubtract(m, c, b, a)
+////////////////////////////////////////////////////////////////////////////////
+
+void vectorSubtract(int length, float vectorC[], float vectorA[], float vectorB[]);
+
+////////////////////////////////////////////////////////////////////////////////
+// Matrix Multiply
+// Multiply matrix A times matrix B, matrix A dimension m x n, matrix B dimension n x p
+// Result placed in matrix C, dimension m x p
+//
+// Call as: matrixMultiply(m, n, p, C, A, B)
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixMultiply(int aRows, int aCols_bRows, int bCols, float matrixC[], float matrixA[], float matrixB[]);
+
+////////////////////////////////////////////////////////////////////////////////
+// Matrix Addition
+// Add matrix A to matrix B, dimensions m x n
+// Result placed in matrix C, dimension m x n
+//
+// Call as: matrixAdd(m, n, C, A, B)
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixAdd(int rows, int cols, float matrixC[], float matrixA[], float matrixB[]);
+
+////////////////////////////////////////////////////////////////////////////////
+// Matrix Subtraction
+// Subtract matrix A from matrix B, dimensions m x n
+// Result placed in matrix C, dimension m x n
+//
+// Call as: matrixSubtract(m, n, C, A, B)
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixSubtract(int rows, int cols, float matrixC[], float matrixA[], float matrixB[]);
+
+
+////////////////////////////////////////////////////////////////////////////////
+// Matrix Scaling
+// Scale matrix A, dimensions m x n, by a scaler, S
+// Result placed in matrix C, dimension m x n
+//
+// Call as: matrixScale(m, n, C, S, B)
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixScale(int rows, int cols, float matrixC[], float scaler, float matrixA[]);
+
+////////////////////////////////////////////////////////////////////////////////
+// 3 x 3 Matrix Transpose
+// Compute 3 x 3 Transpose of A
+// Result placed in matrix C, dimension 3 x 3
+//
+// Call as: Transpose3x3(C, A)
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixTranspose3x3(float matrixC[9], float matrixA[9]);
+
+////////////////////////////////////////////////////////////////////////////////
+// 3 x 3 Matrix Inverse
+// Compute 3 x 3 Inverse of A
+// Result placed in matrix C, dimension 3 x 3
+//
+// Call as: Inverse3x3(C, A)
+////////////////////////////////////////////////////////////////////////////////
+
+void matrixInverse3x3(float matrixC[9], float matrixA[9]);
+
+
+// Alternate method to calculate arctangent from: http://www.dspguru.com/comp.dsp/tricks/alg/fxdatan2.htm
+float arctan2(float y, float x);
+
+// Used for sensor calibration
+// Takes the median of 50 results as zero
+float findMedianFloat(float *data, int arraySize);
+int findMedianInt(int *data, int arraySize);
+
+boolean isSwitched(float previousError, float currentError);
+
+#endif
diff --git a/Libraries/AQ_Math/FourtOrderFilter.h b/Libraries/AQ_Math/FourtOrderFilter.h
new file mode 100644
index 00000000..a432d602
--- /dev/null
+++ b/Libraries/AQ_Math/FourtOrderFilter.h
@@ -0,0 +1,117 @@
+/*
+ AeroQuad v2.2 - Feburary 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AQ_FOURTH_ORDER_FILTER_H_
+#define _AQ_FOURTH_ORDER_FILTER_H_
+
+////////////////////////////////////////////////////////////////////////////////
+//
+//
+////////////////////////////////////////////////////////////////////////////////
+
+struct fourthOrderData
+{
+ float inputTm1, inputTm2, inputTm3, inputTm4;
+ float outputTm1, outputTm2, outputTm3, outputTm4;
+} fourthOrder[3];
+
+#define AX_FILTER 0
+#define AY_FILTER 1
+#define AZ_FILTER 2
+
+float computeFourthOrder(float currentInput, struct fourthOrderData *filterParameters)
+{
+ // cheby2(4,60,12.5/50)
+ #define _b0 0.001893594048567
+ #define _b1 -0.002220262954039
+ #define _b2 0.003389066536478
+ #define _b3 -0.002220262954039
+ #define _b4 0.001893594048567
+
+ #define _a1 -3.362256889209355
+ #define _a2 4.282608240117919
+ #define _a3 -2.444765517272841
+ #define _a4 0.527149895089809
+
+ float output;
+
+ output = _b0 * currentInput +
+ _b1 * filterParameters->inputTm1 +
+ _b2 * filterParameters->inputTm2 +
+ _b3 * filterParameters->inputTm3 +
+ _b4 * filterParameters->inputTm4 -
+ _a1 * filterParameters->outputTm1 -
+ _a2 * filterParameters->outputTm2 -
+ _a3 * filterParameters->outputTm3 -
+ _a4 * filterParameters->outputTm4;
+
+ filterParameters->inputTm4 = filterParameters->inputTm3;
+ filterParameters->inputTm3 = filterParameters->inputTm2;
+ filterParameters->inputTm2 = filterParameters->inputTm1;
+ filterParameters->inputTm1 = currentInput;
+
+ filterParameters->outputTm4 = filterParameters->outputTm3;
+ filterParameters->outputTm3 = filterParameters->outputTm2;
+ filterParameters->outputTm2 = filterParameters->outputTm1;
+ filterParameters->outputTm1 = output;
+
+ return output;
+}
+
+void setupFourthOrder(void)
+{
+ fourthOrder[AX_FILTER].inputTm1 = 0.0;
+ fourthOrder[AX_FILTER].inputTm2 = 0.0;
+ fourthOrder[AX_FILTER].inputTm3 = 0.0;
+ fourthOrder[AX_FILTER].inputTm4 = 0.0;
+
+ fourthOrder[AX_FILTER].outputTm1 = 0.0;
+ fourthOrder[AX_FILTER].outputTm2 = 0.0;
+ fourthOrder[AX_FILTER].outputTm3 = 0.0;
+ fourthOrder[AX_FILTER].outputTm4 = 0.0;
+
+ //////////
+
+ fourthOrder[AY_FILTER].inputTm1 = 0.0;
+ fourthOrder[AY_FILTER].inputTm2 = 0.0;
+ fourthOrder[AY_FILTER].inputTm3 = 0.0;
+ fourthOrder[AY_FILTER].inputTm4 = 0.0;
+
+ fourthOrder[AY_FILTER].outputTm1 = 0.0;
+ fourthOrder[AY_FILTER].outputTm2 = 0.0;
+ fourthOrder[AY_FILTER].outputTm3 = 0.0;
+ fourthOrder[AY_FILTER].outputTm4 = 0.0;
+
+ //////////
+
+ fourthOrder[AZ_FILTER].inputTm1 = -9.8065;
+ fourthOrder[AZ_FILTER].inputTm2 = -9.8065;
+ fourthOrder[AZ_FILTER].inputTm3 = -9.8065;
+ fourthOrder[AZ_FILTER].inputTm4 = -9.8065;
+
+ fourthOrder[AZ_FILTER].outputTm1 = -9.8065;
+ fourthOrder[AZ_FILTER].outputTm2 = -9.8065;
+ fourthOrder[AZ_FILTER].outputTm3 = -9.8065;
+ fourthOrder[AZ_FILTER].outputTm4 = -9.8065;
+ }
+
+////////////////////////////////////////////////////////////////////////////////
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_Motors/Examples/MotorTest/MotorTest.ino b/Libraries/AQ_Motors/Examples/MotorTest/MotorTest.ino
new file mode 100644
index 00000000..d7931b99
--- /dev/null
+++ b/Libraries/AQ_Motors/Examples/MotorTest/MotorTest.ino
@@ -0,0 +1,114 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+//#define MOTOR_PWM
+#define MOTOR_PWM_Timer
+//#define MOTOR_APM
+//#define MOTOR_I2C
+
+#define NB_MOTOR_4
+//#define NB_MOTOR_6
+//#define NB_MOTOR_8
+
+
+#if defined MOTOR_PWM
+ #include
+
+ void initMotors(NB_Motors motorConfig) {
+ initializeMotors(motorConfig);
+ }
+#elif defined MOTOR_PWM_Timer
+ #include
+
+ void initMotors(NB_Motors motorConfig) {
+ initializeMotors(motorConfig);
+ }
+
+#elif defined MOTOR_APM
+ #include
+
+ void initMotors(NB_Motors motorConfig) {
+ initRC();
+ initializeMotors(motorConfig);
+ }
+
+#elif defined MOTOR_I2C
+ #include
+ #include
+
+ void initMotors(NB_Motors motorConfig) {
+ Wire.begin();
+ initializeMotors(motorConfig);
+ }
+
+
+#endif
+
+#if defined (NB_MOTOR_4)
+ #define NB_MOTOR 4
+ #define NB_MOTOR_CONFIG FOUR_Motors
+#elif defined (NB_MOTOR_6)
+ #define NB_MOTOR 6
+ #define NB_MOTOR_CONFIG SIX_Motors
+#else
+ #define NB_MOTOR 8
+ #define NB_MOTOR_CONFIG HEIGHT_Motors
+#endif
+
+
+void setup() {
+ Serial.begin(115200);
+ initMotors(NB_MOTOR_CONFIG);
+}
+
+void testMotor(int motor) {
+ Serial.println();
+ Serial.print("TEST MOTOR ");
+ Serial.println(motor);
+ for (int motorTrust = 1000; motorTrust < 1200; motorTrust+=10) {
+ motorCommand[motor] = motorTrust;
+ writeMotors();
+ delay(200);
+ }
+ for (int motorTrust = 1200; motorTrust > 1000; motorTrust-=10) {
+ motorCommand[motor] = motorTrust;
+ writeMotors();
+ delay(200);
+ }
+ motorCommand[motor] = 1000;
+ writeMotors();
+}
+
+void loop() {
+
+ Serial.println("===================== START MOTOR TEST =========================");
+ for (int motor = 0; motor < NB_MOTOR; motor++) {
+ testMotor(motor);
+ delay(1000);
+ }
+}
+
+
+
+
+
+
+
+
diff --git a/Libraries/AQ_Motors/Motors.h b/Libraries/AQ_Motors/Motors.h
new file mode 100644
index 00000000..c57fac44
--- /dev/null
+++ b/Libraries/AQ_Motors/Motors.h
@@ -0,0 +1,61 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+
+#ifndef _AEROQUAD_MOTORS_H_
+#define _AEROQUAD_MOTORS_H_
+
+#include "Arduino.h"
+
+#define MOTOR1 0
+#define MOTOR2 1
+#define MOTOR3 2
+#define MOTOR4 3
+#define MOTOR5 4
+#define MOTOR6 5
+#define MOTOR7 6
+#define MOTOR8 7
+#define MINCOMMAND 1000
+#define MAXCOMMAND 2000
+
+enum NB_Motors{
+ FOUR_Motors = 4,
+ SIX_Motors = 6,
+ EIGHT_Motors = 8
+};
+
+NB_Motors numberOfMotors = FOUR_Motors;
+int motorCommand[8] = {0,0,0,0,0,0,0,0}; // LASTMOTOR not know here, so, default at 8 @todo : Kenny, find a better way
+
+void initializeMotors(NB_Motors numbers = FOUR_Motors);
+void writeMotors();
+void commandAllMotors(int command);
+
+void pulseMotors(byte nbPulse) {
+ for (byte i = 0; i < nbPulse; i++) {
+ commandAllMotors(MINCOMMAND + 100);
+ delay(250);
+ commandAllMotors(MINCOMMAND);
+ delay(250);
+ }
+}
+
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_Motors/Motors_APM.h b/Libraries/AQ_Motors/Motors_APM.h
new file mode 100644
index 00000000..1802e15a
--- /dev/null
+++ b/Libraries/AQ_Motors/Motors_APM.h
@@ -0,0 +1,64 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+
+#ifndef _AEROQUAD_MOTORS_APM_H_
+#define _AEROQUAD_MOTORS_APM_H_
+
+#include "Arduino.h"
+#include
+#include "Motors.h"
+
+void initializeMotors(NB_Motors numbers) {
+ commandAllMotors(1000);
+}
+
+void writeMotors() {
+ writeMotorCommand(0,motorCommand[MOTOR1]);
+ writeMotorCommand(1,motorCommand[MOTOR2]);
+ writeMotorCommand(2,motorCommand[MOTOR3]);
+ writeMotorCommand(3,motorCommand[MOTOR4]);
+ writeMotorCommand(6,motorCommand[MOTOR5]);
+ writeMotorCommand(7,motorCommand[MOTOR6]);
+ writeMotorCommand(9,motorCommand[MOTOR7]);
+ writeMotorCommand(10,motorCommand[MOTOR8]);
+ force_Out0_Out1();
+ force_Out2_Out3();
+ force_Out6_Out7();
+}
+
+void commandAllMotors(int command) {
+ writeMotorCommand(0,command);
+ writeMotorCommand(1,command);
+ writeMotorCommand(2,command);
+ writeMotorCommand(3,command);
+ writeMotorCommand(6,command);
+ writeMotorCommand(6,command);
+ writeMotorCommand(7,command);
+ writeMotorCommand(9,command);
+ writeMotorCommand(10,command);
+ force_Out0_Out1();
+ force_Out2_Out3();
+ force_Out6_Out7();
+}
+
+
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_Motors/Motors_I2C.h b/Libraries/AQ_Motors/Motors_I2C.h
new file mode 100644
index 00000000..4ca5b306
--- /dev/null
+++ b/Libraries/AQ_Motors/Motors_I2C.h
@@ -0,0 +1,63 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+
+#ifndef _AEROQUAD_MOTORS_I2C_H_
+#define _AEROQUAD_MOTORS_I2C_H_
+
+#include "Arduino.h"
+
+#include "Motors.h"
+
+#define MOTORBASE 0x28 // I2C controller base address
+#define MOTOR_ADDR_0 MOTORBASE + 1 // define I2C controller addresses per your configuration
+#define MOTOR_ADDR_1 MOTORBASE + 3 // these addresses are for Phifun controllers
+#define MOTOR_ADDR_2 MOTORBASE + 2 // as installed on jihlein's homebrew AeroQuad 3.0
+#define MOTOR_ADDR_3 MOTORBASE + 4 // inspired frame
+#define MOTOR_ADDR_4 MOTORBASE + 5
+#define MOTOR_ADDR_5 MOTORBASE + 6
+
+
+byte motorAddress[6];
+
+void initializeMotors(NB_Motors numbers) {
+ motorAddress[MOTOR1] = MOTOR_ADDR_0;
+ motorAddress[MOTOR2] = MOTOR_ADDR_1;
+ motorAddress[MOTOR3] = MOTOR_ADDR_2;
+ motorAddress[MOTOR4] = MOTOR_ADDR_3;
+ motorAddress[MOTOR5] = MOTOR_ADDR_4;
+ motorAddress[MOTOR6] = MOTOR_ADDR_5;
+
+ numberOfMotors = numbers;
+ for (byte motor = MOTOR1; motor < numberOfMotors; motor++)
+ sendByteI2C(motorAddress[motor], 0);
+}
+
+void writeMotors() {
+ for (byte motor = MOTOR1; motor < numberOfMotors; motor++)
+ sendByteI2C(motorAddress[motor], constrain((motorCommand[motor] - 1000) / 4, 0, 255));
+}
+
+void commandAllMotors(int command) {
+ for (byte motor = MOTOR1; motor < numberOfMotors; motor++)
+ sendByteI2C(motorAddress[motor], constrain((motorCommand[motor] - 1000) / 4, 0, 255));
+}
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_Motors/Motors_PWM.h b/Libraries/AQ_Motors/Motors_PWM.h
new file mode 100644
index 00000000..2f56f016
--- /dev/null
+++ b/Libraries/AQ_Motors/Motors_PWM.h
@@ -0,0 +1,160 @@
+/*
+ AeroQuad v3.0 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+
+#ifndef _AEROQUAD_MOTORS_PWM_H_
+#define _AEROQUAD_MOTORS_PWM_H_
+
+#include "Arduino.h"
+
+#include "Motors.h"
+
+#if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+ #define MOTORPIN0 2
+ #define MOTORPIN1 3
+ #define MOTORPIN2 5
+ #define MOTORPIN3 6
+ #define MOTORPIN4 7
+ #define MOTORPIN5 8
+ #define MOTORPIN6 9
+ #define MOTORPIN7 10
+#else
+ #define MOTORPIN0 3
+ #define MOTORPIN1 9
+ #define MOTORPIN2 10
+ #define MOTORPIN3 11
+ #define MOTORPIN4 5
+ #define MOTORPIN5 6
+
+volatile uint8_t atomicPWM_PIN5_lowState = 0;
+volatile uint8_t atomicPWM_PIN5_highState = 0;
+volatile uint8_t atomicPWM_PIN6_lowState = 0;
+volatile uint8_t atomicPWM_PIN6_highState = 0;
+
+void initializeSoftPWM() {
+ TCCR0A = 0; // normal counting mode
+ TIMSK0 |= (1<.
+*/
+
+
+#ifndef _AEROQUAD_MOTORS_PWM_TIMER_H_
+#define _AEROQUAD_MOTORS_PWM_TIMER_H_
+
+///***********************************************************/
+///********************* PWMtimer Motors *********************/
+///***********************************************************/
+//// Special thanks to CupOfTea for authorting this class
+//// http://aeroquad.com/showthread.php?1553-Timed-Motors_PWM
+//// Uses system timers directly instead of analogWrite
+///*Some basics about the 16 bit timer:
+//- The timer counts clock ticks derived from the CPU clock. Using 16MHz CPU clock
+// and a prescaler of 8 gives a timer clock of 2MHz, one tick every 0.5us. This
+// is also called timer resolution.
+//- The timer is used as cyclic upwards counter, the counter period is set in the
+// ICRx register. IIRC period-1 has to be set in the ICRx register.
+//- When the counter reaches 0, the outputs are set
+//- When the counter reaches OCRxy, the corresponding output is cleared.
+//In the code below, the period shall be 3.3ms (300hz), so the ICRx register is
+// set to 6600 ticks of 0.5us/tick. It probably should be 6599, but who cares about
+// this 0.5us for the period. This value is #define TOP
+//The high time shall be 1000us, so the OCRxy register is set to 2000. In the code
+// below this can be seen in the line "commandAllMotors(1000);" A change of
+// the timer period does not change this setting, as the clock rate is still one
+// tick every 0.5us. If the prescaler was changed, the OCRxy register value would
+// be different.
+//*/
+///* Motor Mega Pin Port Uno Pin Port HEXA Mega Pin Port
+// FRONT 2 PE4 3 PD3
+// REAR 3 PE5 9 PB1
+// RIGHT 5 PE3 10 PB2 7 PH4
+// LEFT 6 PH3 11 PB3 8 PH5
+//*/
+
+#include "Arduino.h"
+
+#include "Motors.h"
+
+#define PWM_FREQUENCY 300 // in Hz
+#define PWM_PRESCALER 8
+#define PWM_COUNTER_PERIOD (F_CPU/PWM_PRESCALER/PWM_FREQUENCY)
+
+
+
+
+void initializeMotors(NB_Motors numbers) {
+ numberOfMotors = numbers;
+
+ #if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+ DDRE = DDRE | B00111000; // Set ports to output PE3-5
+ if (numberOfMotors == FOUR_Motors) {
+ DDRH = DDRH | B00001000; // Set port to output PH3
+ }
+ else if (numberOfMotors == SIX_Motors) { // for 6
+ DDRH = DDRH | B00111000; // Set ports to output PH3-5
+ }
+ else if (numberOfMotors == EIGHT_Motors) { // for 8 motor
+ DDRH = DDRH | B00111000; // Set ports to output PH3-5
+ DDRB = DDRB | B01100000;
+ }
+ #else
+ DDRB = DDRB | B00001110; // Set ports to output PB1-3
+ DDRD = DDRD | B00001000; // Set port to output PD3
+ #endif
+
+ commandAllMotors(1000); // Initialise motors to 1000us (stopped)
+
+ #if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+ // Init PWM Timer 3 // WGMn1 WGMn2 WGMn3 = Mode 14 Fast PWM, TOP = ICRn ,Update of OCRnx at BOTTOM
+ TCCR3A = (1<.
+*/
+
+
+#ifndef _AEROQUAD_MOTORS_PWM_H_
+#define _AEROQUAD_MOTORS_PWM_H_
+
+#include "Arduino.h"
+#include "Motors.h"
+
+#if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+ #define MOTORPIN0 2
+ #define MOTORPIN1 3
+ #define MOTORPIN2 5
+ #define MOTORPIN3 6
+ #define MOTORPIN4 7
+ #define MOTORPIN5 8
+ #define MOTORPIN6 9
+ #define MOTORPIN7 10
+ #define DIGITAL_SERVO_TRI_PINMODE pinMode(2,OUTPUT); //PIN 2 //also right servo for BI COPTER
+ #define DIGITAL_SERVO_TRI_HIGH PORTE |= 1<<4;
+ #define DIGITAL_SERVO_TRI_LOW PORTE &= ~(1<<4);
+#else
+ #define MOTORPIN0 3
+ #define MOTORPIN1 9
+ #define MOTORPIN2 10
+ #define MOTORPIN3 11
+ #define DIGITAL_SERVO_TRI_PINMODE pinMode(3,OUTPUT); //also right servo for BI COPTER
+ #define DIGITAL_SERVO_TRI_HIGH PORTD |= 1<<3;
+ #define DIGITAL_SERVO_TRI_LOW PORTD &= ~(1<<3);
+#endif
+
+volatile uint8_t atomicServo = 125;
+
+
+void initializeServo() {
+ DIGITAL_SERVO_TRI_PINMODE
+ TCCR0A = 0; // normal counting mode
+ TIMSK0 |= (1< 4 us
+// 256 steps = 1 counter cycle = 1024 us
+// algorithm strategy:
+// pulse high servo 0 -> do nothing for 1000 us -> do nothing for [0 to 1000] us -> pulse down servo 0
+// pulse high servo 1 -> do nothing for 1000 us -> do nothing for [0 to 1000] us -> pulse down servo 1
+// pulse high servo 2 -> do nothing for 1000 us -> do nothing for [0 to 1000] us -> pulse down servo 2
+// pulse high servo 3 -> do nothing for 1000 us -> do nothing for [0 to 1000] us -> pulse down servo 3
+// do nothing for 14 x 1000 us
+ISR(TIMER0_COMPA_vect) {
+ static uint8_t state = 0;
+ static uint8_t count;
+ if (state == 0) {
+ //http://billgrundmann.wordpress.com/2009/03/03/to-use-or-not-use-writedigital/
+ DIGITAL_SERVO_TRI_HIGH
+ OCR0A+= 250; // 1000 us
+ state++ ;
+ } else if (state == 1) {
+ OCR0A+= atomicServo; // 1000 + [0-1020] us
+ state++;
+ } else if (state == 2) {
+ DIGITAL_SERVO_TRI_LOW
+ OCR0A+= 250; // 1000 us
+ state++;
+ } else if (state == 3) {
+ state++;
+ } else if (state == 4) {
+ state++;
+ OCR0A+= 250; // 1000 us
+ } else if (state == 5) {
+ state++;
+ } else if (state == 6) {
+ state++;
+ OCR0A+= 250; // 1000 us
+ } else if (state == 7) {
+ state++;
+ } else if (state == 8) {
+ count = 10; // 12 x 1000 us
+ state++;
+ OCR0A+= 250; // 1000 us
+ } else if (state == 9) {
+ if (count > 0) count--;
+ else state = 0;
+ OCR0A+= 250;
+ }
+}
+
+
+void initializeMotors(NB_Motors numbers) {
+
+ numberOfMotors = numbers;
+
+ pinMode(MOTORPIN0, OUTPUT);
+ pinMode(MOTORPIN1, OUTPUT);
+ pinMode(MOTORPIN2, OUTPUT);
+ pinMode(MOTORPIN3, OUTPUT);
+
+ initializeServo();
+
+ commandAllMotors(1000);
+}
+
+void writeMotors() {
+
+ atomicServo = (motorCommand[MOTOR1]-1000)/4;
+ analogWrite(MOTORPIN1, motorCommand[MOTOR2] / 8);
+ analogWrite(MOTORPIN2, motorCommand[MOTOR3] / 8);
+ analogWrite(MOTORPIN3, motorCommand[MOTOR4] / 8);
+}
+
+void commandAllMotors(int command) {
+
+ atomicServo = (command-1000)/4;
+ analogWrite(MOTORPIN1, command / 8);
+ analogWrite(MOTORPIN2, command / 8);
+ analogWrite(MOTORPIN3, command / 8);
+}
+
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_OSD/MAX7456.h b/Libraries/AQ_OSD/MAX7456.h
new file mode 100644
index 00000000..7eba7fe1
--- /dev/null
+++ b/Libraries/AQ_OSD/MAX7456.h
@@ -0,0 +1,673 @@
+/*
+ AeroQuad v3.0 - Nov 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+ */
+
+/*
+ This module provides on screen display (OSD) for Aeroquad FPV flying.
+
+ It can display
+ - artificial horizon with pitch lines
+ - battery information
+ - altitude (and altitude hold state and target )
+ - compass heading
+ - flight timer
+ - callsign
+ - RSSI information
+ - additional notification strings
+
+ You will need to upload a special character set initially using the
+ provided MAX7456_Font_Updater sketch.
+
+ The user must connect a MAX7456 OSD chip to the appropriate header pins on
+ the Arduino. These pins are marked 'OSD' on the AeroQuad Shield v2.
+
+ If the chip is not connected properly, this code may hang.
+
+ If using the SparkFun MAX7456 breakout board, the reset pin should be wired
+ high (+5V) either directly or with 10kOhm resistor.
+
+ As the MAX7456 may draw up to 100mA it is a good idea to power it using
+ separate regulator (or power it from one of the BEC:s on ESCs). It is known
+ that powering from arduino and using 3S battery will overheat the regulator
+ which will lead to crash.
+
+ Special thanks to Alamo for contributing this capability!
+
+ */
+
+#ifndef _AQ_OSD_MAX7456_H_
+#define _AQ_OSD_MAX7456_H_
+
+#include
+#include
+
+#include "OSD.h"
+#include "GlobalDefined.h"
+
+// You can configure positioning of various display elements below.
+// '#defines' for elements which will not be displayed, can be ignored.
+//
+// The MAX7456 overlays characters in a grid 30 characters wide, 16/13 high
+// (PAL/NTSC respectively). The row/column defines below correspond to
+// positions in the grid of characters, with the origin at the top left.
+// 0-origin indexing is used - ie row 0, col 0 is the highest, leftmost
+// character on the screen while row 15, col 29 is the bottom right (for PAL).
+//
+// Generally avoid using the extreme border rows/columns as they are not
+// always visible.
+//
+// Display elements start at the position you give and print to the right.
+// They will wrap around to the next row if there are too few columns remaining
+// on the row you specify.
+
+//Battery info - 5-16 characters long
+#define VOLTAGE_ROW 2
+#define VOLTAGE_COL 1
+
+//Compass reading - 5 characters long
+#define COMPASS_ROW 1
+#define COMPASS_COL 13
+
+//Altitude reading - up to 8 characters long (32768 max)
+#define ALTITUDE_ROW 1
+#define ALTITUDE_COL 1
+
+//Flight timer - 6 characters long
+#define TIMER_ROW 1
+#define TIMER_COL 23
+
+//Callsign
+#define CALLSIGN_ROW 2
+#define CALLSIGN_COL 23
+#ifdef ShowCallSign
+const char *callsign = "AeroQD";
+#endif
+
+// RSSI monitor
+#define RSSI_ROW 3
+#define RSSI_COL 23
+#define RSSI_PIN A6 // analog pin to read
+#define RSSI_RAWVAL // show raw A/D value instead of percents (for tuning)
+#define RSSI_100P 1023 // A/D value for 100%
+#define RSSI_0P 0 // A/D value for 0%
+#define RSSI_WARN 20 // show alarm at %
+
+// Notify
+#define NOTIFY_ROW MAX_screen_rows-3
+#define NOTIFY_COL 1 // don't change this, it needs a full line
+
+/********************** End of user configuration section ********************************/
+
+
+//MAX7456 register write addresses - see datasheet for lots of info
+#define DMM 0x04 //Display memory mode register - for choosing 16bit/8bit write mode, clearing display memory, enabling auto-increment
+#define DMAH 0x05 //Holds MSB of display memory address, for setting location of a character on display
+#define DMAL 0x06 //Holds remaining 8 bits of display memory address - 480 characters displayed -> 9 bits req'd for addressing
+#define DMDI 0x07 //Display memory data in - character address or attribute byte, depending on 8b/16b mode and DMAH[1]
+#define VM0 0x00 //Video mode 0 register - for choosing, NTSC/PAL, sync mode, OSD on/off, reset, VOUT on/off
+#define VM1 0x01 //Video mode 1 register - nothing very interesting in this one
+#define RB0 0x10 //Row 0 brightness register - 15 more follow sequentially (ending at 0x1F)
+#define STAT 0xA2 //Status register read address
+
+//MAX7456 commands - provided in datasheet.
+#define CLEAR_display 0x04
+#define CLEAR_display_vert 0x06
+#define END_string 0xff
+
+#define WHITE_level_90 0x02
+
+unsigned MAX_screen_size = 0;
+unsigned MAX_screen_rows = 0;
+byte ENABLE_display = 0;
+byte ENABLE_display_vert = 0;
+byte MAX7456_reset = 0;
+byte DISABLE_display = 0;
+
+//configuration for AI
+#define LINE_ROW_0 0x80 // character address of a character with a horizontal line in row 0. Other rows follow this one
+#define AI_MAX_PITCH_ANGLE (PI/4) // bounds of scale used for displaying pitch. When pitch is >= |this number|, the pitch lines will be at top or bottom of bounding box
+static const byte ROLL_COLUMNS[4] = {10,12,17,19}; // columns where the roll line is printed
+#define PITCH_L_COL 7
+#define PITCH_R_COL 22
+#define AI_DISPLAY_RECT_HEIGHT 9 // Height of rectangle bounding AI. Should be odd so that there is an equal space above/below the centre reticle
+
+#define RETICLE_ROW (MAX_screen_rows/2) // centre row - don't change this
+#define RETICLE_COL 14 // reticle will be in this col, and col to the right
+
+#define AI_TOP_PIXEL ((RETICLE_ROW - AI_DISPLAY_RECT_HEIGHT/2)*18)
+#define AI_BOTTOM_PIXEL ((RETICLE_ROW + AI_DISPLAY_RECT_HEIGHT/2)*18)
+#define AI_CENTRE (RETICLE_ROW*18+10) // row, in pixels, corresponding to zero pitch/roll.
+
+// void notifyOSD(byte flags, char *fmt, ...)
+// - display notification string on OSD
+//
+// void notifyOSDmenu(byte flags, byte cursorLeft, byte cursorRight, char *fmt, ...)
+// - display notification with blinking region = 'cursor'
+// - characters between cursorLeft and cursorRight will blink if OSD_CURSOR flag is used
+//
+// fmt == NULL will clear
+// flags -- message priority and options i.e. (OSD_CRIT|OSD_BLINK|OSD_CENTER)
+#define OSD_INFO 0x00
+#define OSD_WARN 0x40
+#define OSD_ERR 0x80
+#define OSD_CRIT 0xc0
+#define OSD_NOCLEAR 0x20 // do not clear the message after ~5s
+#define OSD_CURSOR 0x10 // enable cursor
+#define OSD_BLINK 0x08 // blinking message
+#define OSD_INVERT 0x04 // inverted message
+#define OSD_NOW 0x02 // show message immediately
+#define OSD_CENTER 0x01 // Justify at center
+
+
+byte osdNotificationTimeToShow = 0;
+byte osdNotificationFlags = 0;
+byte osdNotificationCursorL = 0;
+byte osdNotificationCursorR = 0;
+char osdNotificationBuffer[29]; // do not change this
+
+#define notifyOSD(flags,fmt,args...) notifyOSDmenu(flags,255,255,fmt, ## args)
+
+// Writes 'len' character address bytes to the display memory corresponding to row y, column x
+// - uses autoincrement mode when writing more than one character
+// - will wrap around to next row if 'len' is greater than the remaining cols in row y
+// - buf=NULL can be used to write zeroes (clear)
+// - flags: 0x01 blink, 0x02 invert (can be combined)
+void writeChars( const char* buf, byte len, byte flags, byte y, byte x ) {
+
+ unsigned offset = y * 30 + x;
+ spi_select();
+ // 16bit transfer, transparent BG, autoincrement mode (if len!=1)
+ spi_writereg(DMM, ((flags&1) ? 0x10 : 0x00) | ((flags&2) ? 0x08 : 0x00) | ((len!=1)?0x01:0x00) );
+
+ // send starting display memory address (position of text)
+ spi_writereg(DMAH, offset >> 8 );
+ spi_writereg(DMAL, offset & 0xff );
+
+ // write out data
+ for ( int i = 0; i < len; i++ ) {
+ spi_writereg(DMDI, buf==NULL?0:buf[i] );
+ }
+
+ // Send escape 11111111 to exit autoincrement mode
+ if (len!=1) {
+ spi_writereg(DMDI, END_string );
+ }
+ // finished writing
+ spi_deselect();
+}
+
+byte notifyOSDmenu(byte flags, byte cursorLeft, byte cursorRight, const char *fmt, ...) {
+
+ va_list ap;
+ if ((osdNotificationTimeToShow > 0) && ((flags >> 6) < (osdNotificationFlags >> 6))) {
+ return 1; // drop message, we tell it to caller
+ }
+ if (fmt == NULL) {
+ // clear
+ memset(osdNotificationBuffer, 0, 28);
+ osdNotificationFlags = 0;
+ }
+ else {
+ osdNotificationFlags = flags; // will set priority and flags
+ osdNotificationTimeToShow = (flags & OSD_NOCLEAR) ? 255 : 50; // set timeout for message
+ va_start(ap, fmt);
+ byte len=vsnprintf(osdNotificationBuffer, 29, fmt, ap);
+ va_end(ap);
+ if (len > 28) {
+ len = 28;
+ }
+ memset(osdNotificationBuffer+len, 0, 28-len);
+ if (flags & OSD_CENTER) {
+ byte i = (28 - len) / 2;
+ if (i) {
+ // move text right to center it
+ memmove(osdNotificationBuffer + i, osdNotificationBuffer, strlen(osdNotificationBuffer));
+ memset(osdNotificationBuffer, 0, i);
+ // adjust cursor position also if needed
+ if (flags & OSD_CURSOR) {
+ cursorLeft += i;
+ cursorRight += i;
+ }
+ }
+ }
+ osdNotificationCursorL = cursorLeft < 27 ? cursorLeft : 27;
+ osdNotificationCursorR = cursorRight < 27 ? cursorRight : 27;
+ }
+ if (flags & OSD_NOW) {
+ displayNotify();
+ }
+ else {
+ osdNotificationFlags |= OSD_NOW; // this will tell next update to show message
+ }
+ return 0;
+}
+
+void detectVideoStandard() {
+
+ // First set the default
+ boolean pal = false;
+ #ifdef PAL
+ pal = true;
+ #endif
+ #ifdef AUTODETECT_VIDEO_STANDARD
+ // if autodetect enabled modify the default if signal is present on either standard
+ // otherwise default is preserved
+ spi_select();
+ byte stat=spi_readreg(STAT);
+ if (stat & 0x01) {
+ pal = true;
+ }
+ if (stat & 0x02) {
+ pal = false;
+ }
+ spi_deselect();
+ #endif
+
+ if (pal) {
+ MAX_screen_size=480;
+ MAX_screen_rows=16;
+ ENABLE_display=0x48;
+ ENABLE_display_vert=0x4c;
+ MAX7456_reset=0x42;
+ DISABLE_display=0x40;
+ }
+ else {
+ MAX_screen_size=390;
+ MAX_screen_rows=13;
+ ENABLE_display=0x08;
+ ENABLE_display_vert=0x0c;
+ MAX7456_reset=0x02;
+ DISABLE_display=0x00;
+ }
+}
+
+//////////////////////////////////////////////////////////////////////////////
+/////////////////////////// Battery voltage Display //////////////////////////
+//////////////////////////////////////////////////////////////////////////////
+
+#ifdef BattMonitor
+
+#include "BatteryMonitorTypes.h"
+
+byte osdBatCounter = 0;
+boolean descentWarningShown = false;
+
+void displayVoltage(byte areMotorsArmed) {
+
+ byte osdBatNo = osdBatCounter % numberOfBatteries;
+ boolean osdBatMinMax = osdBatCounter / numberOfBatteries / 4;
+
+ // only show min/max values when not armed
+ if (areMotorsArmed == true) {
+ osdBatMinMax = false;
+ }
+
+ int currentValue;
+ if (osdBatMinMax) {
+ currentValue = batteryData[osdBatNo].minVoltage*10.0;
+ }
+ else {
+ currentValue = batteryData[osdBatNo].voltage*10.0;
+ }
+
+ char buf[12];
+ snprintf(buf,7,"%c%2d.%1dV",(osdBatMinMax) ? '\23' : '\20', currentValue/10,currentValue%10);
+
+ // Following blink only symbol on warning and all on alarm
+ writeChars( buf, 1, batteryIsWarning(osdBatNo)?1:0, VOLTAGE_ROW + osdBatNo, VOLTAGE_COL );
+ writeChars( buf+1, 5, batteryIsAlarm(osdBatNo)?1:0, VOLTAGE_ROW + osdBatNo, VOLTAGE_COL + 1 );
+
+ if (batteryData[osdBatNo].cPin != BM_NOPIN) {
+ // current sensor installed
+ if (osdBatMinMax) {
+ currentValue = batteryData[osdBatNo].maxCurrent*10.0;
+ }
+ else {
+ currentValue = batteryData[osdBatNo].current*10.0;
+ }
+ snprintf(buf,12,"%3d.%1dA%4u\24", currentValue/10,currentValue%10,(unsigned)batteryData[osdBatNo].usedCapacity);
+ writeChars( buf, 11, 0, VOLTAGE_ROW+osdBatNo, VOLTAGE_COL+6 );
+ }
+
+ osdBatCounter++;
+ if (osdBatCounter >= numberOfBatteries * 8) {
+ osdBatCounter = 0;
+ }
+
+ #if defined (BattMonitorAutoDescent)
+ if (batteryAlarm && areMotorsArmed) {
+ if (!descentWarningShown) {
+ notifyOSD(OSD_CENTER|OSD_CRIT|OSD_BLINK, "BAT. CRITICAL - DESCENTING");
+ descentWarningShown = true;
+ }
+ }
+ else {
+ descentWarningShown = false;
+ }
+ #endif
+}
+#endif
+
+//////////////////////////////////////////////////////////////////////////////
+/////////////////////////// AltitudeHold Display /////////////////////////////
+//////////////////////////////////////////////////////////////////////////////
+#if defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+
+int lastAltitude = 12345; // bogus initial values to force update
+int lastHoldAltitude = 12345;
+byte lastHoldState = 6;
+
+void displayAltitude(float readedAltitude, float desiredAltitudeToKeep, boolean altHoldState) {
+ #ifdef feet
+ int currentAltitude = readedAltitude*3.281;
+ int currentHoldAltitude = desiredAltitudeToKeep*3.281;
+ #else // metric
+ int currentAltitude = readedAltitude*10.0; // 0.1m accuracy!!
+ int currentHoldAltitude = desiredAltitudeToKeep*10.0;
+ #endif
+ char buf[7];
+
+ if ( lastAltitude != currentAltitude ) {
+ #ifdef feet
+ snprintf(buf,7,"\10%4df",currentAltitude);
+ #else
+ if (abs(currentAltitude)<100) {
+ snprintf(buf,7,"\010%c%1d.%1dm",currentAltitude < 0 ? '-' : ' ', abs(currentAltitude/10),abs(currentAltitude%10));
+ }
+ else {
+ snprintf(buf,7,"\010%4dm",currentAltitude/10);
+ }
+ #endif
+ writeChars( buf, 6, 0, ALTITUDE_ROW, ALTITUDE_COL );
+ lastAltitude = currentAltitude;
+ }
+
+ // AltitudeHold handling:
+ // - show hold altitude when it is active
+ // - show "panic" if 'paniced' out
+ boolean isWriteNeeded = false;
+ switch (altHoldState) {
+ case OFF:
+ if (lastHoldState != OFF) {
+ lastHoldState = OFF;
+ memset(buf,0,6);
+ isWriteNeeded = true;
+ }
+ break;
+ case ON:
+ if ((lastHoldState != ON) || (lastHoldAltitude != currentHoldAltitude)) {
+ lastHoldState = ON;
+ lastHoldAltitude=currentHoldAltitude;
+ #ifdef feet
+ snprintf(buf,7,"\11%4df",currentHoldAltitude);
+ #else
+ if (abs(currentHoldAltitude)<100) {
+ snprintf(buf,7,"\011%c%1d.%1dm", currentHoldAltitude < 0 ? '-' : ' ',abs(currentHoldAltitude/10),abs(currentHoldAltitude%10));
+ }
+ else {
+ snprintf(buf,7,"\011%4dm",currentHoldAltitude/10);
+ }
+ #endif
+ isWriteNeeded = true;
+ }
+ break;
+ case ALTPANIC:
+ if (lastHoldState != ALTPANIC) {
+ lastHoldState = ALTPANIC;
+ snprintf(buf,7,"\11panic");
+ isWriteNeeded = true;
+ }
+ break;
+ }
+
+ if (isWriteNeeded) {
+ writeChars( buf, 6, 0, ALTITUDE_ROW, ALTITUDE_COL+6 );
+ }
+}
+#endif
+
+//////////////////////////////////////////////////////////////////////////////
+/////////////////////////// HeadingMagHold Display ///////////////////////////
+//////////////////////////////////////////////////////////////////////////////
+#ifdef HeadingMagHold
+
+int lastHeading = 361; // bogus to force update
+
+void displayHeading(int currentHeading) {
+
+ if (currentHeading != lastHeading) {
+ char buf[6];
+ snprintf(buf,6,"\6%3d\7",currentHeading); // \6 is compass \7 is degree symbol
+ writeChars( buf, 5, 0, COMPASS_ROW, COMPASS_COL );
+ lastHeading = currentHeading;
+ }
+}
+#endif
+
+//////////////////////////////////////////////////////////////////////////////
+/////////////////////////// Flight time Display //////////////////////////////
+//////////////////////////////////////////////////////////////////////////////
+#ifdef ShowFlightTimer
+
+unsigned long prevTime = 0; // previous time since start when OSD.update() ran
+unsigned int prevArmedTimeSecs = 111; // bogus to force update
+unsigned long armedTime = 0; // time motors have spent armed
+
+void displayFlightTime(byte areMotorsArmed) {
+ if (areMotorsArmed == ON) {
+ armedTime += ( currentTime-prevTime );
+ }
+
+ prevTime = currentTime;
+ unsigned int armedTimeSecs = armedTime / 1000000;
+ if (armedTimeSecs != prevArmedTimeSecs) {
+ prevArmedTimeSecs = armedTimeSecs;
+ char buf[7];
+ snprintf(buf,7,"\5%02u:%02u",armedTimeSecs/60,armedTimeSecs%60);
+ writeChars(buf, 6, 0, TIMER_ROW, TIMER_COL );
+ }
+}
+#endif
+
+//////////////////////////////////////////////////////////////////////////////
+/////////////////////////// RSSI Display /////////////////////////////////////
+//////////////////////////////////////////////////////////////////////////////
+// Show RSSI information (analog input value optionally mapped to percents.)
+#ifdef ShowRSSI
+
+short lastRSSI = 1234; //forces update at first run
+
+void displayRSSI() {
+
+ int val = analogRead(RSSI_PIN);
+ #ifndef RSSI_RAWVAL
+ val = (val - RSSI_0P) * 100 / (RSSI_100P - RSSI_0P);
+ if (val < 0) {
+ val = 0;
+ }
+ if (val > 100) {
+ val = 100;
+ }
+ #endif
+ if (val != lastRSSI) {
+ lastRSSI = val;
+ char buf[6];
+ #ifdef RSSI_RAWVAL
+ snprintf(buf, 6, "\372%4u", val);
+ writeChars(buf, 5, 0, RSSI_ROW, RSSI_COL);
+ #else
+ snprintf(buf, 6, "\372%3u%%", val);
+ writeChars(buf, 5, (RSSI_WARN>val)?1:0, RSSI_ROW, RSSI_COL);
+ #endif
+ }
+}
+#endif
+
+//////////////////////////////////////////////////////////////////////////////
+/////////////////////////// ATTITUDE Display /////////////////////////////////
+//////////////////////////////////////////////////////////////////////////////
+#ifdef ShowAttitudeIndicator
+
+byte AIoldline[5] = {0,0,0,0,0};
+
+void displayArtificialHorizon(float roll, float pitch) {
+
+ short AIrows[5] = {0,0,0,0,0}; //Holds the row, in pixels, of AI elements: pitch then roll from left to right.
+ //Calculate row of new pitch lines
+ AIrows[0] = constrain( (int)AI_CENTRE + (int)((pitch/AI_MAX_PITCH_ANGLE)*(AI_CENTRE-AI_TOP_PIXEL) ), AI_TOP_PIXEL, AI_BOTTOM_PIXEL ); //centre + proportion of full scale
+ char pitchLine = LINE_ROW_0 + (AIrows[0] % 18);
+
+ if (AIoldline[0] != AIrows[0]/18) {
+ //Remove old pitch lines if not overwritten by new ones
+ writeChars( NULL, 1, 0, AIoldline[0], PITCH_L_COL );
+ writeChars( NULL, 1, 0, AIoldline[0], PITCH_R_COL );
+ AIoldline[0] = AIrows[0]/18;
+ }
+
+ //Write new pitch lines
+ writeChars( &pitchLine, 1, 0, AIoldline[0], PITCH_L_COL );
+ writeChars( &pitchLine, 1, 0, AIoldline[0], PITCH_R_COL );
+
+ //Calculate row (in pixels) of new roll lines
+ int distFar = (ROLL_COLUMNS[3] - (RETICLE_COL + 1))*12 + 6; //horizontal pixels between centre of reticle and centre of far angle line
+ int distNear = (ROLL_COLUMNS[2] - (RETICLE_COL + 1))*12 + 6;
+ float gradient = 1.4 * roll; // was "tan(roll)", yes rude but damn fast !!
+ AIrows[4] = constrain( AI_CENTRE - (int)(((float)distFar)*gradient), AI_TOP_PIXEL, AI_BOTTOM_PIXEL );
+ AIrows[3] = constrain( AI_CENTRE - (int)(((float)distNear)*gradient), AI_TOP_PIXEL, AI_BOTTOM_PIXEL );
+ AIrows[1] = constrain( 2*AI_CENTRE - AIrows[4], AI_TOP_PIXEL, AI_BOTTOM_PIXEL );
+ AIrows[2] = constrain( 2*AI_CENTRE - AIrows[3], AI_TOP_PIXEL, AI_BOTTOM_PIXEL );
+
+ //writing new roll lines to screen
+ for (byte i=1; i<5; i++ ) {
+ // clear previous roll lines if not going to overwrite
+ if (AIoldline[i] != AIrows[i]/18) {
+ writeChars( NULL, 1, 0, AIoldline[i], ROLL_COLUMNS[i-1] );
+ AIoldline[i] = AIrows[i]/18;
+ }
+ //converting rows (in pixels) to character addresses used for the 'lines'
+ char RollLine = LINE_ROW_0 + (AIrows[i] % 18);
+ writeChars( &RollLine, 1, 0, AIoldline[i], ROLL_COLUMNS[i-1] );
+ }
+}
+#endif
+
+//////////////////////////////////////////////////////////////////////////////
+/////////////////////////// Reticle Display //////////////////////////////////
+//////////////////////////////////////////////////////////////////////////////
+// Reticle on the center of the screen
+// We have two reticles empty one for RATE_FLIGHT_MODE and one with (s) for 'ATTITUDE_FLIGHT_MODE' mode
+#ifdef ShowReticle
+
+byte lastFlightMode = 9;
+
+void displayReticle(byte flightMode) {
+
+ if (lastFlightMode != flightMode) {
+ writeChars( (flightMode == 0) ? "\1\2" : "\3\4", 2, 0, RETICLE_ROW, RETICLE_COL ); //write 2 chars to row (middle), column 14
+ lastFlightMode = flightMode;
+ }
+}
+#endif
+
+
+byte displayNotify(){
+
+ if (osdNotificationFlags & OSD_NOW) {
+ osdNotificationFlags &= ~OSD_NOW;
+ // we have new message to show
+
+ if ((osdNotificationFlags&OSD_CURSOR) && (osdNotificationCursorL!=255)) {
+
+ if (osdNotificationCursorL > 0) {
+ writeChars(osdNotificationBuffer,osdNotificationCursorL,
+ ((osdNotificationFlags&OSD_INVERT)?2:0)|((osdNotificationFlags&OSD_BLINK)?1:0),
+ NOTIFY_ROW,NOTIFY_COL);
+ }
+
+ writeChars(osdNotificationBuffer+osdNotificationCursorL,osdNotificationCursorR-osdNotificationCursorL+1,
+ ((osdNotificationFlags&OSD_INVERT)?2:0)|((osdNotificationFlags&OSD_BLINK)?0:1),
+ NOTIFY_ROW,NOTIFY_COL+osdNotificationCursorL);
+
+ if (osdNotificationCursorR < 27) {
+ writeChars(osdNotificationBuffer+osdNotificationCursorR+1,27-osdNotificationCursorR,
+ ((osdNotificationFlags&OSD_INVERT)?2:0)|((osdNotificationFlags&OSD_BLINK)?1:0),
+ NOTIFY_ROW,NOTIFY_COL+osdNotificationCursorR+1);
+ }
+ }
+ else {
+ writeChars(osdNotificationBuffer,28,
+ ((osdNotificationFlags&OSD_INVERT)?2:0)|((osdNotificationFlags&OSD_BLINK)?1:0),
+ NOTIFY_ROW,NOTIFY_COL);
+ }
+ return 1;
+ }
+
+ if ((osdNotificationTimeToShow > 0) && (osdNotificationTimeToShow != 255)) {
+ if (osdNotificationTimeToShow-- == 1) {
+ writeChars(NULL,28,0,NOTIFY_ROW,NOTIFY_COL);
+ return 1;
+ }
+ }
+ return 0; // nothing was done
+}
+
+void initializeOSD() {
+
+ // SPCR = 01010000
+ // interrupt disabled,spi enabled,msb 1st,master,clk low when idle,
+ // sample on leading edge of clk,system clock/4 rate (fastest)
+ SPCR = (1 << SPE) | (1 << MSTR);
+ SPSR; // dummy read from HW register
+ SPDR; // dummy read from HW register
+ delay( 10 );
+
+ detectVideoStandard();
+
+ //Soft reset the MAX7456 - clear display memory
+ spi_select();
+ spi_writereg( VM0, MAX7456_reset );
+ spi_deselect();
+ delay( 1 ); //Only takes ~100us typically
+
+ //Set white level to 90% for all rows
+ spi_select();
+ for( int i = 0; i < MAX_screen_rows; i++ ) {
+ spi_writereg( RB0 + i, WHITE_level_90 );
+ }
+
+ //ensure device is enabled
+ spi_writereg( VM0, ENABLE_display );
+ delay(100);
+ //finished writing
+ spi_deselect();
+
+ OSDsched = 0xff; // This will make everything to be updated next round
+ updateOSD(); // Make first update now
+
+ #ifdef ShowCallSign
+ writeChars(callsign,strlen(callsign),0,CALLSIGN_ROW,CALLSIGN_COL);
+ #endif
+
+ // show notification of active video format
+ notifyOSD(OSD_NOW, "VIDEO: %s", (DISABLE_display) ? "PAL" : "NTSC");
+}
+
+#endif // #define _AQ_OSD_MAX7456_H_
+
+
diff --git a/Libraries/AQ_OSD/OSD.h b/Libraries/AQ_OSD/OSD.h
new file mode 100644
index 00000000..c914bb4e
--- /dev/null
+++ b/Libraries/AQ_OSD/OSD.h
@@ -0,0 +1,53 @@
+/*
+ AeroQuad v3.0 - Nov 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+ */
+
+#ifndef _AQ_OSD_H_
+#define _AQ_OSD_H_
+
+byte OSDsched = 0;
+
+#ifdef BattMonitor
+ void displayVoltage(byte areMotorsArmed);
+#endif
+#if defined AltitudeHoldBaro || defined AltitudeHoldRangeFinder
+ void displayAltitude(float readedAltitude, float desiredAltitudeToKeep, boolean altitudeHoldState);
+#endif
+#ifdef HeadingMagHold
+ void displayHeading(int currentHeading);
+#endif
+#ifdef ShowFlightTimer
+ void displayFlightTime(byte areMotorsArmed);
+#endif
+#ifdef ShowRSSI
+ void displayRSSI();
+#endif
+#ifdef ShowAttitudeIndicator
+ void displayArtificialHorizon(float roll, float pitch);
+#endif
+#ifdef ShowReticle
+ void displayReticle(byte flightMode);
+#endif
+
+void initializeOSD();
+void updateOSD();
+byte displayNotify();
+byte notifyOSDmenu(byte flags, byte cursorLeft, byte cursorRight, const char *fmt, ...);
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_Platform_APM/APM_ADC.h b/Libraries/AQ_Platform_APM/APM_ADC.h
new file mode 100644
index 00000000..a89e044a
--- /dev/null
+++ b/Libraries/AQ_Platform_APM/APM_ADC.h
@@ -0,0 +1,129 @@
+/*
+ AeroQuad v2.2 - Feburary 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _APM_ADC_H_
+#define _APM_ADC_H_
+
+#if defined (__AVR_ATmega1280__) || defined (__AVR_ATmega2560__)
+
+
+#include
+#include
+
+#define bit_set(p,m) ((p) |= (1<= 16) {
+ adc_value[ch] /=2;
+ adc_counter[ch] /=2;
+ }
+ adc_tmp = adcSpiTransfer(0) << 8; // Read first byte
+ adc_tmp |= adcSpiTransfer(adc_cmd[ch+1]); // Read second byte and send next command
+ adc_value[ch] += adc_tmp >> 3; // Shift to 12 bits
+ adc_counter[ch]++; // Number of samples
+ }
+ bit_set(PORTC,4); // Disable Chip Select (PIN PC4)
+ //bit_clear(PORTL,6); // To test performance
+ TCNT2 = 104; // 400 Hz
+}
+
+void initializeADC() {
+ unsigned char tmp;
+
+ pinMode(ADC_CHIP_SELECT,OUTPUT);
+
+ digitalWrite(ADC_CHIP_SELECT,HIGH); // Disable device (Chip select is active low)
+
+ // Setup Serial Port2 in SPI mode
+ UBRR2 = 0;
+ DDRH |= (1<0)
+ result = adc_value[ch_num]/adc_counter[ch_num];
+ else
+ result = 0;
+ adc_value[ch_num] = 0; // Initialize for next reading
+ adc_counter[ch_num] = 0;
+ sei();
+ return(result);
+}
+
+#endif // #if defined (__AVR_ATmega1280__) || defined (__AVR_ATmega2560__)
+
+#endif //#define _APM_ADC_H_
diff --git a/Libraries/AQ_Platform_APM/APM_ADC_Optimized.h b/Libraries/AQ_Platform_APM/APM_ADC_Optimized.h
new file mode 100644
index 00000000..81fdd304
--- /dev/null
+++ b/Libraries/AQ_Platform_APM/APM_ADC_Optimized.h
@@ -0,0 +1,248 @@
+/*
+ AeroQuad v2.2 - Feburary 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _APM_ADC_OPTIMIZED_H_
+#define _APM_ADC_OPTIMIZED_H_
+
+#if defined (__AVR_ATmega1280__) || defined (__AVR_ATmega2560__)
+
+
+#include
+#include
+
+//#define SPI_MEASURE
+#define ADC_SPI_LASTCHANNEL 6
+
+#define bit_set(p,m) ((p) |= (1<cmd;
+ for (uint8_t ch = 0; ch < ADC_SPI_LASTCHANNEL; ch++) {
+ ADCValue.highByte = ADC_SPI_WaitReadByte(); // read high byte
+ ADC_SPI_WaitSendByte(cmd); // select next ADC input
+
+ // after sending a byte, we have 8 SPI clock cycles time,
+ // which is 3us at 375ns cycle time
+ p++;
+ cmd = (p+1)->cmd;
+ p->numberOfSamples++;
+ if(p->numberOfSamples == 0) { // during start up the counter could overrun
+ p->numberOfSamples = 1; // this does not happen during normal operation
+ p->value = 0; // so dropping the old values is fine here
+ }
+
+ ADCValue.lowByte = ADC_SPI_WaitReadByte(); // read low byte
+ if(ch != ADC_SPI_LASTCHANNEL-1) {
+ ADC_SPI_WaitSendByte(0);
+ }
+
+ // after sending a byte, we have 8 SPI clock cycles time
+ // which is 3us at 375ns cycle time
+ p->value += ADCValue.val;
+ }
+
+ DisableADCChipSelect();
+ //bit_clear(PORTL,6); // To test performance
+
+#ifdef SPI_MEASURE
+ unsigned long t1 = micros();
+
+ if(adcloop++ == 0)
+ {
+ Serial.println(t1-t0);
+ }
+#endif
+
+ //TCNT2 = SPI_CLOCK_RATE_2_COUNTER_START_VALUE(411);
+ TCNT2 = SPI_CLOCK_RATE_2_COUNTER_START_VALUE(1000);
+}
+
+ISR (TIMER2_OVF_vect) {
+ ReadADCs();
+}
+
+
+
+void zero_ArduCopter_ADC(void) {
+ cli();
+ for (byte i=0; i < sizeof(ADCData)/sizeof(ADCData[0]); i++) {
+ ADCData[i].value = 0;
+ ADCData[i].numberOfSamples = 0;
+ }
+ sei();
+}
+
+void initializeADC(void) {
+ zero_ArduCopter_ADC();
+ for (byte i=0; i < sizeof(ADCData)/sizeof(ADCData[0]); i++) {
+ ADCData[i].cmd = adc_cmd[i+1];
+ }
+ ADCData[ADC_SPI_LASTCHANNEL-1].cmd = 0;
+
+
+ pinMode(ADC_CHIP_SELECT,OUTPUT);
+ DisableADCChipSelect();
+
+ // Setup Serial Port2 in SPI mode
+ UBRR2 = 0;
+ DDRH |= (1<numberOfSamples > 0)
+ result = p->value/(p->numberOfSamples*8);
+ else
+ result = 0;
+
+ p->value = 0; // Initialize for next reading
+ p->numberOfSamples = 0;
+ sei();
+
+ return(result);
+}
+
+#endif // #if defined (__AVR_ATmega1280__) || defined (__AVR_ATmega2560__)
+
+#endif //#define _APM_ADC_OPTIMIZED_H_
diff --git a/Libraries/AQ_Platform_APM/APM_RC.h b/Libraries/AQ_Platform_APM/APM_RC.h
new file mode 100644
index 00000000..f4487e17
--- /dev/null
+++ b/Libraries/AQ_Platform_APM/APM_RC.h
@@ -0,0 +1,190 @@
+/*
+ AeroQuad v2.2 - Feburary 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _APM_RC_H_
+#define _APM_RC_H_
+
+#if defined (__AVR_ATmega1280__) || defined (__AVR_ATmega2560__)
+
+#include
+#include "Arduino.h"
+
+#define NUM_CHANNELS 8
+#define MIN_PULSEWIDTH 900
+#define MAX_PULSEWIDTH 2100
+
+// Variable definition for Input Capture interrupt
+volatile unsigned int ICR4_old = 0;
+volatile unsigned char PPM_Counter = 0;
+volatile uint16_t PWM_RAW[8] = {2400,2400,2400,2400,2400,2400,2400,2400};
+volatile unsigned char radio_status = 0;
+
+/****************************************************
+ Input Capture Interrupt ICP4 => PPM signal read
+ ****************************************************/
+ISR(TIMER4_CAPT_vect)
+{
+ unsigned int Pulse;
+ unsigned int Pulse_Width;
+
+ Pulse=ICR4;
+ if (Pulse8000) // SYNC pulse?
+ PPM_Counter=0;
+ else
+ {
+ PPM_Counter &= 0x07; // For safety only (limit PPM_Counter to 7)
+ PWM_RAW[PPM_Counter++]=Pulse_Width; //Saving pulse.
+ if (PPM_Counter >= NUM_CHANNELS)
+ radio_status = 1;
+ }
+ ICR4_old = Pulse;
+}
+
+
+
+// Public Methods //////////////////////////////////////////////////////////////
+void initRC()
+{
+ // Init PWM Timer 1
+ pinMode(11,OUTPUT); //OUT9 (PB5/OC1A)
+ pinMode(12,OUTPUT); //OUT2 (PB6/OC1B)
+ pinMode(13,OUTPUT); //OUT3 (PB7/OC1C)
+
+ //Remember the registers not declared here remains zero by default...
+ TCCR1A =((1<>1; // Because timer runs at 0.5us we need to do value/2
+ result2 = PWM_RAW[ch]>>1;
+ if (result != result2)
+ result = PWM_RAW[ch]>>1; // if the results are different we make a third reading (this should be fine)
+
+ // Limit values to a valid range
+ result = constrain(result,MIN_PULSEWIDTH,MAX_PULSEWIDTH);
+ radio_status=0; // Radio channel read
+ return(result);
+}
+
+unsigned char isNewReiceiverDataAvailable()
+{
+ return(radio_status);
+}
+
+// InstantPWM implementation
+// This function forces the PWM output (reset PWM) on Out0 and Out1 (Timer5). For quadcopters use
+void force_Out0_Out1()
+{
+ if (TCNT5>5000) // We take care that there are not a pulse in the output
+ TCNT5=39990; // This forces the PWM output to reset in 5us (10 counts of 0.5us). The counter resets at 40000
+}
+// This function forces the PWM output (reset PWM) on Out2 and Out3 (Timer1). For quadcopters use
+void force_Out2_Out3()
+{
+ if (TCNT1>5000)
+ TCNT1=39990;
+}
+// This function forces the PWM output (reset PWM) on Out6 and Out7 (Timer3). For quadcopters use
+void force_Out6_Out7()
+{
+ if (TCNT3>5000)
+ TCNT3=39990;
+}
+
+#endif // #if defined (__AVR_ATmega1280__)
+
+#endif //#define _APM_ADC_H_
\ No newline at end of file
diff --git a/Libraries/AQ_Platform_CHR6DM/Platform_CHR6DM.h b/Libraries/AQ_Platform_CHR6DM/Platform_CHR6DM.h
new file mode 100644
index 00000000..affb4acc
--- /dev/null
+++ b/Libraries/AQ_Platform_CHR6DM/Platform_CHR6DM.h
@@ -0,0 +1,493 @@
+/*
+ AeroQuad v2.4 - April 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+// Written by Lokling & Honk: http://aeroquad.com/showthread.php?1287-Experimental-CHR6DM-sensor-board
+
+// Usage: define a global var such as "CHR6DM chr6 ;" in Aeroquad.pde
+// Values can then be read such as chr6.data.pitch and so on
+
+#if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+
+#ifndef _AEROQUAD_PLATFORM_CHR6DM_H_
+#define _AEROQUAD_PLATFORM_CHR6DM_H_
+
+#include "Arduino.h"
+
+#define DEFAULT_TIMEOUT 1000
+
+
+
+// Null packet
+
+ const int NO_DATA = 0x00;
+ const int FAILED_CHECKSUM = 0x01;
+
+
+ int packet[100];
+ int packet_length = 0;
+
+ // Client command packets
+ const int SET_ACTIVE_CHANNELS = 0x80;
+ const int SET_SILENT_MODE = 0x81;
+ const int SET_BROADCAST_MODE = 0x82;
+ const int SET_GYRO_BIAS = 0x83;
+ const int SET_ACCEL_BIAS = 0x84;
+ const int SET_ACCEL_REF_VECTOR = 0x85;
+ const int AUTO_SET_ACCEL_REF = 0x86;
+ const int ZERO_RATE_GYROS = 0x87;
+ const int SELF_TEST = 0x88;
+ const int SET_START_CAL = 0x89;
+ const int SET_PROCESS_COVARIANCE = 0x8A;
+ const int SET_MAG_COVARIANCE = 0x8B;
+ const int SET_ACCEL_COVARIANCE = 0x8C;
+ const int SET_EKF_CONFIG = 0x8D;
+ const int SET_GYRO_ALIGNMENT = 0x8E;
+ const int SET_ACCEL_ALIGNMENT = 0x8F;
+ const int SET_MAG_REF_VECTOR = 0x90;
+ const int AUTO_SET_MAG_REF = 0x91;
+ const int SET_MAG_CAL = 0x92;
+ const int SET_MAG_BIAS = 0x93;
+ const int SET_GYRO_SCALE = 0x94;
+ const int EKF_RESET = 0x95;
+ const int RESET_TO_FACTORY = 0x96;
+ const int WRITE_TO_FLASH = 0xA0;
+ const int GET_DATA = 0x01;
+ const int GET_ACTIVE_CHANNELS = 0x02;
+ const int GET_BROADCAST_MODE = 0x03;
+ const int GET_ACCEL_BIAS = 0x04;
+ const int GET_ACCEL_REF_VECTOR = 0x05;
+ const int GET_GYRO_BIAS = 0x06;
+ const int GET_GYRO_SCALE = 0x07;
+ const int GET_START_CAL = 0x08;
+ const int GET_EKF_CONFIG = 0x09;
+ const int GET_ACCEL_COVARIANCE = 0x0A;
+ const int GET_MAG_COVARIANCE = 0x0B;
+ const int GET_PROCESS_COVARIANCE = 0x0C;
+ const int GET_STATE_COVARIANCE = 0x0D;
+ const int GET_GYRO_ALIGNMENT = 0x0E;
+ const int GET_ACCEL_ALIGNMENT = 0x0F;
+ const int GET_MAG_REF_VECTOR = 0x10;
+ const int GET_MAG_CAL = 0x11;
+ const int GET_MAG_BIAS = 0x12;
+
+ // Board status and data packets
+ const int COMMAND_COMPLETE = 0xB0;
+ const int COMMAND_FAILED = 0xB1;
+ const int BAD_CHECKSUM = 0xB2;
+ const int BAD_DATA_LENGTH = 0xB3;
+ const int UNRECOGNIZED_PACKET = 0xB4;
+ const int BUFFER_OVERFLOW = 0xB5;
+ const int STATUS_REPORT = 0xB6;
+ const int SENSOR_DATA = 0xB7;
+ const int GYRO_BIAS_REPORT = 0xB8;
+ const int GYRO_SCALE_REPORT = 0xB9;
+ const int START_CAL_REPORT = 0xBA;
+ const int ACCEL_BIAS_REPORT = 0xBB;
+ const int ACCEL_REF_VECTOR_REPORT = 0xBC;
+ const int ACTIVE_CHANNEL_REPORT = 0xBD;
+ const int ACCEL_COVARIANCE_REPORT = 0xBE;
+ const int MAG_COVARIANCE_REPORT = 0xBF;
+ const int PROCESS_COVARIANCE_REPORT = 0xC0;
+ const int STATE_COVARIANCE_REPORT = 0xC1;
+ const int EKF_CONFIG_REPORT = 0xC2;
+ const int GYRO_ALIGNMENT_REPORT = 0xC3;
+ const int ACCEL_ALIGNMENT_REPORT = 0xC4;
+ const int MAG_REF_VECTOR_REPORT = 0xC5;
+ const int MAG_CAL_REPORT = 0xC6;
+ const int MAG_BIAS_REPORT = 0xC7;
+ const int BROADCAST_MODE_REPORT = 0xC8;
+
+
+ const int CHANNEL_YAW_MASK = 1<<15;
+ const int CHANNEL_PITCH_MASK = 1<<14;
+ const int CHANNEL_ROLL_MASK = 1<<13;
+ const int CHANNEL_YAW_RATE_MASK = 1<<12;
+ const int CHANNEL_PITCH_RATE_MASK = 1<<11;
+ const int CHANNEL_ROLL_RATE_MASK = 1<<10;
+ const int CHANNEL_MX_MASK = 1<<9;
+ const int CHANNEL_MY_MASK = 1<<8;
+ const int CHANNEL_MZ_MASK = 1<<7;
+ const int CHANNEL_GX_MASK = 1<<6;
+ const int CHANNEL_GY_MASK = 1<<5;
+ const int CHANNEL_GZ_MASK = 1<<4;
+ const int CHANNEL_AY_MASK = 1<<3;
+ const int CHANNEL_AX_MASK = 1<<2;
+ const int CHANNEL_AZ_MASK = 1<<1;
+ const int CHANNEL_ALL_MASK = 65535;
+
+
+ // Scale factors
+ const double SCALE_YAW = 0.0109863; // �/LSB
+ const double SCALE_PITCH = 0.0109863;
+ const double SCALE_ROLL = 0.0109863;
+ const double SCALE_YAW_RATE = 0.0137329; // �/s/LSB
+ const double SCALE_PITCH_RATE = 0.0137329;
+ const double SCALE_ROLL_RATE = 0.0137329;
+ const double SCALE_MAG_X = 0.061035; // mGauss/LSB
+ const double SCALE_MAG_Y = 0.061035;
+ const double SCALE_MAG_Z = 0.061035;
+ const double SCALE_GYRO_X = 0.01812; // �/s/LSB
+ const double SCALE_GYRO_Y = 0.01812;
+ const double SCALE_GYRO_Z = 0.01812;
+ const double SCALE_ACCEL_X = 0.106812; // mg/LSB
+ const double SCALE_ACCEL_Y = 0.106812;
+ const double SCALE_ACCEL_Z = 0.106812;
+
+ const char PACKET_HEADER[] = {'s','n','p'};
+ const int HEADER_CHECKSUM = 's'+'n'+'p';
+
+
+#include
+
+
+
+
+class Data{
+
+public:
+ bool yawEnabled;
+ bool pitchEnabled;
+ bool rollEnabled;
+ bool yawRateEnabled;
+ bool pitchRateEnabled;
+ bool rollRateEnabled;
+ bool mxEnabled;
+ bool myEnabled;
+ bool mzEnabled;
+ bool gxEnabled;
+ bool gyEnabled;
+ bool gzEnabled;
+ bool axEnabled;
+ bool ayEnabled;
+ bool azEnabled;
+
+ double yaw;
+ double pitch;
+ double roll;
+ double yawRate;
+ double pitchRate;
+ double rollRate;
+ double mx;
+ double my;
+ double mz;
+ double gx;
+ double gy;
+ double gz;
+ double ax;
+ double ay;
+ double az;
+ };
+
+
+
+
+class CHR6DM {
+
+public:
+
+
+ CHR6DM(void){
+ //Nothing here
+ }
+
+
+
+ Data data;
+
+ void EKFReset() {
+ sendPacket(EKF_RESET);
+ waitForAck(DEFAULT_TIMEOUT);
+ }
+
+ void writeToFlash() {
+ sendPacket(WRITE_TO_FLASH);
+ waitForAck(5000);
+ }
+
+
+ int readPacket() {
+
+ if (!syncToHeader()){
+ //Serial.println("Not synced to header");
+ packet[0]= NO_DATA;
+ packet_length=1;
+ return NO_DATA;
+ }
+
+
+ int packetType = blockingRead();
+ int dataBytes = blockingRead();
+
+ int calculatedChecksum = HEADER_CHECKSUM + packetType + dataBytes;
+
+ int length = dataBytes+1;
+ packet[0] = packetType;
+
+ for (int i = 1; i <= dataBytes ;i++ ){
+ packet[i] = blockingRead() ;
+ calculatedChecksum+=packet[i];
+ }
+
+ int high = blockingRead();
+ int low = blockingRead();
+
+ int packetChecksum = bytesToSignedShort(high,low);
+
+ if (calculatedChecksum!=packetChecksum) {
+ //Serial.print("Bad checksum ");Serial.print(" calculated="); Serial.print(calculatedChecksum);Serial.print(" actual="); Serial.println(packetChecksum);
+ packet[0] = FAILED_CHECKSUM;
+ packet_length=1;
+ return FAILED_CHECKSUM;
+ }
+
+ packet_length=length;
+ return packet[0];
+
+ }
+
+ int blockingRead(){
+ int read=-1;
+
+ long starttime = millis();
+ while(read==-1 && (millis()-starttime)<100){
+ read = Serial1.read();
+ }
+
+ return read;
+ }
+
+ bool syncToHeader() {
+
+ int MAX_PACKET_LENGTH = 41; // TODO - Unsure about this, calculate the actual
+ int available = Serial1.available();
+
+ if (available > MAX_PACKET_LENGTH ){
+ for (int i = 0; i < available - MAX_PACKET_LENGTH; i++){
+ Serial1.read();
+ }
+ }
+
+ while (Serial1.available()>0){
+ if (blockingRead()==PACKET_HEADER[0] && blockingRead()==PACKET_HEADER[1] && blockingRead()==PACKET_HEADER[2] ) return true;
+ }
+
+ return false;
+ }
+
+
+ void resetToFactory() {
+ sendPacket(RESET_TO_FACTORY);
+ }
+
+ bool setActiveChannels(int channels) {
+ sendPacket(SET_ACTIVE_CHANNELS,(int[]){channels},1);
+ return waitForAck(DEFAULT_TIMEOUT);
+ }
+
+
+ void setBroadCastMode(int x) {
+ sendPacket(SET_BROADCAST_MODE,(int[]){x},1);
+ }
+
+ void sendPacket(int command) {
+ sendPacket(command,0,0);
+ }
+
+ void sendPacket(int command, int* bytes, int byteslength) {
+
+ int checksum = 0;
+ int buffer[] = {'s','n','p',command,byteslength};
+ int bufferlength=5;
+ for (int i = 0; i < bufferlength; i++) {
+ Serial1.write(buffer[i]);
+ checksum+=buffer[i];
+ }
+
+ for (int i = 0; i < byteslength; i++) {
+ Serial1.write(bytes[i]);
+ checksum+=bytes[i];
+
+ }
+
+ Serial1.write(checksum>>8);
+ Serial1.write(checksum);
+
+ }
+
+ bool requestPacket(){
+ sendPacket(GET_DATA);
+ }
+
+ bool waitForAndReadPacket(){
+ waitFor(SENSOR_DATA, DEFAULT_TIMEOUT);
+ }
+
+ bool requestAndReadPacket() {
+ requestPacket();
+ return waitForAndReadPacket();
+ }
+
+
+ bool waitFor(int command,int timeout) {
+
+ long startTime = millis();
+ while((millis()-startTime)1){
+ bool result = decodePacket();
+
+ if (packetType==command){
+ return result;
+ } /*else {
+ Serial.println("Didnt get the expected.. looping");
+ }
+ */
+ }
+
+ }
+
+ //Serial.println("Timed out !");
+ return false;
+ }
+
+ bool decodePacket() {
+ int index = 0;
+ switch (packet[index++]) {
+ case SENSOR_DATA: {
+
+ int flags = bytesToSignedShort(packet[index++],packet[index++]);
+
+ data.yawEnabled = (flags & CHANNEL_YAW_MASK ) == CHANNEL_YAW_MASK;
+ data.pitchEnabled = (flags & CHANNEL_PITCH_MASK ) == CHANNEL_PITCH_MASK;
+ data.rollEnabled = (flags & CHANNEL_ROLL_MASK ) == CHANNEL_ROLL_MASK;
+ data.yawRateEnabled = (flags & CHANNEL_YAW_RATE_MASK ) == CHANNEL_YAW_RATE_MASK;
+ data.pitchRateEnabled = (flags & CHANNEL_PITCH_RATE_MASK ) == CHANNEL_PITCH_RATE_MASK;
+ data.rollRateEnabled = (flags & CHANNEL_ROLL_RATE_MASK ) == CHANNEL_ROLL_RATE_MASK;
+ data.mxEnabled = (flags & CHANNEL_MX_MASK ) == CHANNEL_MX_MASK;
+ data.myEnabled = (flags & CHANNEL_MY_MASK ) == CHANNEL_MY_MASK;
+ data.mzEnabled = (flags & CHANNEL_MZ_MASK ) == CHANNEL_MZ_MASK;
+ data.gxEnabled = (flags & CHANNEL_GX_MASK ) == CHANNEL_GX_MASK;
+ data.gyEnabled = (flags & CHANNEL_GY_MASK ) == CHANNEL_GY_MASK;
+ data.gzEnabled = (flags & CHANNEL_GZ_MASK ) == CHANNEL_GZ_MASK;
+ data.axEnabled = (flags & CHANNEL_AX_MASK ) == CHANNEL_AX_MASK;
+ data.ayEnabled = (flags & CHANNEL_AY_MASK ) == CHANNEL_AY_MASK;
+ data.azEnabled = (flags & CHANNEL_AZ_MASK ) == CHANNEL_AZ_MASK;
+
+
+ if (data.yawEnabled ){ data.yaw = SCALE_YAW * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.pitchEnabled ){ data.pitch = SCALE_PITCH * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.rollEnabled ){ data.roll = SCALE_ROLL * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.yawRateEnabled ){ data.yawRate = SCALE_YAW_RATE * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.pitchRateEnabled ){ data.pitchRate = SCALE_PITCH_RATE * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.rollRateEnabled ){ data.rollRate = SCALE_ROLL_RATE * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.mxEnabled ){ data.mx = SCALE_MAG_X * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.myEnabled ){ data.my = SCALE_MAG_Y * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.mzEnabled ){ data.mz = SCALE_MAG_Z * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.gxEnabled ){ data.gx = SCALE_GYRO_X * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.gyEnabled ){ data.gy = SCALE_GYRO_Y * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.gzEnabled ){ data.gz = SCALE_GYRO_Z * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.axEnabled ){ data.ax = SCALE_ACCEL_X * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.ayEnabled ){ data.ay = SCALE_ACCEL_Y * bytesToSignedShort(packet[index++],packet[index++]); }
+ if (data.azEnabled ){ data.az = SCALE_ACCEL_Z * bytesToSignedShort(packet[index++],packet[index++]); }
+
+ if (index!=packet_length){
+ //Serial.println("Recevied bad length packet!");
+ return false;
+ }
+
+
+ return true;
+ }
+ case STATUS_REPORT:
+ Serial.println("Received status report");
+ return true;
+ case BAD_CHECKSUM:
+ Serial.println("CHR6DM reported bad checksum!");
+ return true;
+ case NO_DATA:
+ //Serial.println("CHR6DM No data!");
+ return false;
+ case FAILED_CHECKSUM:
+ //Serial.println("CHR6DM reported failed checksum!");
+ return false;
+ case COMMAND_COMPLETE:
+ Serial.println("COMMAND_COMPLETE");
+ return true;
+ case COMMAND_FAILED:
+ Serial.println("COMMAND_FAILED");
+ return false;
+ default:
+ Serial.print("Received unknown packet ");
+ Serial.println(packet[0]);
+ return false;
+
+ }
+ }
+
+
+ bool selfTest(){
+ sendPacket(SELF_TEST);
+ return waitFor(STATUS_REPORT,DEFAULT_TIMEOUT);
+ }
+
+ int bytesToSignedShort(int high, int low) {
+ return word(high,low);
+ }
+
+ bool setListenMode() {
+ sendPacket(SET_SILENT_MODE);
+ return waitForAck(DEFAULT_TIMEOUT);
+ }
+
+ bool waitForAck(int timeout) {
+
+ long startTime = millis();
+ while(millis()-startTime.
+*/
+
+#ifndef _AEROQUAD_PLATFORM_WII_H_
+#define _AEROQUAD_PLATFORM_WII_H_
+
+#include "Arduino.h"
+
+short wiiAccelADC[3];
+short wiiGyroADC[3];
+byte wmpSlow[3];
+
+void initializeWiiSensors(boolean paris3Board = false)
+{
+ if (paris3Board) {
+ pinMode(12, OUTPUT);
+ digitalWrite(12, LOW);
+ delay(200);
+ digitalWrite(12, HIGH);
+ delay(100);
+ }
+
+ //Init WM+ and Nunchuk
+ updateRegisterI2C(0x53, 0xF0, 0x55);
+ delay(100);
+ updateRegisterI2C(0x53, 0xFE, 0x05);
+ delay(100);
+};
+
+void readWiiSensors()
+{
+ unsigned char buffer[6];
+
+ for(byte j=0;j<2;j++) {
+ sendByteI2C(0x52, 0x00);
+ Wire.requestFrom(0x52,6);
+
+ for(byte i = 0; i < 6; i++)
+ buffer[i] = Wire.read();
+
+ if ((buffer[5] & 0x02) == 0x02 && (buffer[5]&0x01) == 0) { //If WiiMP
+ wiiGyroADC[XAXIS] = (((buffer[5]>>2)<<8) + buffer[2]); // Configured for Paris MultiWii Board
+ wiiGyroADC[YAXIS] = (((buffer[4]>>2)<<8) + buffer[1]); // Configured for Paris MultiWii Board
+ wiiGyroADC[ZAXIS] = (((buffer[3]>>2)<<8) + buffer[0]); // Configured for Paris MultiWii Board
+
+ wmpSlow[XAXIS] = (buffer[4] & 0x02) >> 1 ;
+ wmpSlow[YAXIS] = (buffer[3] & 0x01) >> 0 ;
+ wmpSlow[ZAXIS] = (buffer[3] & 0x02) >> 1 ;
+ }
+ else if ((buffer[5]&0x02) == 0 && (buffer[5]&0x01) == 0) {//If Nunchuk
+ wiiAccelADC[XAXIS] = (buffer[2]<<1)|((buffer[5]>>4)&0x01); // Configured for Paris MultiWii Board
+ wiiAccelADC[YAXIS] = (buffer[3]<<1)|((buffer[5]>>5)&0x01); // Configured for Paris MultiWii Board
+ wiiAccelADC[ZAXIS] = buffer[4];
+ wiiAccelADC[ZAXIS] = wiiAccelADC[2]<<1;
+ wiiAccelADC[ZAXIS] = wiiAccelADC[2] & 0xFFFC;
+ wiiAccelADC[ZAXIS] = wiiAccelADC[2]|((buffer[5]>>6)&0x03); // Configured for Paris MultiWii Board
+ }
+ if (j == 0)
+ delay(3);
+ }
+}
+
+short getWiiAccelADC(byte axis)
+{
+ return wiiAccelADC[axis];
+}
+
+short getWiiGyroADC(byte axis)
+{
+ return wiiGyroADC[axis];
+}
+
+byte getWmpSlow(byte axis)
+{
+ return wmpSlow[axis];
+}
+
+
+
+#endif
\ No newline at end of file
diff --git a/Libraries/AQ_RangeFinder/Examples/Test_MaxSonarRangeFinder/Test_MaxSonarRangeFinder.ino b/Libraries/AQ_RangeFinder/Examples/Test_MaxSonarRangeFinder/Test_MaxSonarRangeFinder.ino
new file mode 100644
index 00000000..1b355c00
--- /dev/null
+++ b/Libraries/AQ_RangeFinder/Examples/Test_MaxSonarRangeFinder/Test_MaxSonarRangeFinder.ino
@@ -0,0 +1,39 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include
+#include
+
+void setup() {
+ Serial.begin(115200);
+ inititalizeRangeFinder(ALTITUDE_RANGE_FINDER_INDEX);
+}
+
+void loop() {
+
+ for (int i = 0; i < 20;i++) {
+ readRangeFinderDistanceSum(ALTITUDE_RANGE_FINDER_INDEX);
+ delay(10);
+ }
+ evaluateDistanceFromSample(ALTITUDE_RANGE_FINDER_INDEX);
+
+ Serial.print("Distance = ");
+ Serial.println(rangeFinderRange[ALTITUDE_RANGE_FINDER_INDEX]);
+}
diff --git a/Libraries/AQ_RangeFinder/MaxSonarRangeFinder.h b/Libraries/AQ_RangeFinder/MaxSonarRangeFinder.h
new file mode 100644
index 00000000..0b32ecae
--- /dev/null
+++ b/Libraries/AQ_RangeFinder/MaxSonarRangeFinder.h
@@ -0,0 +1,96 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_MAX_SONAR_RANGE_FINDER_H_
+#define _AEROQUAD_MAX_SONAR_RANGE_FINDER_H_
+
+// @see http://www.arduino.cc/playground/Main/MaxSonar
+
+#if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+
+
+#include "RangeFinder.h"
+
+#define ALTITUDE_RANGE_FINDER_PIN 1 // analog
+#define FRONT_RANGE_FINDER_PIN 5 // analog
+#define RIGHT_RANGE_FINDER_PIN 4 // analog
+#define REAR_RANGE_FINDER_PIN 3 // analog
+#define LEFT_RANGE_FINDER_PIN 2 // analog
+
+
+
+
+byte rangeFinderPins[5] = {ALTITUDE_RANGE_FINDER_PIN,
+ FRONT_RANGE_FINDER_PIN,
+ RIGHT_RANGE_FINDER_PIN,
+ REAR_RANGE_FINDER_PIN,
+ LEFT_RANGE_FINDER_PIN};
+
+//
+// default unit are centimeter
+//
+
+// default min max range constrain
+
+void inititalizeRangeFinder(byte idx) {
+
+ maxRangeFinderRange = 3.0;
+ minRangeFinderRange = 0.25;
+ vehicleState |= RANGE_ENABLED;
+
+ pinMode(rangeFinderPins[idx], INPUT);
+}
+
+/**
+ * inches * 2.54 = cm
+ */
+void readRangeFinderDistanceSum(byte idx) {
+ rangeFinderRangeSum[idx] += (analogRead(rangeFinderPins[idx]) * 1.8333);
+ rangeFinderSampleCount[idx]++;
+}
+
+void evaluateDistanceFromSample(byte idx) {
+ rangeFinderRange[idx] = ((float)rangeFinderRangeSum[idx] / (float)rangeFinderSampleCount[idx]) / 100;
+ if (!isInRangeOfRangeFinder(idx)) {
+ rangeFinderRange[idx] = INVALID_ALTITUDE;
+ }
+ rangeFinderRangeSum[idx] = 0;
+ rangeFinderSampleCount[idx] = 0;
+}
+
+/**
+ * @return true if we can use safely the sonar
+ */
+boolean isInRangeOfRangeFinder(byte idx) {
+ return ((rangeFinderRange[idx] < maxRangeFinderRange) &&
+ (rangeFinderRange[idx] > minRangeFinderRange));
+}
+
+#endif
+
+#endif
+
+
+
+
+
+
+
+
diff --git a/Libraries/AQ_RangeFinder/RangeFinder.h b/Libraries/AQ_RangeFinder/RangeFinder.h
new file mode 100644
index 00000000..5d4134d9
--- /dev/null
+++ b/Libraries/AQ_RangeFinder/RangeFinder.h
@@ -0,0 +1,53 @@
+/*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_RANGE_FINDER_H_
+#define _AEROQUAD_RANGE_FINDER_H_
+
+#include "Arduino.h"
+#include "GlobalDefined.h"
+
+#define ALTITUDE_RANGE_FINDER_INDEX 0
+#define FRONT_RANGE_FINDER_INDEX 1
+#define RIGHT_RANGE_FINDER_INDEX 2
+#define REAR_RANGE_FINDER_INDEX 3
+#define LEFT_RANGE_FINDER_INDEX 4
+
+
+
+byte rangeFinderSampleCount[5] = {0,0,0,0,0};
+int rangeFinderRangeSum[5] = {0,0,0,0,0};
+float rangeFinderRange[5] = {0.0,0.0,0.0,0.0,0.0};
+
+
+//
+// default unit are centimeter
+//
+
+// default min max range constrain
+float maxRangeFinderRange = 3.0;
+float minRangeFinderRange = 0.25;
+
+void inititalizeRangeFinder(byte idx);
+void readRangeFinderDistanceSum(byte idx);
+void evaluateDistanceFromSample(byte idx);
+boolean isInRangeOfRangeFinder(byte idx);
+
+#endif // #ifdef _AEROQUAD_RANGE_FINDER_H_
\ No newline at end of file
diff --git a/Libraries/AQ_Receiver/Examples/Test_328p/Test_328p.ino b/Libraries/AQ_Receiver/Examples/Test_328p/Test_328p.ino
new file mode 100644
index 00000000..b1878282
--- /dev/null
+++ b/Libraries/AQ_Receiver/Examples/Test_328p/Test_328p.ino
@@ -0,0 +1,57 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include
+#include
+#include
+
+
+unsigned long timer;
+
+void setup() {
+
+ Serial.begin(115200);
+ Serial.println("Receiver library test (Receiver_APM)");
+
+ initializeReceiver();
+}
+
+void loop() {
+
+ if((millis() - timer) > 50) // 20Hz
+ {
+ timer = millis();
+ readReceiver();
+
+ Serial.print("Throttle: ");
+ Serial.print(receiverCommand[THROTTLE]);
+ Serial.print(" Yaw: ");
+ Serial.print(receiverCommand[YAW]);
+ Serial.print(" Roll: ");
+ Serial.print(receiverCommand[XAXIS]);
+ Serial.print(" Pitch: ");
+ Serial.print(receiverCommand[YAXIS]);
+ Serial.print(" Mode: ");
+ Serial.print(receiverCommand[ZAXIS]);
+ Serial.print(" Aux: ");
+ Serial.print(receiverCommand[AUX]);
+ Serial.println();
+ }
+}
diff --git a/Libraries/AQ_Receiver/Examples/Test_APM/Test_APM.ino b/Libraries/AQ_Receiver/Examples/Test_APM/Test_APM.ino
new file mode 100644
index 00000000..ed9ff243
--- /dev/null
+++ b/Libraries/AQ_Receiver/Examples/Test_APM/Test_APM.ino
@@ -0,0 +1,59 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include
+#include
+#include
+#include
+
+
+unsigned long timer;
+
+void setup() {
+
+ Serial.begin(115200);
+ Serial.println("Receiver library test (Receiver_APM)");
+
+ initRC();
+ initializeReceiver();
+}
+
+void loop() {
+
+ if((millis() - timer) > 50) // 20Hz
+ {
+ timer = millis();
+ readReceiver();
+
+ Serial.print("Throttle: ");
+ Serial.print(receiverCommand[THROTTLE]);
+ Serial.print(" Yaw: ");
+ Serial.print(receiverCommand[YAW]);
+ Serial.print(" Roll: ");
+ Serial.print(receiverCommand[XAXIS]);
+ Serial.print(" Pitch: ");
+ Serial.print(receiverCommand[YAXIS]);
+ Serial.print(" Mode: ");
+ Serial.print(receiverCommand[ZAXIS]);
+ Serial.print(" Aux: ");
+ Serial.print(receiverCommand[AUX]);
+ Serial.println();
+ }
+}
diff --git a/Libraries/AQ_Receiver/Examples/Test_MEGA/Test_MEGA.ino b/Libraries/AQ_Receiver/Examples/Test_MEGA/Test_MEGA.ino
new file mode 100644
index 00000000..7833f6db
--- /dev/null
+++ b/Libraries/AQ_Receiver/Examples/Test_MEGA/Test_MEGA.ino
@@ -0,0 +1,57 @@
+/*
+ AeroQuad v3.0 - March 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#include
+#include
+#include
+
+
+unsigned long timer;
+
+void setup() {
+
+ Serial.begin(115200);
+ Serial.println("Receiver library test (Receiver_APM)");
+
+ initializeReceiver();
+}
+
+void loop() {
+
+ if((millis() - timer) > 50) // 20Hz
+ {
+ timer = millis();
+ readReceiver();
+
+ Serial.print("Throttle: ");
+ Serial.print(receiverCommand[THROTTLE]);
+ Serial.print(" Yaw: ");
+ Serial.print(receiverCommand[YAW]);
+ Serial.print(" Roll: ");
+ Serial.print(receiverCommand[XAXIS]);
+ Serial.print(" Pitch: ");
+ Serial.print(receiverCommand[YAXIS]);
+ Serial.print(" Mode: ");
+ Serial.print(receiverCommand[ZAXIS]);
+ Serial.print(" Aux: ");
+ Serial.print(receiverCommand[AUX]);
+ Serial.println();
+ }
+}
diff --git a/Libraries/AQ_Receiver/Receiver.h b/Libraries/AQ_Receiver/Receiver.h
new file mode 100644
index 00000000..89d88c1f
--- /dev/null
+++ b/Libraries/AQ_Receiver/Receiver.h
@@ -0,0 +1,116 @@
+ /*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_RECEIVER_H_
+#define _AEROQUAD_RECEIVER_H_
+
+#include "Arduino.h"
+
+#define PWM2RAD 0.002 // Based upon 5RAD for full stick movement, you take this times the RAD to get the PWM conversion factor
+
+// Receiver variables
+#define TIMEOUT 25000
+#define MINCOMMAND 1000
+#define MIDCOMMAND 1500
+#define MAXCOMMAND 2000
+#define MINDELTA 200
+#define MINCHECK MINCOMMAND + 100
+#define MAXCHECK MAXCOMMAND - 100
+#define MINTHROTTLE MINCOMMAND + 100
+#define LEVELOFF 100
+#define MAX_NB_CHANNEL 8
+
+int lastReceiverChannel = 0;
+
+float receiverXmitFactor = 0.0;
+int receiverData[MAX_NB_CHANNEL] = {0,0,0,0,0,0,0,0};
+int receiverZero[3] = {0,0,0};
+int receiverCommand[MAX_NB_CHANNEL] = {0,0,0,0,0,0,0,0};
+int receiverCommandSmooth[MAX_NB_CHANNEL] = {0,0,0,0,0,0,0,0};
+float receiverSlope[MAX_NB_CHANNEL] = {0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
+float receiverOffset[MAX_NB_CHANNEL] = {0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
+float receiverSmoothFactor[MAX_NB_CHANNEL] = {0.0,0.0,0.0,0.0,0.0,0.0,0.0,0.0};
+
+void initializeReceiverParam(int nbChannel = 6) {
+
+ lastReceiverChannel = nbChannel;
+
+ receiverCommand[XAXIS] = 1500;
+ receiverCommand[YAXIS] = 1500;
+ receiverCommand[ZAXIS] = 1500;
+ receiverCommand[THROTTLE] = 1000;
+ receiverCommand[MODE] = 1000;
+ receiverCommand[AUX] = 1000;
+ receiverCommand[AUX+1] = 1000;
+ receiverCommand[AUX+2] = 1000;
+
+ for (byte channel = XAXIS; channel < lastReceiverChannel; channel++) {
+ receiverCommandSmooth[channel] = 1.0;
+ }
+ for (byte channel = XAXIS; channel < THROTTLE; channel++) {
+ receiverZero[channel] = 1500;
+ }
+
+ for (byte channel = XAXIS; channel < lastReceiverChannel; channel++) {
+ receiverSlope[channel] = 1;
+ }
+ for (byte channel = XAXIS; channel < lastReceiverChannel; channel++) {
+ receiverOffset[channel] = 1;
+ }
+ for (byte channel = XAXIS; channel < lastReceiverChannel; channel++) {
+ receiverSmoothFactor[channel] = 1;
+ }
+}
+
+int getRawChannelValue(byte channel);
+void readReceiver();
+
+void readReceiver()
+{
+ for(byte channel = XAXIS; channel < lastReceiverChannel; channel++) {
+
+ // Apply receiver calibration adjustment
+ receiverData[channel] = (receiverSlope[channel] * getRawChannelValue(channel)) + receiverOffset[channel];
+ // Smooth the flight control receiver inputs
+ receiverCommandSmooth[channel] = filterSmooth(receiverData[channel], receiverCommandSmooth[channel], receiverSmoothFactor[channel]);
+ }
+
+ // Reduce receiver commands using receiverXmitFactor and center around 1500
+ for (byte channel = XAXIS; channel < THROTTLE; channel++) {
+ receiverCommand[channel] = ((receiverCommandSmooth[channel] - receiverZero[channel]) * receiverXmitFactor) + receiverZero[channel];
+ }
+ // No xmitFactor reduction applied for throttle, mode and AUX
+ for (byte channel = THROTTLE; channel < lastReceiverChannel; channel++) {
+ receiverCommand[channel] = receiverCommandSmooth[channel];
+ }
+}
+
+
+void setChannelValue(byte channel,int value);
+
+// return the smoothed & scaled number of radians/sec in stick movement - zero centered
+const float getReceiverSIData(byte channel) {
+ return ((receiverCommand[channel] - receiverZero[channel]) * (2.5 * PWM2RAD)); // +/- 2.5RPS 50% of full rate
+}
+
+#endif
+
+
+
diff --git a/Libraries/AQ_Receiver/Receiver_328p.h b/Libraries/AQ_Receiver/Receiver_328p.h
new file mode 100644
index 00000000..c6c76907
--- /dev/null
+++ b/Libraries/AQ_Receiver/Receiver_328p.h
@@ -0,0 +1,159 @@
+ /*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_RECEIVER_328p_H_
+#define _AEROQUAD_RECEIVER_328p_H_
+
+#if defined (__AVR_ATmega328P__) || defined(__AVR_ATmegaUNO__)
+
+#include "Arduino.h"
+#include "Receiver.h"
+
+#define RISING_EDGE 1
+#define FALLING_EDGE 0
+#define MINONWIDTH 950
+#define MAXONWIDTH 2075
+#define MINOFFWIDTH 12000
+#define MAXOFFWIDTH 24000
+#define MAX_NO_SIGNAL_COUNTER 10
+
+#include "pins_arduino.h"
+#include
+#include "GlobalDefined.h"
+
+volatile uint8_t *port_to_pcmask[] = {
+ &PCMSK0,
+ &PCMSK1,
+ &PCMSK2
+};
+volatile static uint8_t PCintLast[3];
+
+// Channel data
+typedef struct {
+ byte edge;
+ unsigned long riseTime;
+ unsigned long fallTime;
+ unsigned int lastGoodWidth;
+} tPinTimingData;
+volatile static tPinTimingData pinData[9];
+
+// Attaches PCINT to Arduino Pin
+void attachPinChangeInterrupt(uint8_t pin) {
+ uint8_t bit = digitalPinToBitMask(pin);
+ uint8_t port = digitalPinToPort(pin);
+ volatile uint8_t *pcmask;
+
+ // map pin to PCIR register
+ if (port == NOT_A_PORT) {
+ return;
+ }
+ else {
+ port -= 2;
+ pcmask = port_to_pcmask[port];
+ }
+ // set the mask
+ *pcmask |= bit;
+ // enable the interrupt
+ PCICR |= 0x01 << port;
+}
+
+// ISR which records time of rising or falling edge of signal
+static void measurePulseWidthISR(uint8_t port, uint8_t pinoffset) {
+ uint8_t bit;
+ uint8_t curr;
+ uint8_t mask;
+ uint8_t pin;
+ uint32_t currentTime;
+ uint32_t time;
+
+ // get the pin states for the indicated port.
+ curr = *portInputRegister(port+2);
+ mask = curr ^ PCintLast[port];
+ PCintLast[port] = curr;
+ // mask is pins that have changed. screen out non pcint pins.
+ if ((mask &= *port_to_pcmask[port]) == 0) {
+ return;
+ }
+ currentTime = micros();
+ // mask is pcint pins that have changed.
+ for (uint8_t i=0; i < 8; i++) {
+ bit = 0x01 << i;
+ if (bit & mask) {
+ pin = pinoffset + i;
+ // for each pin changed, record time of change
+ if (bit & PCintLast[port]) {
+ time = currentTime - pinData[pin].fallTime;
+ pinData[pin].riseTime = currentTime;
+ if ((time >= MINOFFWIDTH) && (time <= MAXOFFWIDTH))
+ pinData[pin].edge = RISING_EDGE;
+ else
+ pinData[pin].edge = FALLING_EDGE; // invalid rising edge detected
+ }
+ else {
+ time = currentTime - pinData[pin].riseTime;
+ pinData[pin].fallTime = currentTime;
+ if ((time >= MINONWIDTH) && (time <= MAXONWIDTH) && (pinData[pin].edge == RISING_EDGE)) {
+ pinData[pin].lastGoodWidth = time;
+ pinData[pin].edge = FALLING_EDGE;
+ }
+ }
+ }
+ }
+}
+
+SIGNAL(PCINT0_vect) {
+ measurePulseWidthISR(0, 8); // PORT B
+}
+
+SIGNAL(PCINT2_vect) {
+ measurePulseWidthISR(2, 0); // PORT D
+}
+
+// defines arduino pins used for receiver in arduino pin numbering schema
+static byte receiverPin[6] = {2, 5, 6, 4, 7, 8}; // pins used for XAXIS, YAXIS, ZAXIS, THROTTLE, MODE, AUX
+
+
+void initializeReceiver(int nbChannel = 6) {
+
+ initializeReceiverParam(nbChannel);
+ for (byte channel = XAXIS; channel < lastReceiverChannel; channel++) {
+ pinMode(receiverPin[channel], INPUT);
+ pinData[receiverPin[channel]].edge = FALLING_EDGE;
+ attachPinChangeInterrupt(receiverPin[channel]);
+ }
+}
+
+int getRawChannelValue(byte channel) {
+ byte pin = receiverPin[channel];
+ uint8_t oldSREG = SREG;
+ cli();
+ // Get receiver value read by pin change interrupt handler
+ uint16_t receiverRawValue = pinData[pin].lastGoodWidth;
+ SREG = oldSREG;
+
+ return receiverRawValue;
+}
+
+#endif
+
+#endif
+
+
+
diff --git a/Libraries/AQ_Receiver/Receiver_APM.h b/Libraries/AQ_Receiver/Receiver_APM.h
new file mode 100644
index 00000000..7133b4cc
--- /dev/null
+++ b/Libraries/AQ_Receiver/Receiver_APM.h
@@ -0,0 +1,53 @@
+ /*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_RECEIVER_APM_H_
+#define _AEROQUAD_RECEIVER_APM_H_
+
+#include "Arduino.h"
+#include "Receiver.h"
+#include
+
+#if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+
+#include
+#include "GlobalDefined.h"
+#include
+
+byte receiverPin[8] = {0,1,3,2,4,5,6,7};
+
+void initializeReceiver(int nbChannel = 6) {
+
+ initializeReceiverParam(nbChannel);
+}
+
+
+int getRawChannelValue(byte channel) {
+ return readReceiverChannel(receiverPin[channel]);
+}
+
+void setChannelValue(byte channel,int value) {
+}
+
+#endif
+
+#endif
+
+
diff --git a/Libraries/AQ_Receiver/Receiver_HWPPM.h b/Libraries/AQ_Receiver/Receiver_HWPPM.h
new file mode 100644
index 00000000..a8b3966d
--- /dev/null
+++ b/Libraries/AQ_Receiver/Receiver_HWPPM.h
@@ -0,0 +1,120 @@
+ /*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+/* This code will need a HW modification on v2 shield, see AQ forums
+ http://aeroquad.com/showthread.php?4239-Timer-based-PPM-sum-input-on-mega-%28v3-SW%29&highlight=jitter
+
+ In short it will expect to receive cPPM signal at ICP5 pin.
+*/
+
+#ifndef _AEROQUAD_RECEIVER_HWPPM_H_
+#define _AEROQUAD_RECEIVER_HWPPM_H_
+
+#if !defined (__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__)
+ #error Receiver_HWPPM can only be used on ATMega
+#endif
+
+#include
+#include "Receiver.h"
+#include "pins_arduino.h"
+#include
+#include
+#include "GlobalDefined.h"
+
+// Channel data
+volatile unsigned int startPulse = 0;
+volatile byte ppmCounter = 8; // ignore data until first sync pulse
+volatile int PWM_RAW[8] = { 2200,2200,2200,2200,2200,2200,2200,2200 };
+
+#define TIMER5_FREQUENCY_HZ 50
+#define TIMER5_PRESCALER 8
+#define TIMER5_PERIOD (F_CPU/TIMER5_PRESCALER/TIMER5_FREQUENCY_HZ)
+
+/****************************************************
+ * Interrupt Vector
+ ****************************************************/
+ISR(TIMER5_CAPT_vect)//interrupt.
+{
+ if ((1 << ICES5) & TCCR5B) {
+ // Triggered at rising edge
+ startPulse = ICR5; // Save time at pulse start
+ }
+ else {
+ // Triggered at dropping edge; measure pulse length
+ unsigned int stopPulse = ICR5;
+ // Note: compensate for timer overflow if needed
+ unsigned int pulseWidth = ((startPulse > stopPulse) ? TIMER5_PERIOD : 0) + stopPulse - startPulse;
+
+ if (pulseWidth > 5000) { // Verify if this is the sync pulse
+ ppmCounter = 0; // -> restart the channel counter
+ }
+ else {
+ if (ppmCounter < 8) { // channels 9- will get ignored here
+ PWM_RAW[ppmCounter] = pulseWidth; // Store measured pulse length
+ ppmCounter++; // Advance to next channel
+ }
+ }
+ }
+ TCCR5B ^= (1 << ICES5); // Switch edge
+}
+
+#define SERIAL_SUM_PPM_1 1,2,3,0,4,5,6,7 // PITCH,YAW,THR,ROLL... For Graupner/Spektrum
+#define SERIAL_SUM_PPM_2 0,1,3,2,4,5,6,7 // ROLL,PITCH,THR,YAW... For Robe/Hitec/Futaba
+#define SERIAL_SUM_PPM_3 1,0,3,2,4,5,6,7 // PITCH,ROLL,THR,YAW... For some Hitec/Sanwa/Others
+
+#if defined (SKETCH_SERIAL_SUM_PPM)
+ #define SERIAL_SUM_PPM SKETCH_SERIAL_SUM_PPM
+#else
+ #define SERIAL_SUM_PPM SERIAL_SUM_PPM_1
+#endif
+
+static uint8_t rcChannel[8] = {SERIAL_SUM_PPM};
+
+void initializeReceiver(int nbChannel) {
+
+ initializeReceiverParam(nbChannel);
+ pinMode(48, INPUT); // ICP5
+ pinMode(A8, INPUT); // this is the original location of the first RX channel
+
+ // Configure timer HW
+ TCCR5A = ((1<.
+*/
+
+#ifndef _AEROQUAD_RECEIVER_MEGA_H_
+#define _AEROQUAD_RECEIVER_MEGA_H_
+
+
+#if defined (__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
+
+#include "Arduino.h"
+#include "Receiver.h"
+
+#define RISING_EDGE 1
+#define FALLING_EDGE 0
+#define MINONWIDTH 950
+#define MAXONWIDTH 2075
+#define MINOFFWIDTH 12000
+#define MAXOFFWIDTH 24000
+
+#include "pins_arduino.h"
+#include
+#include "GlobalDefined.h"
+
+volatile uint8_t *port_to_pcmask[] = {
+ &PCMSK0,
+ &PCMSK1,
+ &PCMSK2
+};
+volatile static uint8_t PCintLast[3];
+// Channel data
+typedef struct {
+ byte edge;
+ unsigned long riseTime;
+ unsigned long fallTime;
+ unsigned int lastGoodWidth;
+} tPinTimingData;
+volatile static tPinTimingData pinData[9];
+
+static void MegaPcIntISR() {
+ uint8_t bit;
+ uint8_t curr;
+ uint8_t mask;
+ uint8_t pin;
+ uint32_t currentTime;
+ uint32_t time;
+
+ curr = *portInputRegister(11);
+ mask = curr ^ PCintLast[0];
+ PCintLast[0] = curr;
+
+ // mask is pins that have changed. screen out non pcint pins.
+ if ((mask &= PCMSK2) == 0) {
+ return;
+ }
+
+ currentTime = micros();
+
+ // mask is pcint pins that have changed.
+ for (uint8_t i=0; i < 8; i++) {
+ bit = 0x01 << i;
+ if (bit & mask) {
+ pin = i;
+ // for each pin changed, record time of change
+ if (bit & PCintLast[0]) {
+ time = currentTime - pinData[pin].fallTime;
+ pinData[pin].riseTime = currentTime;
+ if ((time >= MINOFFWIDTH) && (time <= MAXOFFWIDTH))
+ pinData[pin].edge = RISING_EDGE;
+ else
+ pinData[pin].edge = FALLING_EDGE; // invalid rising edge detected
+ }
+ else {
+ time = currentTime - pinData[pin].riseTime;
+ pinData[pin].fallTime = currentTime;
+ if ((time >= MINONWIDTH) && (time <= MAXONWIDTH) && (pinData[pin].edge == RISING_EDGE)) {
+ pinData[pin].lastGoodWidth = time;
+ pinData[pin].edge = FALLING_EDGE;
+ }
+ }
+ }
+ }
+}
+
+SIGNAL(PCINT2_vect) {
+ MegaPcIntISR();
+}
+
+#ifdef OLD_RECEIVER_PIN_ORDER
+ // arduino pins 67, 65, 64, 66, 63, 62
+ static byte receiverPin[6] = {5, 3, 2, 4, 1, 0}; // bit number of PORTK used for XAXIS, YAXIS, ZAXIS, THROTTLE, MODE, AUX
+#else
+ //arduino pins 63, 64, 65, 62, 66, 67
+ static byte receiverPin[8] = {1, 2, 3, 0, 4, 5, 6, 7}; // bit number of PORTK used for XAXIS, YAXIS, ZAXIS, THROTTLE, MODE, AUX
+#endif
+
+void initializeReceiver(int nbChannel = 6) {
+
+ initializeReceiverParam(nbChannel);
+
+ DDRK = 0;
+ PORTK = 0;
+ PCMSK2 |=(1<.
+*/
+
+#ifndef _AEROQUAD_RECEIVER_PPM_H_
+#define _AEROQUAD_RECEIVER_PPM_H_
+
+#if defined (__AVR_ATmega328P__) || defined(__AVR_ATmegaUNO__)
+ #define PPM_PIN_INTERRUPT() attachInterrupt(0, rxInt, RISING) //PIN 0
+#else
+ #define PPM_PIN_INTERRUPT() attachInterrupt(4, rxInt, RISING) //PIN 19, also used for Spektrum satellite option
+#endif
+
+#include "Arduino.h"
+#include "Receiver.h"
+
+#include "pins_arduino.h"
+#include
+#include "GlobalDefined.h"
+
+
+#define XAXIS 0
+#define YAXIS 1
+#define ZAXIS 2
+#define THROTTLE 3
+#define AUX1 4
+#define AUX2 5
+
+#define SERIAL_SUM_PPM_1 YAXIS,ZAXIS,THROTTLE,XAXIS,AUX1,AUX2,0,0 //For Graupner/Spektrum
+#define SERIAL_SUM_PPM_2 XAXIS,YAXIS,THROTTLE,ZAXIS,AUX1,AUX2,0,0 //For Robe/Hitec/Futaba
+#define SERIAL_SUM_PPM_3 YAXIS,XAXIS,THROTTLE,ZAXIS,AUX1,AUX2,0,0 //For some Hitec/Sanwa/Others
+
+#if defined (SKETCH_SERIAL_SUM_PPM)
+ #define SERIAL_SUM_PPM SKETCH_SERIAL_SUM_PPM
+#else
+ #define SERIAL_SUM_PPM SERIAL_SUM_PPM_1
+#endif
+
+static uint8_t rcChannel[8] = {SERIAL_SUM_PPM};
+volatile uint16_t rcValue[8] = {1500,1500,1500,1500,1500,1500,1500,1500}; // interval [1000;2000]
+
+static void rxInt() {
+ uint16_t now,diff;
+ static uint16_t last = 0;
+ static uint8_t chan = 0;
+
+ now = micros();
+ diff = now - last;
+ last = now;
+ if(diff>3000) {
+ chan = 0;
+ }
+ else {
+ if( 900 < diff && diff < 2200 && chan < 8 ) {
+ rcValue[chan] = diff;
+ }
+ chan++;
+ }
+}
+
+void initializeReceiver(int nbChannel) {
+
+ initializeReceiverParam(nbChannel);
+ PPM_PIN_INTERRUPT();
+}
+
+int getRawChannelValue(byte channel) {
+ uint8_t oldSREG;
+ oldSREG = SREG;
+ cli(); // Let's disable interrupts
+
+ int rawChannelValue = rcValue[rcChannel[channel]];
+ SREG = oldSREG;
+
+ return rawChannelValue;
+}
+
+
+#endif
+
+
+
diff --git a/Libraries/AQ_Receiver/Receiver_RemotePC.h b/Libraries/AQ_Receiver/Receiver_RemotePC.h
new file mode 100644
index 00000000..fc133db6
--- /dev/null
+++ b/Libraries/AQ_Receiver/Receiver_RemotePC.h
@@ -0,0 +1,54 @@
+ /*
+ AeroQuad v3.0 - May 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_RECEIVER_REMOTE_PC_H_
+#define _AEROQUAD_RECEIVER_REMOTE_PC_H_
+
+#include "Arduino.h"
+#include "Receiver.h"
+
+void initializeReceiver(int nbChannel) {
+
+ initializeReceiverParam(nbChannel);
+ for (byte channel = XAXIS; channel < THROTTLE; channel++) {
+ receiverCommand[channel] = 1500;
+ receiverZero[channel] = 1500;
+ }
+ receiverCommand[THROTTLE] = 0;
+ receiverZero[THROTTLE] = 0;
+ receiverCommand[MODE] = 2000;
+ receiverZero[MODE] = 0;
+ receiverCommand[AUX] = 2000;
+ receiverZero[AUX] = 0;
+}
+
+int getRawChannelValue(byte channel) {
+ return receiverCommand[channel];
+}
+
+void setChannelValue(byte channel,int value) {
+ receiverCommand[channel] = value;
+}
+
+
+#endif
+
+
+
diff --git a/Libraries/AQ_SPI/Device_SPI.h b/Libraries/AQ_SPI/Device_SPI.h
new file mode 100644
index 00000000..4d2d3e9d
--- /dev/null
+++ b/Libraries/AQ_SPI/Device_SPI.h
@@ -0,0 +1,74 @@
+/*
+ AeroQuad v2.2 - Feburary 2011
+ www.AeroQuad.com
+ Copyright (c) 2011 Ted Carancho. All rights reserved.
+ An Open Source Arduino based multicopter.
+
+ 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 .
+*/
+
+#ifndef _AEROQUAD_DEVICE_SPI_H_
+#define _AEROQUAD_DEVICE_SPI_H_
+
+//OSD pins on AQ v2 shield:
+#define CS 22 //SS_OSD
+#define DOUT 51 //MOSI
+#define DIN 50 //MISO
+#define SCK 52 //SCLK
+
+
+void initializeSPI() {
+
+ pinMode( CS, OUTPUT );
+ pinMode( 53, OUTPUT ); //Default CS pin - needs to be output or SPI peripheral will behave as a slave instead of master
+ digitalWrite( CS, HIGH );
+
+ pinMode( DOUT, OUTPUT );
+ pinMode( DIN, INPUT );
+ pinMode( SCK, OUTPUT );
+}
+
+
+//////////////////////////////////////////////////////////////
+//Performs an 8-bit SPI transfer operation
+byte spi_transfer( byte data ) {
+
+ SPDR = data; //transfer data with hardware SPI
+ while ( !(SPSR & _BV(SPIF)) ) ;
+ return SPDR;
+}
+
+void spi_writereg(byte r, byte d) {
+
+ spi_transfer(r);
+ spi_transfer(d);
+}
+
+byte spi_readreg(byte r) {
+
+ spi_transfer(r);
+ return spi_transfer(0);
+}
+
+void spi_select() {
+ digitalWrite( CS, LOW );
+}
+
+void spi_deselect() {
+ digitalWrite( CS, HIGH );
+}
+
+
+
+#endif
\ No newline at end of file
diff --git a/MAX7456_Font_Updater/MAX7456_Font_Updater.ino b/MAX7456_Font_Updater/MAX7456_Font_Updater.ino
new file mode 100644
index 00000000..303562e3
--- /dev/null
+++ b/MAX7456_Font_Updater/MAX7456_Font_Updater.ino
@@ -0,0 +1,252 @@
+// Code to copy a MCM font file (converted for C by mcm2h.pl) to the Arduino + Max7456 OSD
+//
+// MAX7456_font Sketch
+//
+// http://www.maxim-ic.com/tools/evkit/index.cfm?EVKit=558
+// max7456 evaluation kit software
+#define SPI_DATAOUT 51 //MOSI
+#define SPI_DATAIN 50 //MISO
+#define SPICLOCK 52 //SCLK
+#define MAX7456SELECT 22 //22-SS
+
+//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
+
+#define READ_REG 0x80
+
+//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 int incomingByte;
+
+byte charbuf[54]; // for NVM_read
+
+#include
+#include "font.h"
+
+
+//////////////////////////////////////////////////////////////
+void setup()
+{
+ volatile byte spi_junk;
+ Serial.begin(9600);
+ Serial.flush();
+ pinMode( 53, OUTPUT );
+ pinMode(MAX7456SELECT,OUTPUT);
+ digitalWrite(MAX7456SELECT,HIGH); //disable device
+
+ pinMode(SPI_DATAOUT, OUTPUT);
+ pinMode(SPI_DATAIN, INPUT);
+ pinMode(SPICLOCK,OUTPUT);
+
+ // 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<");
+}
+
+void reset_max7456()
+{
+ // force soft reset on Max7456
+ digitalWrite(MAX7456SELECT,LOW);
+ spi_writereg(VM0_reg,MAX7456_reset);
+ digitalWrite(MAX7456SELECT,HIGH);
+ delay(500);
+
+ // set all rows to same character white level, 90%
+ digitalWrite(MAX7456SELECT,LOW);
+ for (byte x = 0; x < MAX_screen_rows; x++)
+ {
+ spi_writereg(x + 0x10,WHITE_level_90);
+ }
+
+ // make sure the Max7456 is enabled
+ spi_writereg(VM0_reg,ENABLE_display);
+ digitalWrite(MAX7456SELECT,HIGH);
+}
+
+//////////////////////////////////////////////////////////////
+void loop()
+{
+ if (Serial.available() > 0)
+ {
+ // read the incoming byte:
+ incomingByte = Serial.read();
+ switch(incomingByte) // wait for commands
+ {
+ case 'D': // download font
+ transfer_fontdata();
+ break;
+ case 'r': // reset
+ reset_max7456();
+ break;
+ case 's': // show charset
+ show_font();
+ break;
+ case '?': // read status
+ digitalWrite(MAX7456SELECT,LOW);
+ Serial.print("STAT=");
+ Serial.println((int)spi_readreg(STAT_reg));
+ digitalWrite(MAX7456SELECT,HIGH);
+ break;
+ default:
+ Serial.println("invalid command");
+ break;
+ }
+ Serial.println("MAX7456>");
+ }
+}
+
+//////////////////////////////////////////////////////////////
+//Performs an 8-bit SPI transfer operation
+byte spi_transfer( byte data ) {
+ SPDR = data; //transfer data with hardware SPI
+ while ( !(SPSR & _BV(SPIF)) ) ;
+ return SPDR;
+}
+
+void spi_writereg(byte r, byte d) {
+ spi_transfer(r);
+ spi_transfer(d);
+}
+
+byte spi_readreg(byte r) {
+ spi_transfer(r);
+ return spi_transfer(0);
+}
+
+//////////////////////////////////////////////////////////////
+void show_font() //show all chars on 24 wide grid
+{
+ unsigned short x;
+
+ // clear the screen
+ digitalWrite(MAX7456SELECT,LOW);
+ spi_writereg(DMM_reg,CLEAR_display);
+ digitalWrite(MAX7456SELECT,HIGH);
+ delay(1); // clearing display takes 20uS so wait some...
+ // disable display
+ digitalWrite(MAX7456SELECT,LOW);
+ // spi_writereg(VM0_reg,DISABLE_display);
+
+ spi_writereg(DMM_reg,0x01); //16 bit trans w/o background, autoincrement
+ spi_writereg(DMAH_reg,0); // set start address high
+ spi_writereg(DMAL_reg,33); // set start address low (line 1 col 3 (0 based)
+
+ // show all characters on screen (actually 0-254)
+ for (x = 0;x<255;x++) {
+ spi_writereg(DMDI_reg,(byte)x);
+ if ((x%24)==23) {
+ for (byte i=0;i<6;i++) spi_writereg(DMDI_reg,0);
+ }
+ }
+
+ spi_writereg(DMDI_reg,END_string);
+
+ // spi_writereg(VM0_reg,ENABLE_display_vert); // turn on screen next vertical
+ digitalWrite(MAX7456SELECT,HIGH);
+}
+
+void transfer_fontdata()
+{
+ if (sizeof(fontdata)!=16384) {
+ Serial.println("ERROR: fontdata with invalid size, aborting!!!");
+ return;
+ }
+ Serial.println("Downloading font to MAX7456 NVM, this may take a while...");
+ for (int ch=0; ch<256; ch++) {
+ Serial.print((int)ch);
+ write_NVM_character(ch,fontdata+64*ch,1);
+ Serial.println(" OK");
+ delay(30);
+ }
+ // force soft reset on Max7456
+ reset_max7456();
+ show_font();
+
+ Serial.println("");
+ Serial.println("Done with font download");
+ Serial.println("MAX7456>");
+}
+
+void wait_NVM() {
+ while (spi_readreg(STAT_reg)&STATUS_reg_nvr_busy) ;
+}
+
+void write_NVM_character(byte ch, const byte* addr, byte progmem)
+{
+ byte x;
+ // disable display
+ digitalWrite(MAX7456SELECT,LOW);
+ spi_writereg(VM0_reg,DISABLE_display);
+ spi_writereg(CMAH_reg,ch); // set start address high
+ for(x = 0; x < NVM_ram_size; x++) // write out 54 (out of 64) bytes of character to shadow ram
+ {
+ spi_writereg(CMAL_reg,x); // set start address low
+ if (progmem) {
+ spi_writereg(CMDI_reg,pgm_read_byte_near(addr+x));
+ } else {
+ spi_writereg(CMDI_reg,*(addr+x));
+ }
+ }
+ // transfer a 54 bytes from shadow ram to NVM
+ spi_writereg(CMM_reg,WRITE_nvr);
+ wait_NVM(); // NVM should be busy around 12ms
+ spi_writereg(VM0_reg,ENABLE_display_vert);
+ digitalWrite(MAX7456SELECT,HIGH);
+}
+
+
diff --git a/MAX7456_Font_Updater/font.h b/MAX7456_Font_Updater/font.h
new file mode 100644
index 00000000..dff03c2f
--- /dev/null
+++ b/MAX7456_Font_Updater/font.h
@@ -0,0 +1,513 @@
+PROGMEM const byte fontdata[16384] = {
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x54,0x55,0x55,0x52,0x55,0x55,0x52,0x55,0x55,0x52,0x55,0x55,0x42,0x55,0x55,0x2a,0x55,0x54,0x80,0x55,0x52,0x15,0x55,0x52,0x15,0x40,0x02,0x15,0x2a,0xaa,
+ 0x15,0x40,0x02,0x15,0x55,0x52,0x15,0x55,0x54,0x80,0x55,0x55,0x2a,0x55,0x55,0x40,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x15,0x55,0x55,0x85,0x55,0x55,0x85,0x55,0x55,0x85,0x55,0x55,0x81,0x55,0x55,0xa8,0x55,0x55,0x02,0x15,0x55,0x54,0x85,0x55,0x54,0x85,0x55,0x54,0x80,0x01,0x54,0xaa,
+ 0xa8,0x54,0x80,0x01,0x54,0x85,0x55,0x02,0x15,0x55,0xa8,0x55,0x55,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x54,0x55,0x55,0x52,0x55,0x55,0x52,0x55,0x55,0x52,0x55,0x55,0x42,0x55,0x55,0x2a,0x55,0x54,0x80,0x55,0x52,0x14,0x55,0x52,0x12,0x40,0x02,0x08,0x2a,0xaa,
+ 0x12,0x40,0x02,0x14,0x55,0x52,0x12,0x55,0x54,0x80,0x55,0x55,0x2a,0x55,0x55,0x40,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x15,0x55,0x55,0x85,0x55,0x55,0x85,0x55,0x55,0x85,0x55,0x55,0x81,0x55,0x55,0xa8,0x55,0x55,0x02,0x15,0x55,0x14,0x85,0x55,0x84,0x85,0x55,0x14,0x80,0x01,0x84,0xaa,
+ 0xa8,0x20,0x80,0x01,0x84,0x85,0x55,0x02,0x15,0x55,0xa8,0x55,0x55,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0x8a,0x85,0x4a,0x8a,0xa1,0x2a,0x8a,0xa8,0x2a,0x8a,0xa8,0x2a,0x8a,0xa8,0x2a,0x80,
+ 0x28,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x04,0x55,0x54,0x82,0x15,0x54,0xa2,0x15,0x54,0x8a,0x15,0x54,0x82,0x15,0x55,0x14,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x80,0x28,0x2a,0xa8,
+ 0x28,0x2a,0xa2,0x28,0x2a,0x8a,0x28,0x2a,0x2a,0xa8,0x20,0xaa,0xa8,0x48,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x54,0x82,0x15,0x54,0x82,0x15,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x40,0x00,0x01,0x2a,0xaa,0xa8,0x40,0x80,0x01,0x52,0xa1,0x55,0x4a,0xa8,0x55,0x50,0x81,0x55,0x54,0x85,0x55,0x54,0x85,0x55,0x54,0x85,0x55,0x54,0x85,
+ 0x55,0x54,0x85,0x55,0x50,0x81,0x55,0x4a,0xa8,0x55,0x52,0xa1,0x55,0x40,0x80,0x01,0x2a,0xaa,0xa8,0x40,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x40,0x00,0x01,0x2a,0xaa,0xa8,0x40,0x80,0x01,0x52,0xa1,0x55,0x4a,0xa8,0x55,0x40,0x81,0x11,0x20,0x84,0x88,0x28,0x84,0x88,0x2a,0x94,0xa8,0x28,0x84,
+ 0x88,0x20,0x84,0x88,0x40,0x81,0x11,0x4a,0xa8,0x55,0x52,0xa1,0x55,0x40,0x80,0x01,0x2a,0xaa,0xa8,0x40,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x54,0xaa,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0xaa,0xa8,0x40,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,
+ 0x01,0x2a,0xaa,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0xaa,0x15,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x54,0xaa,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0xaa,0xa8,0x40,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,
+ 0x01,0x15,0x55,0x54,0x45,0x55,0x51,0x51,0x55,0x45,0x54,0x55,0x15,0x55,0x14,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x14,0x55,0x54,0x55,0x15,0x51,0x55,0x45,0x45,0x55,0x51,0x15,0x55,0x54,0x40,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,
+ 0x01,0x2a,0xaa,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0xaa,0x15,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x41,0x55,0x54,0x28,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x4a,0xaa,
+ 0xa1,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x50,0x00,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x41,0x55,0x54,0x28,0x15,0x52,0xaa,0x85,0x48,0x00,0x21,0x48,0xa2,0x21,0x48,0xaa,0x21,0x4a,0xaa,0xa1,0x48,0x00,0x21,0x4a,0xa0,0xa1,0x4a,0x8a,
+ 0xa1,0x48,0x00,0x21,0x4a,0xaa,0xa1,0x48,0x00,0x21,0x48,0xaa,0x21,0x48,0x02,0x21,0x4a,0xaa,0xa1,0x50,0x00,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x41,0x55,0x54,0x28,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x4a,0xa0,0x21,0x48,0x0a,0xa1,0x4a,0xa0,0x21,0x4a,0xaa,0xa1,0x48,0x00,
+ 0x21,0x4a,0xaa,0xa1,0x48,0x00,0x21,0x48,0xaa,0x21,0x4a,0x00,0xa1,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x50,0x00,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x41,0x55,0x54,0x28,0x15,0x52,0xaa,0x85,0x48,0xa2,0xa1,0x48,0xa2,0xa1,0x48,0x02,0x21,0x48,0xa2,0x21,0x48,0xa2,0x21,0x4a,0xaa,0xa1,0x4a,0xaa,
+ 0xa1,0x48,0xaa,0xa1,0x48,0xa8,0xa1,0x48,0xa2,0x21,0x48,0xa2,0x21,0x48,0x08,0xa1,0x4a,0xaa,0xa1,0x50,0x00,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x51,0x15,0x55,0x48,0x85,0x55,0x22,0x21,0x55,0x22,0x21,0x55,0x22,0x21,0x55,0x22,0x21,0x55,0x40,0x05,0x55,0x54,0x55,0x55,0x52,0x14,
+ 0x55,0x48,0x82,0x15,0x48,0x82,0x15,0x20,0x22,0x15,0x2a,0xa2,0x85,0x20,0x22,0x21,0x21,0x22,0x21,0x45,0x44,0x45,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x05,0x55,0x54,0x85,0x55,0x52,0x15,0x55,0x4a,0x15,0x55,0x28,0x55,0x54,0xa8,0x01,0x52,0xaa,0xa1,0x4a,0xaa,0x85,0x40,0x2a,0x15,0x54,0xa8,
+ 0x55,0x54,0xa1,0x55,0x52,0x85,0x55,0x52,0x15,0x55,0x48,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x54,0x55,0x15,0x52,0x14,0x85,0x4a,0x82,0xa1,0x52,0x84,0xa1,0x54,0x85,0x21,0x54,0x85,0x21,0x52,0x14,0x85,0x54,0x55,0x15,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x14,0x15,0x52,0x82,0x85,0x52,0x82,0x85,0x42,0x82,0x81,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x42,0x82,0x81,0x42,0x82,0x81,0x2a,0xaa,
+ 0xa8,0x2a,0xaa,0xa8,0x42,0x82,0x81,0x52,0x82,0x85,0x52,0x82,0x85,0x54,0x14,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x54,0x28,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x4a,0x28,0xa1,0x4a,0x28,0x05,0x4a,0xaa,0x15,0x52,0xaa,0x85,0x50,0x28,
+ 0xa1,0x4a,0x28,0xa1,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x28,0x15,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x50,0x55,0x41,0x4a,0x15,0x28,0x4a,0x14,0xa8,0x50,0x52,0xa1,0x55,0x4a,0x85,0x55,0x2a,0x15,0x54,0xa8,
+ 0x55,0x52,0xa1,0x55,0x4a,0x85,0x05,0x2a,0x14,0xa1,0x28,0x54,0xa1,0x41,0x55,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x01,0x55,0x54,0xa8,0x55,0x52,0x82,0x15,0x52,0x12,0x15,0x52,0x12,0x15,0x52,0x08,0x55,0x54,0xa1,0x55,0x54,0xa1,
+ 0x55,0x52,0x08,0x05,0x48,0x52,0x21,0x48,0x54,0x85,0x48,0x02,0x21,0x52,0xa8,0x48,0x54,0x01,0x51,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x51,0x55,0x55,0x48,0x55,0x55,0x2a,0x15,0x55,0x4a,0x15,0x55,0x52,0x15,0x55,0x52,0x15,0x55,0x48,0x55,0x55,0x51,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x05,0x55,0x54,0xa1,0x55,0x52,0x85,0x55,0x4a,0x15,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x4a,0x15,0x55,0x52,0x85,0x55,0x54,0xa1,0x55,0x55,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x15,0x55,0x52,0x85,0x55,0x54,0xa1,0x55,0x55,0x28,0x55,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,
+ 0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x28,0x55,0x54,0xa1,0x55,0x52,0x85,0x55,0x54,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x45,0x55,0x51,0x21,0x55,0x48,0x28,0x55,0x28,0x4a,0x14,0xa1,0x52,0x82,0x85,0x40,0xaa,0x01,0x2a,0xaa,0xa8,0x40,0xaa,0x01,0x52,0x82,
+ 0x85,0x4a,0x14,0xa1,0x28,0x55,0x28,0x21,0x55,0x48,0x45,0x55,0x51,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x50,0x28,0x05,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x50,0x28,0x05,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x54,0xa1,0x55,0x52,0x85,0x55,0x54,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x05,0x52,0xaa,0xa1,0x52,0xaa,0xa1,0x54,0x00,
+ 0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x15,0x55,0x52,0x85,0x55,0x52,0x85,0x55,0x54,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x54,0xa8,0x55,0x52,0xa1,0x55,0x4a,0x85,0x55,0x2a,0x15,0x54,0xa8,
+ 0x55,0x52,0xa1,0x55,0x4a,0x85,0x55,0x2a,0x15,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,
+ 0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x54,0xa8,0x55,0x52,0xa8,0x55,0x52,0xa8,0x55,0x50,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x54,0x28,0x15,0x52,0xaa,0x85,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x80,0xa8,0x2a,0x15,0x28,0x40,0x55,0x28,0x55,0x54,0xa8,0x55,0x52,0xa1,0x55,0x4a,
+ 0x85,0x55,0x2a,0x15,0x54,0xa8,0x55,0x52,0xa1,0x55,0x4a,0x80,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x40,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x41,0x55,0x28,0x55,0x40,0xa8,0x55,0x2a,0xa1,0x55,0x2a,
+ 0xa1,0x55,0x40,0xa8,0x41,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x15,0x55,0x52,0x85,0x55,0x4a,0x85,0x55,0x2a,0x85,0x54,0xaa,0x85,0x52,0xa2,0x85,0x4a,0x82,0x85,0x2a,0x12,0x85,0x28,0x02,
+ 0x81,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x40,0x02,0x81,0x55,0x52,0x85,0x55,0x52,0x85,0x55,0x52,0x85,0x55,0x54,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x28,0x00,0x01,0x28,0x00,0x15,0x2a,0xaa,0x85,0x2a,0xaa,0xa1,0x40,0x00,0xa8,0x55,0x55,
+ 0x28,0x55,0x55,0x28,0x41,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x41,0x28,0x00,0x15,0x2a,0xaa,0x85,0x2a,0xaa,
+ 0xa1,0x28,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x40,0x00,0x28,0x55,0x54,0xa8,0x55,0x52,0xa1,0x55,0x4a,0x85,0x55,0x2a,0x15,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x4a,0xaa,
+ 0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0x28,0x4a,0xaa,0xa8,0x52,0xaa,
+ 0xa8,0x54,0x00,0x28,0x41,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x54,0xa1,0x55,0x52,0x85,0x55,0x54,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x05,0x55,0x54,0xa1,0x55,0x52,0xa1,0x55,0x4a,0x85,0x55,0x2a,0x15,0x54,0xa8,0x55,0x52,0xa1,0x55,0x4a,0x85,0x55,0x4a,0x85,
+ 0x55,0x52,0xa1,0x55,0x54,0xa8,0x55,0x55,0x2a,0x15,0x55,0x4a,0x85,0x55,0x52,0xa1,0x55,0x54,0xa1,0x55,0x55,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x05,0x52,0xaa,0xa1,0x52,0xaa,0xa1,0x54,0x00,0x05,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x54,0x00,0x05,0x52,0xaa,0xa1,0x52,0xaa,0xa1,0x54,0x00,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x50,0x55,0x55,0x4a,0x15,0x55,0x4a,0x85,0x55,0x52,0xa1,0x55,0x54,0xa8,0x55,0x55,0x2a,0x15,0x55,0x4a,0x85,0x55,0x52,0xa1,0x55,0x52,
+ 0xa1,0x55,0x4a,0x85,0x55,0x2a,0x15,0x54,0xa8,0x55,0x52,0xa1,0x55,0x4a,0x85,0x55,0x4a,0x15,0x55,0x50,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x41,0x55,0x28,0x55,0x54,0xa8,0x55,0x52,0xa1,0x55,0x4a,
+ 0x85,0x55,0x2a,0x15,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x55,0x54,0xaa,0x15,0x52,0x00,0x85,0x48,0x04,0x21,0x20,0xa2,0x08,0x22,0x0a,0x08,0x22,0x02,
+ 0x08,0x22,0x0a,0x08,0x20,0xa2,0x21,0x21,0x04,0x85,0x48,0x55,0x05,0x52,0x00,0x21,0x54,0xaa,0x85,0x55,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x54,0xaa,0x15,0x52,0xaa,0x85,0x4a,0x82,0xa1,0x2a,0x14,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x00,
+ 0x28,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x28,0x00,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x41,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,0x15,0x2a,0xaa,0x85,0x2a,0xaa,0xa1,0x28,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x00,0xa8,0x2a,0xaa,0xa1,0x2a,0xaa,
+ 0xa1,0x28,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x00,0xa8,0x2a,0xaa,0xa1,0x2a,0xaa,0x85,0x40,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x41,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,
+ 0x55,0x28,0x55,0x55,0x28,0x55,0x41,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x01,0x55,0x2a,0xa8,0x55,0x2a,0xaa,0x15,0x28,0x0a,0x85,0x28,0x52,0xa1,0x28,0x54,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,
+ 0x28,0x28,0x55,0x28,0x28,0x54,0xa8,0x28,0x52,0xa1,0x28,0x0a,0x85,0x2a,0xaa,0x15,0x2a,0xa8,0x55,0x40,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x28,0x00,0x01,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x00,0x15,0x2a,0xaa,0x85,0x2a,0xaa,
+ 0x85,0x28,0x00,0x15,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x00,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x40,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x28,0x00,0x01,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x00,0x15,0x2a,0xaa,0x85,0x2a,0xaa,
+ 0x85,0x28,0x00,0x15,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x02,0xa1,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x41,0x28,0x40,0x01,0x28,0x2a,
+ 0xa8,0x28,0x2a,0xa8,0x28,0x40,0x28,0x28,0x55,0x28,0x2a,0x00,0x28,0x4a,0xaa,0xa8,0x52,0xaa,0xa8,0x54,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x00,0x28,0x2a,0xaa,0xa8,0x2a,0xaa,
+ 0xa8,0x28,0x00,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x41,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x52,0xaa,0x85,0x54,0x28,0x15,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x54,0x28,0x15,0x52,0xaa,0x85,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x01,0x55,0x2a,0xa8,0x55,0x2a,0xa8,0x55,0x42,0x81,0x55,0x52,0x85,0x55,0x52,0x85,0x55,0x52,0x85,0x55,0x52,0x85,0x55,0x52,
+ 0x85,0x55,0x52,0x85,0x41,0x52,0x85,0x28,0x52,0x85,0x2a,0x0a,0x85,0x4a,0xaa,0x15,0x52,0xa8,0x55,0x54,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x28,0x54,0xa8,0x28,0x52,0xa1,0x28,0x4a,0x85,0x28,0x2a,0x15,0x28,0xa8,0x55,0x2a,0xa1,0x55,0x2a,0xa1,
+ 0x55,0x28,0xa8,0x55,0x28,0x2a,0x15,0x28,0x4a,0x85,0x28,0x52,0xa1,0x28,0x54,0xa8,0x28,0x55,0x28,0x41,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,
+ 0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x00,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x40,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x2a,0x14,0xa8,0x2a,0x82,0xa8,0x2a,0xaa,0xa8,0x28,0xaa,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x41,
+ 0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x41,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x2a,0x15,0x28,0x2a,0x85,0x28,0x2a,0x85,0x28,0x28,0xa1,0x28,0x28,0xa1,0x28,0x28,0x28,0x28,0x28,0x28,
+ 0x28,0x28,0x4a,0x28,0x28,0x4a,0x28,0x28,0x52,0xa8,0x28,0x52,0xa8,0x28,0x54,0xa8,0x28,0x55,0x28,0x41,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,
+ 0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,0x15,0x2a,0xaa,0x85,0x2a,0xaa,0xa1,0x28,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x00,0xa8,0x2a,0xaa,0xa1,0x2a,0xaa,
+ 0x85,0x28,0x00,0x15,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x41,
+ 0x28,0x28,0x28,0x28,0x28,0x2a,0x28,0x28,0x4a,0xa8,0x2a,0x02,0xa1,0x4a,0xaa,0xa8,0x52,0xa8,0x28,0x54,0x01,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,0x15,0x2a,0xaa,0x85,0x2a,0xaa,0xa1,0x28,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x00,0xa8,0x2a,0xaa,0xa1,0x2a,0xaa,
+ 0x85,0x28,0xa8,0x15,0x28,0x2a,0x15,0x28,0x4a,0x85,0x28,0x52,0xa1,0x28,0x54,0xa8,0x28,0x55,0x28,0x41,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x05,0x52,0xaa,0xa1,0x4a,0xaa,0xa8,0x2a,0x00,0x28,0x28,0x55,0x41,0x28,0x55,0x55,0x2a,0x00,0x15,0x4a,0xaa,0x85,0x52,0xaa,
+ 0xa1,0x54,0x00,0xa8,0x55,0x55,0x28,0x41,0x55,0x28,0x28,0x00,0xa8,0x2a,0xaa,0xa1,0x4a,0xaa,0x85,0x50,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x40,0x28,0x01,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,
+ 0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,
+ 0x28,0x28,0x55,0x28,0x2a,0x14,0xa8,0x4a,0x82,0xa1,0x52,0xaa,0x85,0x54,0xaa,0x15,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x41,0x28,0x28,0x28,0x28,0x28,0x28,
+ 0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x2a,0xaa,0xa8,0x4a,0xaa,0xa1,0x52,0x82,0x85,0x54,0x14,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x2a,0x14,0xa8,0x4a,0x82,0xa1,0x52,0xaa,0x85,0x54,0xaa,0x15,0x54,0xaa,
+ 0x15,0x52,0xaa,0x85,0x4a,0x82,0xa1,0x2a,0x14,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x41,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x2a,0x14,0xa8,0x4a,0x82,0xa1,0x52,0xaa,
+ 0x85,0x54,0xaa,0x15,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x40,0x00,0x28,0x55,0x54,0xa8,0x55,0x52,0xa1,0x55,0x4a,0x85,0x55,0x2a,0x15,0x54,0xa8,
+ 0x55,0x52,0xa1,0x55,0x4a,0x85,0x55,0x2a,0x15,0x55,0x28,0x00,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x40,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x15,0x55,0x2a,0x85,0x55,0x2a,0x85,0x55,0x28,0x15,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x15,0x55,0x2a,0x85,0x55,0x2a,0x85,0x55,0x40,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x2a,0x15,0x55,0x4a,0x85,0x55,0x52,0xa1,0x55,0x54,0xa8,0x55,0x55,0x2a,
+ 0x15,0x55,0x4a,0x85,0x55,0x52,0xa1,0x55,0x54,0xa8,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x01,0x55,0x52,0xa8,0x55,0x52,0xa8,0x55,0x54,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x54,0x28,0x55,0x52,0xa8,0x55,0x52,0xa8,0x55,0x54,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x54,0xaa,0x15,0x52,0x82,0x85,0x52,0x14,0x85,0x50,0x55,0x05,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x40,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x50,0x55,0x55,0x4a,0x15,0x55,0x52,0x85,0x55,0x54,0xa1,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x52,0xaa,0xa1,0x54,0x00,0xa8,0x54,0x00,0x28,0x52,0xaa,0x28,0x4a,0xaa,
+ 0xa8,0x2a,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa8,0x52,0xaa,0x28,0x54,0x00,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x40,0x55,0x28,0x2a,0x15,0x28,0xaa,0x85,0x2a,0xa2,0xa1,0x2a,0x84,0xa8,0x2a,0x15,
+ 0x28,0x2a,0x15,0x28,0x2a,0x15,0x28,0x2a,0x84,0xa8,0x2a,0xa2,0xa1,0x28,0xaa,0x85,0x28,0x2a,0x15,0x41,0x40,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,
+ 0x28,0x28,0x55,0x41,0x28,0x55,0x41,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x01,0x28,0x54,0xa8,0x28,0x52,0xaa,0x28,0x4a,0x8a,0xa8,0x2a,0x12,0xa8,0x28,0x54,
+ 0xa8,0x28,0x54,0xa8,0x28,0x54,0xa8,0x2a,0x12,0xa8,0x4a,0x8a,0xa8,0x52,0xaa,0x28,0x54,0xa8,0x28,0x55,0x01,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x00,0x28,0x2a,0xaa,
+ 0xa8,0x2a,0xaa,0xa1,0x28,0x00,0x05,0x28,0x55,0x01,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x50,0x05,0x55,0x4a,0xa1,0x55,0x2a,0xa1,0x55,0x28,0x05,0x50,0x28,0x05,0x4a,0xaa,0xa1,0x4a,0xaa,0xa1,0x50,0x28,0x05,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,
+ 0xa8,0x52,0xaa,0x28,0x54,0x00,0x28,0x50,0x55,0x28,0x4a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x40,0x55,0x28,0x2a,0x15,0x28,0xaa,0x85,0x2a,0xa2,0xa1,0x2a,0x84,0xa8,0x2a,0x15,
+ 0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x41,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x54,0x01,0x55,0x52,0xa8,0x55,0x52,0xa8,0x55,0x54,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x2a,0x15,0x55,0x4a,0x85,0x55,0x52,0x85,0x55,0x54,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x54,0x15,0x55,0x52,0x85,0x55,0x52,0x85,0x55,0x54,0x15,0x55,0x40,0x15,0x55,0x2a,0x85,0x55,0x2a,0x85,0x55,0x42,0x85,0x55,0x52,0x85,0x55,0x52,
+ 0x85,0x55,0x52,0x85,0x55,0x52,0x85,0x55,0x52,0x85,0x54,0x0a,0x85,0x52,0xaa,0x15,0x52,0xa8,0x55,0x54,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x41,0x28,0x55,0x28,0x28,0x54,0xa8,0x28,0x52,0xa1,0x28,0x4a,0x85,0x28,0x2a,
+ 0x15,0x28,0xa8,0x55,0x2a,0xaa,0x15,0x2a,0x8a,0x85,0x2a,0x12,0xa1,0x28,0x54,0xa8,0x28,0x55,0x28,0x41,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x00,0x15,0x28,0xaa,0x85,0x2a,0xaa,0xa1,0x2a,0x28,0xa8,0x28,0x28,0x28,0x28,0x28,
+ 0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x41,0x41,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x00,0x15,0x28,0xaa,0x85,0x2a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,
+ 0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x41,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x28,0x55,0x28,0x28,0x55,
+ 0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x00,0x15,0x28,0xaa,0x85,0x2a,0xaa,0xa1,0x2a,0x80,0xa8,0x2a,0x15,0x28,0x2a,0x15,0x28,0x2a,0x15,
+ 0x28,0x2a,0x80,0xa8,0x2a,0xaa,0xa1,0x28,0xaa,0x85,0x28,0x00,0x15,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x41,0x52,0xaa,0x28,0x4a,0xaa,0xa8,0x2a,0x02,0xa8,0x28,0x54,0xa8,0x28,0x54,0xa8,0x28,0x54,
+ 0xa8,0x2a,0x02,0xa8,0x4a,0xaa,0xa8,0x52,0xa8,0xa8,0x54,0x01,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x40,0x15,0x28,0x2a,0x85,0x28,0xaa,0xa1,0x2a,0xa0,0xa8,0x2a,0x85,0x28,0x2a,0x15,
+ 0x41,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x15,0x52,0xaa,0x85,0x4a,0xaa,0xa1,0x2a,0x00,0xa8,0x2a,0x01,0x28,0x4a,0xa8,
+ 0x01,0x50,0xaa,0x85,0x41,0x0a,0xa1,0x28,0x50,0xa8,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x54,0x28,0x15,0x52,0xaa,0x85,0x52,0xaa,0x85,0x54,0x28,0x15,0x55,0x28,0x55,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x2a,0x15,0x55,0x4a,0x85,0x55,0x52,0x85,0x55,0x54,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,
+ 0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x2a,0x00,0xa8,0x4a,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,
+ 0x28,0x28,0x55,0x28,0x2a,0x14,0xa8,0x4a,0x82,0xa1,0x52,0xaa,0x85,0x54,0xaa,0x15,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x41,0x28,0x28,0x28,
+ 0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x28,0x2a,0x28,0xa8,0x4a,0xaa,0xa1,0x52,0x82,0x85,0x54,0x14,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x2a,0x14,0xa8,0x4a,0x82,0xa1,0x52,0xaa,0x85,0x54,0xaa,
+ 0x15,0x55,0x28,0x55,0x54,0xaa,0x15,0x52,0xaa,0x85,0x4a,0x82,0xa1,0x2a,0x14,0xa8,0x28,0x55,0x28,0x41,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x41,0x28,0x55,0x28,0x28,0x55,0x28,0x28,0x54,0xa8,0x28,0x54,0xa8,0x28,0x52,0xa8,0x2a,0x0a,
+ 0xa8,0x4a,0xaa,0x28,0x52,0xa8,0x28,0x54,0x01,0x28,0x54,0x00,0xa8,0x52,0xaa,0xa1,0x52,0xaa,0x85,0x54,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x40,0x00,0xa8,0x55,0x52,0xa1,0x55,0x4a,
+ 0x85,0x55,0x2a,0x15,0x54,0xa8,0x55,0x52,0xa1,0x55,0x4a,0x80,0x01,0x2a,0xaa,0xa8,0x2a,0xaa,0xa8,0x40,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x50,0x15,0x55,0x4a,0x85,0x55,0x4a,0x85,0x55,0x2a,0x85,0x55,0x28,0x15,0x55,0x28,0x55,0x55,0x28,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x15,0x55,0x2a,0x85,0x55,0x4a,0x85,0x55,0x4a,0x85,0x55,0x50,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x54,0x05,0x55,0x52,0xa1,0x55,0x52,0xa8,0x55,0x52,0xa8,0x55,0x54,0x28,0x55,0x55,0x28,0x55,0x55,0x28,0x55,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x28,
+ 0x55,0x55,0x28,0x55,0x54,0x28,0x55,0x52,0xa8,0x55,0x52,0xa8,0x55,0x52,0xa1,0x55,0x54,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x05,0x51,0x54,0xa1,0x48,0x52,0xa8,0x28,0x4a,0x0a,0xa1,0x28,0x52,0x85,0x41,0x54,
+ 0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,
+ 0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,
+ 0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,
+ 0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x54,0x55,0x55,0x40,0x55,0x54,0x0a,0x55,0x42,0xaa,0x54,0x02,0xaa,0x50,0x00,0xaa,0x50,0x00,0xaa,0x54,0x00,0xaa,0x55,0x50,0xaa,0x55,0x50,0xaa,0x55,0x50,
+ 0xaa,0x55,0x50,0x00,0x55,0x50,0x00,0x55,0x50,0x00,0x55,0x54,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x05,0x55,0x55,0x80,0x15,0x55,0xaa,0x01,0x55,0xa8,0x00,0x15,0xa8,0x00,0x05,0xa8,0x00,0x05,0xa8,0x00,0x15,0xa8,0x15,0x55,0xa8,0x15,0x55,0xa8,0x15,
+ 0x55,0x00,0x15,0x55,0x00,0x15,0x55,0x00,0x15,0x55,0x00,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x54,0x55,0x54,0x00,0x55,0x00,0x2a,0x55,0x00,0x0a,0x55,0x00,0x2a,0x55,0x50,0xaa,0x55,0x42,0xaa,0x55,0x0a,0xaa,0x54,0x0a,0xaa,0x54,0x00,
+ 0x2a,0x54,0x00,0x00,0x54,0x00,0x00,0x55,0x54,0x00,0x55,0x55,0x50,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x00,0x05,0x55,0xa8,0x01,0x55,0xaa,0x00,0x55,0xaa,0x80,0x15,0xa8,0x00,0x05,0xa8,0x00,0x05,0xa0,0x00,0x05,0xa0,0x00,0x05,0x80,0x55,0x05,0x00,0x55,
+ 0x55,0x01,0x55,0x55,0x01,0x55,0x55,0x05,0x55,0x55,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x00,0x55,0x54,0x02,0x55,0x54,0x0a,0x55,0x42,0xaa,0x54,0x2a,0xaa,0x50,0xaa,0xaa,0x50,0x2a,0xaa,0x50,0x02,0xa0,0x54,0x00,
+ 0x00,0x55,0x00,0x00,0x55,0x40,0x00,0x55,0x50,0x01,0x55,0x54,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x01,0x55,0x00,0x01,0x55,0xaa,0xa0,0x55,0xaa,0xa0,0x55,0xaa,0xa0,0x55,0xa8,0x28,0x15,0x80,0x00,0x15,0x00,0x00,0x15,0x00,0x00,0x15,0x01,0x40,
+ 0x15,0x15,0x54,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x50,0x55,0x55,0x40,0x55,0x55,0x40,0x54,0x00,0x02,0x50,0x0a,0xaa,0x50,0xaa,0xaa,0x50,0x2a,0xaa,0x54,0x2a,0x80,0x54,0x00,0x00,0x54,0x00,
+ 0x00,0x55,0x00,0x01,0x55,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x05,0x55,0x2a,0x00,0x05,0xaa,0xaa,0x05,0xaa,0xa8,0x05,0xaa,0xa8,0x15,0x80,0xa0,0x15,0x00,0x20,0x55,0x00,0x00,0x55,0x00,0x00,
+ 0x55,0x54,0x01,0x55,0x55,0x01,0x55,0x55,0x45,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x54,0x2a,0xaa,0x54,0x2a,0xaa,0x54,0x2a,0xaa,0x50,0x2a,0xaa,0x50,0x00,0x00,0x50,0x00,0x00,0x50,0x00,
+ 0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x45,0x55,0x55,0x40,0x15,0x55,0x0a,0x01,0x55,0xaa,0xa0,0x05,0xaa,0xaa,0x80,0xaa,0xaa,0x00,0xaa,0xa8,0x00,0x02,0x80,0x01,0x02,0x00,0x05,0x00,0x00,
+ 0x55,0x40,0x01,0x55,0x40,0x05,0x55,0x40,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x50,0x05,0x55,0x42,0x00,0x54,0x0a,0xaa,0x50,0x2a,0xaa,0x50,0x02,0xaa,0x50,0x00,0x02,0x50,0x00,0x00,0x55,0x40,0x00,0x55,0x55,
+ 0x40,0x55,0x55,0x40,0x55,0x55,0x00,0x55,0x55,0x00,0x55,0x55,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x15,0x55,0x00,0x01,0x55,0x80,0x80,0x55,0xaa,0xa8,0x15,0xaa,0xaa,0x05,0xaa,0xaa,0x80,0x2a,0xaa,0x00,0x2a,0x00,0x00,0x00,0x00,
+ 0x00,0x00,0x00,0x05,0x00,0x01,0x55,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x54,0x01,0x55,0x50,0xa0,0x55,0x02,0xaa,0x54,0x0a,0xaa,0x54,0x02,0xaa,0x54,0x00,0x2a,0x55,0x40,0x02,0x55,0x50,0x02,0x55,0x54,0x0a,0x55,0x40,
+ 0x00,0x55,0x00,0x00,0x55,0x00,0x00,0x55,0x40,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x15,0x55,0x55,0x01,0x41,0x55,0xa0,0x00,0x55,0xaa,0xa8,0x55,0xaa,0xaa,0x15,0xaa,0xaa,0x15,0xaa,0xaa,0x85,0xaa,0xaa,0x85,0x00,0x00,
+ 0x01,0x00,0x00,0x01,0x00,0x00,0x01,0x00,0x00,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x50,0x55,0x50,0x00,0x55,0x42,0xaa,0x55,0x40,0xaa,0x55,0x50,0x2a,0x55,0x50,0x2a,0x55,0x50,0x0a,0x54,0x00,0x2a,0x50,0x00,0xaa,0x50,0x00,
+ 0x02,0x54,0x00,0x00,0x55,0x50,0x00,0x55,0x55,0x40,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x05,0x55,0x55,0x05,0x55,0x55,0x81,0x55,0x55,0xa0,0x54,0x15,0xa8,0x00,0x15,0xaa,0x28,0x15,0xaa,0xa0,0x15,0xaa,0xa0,0x55,0xaa,0xa0,0x55,0xaa,0xa0,
+ 0x55,0x02,0x80,0x55,0x00,0x01,0x55,0x00,0x01,0x55,0x00,0x01,0x55,0x54,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x00,0x55,0x55,0x00,0x55,0x54,0x2a,0x55,0x54,0x2a,0x55,0x54,0x2a,0x50,0x00,0x2a,0x50,0x00,0xaa,0x50,0x0a,0xaa,0x54,0x00,0xaa,0x55,0x00,
+ 0x2a,0x55,0x40,0x0a,0x55,0x50,0x00,0x55,0x54,0x00,0x55,0x55,0x40,0x55,0x55,0x50,0x55,0x55,0x54,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x00,0x55,0x55,0x00,0x15,0x55,0xa8,0x15,0x55,0xa8,0x15,0x55,0xa8,0x15,0x55,0xa8,0x00,0x05,0xaa,0x00,0x05,0xaa,0xa0,0x05,0xa8,0x00,0x15,0xa0,0x00,
+ 0x55,0x80,0x01,0x55,0x00,0x05,0x55,0x00,0x15,0x55,0x00,0x55,0x55,0x01,0x55,0x55,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x50,0x55,0x55,0x50,0x55,0x55,0x42,0x54,0x15,0x0a,0x54,0x00,0x2a,0x54,0x28,0xaa,0x54,0x0a,0xaa,0x54,0x0a,0xaa,0x55,0x0a,0xaa,0x55,0x0a,
+ 0xaa,0x55,0x02,0x80,0x55,0x40,0x00,0x55,0x40,0x00,0x55,0x40,0x00,0x55,0x40,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x05,0x55,0x55,0x00,0x05,0x55,0xaa,0x81,0x55,0xaa,0x01,0x55,0xa8,0x05,0x55,0xa8,0x05,0x55,0xa0,0x05,0x55,0xa8,0x00,0x15,0xaa,0x00,0x05,0x80,0x00,
+ 0x05,0x00,0x00,0x15,0x00,0x05,0x55,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x55,0x41,0x40,0x55,0x00,0x0a,0x55,0x0a,0xaa,0x54,0x2a,0xaa,0x54,0x2a,0xaa,0x50,0xaa,0xaa,0x50,0xaa,0xaa,0x40,0x00,
+ 0x00,0x40,0x00,0x00,0x40,0x00,0x00,0x50,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x40,0x15,0x55,0x0a,0x05,0x55,0xaa,0x80,0x55,0xaa,0xa0,0x15,0xaa,0x80,0x15,0xa8,0x00,0x15,0x80,0x01,0x55,0x80,0x05,0x55,0xa0,0x15,0x55,0x00,0x01,
+ 0x55,0x00,0x00,0x55,0x00,0x00,0x55,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x54,0x15,0x55,0x40,0x00,0x55,0x02,0x02,0x54,0x2a,0xaa,0x50,0xaa,0xaa,0x02,0xaa,0xaa,0x00,0xaa,0xa8,0x00,0x00,0xa8,0x00,0x00,
+ 0x00,0x50,0x00,0x00,0x55,0x40,0x00,0x55,0x55,0x40,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x50,0x05,0x55,0x00,0x81,0x55,0xaa,0xa0,0x15,0xaa,0xa8,0x05,0xaa,0x00,0x05,0x80,0x00,0x05,0x00,0x00,0x05,0x00,0x01,0x55,0x01,0x55,
+ 0x55,0x01,0x55,0x55,0x00,0x55,0x55,0x00,0x55,0x55,0x40,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x51,0x55,0x54,0x01,0x55,0x40,0xa0,0x50,0x0a,0xaa,0x02,0xaa,0xaa,0x00,0xaa,0xaa,0x00,0x2a,0xaa,0x40,0x02,0x80,0x50,0x00,0x80,0x55,0x00,
+ 0x00,0x55,0x40,0x01,0x55,0x50,0x01,0x55,0x55,0x01,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x55,0xaa,0xa8,0x15,0xaa,0xa8,0x15,0xaa,0xa8,0x15,0xaa,0xa8,0x05,0x00,0x00,0x05,0x00,0x00,0x05,0x00,0x00,
+ 0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x50,0x00,0x50,0x00,0xa8,0x50,0xaa,0xaa,0x50,0x2a,0xaa,0x54,0x2a,0xaa,0x54,0x0a,0x02,0x55,0x08,0x00,0x55,0x00,0x00,0x55,0x00,
+ 0x00,0x55,0x40,0x15,0x55,0x40,0x55,0x55,0x51,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x05,0x55,0x55,0x01,0x55,0x55,0x01,0x55,0x55,0x80,0x00,0x55,0xaa,0xa0,0x05,0xaa,0xaa,0x05,0xaa,0xa8,0x05,0x02,0xa8,0x15,0x00,0x00,0x15,0x00,0x00,
+ 0x15,0x40,0x00,0x55,0x55,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x40,0x55,0x55,0x40,0x00,0x55,0x0a,0xaa,0x55,0x0a,0xaa,0x55,0x0a,0xaa,0x54,0x28,0x2a,0x54,0x00,0x02,0x54,0x00,0x00,0x54,0x00,0x00,0x54,0x01,
+ 0x40,0x54,0x15,0x54,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x15,0x55,0x80,0x15,0x55,0xa0,0x15,0x55,0xaa,0x81,0x55,0xaa,0xa8,0x15,0xaa,0xaa,0x05,0xaa,0xa8,0x05,0x0a,0x80,0x05,0x00,0x00,
+ 0x15,0x00,0x00,0x55,0x00,0x01,0x55,0x40,0x05,0x55,0x54,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x54,0x00,0x55,0x50,0x2a,0x55,0x40,0xaa,0x55,0x02,0xaa,0x54,0x00,0x2a,0x50,0x00,0x2a,0x50,0x00,0x0a,0x50,0x00,0x0a,0x51,0x55,0x02,0x55,0x55,
+ 0x00,0x55,0x55,0x40,0x55,0x55,0x40,0x55,0x55,0x50,0x55,0x55,0x54,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x15,0x55,0x55,0x00,0x15,0x55,0xa8,0x00,0x55,0xa0,0x00,0x55,0xa8,0x00,0x55,0xaa,0x05,0x55,0xaa,0x81,0x55,0xaa,0xa0,0x55,0xaa,0xa0,0x15,0xa8,0x00,
+ 0x15,0x00,0x00,0x15,0x00,0x00,0x15,0x00,0x15,0x55,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,
+ 0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,
+ 0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x21,0x55,0x55,0x20,0x55,0x55,0x2a,0x55,0x55,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x55,0x55,0x2a,0x55,0x55,0x20,0x55,0x55,0x21,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x55,0x55,0xa8,0x55,0x55,0x08,0x55,0x55,0x48,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x48,0x55,0x55,0x08,0x55,0x55,0xa8,0x55,0x55,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,
+ 0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,
+ 0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x00,0x55,0x4a,0xaa,0x55,0x4a,0xaa,0x55,0x40,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x40,0x00,0x55,0x4a,0xaa,0x55,0x4a,0xaa,0x55,0x4a,0x00,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x4a,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x00,0x01,0x55,0xaa,0xa1,0x55,0xaa,0xa1,0x55,0x00,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x54,0xa1,0x55,0x54,0xa1,0x55,0x54,0xa1,0x55,0x00,0xa1,0x55,0xaa,0xa1,0x55,0xaa,0xa1,0x55,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x45,0x55,0x55,0x05,0x55,0x54,0x85,0x55,0x52,0x80,0x00,0x4a,0xaa,0xa8,0x2a,0xaa,0xa8,0x4a,0xaa,0xa8,0x52,0x80,
+ 0x00,0x54,0x85,0x55,0x55,0x05,0x55,0x55,0x45,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x51,0x55,0x55,0x50,0x55,0x55,0x52,0x15,0x00,0x02,0x85,0x2a,0xaa,0xa1,0x2a,0xaa,0xa8,0x2a,0xaa,0xa1,0x00,0x02,
+ 0x85,0x55,0x52,0x15,0x55,0x50,0x55,0x55,0x51,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x45,0x55,0x55,0x05,0x55,0x54,0x85,0x55,0x52,0x85,0x55,0x4a,0x85,0x55,0x2a,0x85,0x54,0xaa,0x85,0x52,0xaa,0x85,0x54,0xaa,0x85,0x55,0x2a,
+ 0x85,0x55,0x4a,0x85,0x55,0x52,0x85,0x55,0x54,0x85,0x55,0x55,0x05,0x55,0x55,0x45,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x51,0x55,0x55,0x50,0x55,0x55,0x52,0x15,0x55,0x52,0x85,0x55,0x52,0xa1,0x55,0x52,0xa8,0x55,0x52,0xaa,0x15,0x52,0xaa,0x85,0x52,0xaa,0x15,0x52,0xa8,
+ 0x55,0x52,0xa1,0x55,0x52,0x85,0x55,0x52,0x15,0x55,0x50,0x55,0x55,0x51,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x01,0x2a,0xaa,0xa1,0x25,0x55,0x61,0x26,0xaa,0x60,0x26,0x56,0x62,0x26,0x66,0x61,0x26,0x56,0x62,0x26,0xaa,
+ 0x60,0x25,0x55,0x61,0x2a,0xaa,0xa1,0x00,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x00,0x00,0x4a,0xaa,0xa8,0x49,0x55,0x58,0x09,0xaa,0x98,0x89,0x95,0x98,0x49,0x99,0x98,0x89,0x95,0x98,0x09,0xaa,
+ 0x98,0x49,0x55,0x58,0x4a,0xaa,0xa8,0x40,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x40,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x00,0x00,0x4a,0xaa,0xaa,0x49,0x55,0x55,0x4a,0xaa,0xaa,0x48,0x00,
+ 0x00,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x40,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x55,0x55,0x55,0xaa,0xaa,0xaa,0x00,0x00,
+ 0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x01,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x00,0x00,0x21,0xaa,0xaa,0xa1,0x55,0x55,0x61,0xaa,0xaa,0xa1,0x00,0x00,
+ 0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x40,0x00,0x00,0x2a,0xaa,0xaa,0x20,0x00,0x08,0x22,0x14,0x88,0x22,0x12,0x88,0x22,0x0a,0x88,0x22,0x2a,0x88,0x22,0xaa,0x88,0x22,0xaa,0x88,0x22,0x2a,
+ 0x88,0x22,0x0a,0x88,0x22,0x12,0x88,0x22,0x14,0x88,0x20,0x00,0x08,0x2a,0xaa,0xaa,0x40,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x50,0x55,0x55,0x4a,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,
+ 0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x48,0x55,0x55,0x4a,0x55,0x55,0x50,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,
+ 0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0xaa,0xaa,0x85,0xaa,0xaa,0x85,0xaa,0xaa,0x85,0xaa,0xaa,0x85,0xaa,0xaa,0x85,0xaa,0xaa,0x85,0xaa,0xaa,
+ 0x85,0xaa,0xaa,0x85,0xaa,0xaa,0x85,0xaa,0xaa,0x85,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0xaa,0xa1,0x55,0xaa,0xa1,0x55,0xaa,0xa1,0x55,0xaa,0xa1,0x55,0xaa,0xa1,0x55,0xaa,0xa1,0x55,0xaa,0xa1,
+ 0x55,0xaa,0xa1,0x55,0xaa,0xa1,0x55,0xaa,0xa1,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0xa8,0x55,0x55,0xa8,0x55,0x55,0xa8,0x55,0x55,0xa8,0x55,0x55,0xa8,0x55,0x55,0xa8,0x55,0x55,0xa8,0x55,
+ 0x55,0xa8,0x55,0x55,0xa8,0x55,0x55,0xa8,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x00,0x00,0x00,0xaa,0xaa,0xaa,0x00,0x00,0x00,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x05,0x55,0x55,0xa1,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,
+ 0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0x21,0x55,0x55,0xa1,0x55,0x55,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x00,0x00,0x01,0xaa,0xaa,0xa8,0x20,0x00,0x08,0x22,0x14,0x88,0x22,0x84,0x88,0x22,0xa0,0x88,0x22,0xa8,0x88,0x22,0xaa,0x88,0x22,0xaa,0x88,0x22,0xa8,
+ 0x88,0x22,0xa0,0x88,0x22,0x84,0x88,0x22,0x14,0x88,0x20,0x00,0x08,0xaa,0xaa,0xa8,0x00,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x54,0x55,0x55,0x52,0x55,0x50,0x52,0x55,0x4a,0x10,0x55,0x4a,0x0a,0x55,0x50,0x2a,0x55,0x54,0xa0,0x55,0x02,0x85,0x54,0xa2,0x85,0x54,0xa2,0x85,0x55,0x02,
+ 0x85,0x55,0x54,0xa0,0x55,0x50,0x2a,0x55,0x4a,0x0a,0x55,0x4a,0x10,0x55,0x50,0x52,0x55,0x55,0x52,0x55,0x55,0x50,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x15,0x55,0x55,0x85,0x55,0x55,0x85,0x05,0x55,0x04,0xa1,0x55,0xa0,0xa1,0x55,0xa8,0x05,0x55,0x0a,0x15,0x55,0x52,0x80,0x55,0x52,0x8a,0x15,0x52,0x8a,0x15,0x52,0x80,
+ 0x55,0x0a,0x15,0x55,0xa8,0x05,0x55,0xa0,0xa1,0x55,0x04,0xa1,0x55,0x85,0x05,0x55,0x85,0x55,0x55,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x50,0x55,0x55,0x0a,0x55,0x54,0xaa,0x55,0x52,0xa0,0x55,0x4a,0x04,0x55,0x4a,0x14,0x55,0x28,0x54,0x55,0x28,0x54,0x55,0x28,0x54,0x55,0x28,
+ 0x54,0x55,0x4a,0x14,0x55,0x4a,0x04,0x55,0x52,0xa0,0x55,0x54,0xaa,0x55,0x55,0x0a,0x55,0x55,0x50,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x05,0x55,0x55,0xa0,0x55,0x55,0xaa,0x15,0x55,0xaa,0x85,0x55,0xaa,0xa1,0x55,0xaa,0xa1,0x55,0xaa,0xa8,0x55,0xaa,0xa8,0x55,0xaa,0xa8,0x55,0xaa,0xa8,
+ 0x55,0xaa,0xa1,0x55,0xaa,0xa1,0x55,0xaa,0x85,0x55,0xaa,0x15,0x55,0xa0,0x55,0x55,0x05,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x41,0x55,0x55,0x28,0x55,0x54,0xa8,0x55,0x52,0x88,0x40,0x0a,0x08,0x2a,0xa8,0x48,0x20,0xa1,0x48,0x20,0xa1,0x48,0x20,0xa1,0x48,0x20,0xa1,0x48,0x20,0xa1,
+ 0x48,0x2a,0xa8,0x48,0x40,0x0a,0x08,0x55,0x52,0x88,0x55,0x54,0xa8,0x55,0x55,0x28,0x55,0x55,0x41,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x51,0x55,0x55,0x68,0x55,0x55,0x5a,0x15,0x54,0x12,0x15,0x52,0x82,0x15,0x44,0x82,0x85,0x20,0xa0,0x85,0x28,0x20,0x85,0x48,0x20,0x85,0x28,0x20,0x85,0x20,0xa0,
+ 0x85,0x44,0x82,0x85,0x52,0x82,0x15,0x54,0x12,0x15,0x55,0x5a,0x15,0x55,0x68,0x55,0x55,0x51,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x40,0x00,0x01,0x2a,0xaa,0xa8,0x48,0x00,0x21,0x48,0x55,0x21,0x48,0x55,0x21,0x48,0x55,0x21,0x52,0x14,0x85,0x54,0x82,0x15,0x55,0x28,0x55,0x55,0x28,0x55,0x54,0x82,
+ 0x15,0x52,0x14,0x85,0x48,0x55,0x21,0x48,0x55,0x21,0x48,0x55,0x21,0x48,0x00,0x21,0x2a,0xaa,0xa8,0x40,0x00,0x01,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x50,0x55,0x55,0x52,0x15,0x55,0x52,0x85,0x55,0x52,0xa1,0x55,0x52,0xa8,0x55,0x52,0xaa,0x15,0x52,0xaa,0x85,0x52,0xaa,0xa1,0x52,0xaa,0xa8,0x52,0xaa,
+ 0x00,0x52,0xaa,0x05,0x52,0x0a,0x85,0x50,0x0a,0x81,0x55,0x52,0xa1,0x55,0x52,0xa1,0x55,0x50,0x81,0x55,0x55,0x15,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x50,0x51,0x51,0x4a,0x08,0x48,0x20,0x8a,0x28,0x20,0x88,
+ 0x88,0x20,0x88,0x88,0x2a,0x88,0x08,0x20,0x88,0x48,0x20,0x88,0x48,0x20,0x88,0x48,0x20,0x88,0x48,0x45,0x11,0x51,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x40,0x51,0x51,0x2a,0x08,0x48,0x20,0x8a,0x28,0x20,0x88,
+ 0x88,0x20,0x88,0x88,0x2a,0x08,0x08,0x20,0x48,0x48,0x21,0x48,0x48,0x21,0x48,0x48,0x21,0x48,0x48,0x45,0x51,0x51,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,
+ 0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,
+ 0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0xaa,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55,0x55};
diff --git a/MAX7456_Font_Updater/font.mcm b/MAX7456_Font_Updater/font.mcm
new file mode 100644
index 00000000..fca85729
--- /dev/null
+++ b/MAX7456_Font_Updater/font.mcm
@@ -0,0 +1,16385 @@
+MAX7456
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+01010101
+01010101
+01010010
+01010101
+01010101
+01010010
+01010101
+01010101
+01010010
+01010101
+01010101
+01000010
+01010101
+01010101
+00101010
+01010101
+01010100
+10000000
+01010101
+01010010
+00010101
+01010101
+01010010
+00010101
+01000000
+00000010
+00010101
+00101010
+10101010
+00010101
+01000000
+00000010
+00010101
+01010101
+01010010
+00010101
+01010101
+01010100
+10000000
+01010101
+01010101
+00101010
+01010101
+01010101
+01000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00010101
+01010101
+01010101
+10000101
+01010101
+01010101
+10000101
+01010101
+01010101
+10000101
+01010101
+01010101
+10000001
+01010101
+01010101
+10101000
+01010101
+01010101
+00000010
+00010101
+01010101
+01010100
+10000101
+01010101
+01010100
+10000101
+01010101
+01010100
+10000000
+00000001
+01010100
+10101010
+10101000
+01010100
+10000000
+00000001
+01010100
+10000101
+01010101
+00000010
+00010101
+01010101
+10101000
+01010101
+01010101
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+01010101
+01010101
+01010010
+01010101
+01010101
+01010010
+01010101
+01010101
+01010010
+01010101
+01010101
+01000010
+01010101
+01010101
+00101010
+01010101
+01010100
+10000000
+01010101
+01010010
+00010100
+01010101
+01010010
+00010010
+01000000
+00000010
+00001000
+00101010
+10101010
+00010010
+01000000
+00000010
+00010100
+01010101
+01010010
+00010010
+01010101
+01010100
+10000000
+01010101
+01010101
+00101010
+01010101
+01010101
+01000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00010101
+01010101
+01010101
+10000101
+01010101
+01010101
+10000101
+01010101
+01010101
+10000101
+01010101
+01010101
+10000001
+01010101
+01010101
+10101000
+01010101
+01010101
+00000010
+00010101
+01010101
+00010100
+10000101
+01010101
+10000100
+10000101
+01010101
+00010100
+10000000
+00000001
+10000100
+10101010
+10101000
+00100000
+10000000
+00000001
+10000100
+10000101
+01010101
+00000010
+00010101
+01010101
+10101000
+01010101
+01010101
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+00000000
+00010101
+01010010
+10001010
+10000101
+01001010
+10001010
+10100001
+00101010
+10001010
+10101000
+00101010
+10001010
+10101000
+00101010
+10001010
+10101000
+00101010
+10000000
+00101000
+00101010
+10101010
+10101000
+00101010
+10101010
+10101000
+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
+00000100
+01010101
+01010100
+10000010
+00010101
+01010100
+10100010
+00010101
+01010100
+10001010
+00010101
+01010100
+10000010
+00010101
+01010101
+00010100
+01010101
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+10000000
+00101000
+00101010
+10101000
+00101000
+00101010
+10100010
+00101000
+00101010
+10001010
+00101000
+00101010
+00101010
+10101000
+00100000
+10101010
+10101000
+01001000
+10101010
+10100001
+01010010
+10101010
+10000101
+01010100
+00000000
+00010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000001
+01010101
+01010101
+00101000
+01010101
+01010100
+10000010
+00010101
+01010100
+10000010
+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
+01000000
+00000000
+00000001
+00101010
+10101010
+10101000
+01000000
+10000000
+00000001
+01010010
+10100001
+01010101
+01001010
+10101000
+01010101
+01010000
+10000001
+01010101
+01010100
+10000101
+01010101
+01010100
+10000101
+01010101
+01010100
+10000101
+01010101
+01010100
+10000101
+01010101
+01010100
+10000101
+01010101
+01010000
+10000001
+01010101
+01001010
+10101000
+01010101
+01010010
+10100001
+01010101
+01000000
+10000000
+00000001
+00101010
+10101010
+10101000
+01000000
+00000000
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+00000000
+00000001
+00101010
+10101010
+10101000
+01000000
+10000000
+00000001
+01010010
+10100001
+01010101
+01001010
+10101000
+01010101
+01000000
+10000001
+00010001
+00100000
+10000100
+10001000
+00101000
+10000100
+10001000
+00101010
+10010100
+10101000
+00101000
+10000100
+10001000
+00100000
+10000100
+10001000
+01000000
+10000001
+00010001
+01001010
+10101000
+01010101
+01010010
+10100001
+01010101
+01000000
+10000000
+00000001
+00101010
+10101010
+10101000
+01000000
+00000000
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+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
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+10101010
+10101000
+01000000
+00000000
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+00000000
+00000001
+00101010
+10101010
+10101000
+01001010
+10101010
+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
+01000001
+01010101
+01010101
+00101000
+01010101
+01010100
+10101010
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+10101010
+10101000
+01000000
+00000000
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+00000000
+00000001
+00010101
+01010101
+01010100
+01000101
+01010101
+01010001
+01010001
+01010101
+01000101
+01010100
+01010101
+00010101
+01010101
+00010100
+01010101
+01010101
+01000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000001
+01010101
+01010101
+00010100
+01010101
+01010100
+01010101
+00010101
+01010001
+01010101
+01000101
+01000101
+01010101
+01010001
+00010101
+01010101
+01010100
+01000000
+00000000
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+00000000
+00000001
+00101010
+10101010
+10101000
+01001010
+10101010
+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
+01000001
+01010101
+01010100
+00101000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01010000
+00000000
+00000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000001
+01010101
+01010100
+00101000
+00010101
+01010010
+10101010
+10000101
+01001000
+00000000
+00100001
+01001000
+10100010
+00100001
+01001000
+10101010
+00100001
+01001010
+10101010
+10100001
+01001000
+00000000
+00100001
+01001010
+10100000
+10100001
+01001010
+10001010
+10100001
+01001000
+00000000
+00100001
+01001010
+10101010
+10100001
+01001000
+00000000
+00100001
+01001000
+10101010
+00100001
+01001000
+00000010
+00100001
+01001010
+10101010
+10100001
+01010000
+00000000
+00000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000001
+01010101
+01010100
+00101000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001010
+10100000
+00100001
+01001000
+00001010
+10100001
+01001010
+10100000
+00100001
+01001010
+10101010
+10100001
+01001000
+00000000
+00100001
+01001010
+10101010
+10100001
+01001000
+00000000
+00100001
+01001000
+10101010
+00100001
+01001010
+00000000
+10100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01010000
+00000000
+00000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000001
+01010101
+01010100
+00101000
+00010101
+01010010
+10101010
+10000101
+01001000
+10100010
+10100001
+01001000
+10100010
+10100001
+01001000
+00000010
+00100001
+01001000
+10100010
+00100001
+01001000
+10100010
+00100001
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01001000
+10101010
+10100001
+01001000
+10101000
+10100001
+01001000
+10100010
+00100001
+01001000
+10100010
+00100001
+01001000
+00001000
+10100001
+01001010
+10101010
+10100001
+01010000
+00000000
+00000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010001
+00010101
+01010101
+01001000
+10000101
+01010101
+00100010
+00100001
+01010101
+00100010
+00100001
+01010101
+00100010
+00100001
+01010101
+00100010
+00100001
+01010101
+01000000
+00000101
+01010101
+01010100
+01010101
+01010101
+01010010
+00010100
+01010101
+01001000
+10000010
+00010101
+01001000
+10000010
+00010101
+00100000
+00100010
+00010101
+00101010
+10100010
+10000101
+00100000
+00100010
+00100001
+00100001
+00100010
+00100001
+01000101
+01000100
+01000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000101
+01010101
+01010100
+10000101
+01010101
+01010010
+00010101
+01010101
+01001010
+00010101
+01010101
+00101000
+01010101
+01010100
+10101000
+00000001
+01010010
+10101010
+10100001
+01001010
+10101010
+10000101
+01000000
+00101010
+00010101
+01010100
+10101000
+01010101
+01010100
+10100001
+01010101
+01010010
+10000101
+01010101
+01010010
+00010101
+01010101
+01001000
+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
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+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
+01010000
+01010101
+01000001
+01001010
+00010101
+00101000
+01001010
+00010100
+10101000
+01010000
+01010010
+10100001
+01010101
+01001010
+10000101
+01010101
+00101010
+00010101
+01010100
+10101000
+01010101
+01010010
+10100001
+01010101
+01001010
+10000101
+00000101
+00101010
+00010100
+10100001
+00101000
+01010100
+10100001
+01000001
+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
+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
+01000001
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010000
+00101000
+00000101
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+01010000
+00101000
+00000101
+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
+01010101
+01010101
+01010101
+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
+01010100
+00000000
+00000101
+01010010
+10101010
+10100001
+01010010
+10101010
+10100001
+01010100
+00000000
+00000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+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
+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
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+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
+01000001
+01010101
+01010101
+00101000
+01010101
+01010100
+10101000
+01010101
+01010010
+10101000
+01010101
+01010010
+10101000
+01010101
+01010000
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+10000000
+10101000
+00101010
+00010101
+00101000
+01000000
+01010101
+00101000
+01010101
+01010100
+10101000
+01010101
+01010010
+10100001
+01010101
+01001010
+10000101
+01010101
+00101010
+00010101
+01010100
+10101000
+01010101
+01010010
+10100001
+01010101
+01001010
+10000000
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101000
+01010101
+00101000
+01000001
+01010101
+00101000
+01010101
+01000000
+10101000
+01010101
+00101010
+10100001
+01010101
+00101010
+10100001
+01010101
+01000000
+10101000
+01000001
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+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
+01010100
+00010101
+01010101
+01010010
+10000101
+01010101
+01001010
+10000101
+01010101
+00101010
+10000101
+01010100
+10101010
+10000101
+01010010
+10100010
+10000101
+01001010
+10000010
+10000101
+00101010
+00010010
+10000101
+00101000
+00000010
+10000001
+00101010
+10101010
+10101000
+00101010
+10101010
+10101000
+01000000
+00000010
+10000001
+01010101
+01010010
+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
+01000000
+00000000
+00000001
+00101010
+10101010
+10101000
+00101010
+10101010
+10101000
+00101000
+00000000
+00000001
+00101000
+00000000
+00010101
+00101010
+10101010
+10000101
+00101010
+10101010
+10100001
+01000000
+00000000
+10101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01000001
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+01000001
+00101000
+00000000
+00010101
+00101010
+10101010
+10000101
+00101010
+10101010
+10100001
+00101000
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+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
+01000000
+00000000
+00000001
+00101010
+10101010
+10101000
+00101010
+10101010
+10101000
+01000000
+00000000
+00101000
+01010101
+01010100
+10101000
+01010101
+01010010
+10100001
+01010101
+01001010
+10000101
+01010101
+00101010
+00010101
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+01001010
+10101010
+10100001
+01001010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+00101000
+01001010
+10101010
+10101000
+01010010
+10101010
+10101000
+01010100
+00000000
+00101000
+01000001
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+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
+01000001
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+01000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000001
+01010101
+01010101
+00101000
+01010101
+01010101
+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
+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
+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
+00000101
+01010101
+01010100
+10100001
+01010101
+01010010
+10100001
+01010101
+01001010
+10000101
+01010101
+00101010
+00010101
+01010100
+10101000
+01010101
+01010010
+10100001
+01010101
+01001010
+10000101
+01010101
+01001010
+10000101
+01010101
+01010010
+10100001
+01010101
+01010100
+10101000
+01010101
+01010101
+00101010
+00010101
+01010101
+01001010
+10000101
+01010101
+01010010
+10100001
+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
+01010100
+00000000
+00000101
+01010010
+10101010
+10100001
+01010010
+10101010
+10100001
+01010100
+00000000
+00000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+00000000
+00000101
+01010010
+10101010
+10100001
+01010010
+10101010
+10100001
+01010100
+00000000
+00000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010000
+01010101
+01010101
+01001010
+00010101
+01010101
+01001010
+10000101
+01010101
+01010010
+10100001
+01010101
+01010100
+10101000
+01010101
+01010101
+00101010
+00010101
+01010101
+01001010
+10000101
+01010101
+01010010
+10100001
+01010101
+01010010
+10100001
+01010101
+01001010
+10000101
+01010101
+00101010
+00010101
+01010100
+10101000
+01010101
+01010010
+10100001
+01010101
+01001010
+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
+01000001
+01010101
+01010101
+00101000
+01010101
+01010100
+10101010
+00010101
+01010010
+10101010
+10000101
+01001010
+10000010
+10100001
+00101010
+00010100
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+00000000
+00101000
+00101010
+10101010
+10101000
+00101010
+10101010
+10101000
+00101000
+00000000
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+01000001
+01010101
+01000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+00000000
+00010101
+00101010
+10101010
+10000101
+00101010
+10101010
+10100001
+00101000
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+00000000
+10101000
+00101010
+10101010
+10100001
+00101010
+10101010
+10100001
+00101000
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+00000000
+10101000
+00101010
+10101010
+10100001
+00101010
+10101010
+10000101
+01000000
+00000000
+00010101
+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
+00101000
+01010101
+01000001
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01000001
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+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
+01000000
+00000001
+01010101
+00101010
+10101000
+01010101
+00101010
+10101010
+00010101
+00101000
+00001010
+10000101
+00101000
+01010010
+10100001
+00101000
+01010100
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010100
+10101000
+00101000
+01010010
+10100001
+00101000
+00001010
+10000101
+00101010
+10101010
+00010101
+00101010
+10101000
+01010101
+01000000
+00000001
+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
+00101000
+00000000
+00000001
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+00000000
+00010101
+00101010
+10101010
+10000101
+00101010
+10101010
+10000101
+00101000
+00000000
+00010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+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
+01000000
+00000000
+00000001
+00101010
+10101010
+10101000
+00101010
+10101010
+10101000
+00101000
+00000000
+00000001
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+00000000
+00010101
+00101010
+10101010
+10000101
+00101010
+10101010
+10000101
+00101000
+00000000
+00010101
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+00000010
+10100001
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+01000001
+00101000
+01000000
+00000001
+00101000
+00101010
+10101000
+00101000
+00101010
+10101000
+00101000
+01000000
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+00101000
+01001010
+10101010
+10101000
+01010010
+10101010
+10101000
+01010100
+00000000
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+00000000
+00101000
+00101010
+10101010
+10101000
+00101010
+10101010
+10101000
+00101000
+00000000
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+01000001
+01010101
+01000001
+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
+01000000
+00000001
+01010101
+00101010
+10101000
+01010101
+00101010
+10101000
+01010101
+01000010
+10000001
+01010101
+01010010
+10000101
+01010101
+01010010
+10000101
+01010101
+01010010
+10000101
+01010101
+01010010
+10000101
+01010101
+01010010
+10000101
+01010101
+01010010
+10000101
+01000001
+01010010
+10000101
+00101000
+01010010
+10000101
+00101010
+00001010
+10000101
+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
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101000
+01010100
+10101000
+00101000
+01010010
+10100001
+00101000
+01001010
+10000101
+00101000
+00101010
+00010101
+00101000
+10101000
+01010101
+00101010
+10100001
+01010101
+00101010
+10100001
+01010101
+00101000
+10101000
+01010101
+00101000
+00101010
+00010101
+00101000
+01001010
+10000101
+00101000
+01010010
+10100001
+00101000
+01010100
+10101000
+00101000
+01010101
+00101000
+01000001
+01010101
+01000001
+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
+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
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101010
+00010100
+10101000
+00101010
+10000010
+10101000
+00101010
+10101010
+10101000
+00101000
+10101010
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+01000001
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+01000001
+01010101
+01000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101010
+00010101
+00101000
+00101010
+10000101
+00101000
+00101010
+10000101
+00101000
+00101000
+10100001
+00101000
+00101000
+10100001
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+01001010
+00101000
+00101000
+01001010
+00101000
+00101000
+01010010
+10101000
+00101000
+01010010
+10101000
+00101000
+01010100
+10101000
+00101000
+01010101
+00101000
+01000001
+01010101
+01000001
+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
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+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
+01000000
+00000000
+00010101
+00101010
+10101010
+10000101
+00101010
+10101010
+10100001
+00101000
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+00000000
+10101000
+00101010
+10101010
+10100001
+00101010
+10101010
+10000101
+00101000
+00000000
+00010101
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01000001
+00101000
+00101000
+00101000
+00101000
+00101000
+00101010
+00101000
+00101000
+01001010
+10101000
+00101010
+00000010
+10100001
+01001010
+10101010
+10101000
+01010010
+10101000
+00101000
+01010100
+00000001
+01000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+00000000
+00010101
+00101010
+10101010
+10000101
+00101010
+10101010
+10100001
+00101000
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+00000000
+10101000
+00101010
+10101010
+10100001
+00101010
+10101010
+10000101
+00101000
+10101000
+00010101
+00101000
+00101010
+00010101
+00101000
+01001010
+10000101
+00101000
+01010010
+10100001
+00101000
+01010100
+10101000
+00101000
+01010101
+00101000
+01000001
+01010101
+01000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+00000000
+00000101
+01010010
+10101010
+10100001
+01001010
+10101010
+10101000
+00101010
+00000000
+00101000
+00101000
+01010101
+01000001
+00101000
+01010101
+01010101
+00101010
+00000000
+00010101
+01001010
+10101010
+10000101
+01010010
+10101010
+10100001
+01010100
+00000000
+10101000
+01010101
+01010101
+00101000
+01000001
+01010101
+00101000
+00101000
+00000000
+10101000
+00101010
+10101010
+10100001
+01001010
+10101010
+10000101
+01010000
+00000000
+00010101
+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
+00101000
+00000001
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+01000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+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
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00010100
+10101000
+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
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01000001
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101010
+10101010
+10101000
+01001010
+10101010
+10100001
+01010010
+10000010
+10000101
+01010100
+00010100
+00010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00010100
+10101000
+01001010
+10000010
+10100001
+01010010
+10101010
+10000101
+01010100
+10101010
+00010101
+01010100
+10101010
+00010101
+01010010
+10101010
+10000101
+01001010
+10000010
+10100001
+00101010
+00010100
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+01000001
+01010101
+01000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00010100
+10101000
+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
+01000001
+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
+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
+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
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01010010
+10101010
+10100001
+01010100
+00000000
+10101000
+01010100
+00000000
+00101000
+01010010
+10101010
+00101000
+01001010
+10101010
+10101000
+00101010
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+01001010
+10101010
+10101000
+01010010
+10101010
+00101000
+01010100
+00000000
+01000001
+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
+01000000
+01010101
+00101000
+00101010
+00010101
+00101000
+10101010
+10000101
+00101010
+10100010
+10100001
+00101010
+10000100
+10101000
+00101010
+00010101
+00101000
+00101010
+00010101
+00101000
+00101010
+00010101
+00101000
+00101010
+10000100
+10101000
+00101010
+10100010
+10100001
+00101000
+10101010
+10000101
+00101000
+00101010
+00010101
+01000001
+01000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+01000001
+00101000
+01010101
+01000001
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+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
+01000001
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+00000001
+00101000
+01010100
+10101000
+00101000
+01010010
+10101010
+00101000
+01001010
+10001010
+10101000
+00101010
+00010010
+10101000
+00101000
+01010100
+10101000
+00101000
+01010100
+10101000
+00101000
+01010100
+10101000
+00101010
+00010010
+10101000
+01001010
+10001010
+10101000
+01010010
+10101010
+00101000
+01010100
+10101000
+00101000
+01010101
+00000001
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101000
+00000000
+00101000
+00101010
+10101010
+10101000
+00101010
+10101010
+10100001
+00101000
+00000000
+00000101
+00101000
+01010101
+00000001
+00101010
+00000000
+10101000
+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
+01010000
+00000101
+01010101
+01001010
+10100001
+01010101
+00101010
+10100001
+01010101
+00101000
+00000101
+01010000
+00101000
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+01001010
+10101010
+10101000
+01010010
+10101010
+00101000
+01010100
+00000000
+00101000
+01010000
+01010101
+00101000
+01001010
+00000000
+10101000
+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
+01000001
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01000000
+01010101
+00101000
+00101010
+00010101
+00101000
+10101010
+10000101
+00101010
+10100010
+10100001
+00101010
+10000100
+10101000
+00101010
+00010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+01000001
+01010101
+01000001
+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
+01010100
+00000001
+01010101
+01010010
+10101000
+01010101
+01010010
+10101000
+01010101
+01010100
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010101
+00101010
+00010101
+01010101
+01001010
+10000101
+01010101
+01010010
+10000101
+01010101
+01010100
+00010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+00010101
+01010101
+01010010
+10000101
+01010101
+01010010
+10000101
+01010101
+01010100
+00010101
+01010101
+01000000
+00010101
+01010101
+00101010
+10000101
+01010101
+00101010
+10000101
+01010101
+01000010
+10000101
+01010101
+01010010
+10000101
+01010101
+01010010
+10000101
+01010101
+01010010
+10000101
+01010101
+01010010
+10000101
+01010101
+01010010
+10000101
+01010100
+00001010
+10000101
+01010010
+10101010
+00010101
+01010010
+10101000
+01010101
+01010100
+00000001
+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
+01000001
+00101000
+01010101
+00101000
+00101000
+01010100
+10101000
+00101000
+01010010
+10100001
+00101000
+01001010
+10000101
+00101000
+00101010
+00010101
+00101000
+10101000
+01010101
+00101010
+10101010
+00010101
+00101010
+10001010
+10000101
+00101010
+00010010
+10100001
+00101000
+01010100
+10101000
+00101000
+01010101
+00101000
+01000001
+01010101
+01000001
+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
+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
+01000001
+00000000
+00010101
+00101000
+10101010
+10000101
+00101010
+10101010
+10100001
+00101010
+00101000
+10101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+01000001
+01000001
+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
+00000000
+00010101
+00101000
+10101010
+10000101
+00101010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+01000001
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+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
+01000001
+00000000
+00010101
+00101000
+10101010
+10000101
+00101010
+10101010
+10100001
+00101010
+10000000
+10101000
+00101010
+00010101
+00101000
+00101010
+00010101
+00101000
+00101010
+00010101
+00101000
+00101010
+10000000
+10101000
+00101010
+10101010
+10100001
+00101000
+10101010
+10000101
+00101000
+00000000
+00010101
+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
+01010100
+00000000
+01000001
+01010010
+10101010
+00101000
+01001010
+10101010
+10101000
+00101010
+00000010
+10101000
+00101000
+01010100
+10101000
+00101000
+01010100
+10101000
+00101000
+01010100
+10101000
+00101010
+00000010
+10101000
+01001010
+10101010
+10101000
+01010010
+10101000
+10101000
+01010100
+00000001
+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
+01000001
+01000000
+00010101
+00101000
+00101010
+10000101
+00101000
+10101010
+10100001
+00101010
+10100000
+10101000
+00101010
+10000101
+00101000
+00101010
+00010101
+01000001
+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
+01010100
+00000000
+00010101
+01010010
+10101010
+10000101
+01001010
+10101010
+10100001
+00101010
+00000000
+10101000
+00101010
+00000001
+00101000
+01001010
+10101000
+00000001
+01010000
+10101010
+10000101
+01000001
+00001010
+10100001
+00101000
+01010000
+10101000
+00101010
+00000000
+10101000
+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
+01000001
+01010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010100
+00101000
+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
+00101010
+00010101
+01010101
+01001010
+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
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00000000
+10101000
+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
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101010
+00010100
+10101000
+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
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01000001
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101000
+00101010
+00101000
+10101000
+01001010
+10101010
+10100001
+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
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101010
+00010100
+10101000
+01001010
+10000010
+10100001
+01010010
+10101010
+10000101
+01010100
+10101010
+00010101
+01010101
+00101000
+01010101
+01010100
+10101010
+00010101
+01010010
+10101010
+10000101
+01001010
+10000010
+10100001
+00101010
+00010100
+10101000
+00101000
+01010101
+00101000
+01000001
+01010101
+01000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000001
+01010101
+01000001
+00101000
+01010101
+00101000
+00101000
+01010101
+00101000
+00101000
+01010100
+10101000
+00101000
+01010100
+10101000
+00101000
+01010010
+10101000
+00101010
+00001010
+10101000
+01001010
+10101010
+00101000
+01010010
+10101000
+00101000
+01010100
+00000001
+00101000
+01010100
+00000000
+10101000
+01010010
+10101010
+10100001
+01010010
+10101010
+10000101
+01010100
+00000000
+00010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+00000000
+00000001
+00101010
+10101010
+10101000
+00101010
+10101010
+10101000
+01000000
+00000000
+10101000
+01010101
+01010010
+10100001
+01010101
+01001010
+10000101
+01010101
+00101010
+00010101
+01010100
+10101000
+01010101
+01010010
+10100001
+01010101
+01001010
+10000000
+00000001
+00101010
+10101010
+10101000
+00101010
+10101010
+10101000
+01000000
+00000000
+00000001
+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
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+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
+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
+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
+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
+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
+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
+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
+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
+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
+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
+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
+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
+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
+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
+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
+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
+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
+01010101
+01010101
+01010101
+00000000
+00000000
+00000000
+10101010
+10101010
+10101010
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+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
+01000000
+01010101
+01010100
+00001010
+01010101
+01000010
+10101010
+01010100
+00000010
+10101010
+01010000
+00000000
+10101010
+01010000
+00000000
+10101010
+01010100
+00000000
+10101010
+01010101
+01010000
+10101010
+01010101
+01010000
+10101010
+01010101
+01010000
+10101010
+01010101
+01010000
+00000000
+01010101
+01010000
+00000000
+01010101
+01010000
+00000000
+01010101
+01010100
+00000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000101
+01010101
+01010101
+10000000
+00010101
+01010101
+10101010
+00000001
+01010101
+10101000
+00000000
+00010101
+10101000
+00000000
+00000101
+10101000
+00000000
+00000101
+10101000
+00000000
+00010101
+10101000
+00010101
+01010101
+10101000
+00010101
+01010101
+10101000
+00010101
+01010101
+00000000
+00010101
+01010101
+00000000
+00010101
+01010101
+00000000
+00010101
+01010101
+00000000
+00010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+01010101
+01010100
+00000000
+01010101
+00000000
+00101010
+01010101
+00000000
+00001010
+01010101
+00000000
+00101010
+01010101
+01010000
+10101010
+01010101
+01000010
+10101010
+01010101
+00001010
+10101010
+01010100
+00001010
+10101010
+01010100
+00000000
+00101010
+01010100
+00000000
+00000000
+01010100
+00000000
+00000000
+01010101
+01010100
+00000000
+01010101
+01010101
+01010000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000000
+00000101
+01010101
+10101000
+00000001
+01010101
+10101010
+00000000
+01010101
+10101010
+10000000
+00010101
+10101000
+00000000
+00000101
+10101000
+00000000
+00000101
+10100000
+00000000
+00000101
+10100000
+00000000
+00000101
+10000000
+01010101
+00000101
+00000000
+01010101
+01010101
+00000001
+01010101
+01010101
+00000001
+01010101
+01010101
+00000101
+01010101
+01010101
+00010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+00000000
+01010101
+01010100
+00000010
+01010101
+01010100
+00001010
+01010101
+01000010
+10101010
+01010100
+00101010
+10101010
+01010000
+10101010
+10101010
+01010000
+00101010
+10101010
+01010000
+00000010
+10100000
+01010100
+00000000
+00000000
+01010101
+00000000
+00000000
+01010101
+01000000
+00000000
+01010101
+01010000
+00000001
+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
+00000001
+01010101
+00000000
+00000001
+01010101
+10101010
+10100000
+01010101
+10101010
+10100000
+01010101
+10101010
+10100000
+01010101
+10101000
+00101000
+00010101
+10000000
+00000000
+00010101
+00000000
+00000000
+00010101
+00000000
+00000000
+00010101
+00000001
+01000000
+00010101
+00010101
+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
+01010000
+01010101
+01010101
+01000000
+01010101
+01010101
+01000000
+01010100
+00000000
+00000010
+01010000
+00001010
+10101010
+01010000
+10101010
+10101010
+01010000
+00101010
+10101010
+01010100
+00101010
+10000000
+01010100
+00000000
+00000000
+01010100
+00000000
+00000000
+01010101
+00000000
+00000001
+01010101
+00000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000000
+00000101
+01010101
+00101010
+00000000
+00000101
+10101010
+10101010
+00000101
+10101010
+10101000
+00000101
+10101010
+10101000
+00010101
+10000000
+10100000
+00010101
+00000000
+00100000
+01010101
+00000000
+00000000
+01010101
+00000000
+00000000
+01010101
+01010100
+00000001
+01010101
+01010101
+00000001
+01010101
+01010101
+01000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000000
+00000000
+01010100
+00101010
+10101010
+01010100
+00101010
+10101010
+01010100
+00101010
+10101010
+01010000
+00101010
+10101010
+01010000
+00000000
+00000000
+01010000
+00000000
+00000000
+01010000
+00000000
+00000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000101
+01010101
+01010101
+01000000
+00010101
+01010101
+00001010
+00000001
+01010101
+10101010
+10100000
+00000101
+10101010
+10101010
+10000000
+10101010
+10101010
+00000000
+10101010
+10101000
+00000000
+00000010
+10000000
+00000001
+00000010
+00000000
+00000101
+00000000
+00000000
+01010101
+01000000
+00000001
+01010101
+01000000
+00000101
+01010101
+01000000
+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
+01010000
+00000101
+01010101
+01000010
+00000000
+01010100
+00001010
+10101010
+01010000
+00101010
+10101010
+01010000
+00000010
+10101010
+01010000
+00000000
+00000010
+01010000
+00000000
+00000000
+01010101
+01000000
+00000000
+01010101
+01010101
+01000000
+01010101
+01010101
+01000000
+01010101
+01010101
+00000000
+01010101
+01010101
+00000000
+01010101
+01010101
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+00010101
+01010101
+00000000
+00000001
+01010101
+10000000
+10000000
+01010101
+10101010
+10101000
+00010101
+10101010
+10101010
+00000101
+10101010
+10101010
+10000000
+00101010
+10101010
+00000000
+00101010
+00000000
+00000000
+00000000
+00000000
+00000000
+00000000
+00000000
+00000101
+00000000
+00000001
+01010101
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+00000001
+01010101
+01010000
+10100000
+01010101
+00000010
+10101010
+01010100
+00001010
+10101010
+01010100
+00000010
+10101010
+01010100
+00000000
+00101010
+01010101
+01000000
+00000010
+01010101
+01010000
+00000010
+01010101
+01010100
+00001010
+01010101
+01000000
+00000000
+01010101
+00000000
+00000000
+01010101
+00000000
+00000000
+01010101
+01000000
+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
+00010101
+01010101
+01010101
+00000001
+01000001
+01010101
+10100000
+00000000
+01010101
+10101010
+10101000
+01010101
+10101010
+10101010
+00010101
+10101010
+10101010
+00010101
+10101010
+10101010
+10000101
+10101010
+10101010
+10000101
+00000000
+00000000
+00000001
+00000000
+00000000
+00000001
+00000000
+00000000
+00000001
+00000000
+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
+01010000
+01010101
+01010000
+00000000
+01010101
+01000010
+10101010
+01010101
+01000000
+10101010
+01010101
+01010000
+00101010
+01010101
+01010000
+00101010
+01010101
+01010000
+00001010
+01010100
+00000000
+00101010
+01010000
+00000000
+10101010
+01010000
+00000000
+00000010
+01010100
+00000000
+00000000
+01010101
+01010000
+00000000
+01010101
+01010101
+01000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000101
+01010101
+01010101
+00000101
+01010101
+01010101
+10000001
+01010101
+01010101
+10100000
+01010100
+00010101
+10101000
+00000000
+00010101
+10101010
+00101000
+00010101
+10101010
+10100000
+00010101
+10101010
+10100000
+01010101
+10101010
+10100000
+01010101
+10101010
+10100000
+01010101
+00000010
+10000000
+01010101
+00000000
+00000001
+01010101
+00000000
+00000001
+01010101
+00000000
+00000001
+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
+00000000
+01010101
+01010101
+00000000
+01010101
+01010100
+00101010
+01010101
+01010100
+00101010
+01010101
+01010100
+00101010
+01010000
+00000000
+00101010
+01010000
+00000000
+10101010
+01010000
+00001010
+10101010
+01010100
+00000000
+10101010
+01010101
+00000000
+00101010
+01010101
+01000000
+00001010
+01010101
+01010000
+00000000
+01010101
+01010100
+00000000
+01010101
+01010101
+01000000
+01010101
+01010101
+01010000
+01010101
+01010101
+01010100
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000000
+01010101
+01010101
+00000000
+00010101
+01010101
+10101000
+00010101
+01010101
+10101000
+00010101
+01010101
+10101000
+00010101
+01010101
+10101000
+00000000
+00000101
+10101010
+00000000
+00000101
+10101010
+10100000
+00000101
+10101000
+00000000
+00010101
+10100000
+00000000
+01010101
+10000000
+00000001
+01010101
+00000000
+00000101
+01010101
+00000000
+00010101
+01010101
+00000000
+01010101
+01010101
+00000001
+01010101
+01010101
+00000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010000
+01010101
+01010101
+01010000
+01010101
+01010101
+01000010
+01010100
+00010101
+00001010
+01010100
+00000000
+00101010
+01010100
+00101000
+10101010
+01010100
+00001010
+10101010
+01010100
+00001010
+10101010
+01010101
+00001010
+10101010
+01010101
+00001010
+10101010
+01010101
+00000010
+10000000
+01010101
+01000000
+00000000
+01010101
+01000000
+00000000
+01010101
+01000000
+00000000
+01010101
+01000000
+00010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000101
+01010101
+01010101
+00000000
+00000101
+01010101
+10101010
+10000001
+01010101
+10101010
+00000001
+01010101
+10101000
+00000101
+01010101
+10101000
+00000101
+01010101
+10100000
+00000101
+01010101
+10101000
+00000000
+00010101
+10101010
+00000000
+00000101
+10000000
+00000000
+00000101
+00000000
+00000000
+00010101
+00000000
+00000101
+01010101
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+01010101
+01000001
+01000000
+01010101
+00000000
+00001010
+01010101
+00001010
+10101010
+01010100
+00101010
+10101010
+01010100
+00101010
+10101010
+01010000
+10101010
+10101010
+01010000
+10101010
+10101010
+01000000
+00000000
+00000000
+01000000
+00000000
+00000000
+01000000
+00000000
+00000000
+01010000
+00000000
+00000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+00010101
+01010101
+00001010
+00000101
+01010101
+10101010
+10000000
+01010101
+10101010
+10100000
+00010101
+10101010
+10000000
+00010101
+10101000
+00000000
+00010101
+10000000
+00000001
+01010101
+10000000
+00000101
+01010101
+10100000
+00010101
+01010101
+00000000
+00000001
+01010101
+00000000
+00000000
+01010101
+00000000
+00000000
+01010101
+00000000
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+00010101
+01010101
+01000000
+00000000
+01010101
+00000010
+00000010
+01010100
+00101010
+10101010
+01010000
+10101010
+10101010
+00000010
+10101010
+10101010
+00000000
+10101010
+10101000
+00000000
+00000000
+10101000
+00000000
+00000000
+00000000
+01010000
+00000000
+00000000
+01010101
+01000000
+00000000
+01010101
+01010101
+01000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010000
+00000101
+01010101
+00000000
+10000001
+01010101
+10101010
+10100000
+00010101
+10101010
+10101000
+00000101
+10101010
+00000000
+00000101
+10000000
+00000000
+00000101
+00000000
+00000000
+00000101
+00000000
+00000001
+01010101
+00000001
+01010101
+01010101
+00000001
+01010101
+01010101
+00000000
+01010101
+01010101
+00000000
+01010101
+01010101
+01000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010001
+01010101
+01010100
+00000001
+01010101
+01000000
+10100000
+01010000
+00001010
+10101010
+00000010
+10101010
+10101010
+00000000
+10101010
+10101010
+00000000
+00101010
+10101010
+01000000
+00000010
+10000000
+01010000
+00000000
+10000000
+01010101
+00000000
+00000000
+01010101
+01000000
+00000001
+01010101
+01010000
+00000001
+01010101
+01010101
+00000001
+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
+00000000
+00000000
+01010101
+10101010
+10101000
+00010101
+10101010
+10101000
+00010101
+10101010
+10101000
+00010101
+10101010
+10101000
+00000101
+00000000
+00000000
+00000101
+00000000
+00000000
+00000101
+00000000
+00000000
+00000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010000
+00000000
+01010000
+00000000
+10101000
+01010000
+10101010
+10101010
+01010000
+00101010
+10101010
+01010100
+00101010
+10101010
+01010100
+00001010
+00000010
+01010101
+00001000
+00000000
+01010101
+00000000
+00000000
+01010101
+00000000
+00000000
+01010101
+01000000
+00010101
+01010101
+01000000
+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
+00000101
+01010101
+01010101
+00000001
+01010101
+01010101
+00000001
+01010101
+01010101
+10000000
+00000000
+01010101
+10101010
+10100000
+00000101
+10101010
+10101010
+00000101
+10101010
+10101000
+00000101
+00000010
+10101000
+00010101
+00000000
+00000000
+00010101
+00000000
+00000000
+00010101
+01000000
+00000000
+01010101
+01010101
+00000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+01010101
+01010101
+01000000
+00000000
+01010101
+00001010
+10101010
+01010101
+00001010
+10101010
+01010101
+00001010
+10101010
+01010100
+00101000
+00101010
+01010100
+00000000
+00000010
+01010100
+00000000
+00000000
+01010100
+00000000
+00000000
+01010100
+00000001
+01000000
+01010100
+00010101
+01010100
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000000
+00010101
+01010101
+10000000
+00010101
+01010101
+10100000
+00010101
+01010101
+10101010
+10000001
+01010101
+10101010
+10101000
+00010101
+10101010
+10101010
+00000101
+10101010
+10101000
+00000101
+00001010
+10000000
+00000101
+00000000
+00000000
+00010101
+00000000
+00000000
+01010101
+00000000
+00000001
+01010101
+01000000
+00000101
+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
+01010100
+00000000
+01010101
+01010000
+00101010
+01010101
+01000000
+10101010
+01010101
+00000010
+10101010
+01010100
+00000000
+00101010
+01010000
+00000000
+00101010
+01010000
+00000000
+00001010
+01010000
+00000000
+00001010
+01010001
+01010101
+00000010
+01010101
+01010101
+00000000
+01010101
+01010101
+01000000
+01010101
+01010101
+01000000
+01010101
+01010101
+01010000
+01010101
+01010101
+01010100
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00010101
+01010101
+01010101
+00000000
+00010101
+01010101
+10101000
+00000000
+01010101
+10100000
+00000000
+01010101
+10101000
+00000000
+01010101
+10101010
+00000101
+01010101
+10101010
+10000001
+01010101
+10101010
+10100000
+01010101
+10101010
+10100000
+00010101
+10101000
+00000000
+00010101
+00000000
+00000000
+00010101
+00000000
+00000000
+00010101
+00000000
+00010101
+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
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+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
+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
+00100001
+01010101
+01010101
+00100000
+01010101
+01010101
+00101010
+01010101
+01010101
+00000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000000
+01010101
+01010101
+00101010
+01010101
+01010101
+00100000
+01010101
+01010101
+00100001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000000
+01010101
+01010101
+10101000
+01010101
+01010101
+00001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01001000
+01010101
+01010101
+00001000
+01010101
+01010101
+10101000
+01010101
+01010101
+00000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+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
+00010101
+01010101
+01001010
+00010101
+01010101
+01001010
+00010101
+01010101
+01001010
+00010101
+01010101
+01001010
+00010101
+01010101
+01001010
+00010101
+01010101
+01001010
+00010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000000
+00000000
+00000000
+10101010
+10101010
+10101010
+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
+00000000
+00000000
+00000000
+10101010
+10101010
+10101010
+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
+01001010
+00010101
+01010101
+01001010
+00010101
+01010101
+01001010
+00010101
+01010101
+01001010
+00000000
+01010101
+01001010
+10101010
+01010101
+01001010
+10101010
+01010101
+01000000
+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
+01000000
+00000000
+01010101
+01001010
+10101010
+01010101
+01001010
+10101010
+01010101
+01001010
+00000000
+01010101
+01001010
+00010101
+01010101
+01001010
+00010101
+01010101
+01001010
+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
+00000000
+00000001
+01010101
+10101010
+10100001
+01010101
+10101010
+10100001
+01010101
+00000000
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+01010100
+10100001
+01010101
+00000000
+10100001
+01010101
+10101010
+10100001
+01010101
+10101010
+10100001
+01010101
+00000000
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000101
+01010101
+01010101
+00000101
+01010101
+01010100
+10000101
+01010101
+01010010
+10000000
+00000000
+01001010
+10101010
+10101000
+00101010
+10101010
+10101000
+01001010
+10101010
+10101000
+01010010
+10000000
+00000000
+01010100
+10000101
+01010101
+01010101
+00000101
+01010101
+01010101
+01000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010001
+01010101
+01010101
+01010000
+01010101
+01010101
+01010010
+00010101
+00000000
+00000010
+10000101
+00101010
+10101010
+10100001
+00101010
+10101010
+10101000
+00101010
+10101010
+10100001
+00000000
+00000010
+10000101
+01010101
+01010010
+00010101
+01010101
+01010000
+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
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000101
+01010101
+01010101
+00000101
+01010101
+01010100
+10000101
+01010101
+01010010
+10000101
+01010101
+01001010
+10000101
+01010101
+00101010
+10000101
+01010100
+10101010
+10000101
+01010010
+10101010
+10000101
+01010100
+10101010
+10000101
+01010101
+00101010
+10000101
+01010101
+01001010
+10000101
+01010101
+01010010
+10000101
+01010101
+01010100
+10000101
+01010101
+01010101
+00000101
+01010101
+01010101
+01000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010001
+01010101
+01010101
+01010000
+01010101
+01010101
+01010010
+00010101
+01010101
+01010010
+10000101
+01010101
+01010010
+10100001
+01010101
+01010010
+10101000
+01010101
+01010010
+10101010
+00010101
+01010010
+10101010
+10000101
+01010010
+10101010
+00010101
+01010010
+10101000
+01010101
+01010010
+10100001
+01010101
+01010010
+10000101
+01010101
+01010010
+00010101
+01010101
+01010000
+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
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000000
+00000000
+00000001
+00101010
+10101010
+10100001
+00100101
+01010101
+01100001
+00100110
+10101010
+01100000
+00100110
+01010110
+01100010
+00100110
+01100110
+01100001
+00100110
+01010110
+01100010
+00100110
+10101010
+01100000
+00100101
+01010101
+01100001
+00101010
+10101010
+10100001
+00000000
+00000000
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+00000000
+00000000
+01001010
+10101010
+10101000
+01001001
+01010101
+01011000
+00001001
+10101010
+10011000
+10001001
+10010101
+10011000
+01001001
+10011001
+10011000
+10001001
+10010101
+10011000
+00001001
+10101010
+10011000
+01001001
+01010101
+01011000
+01001010
+10101010
+10101000
+01000000
+00000000
+00000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+00000000
+00000000
+01001010
+10101010
+10101010
+01001001
+01010101
+01010101
+01001010
+10101010
+10101010
+01001000
+00000000
+00000000
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000000
+00000000
+00000000
+10101010
+10101010
+10101010
+01010101
+01010101
+01010101
+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
+00000001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+00000000
+00000000
+00100001
+10101010
+10101010
+10100001
+01010101
+01010101
+01100001
+10101010
+10101010
+10100001
+00000000
+00000000
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+00000000
+00000000
+00101010
+10101010
+10101010
+00100000
+00000000
+00001000
+00100010
+00010100
+10001000
+00100010
+00010010
+10001000
+00100010
+00001010
+10001000
+00100010
+00101010
+10001000
+00100010
+10101010
+10001000
+00100010
+10101010
+10001000
+00100010
+00101010
+10001000
+00100010
+00001010
+10001000
+00100010
+00010010
+10001000
+00100010
+00010100
+10001000
+00100000
+00000000
+00001000
+00101010
+10101010
+10101010
+01000000
+00000000
+00000000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010000
+01010101
+01010101
+01001010
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001000
+01010101
+01010101
+01001010
+01010101
+01010101
+01010000
+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
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+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
+00000000
+00000000
+00000000
+10101010
+10101010
+10101010
+00000000
+00000000
+00000000
+10101010
+10101010
+10000101
+10101010
+10101010
+10000101
+10101010
+10101010
+10000101
+10101010
+10101010
+10000101
+10101010
+10101010
+10000101
+10101010
+10101010
+10000101
+10101010
+10101010
+10000101
+10101010
+10101010
+10000101
+10101010
+10101010
+10000101
+10101010
+10101010
+10000101
+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
+00000000
+00000000
+00000000
+10101010
+10101010
+10101010
+00000000
+00000000
+00000000
+10101010
+10100001
+01010101
+10101010
+10100001
+01010101
+10101010
+10100001
+01010101
+10101010
+10100001
+01010101
+10101010
+10100001
+01010101
+10101010
+10100001
+01010101
+10101010
+10100001
+01010101
+10101010
+10100001
+01010101
+10101010
+10100001
+01010101
+10101010
+10100001
+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
+00000000
+00000000
+00000000
+10101010
+10101010
+10101010
+00000000
+00000000
+00000000
+10101000
+01010101
+01010101
+10101000
+01010101
+01010101
+10101000
+01010101
+01010101
+10101000
+01010101
+01010101
+10101000
+01010101
+01010101
+10101000
+01010101
+01010101
+10101000
+01010101
+01010101
+10101000
+01010101
+01010101
+10101000
+01010101
+01010101
+10101000
+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
+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
+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
+00000101
+01010101
+01010101
+10100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+00100001
+01010101
+01010101
+10100001
+01010101
+01010101
+00000101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000000
+00000000
+00000001
+10101010
+10101010
+10101000
+00100000
+00000000
+00001000
+00100010
+00010100
+10001000
+00100010
+10000100
+10001000
+00100010
+10100000
+10001000
+00100010
+10101000
+10001000
+00100010
+10101010
+10001000
+00100010
+10101010
+10001000
+00100010
+10101000
+10001000
+00100010
+10100000
+10001000
+00100010
+10000100
+10001000
+00100010
+00010100
+10001000
+00100000
+00000000
+00001000
+10101010
+10101010
+10101000
+00000000
+00000000
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010100
+01010101
+01010101
+01010010
+01010101
+01010000
+01010010
+01010101
+01001010
+00010000
+01010101
+01001010
+00001010
+01010101
+01010000
+00101010
+01010101
+01010100
+10100000
+01010101
+00000010
+10000101
+01010100
+10100010
+10000101
+01010100
+10100010
+10000101
+01010101
+00000010
+10000101
+01010101
+01010100
+10100000
+01010101
+01010000
+00101010
+01010101
+01001010
+00001010
+01010101
+01001010
+00010000
+01010101
+01010000
+01010010
+01010101
+01010101
+01010010
+01010101
+01010101
+01010000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00010101
+01010101
+01010101
+10000101
+01010101
+01010101
+10000101
+00000101
+01010101
+00000100
+10100001
+01010101
+10100000
+10100001
+01010101
+10101000
+00000101
+01010101
+00001010
+00010101
+01010101
+01010010
+10000000
+01010101
+01010010
+10001010
+00010101
+01010010
+10001010
+00010101
+01010010
+10000000
+01010101
+00001010
+00010101
+01010101
+10101000
+00000101
+01010101
+10100000
+10100001
+01010101
+00000100
+10100001
+01010101
+10000101
+00000101
+01010101
+10000101
+01010101
+01010101
+00010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010000
+01010101
+01010101
+00001010
+01010101
+01010100
+10101010
+01010101
+01010010
+10100000
+01010101
+01001010
+00000100
+01010101
+01001010
+00010100
+01010101
+00101000
+01010100
+01010101
+00101000
+01010100
+01010101
+00101000
+01010100
+01010101
+00101000
+01010100
+01010101
+01001010
+00010100
+01010101
+01001010
+00000100
+01010101
+01010010
+10100000
+01010101
+01010100
+10101010
+01010101
+01010101
+00001010
+01010101
+01010101
+01010000
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+00000101
+01010101
+01010101
+10100000
+01010101
+01010101
+10101010
+00010101
+01010101
+10101010
+10000101
+01010101
+10101010
+10100001
+01010101
+10101010
+10100001
+01010101
+10101010
+10101000
+01010101
+10101010
+10101000
+01010101
+10101010
+10101000
+01010101
+10101010
+10101000
+01010101
+10101010
+10100001
+01010101
+10101010
+10100001
+01010101
+10101010
+10000101
+01010101
+10101010
+00010101
+01010101
+10100000
+01010101
+01010101
+00000101
+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
+10001000
+01000000
+00001010
+00001000
+00101010
+10101000
+01001000
+00100000
+10100001
+01001000
+00100000
+10100001
+01001000
+00100000
+10100001
+01001000
+00100000
+10100001
+01001000
+00100000
+10100001
+01001000
+00101010
+10101000
+01001000
+01000000
+00001010
+00001000
+01010101
+01010010
+10001000
+01010101
+01010100
+10101000
+01010101
+01010101
+00101000
+01010101
+01010101
+01000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010001
+01010101
+01010101
+01101000
+01010101
+01010101
+01011010
+00010101
+01010100
+00010010
+00010101
+01010010
+10000010
+00010101
+01000100
+10000010
+10000101
+00100000
+10100000
+10000101
+00101000
+00100000
+10000101
+01001000
+00100000
+10000101
+00101000
+00100000
+10000101
+00100000
+10100000
+10000101
+01000100
+10000010
+10000101
+01010010
+10000010
+00010101
+01010100
+00010010
+00010101
+01010101
+01011010
+00010101
+01010101
+01101000
+01010101
+01010101
+01010001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01000000
+00000000
+00000001
+00101010
+10101010
+10101000
+01001000
+00000000
+00100001
+01001000
+01010101
+00100001
+01001000
+01010101
+00100001
+01001000
+01010101
+00100001
+01010010
+00010100
+10000101
+01010100
+10000010
+00010101
+01010101
+00101000
+01010101
+01010101
+00101000
+01010101
+01010100
+10000010
+00010101
+01010010
+00010100
+10000101
+01001000
+01010101
+00100001
+01001000
+01010101
+00100001
+01001000
+01010101
+00100001
+01001000
+00000000
+00100001
+00101010
+10101010
+10101000
+01000000
+00000000
+00000001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010000
+01010101
+01010101
+01010010
+00010101
+01010101
+01010010
+10000101
+01010101
+01010010
+10100001
+01010101
+01010010
+10101000
+01010101
+01010010
+10101010
+00010101
+01010010
+10101010
+10000101
+01010010
+10101010
+10100001
+01010010
+10101010
+10101000
+01010010
+10101010
+00000000
+01010010
+10101010
+00000101
+01010010
+00001010
+10000101
+01010000
+00001010
+10000001
+01010101
+01010010
+10100001
+01010101
+01010010
+10100001
+01010101
+01010000
+10000001
+01010101
+01010101
+00010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010000
+01010001
+01010001
+01001010
+00001000
+01001000
+00100000
+10001010
+00101000
+00100000
+10001000
+10001000
+00100000
+10001000
+10001000
+00101010
+10001000
+00001000
+00100000
+10001000
+01001000
+00100000
+10001000
+01001000
+00100000
+10001000
+01001000
+00100000
+10001000
+01001000
+01000101
+00010001
+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
+01000000
+01010001
+01010001
+00101010
+00001000
+01001000
+00100000
+10001010
+00101000
+00100000
+10001000
+10001000
+00100000
+10001000
+10001000
+00101010
+00001000
+00001000
+00100000
+01001000
+01001000
+00100001
+01001000
+01001000
+00100001
+01001000
+01001000
+00100001
+01001000
+01001000
+01000101
+01010001
+01010001
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+10101010
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
+01010101
diff --git a/MAX7456_Font_Updater/mcm2h.pl b/MAX7456_Font_Updater/mcm2h.pl
new file mode 100644
index 00000000..7a31770a
--- /dev/null
+++ b/MAX7456_Font_Updater/mcm2h.pl
@@ -0,0 +1,27 @@
+#!/usr/bin/perl
+
+open(MYINPUTFILE, "font.h");
+my $count = -1;
+print MYOUTPUTFILE "PROGMEM const byte fontdata[16384] = {\n ";
+while()
+{
+ my($line) = $_;
+ chomp($line);
+ if ($count!=-1)
+ {
+ my ($x) = oct("0b".$line);
+ printf MYOUTPUTFILE "0x%02x", $x;
+ if ($count!=16383) {
+ print MYOUTPUTFILE ",";
+ if (($count%32)==31) {
+ print MYOUTPUTFILE "\n ";
+ }
+ }
+ }
+ $count++;
+}
+print MYOUTPUTFILE "};\n";
+
+close(MYINPUTFILE);
+close(MYOUTPUTFILE);
diff --git a/README.markdown b/README.markdown
new file mode 100644
index 00000000..bf97595e
--- /dev/null
+++ b/README.markdown
@@ -0,0 +1,238 @@
+AeroQuad Flight Software Source Code 3.0
+========================================
+[http://www.AeroQuad.com](http://www.AeroQuad.com)
+
+Version 3.0 Release Notes (x/x/xxxx)
+----------------------------------------
+ * under construction
+ * new libraries
+
+Version 2.5.1 Release Notes (12/22/2011)
+----------------------------------------
+* Supports the new Arduino 1.0 IDE
+* Fixed magnetometer issue where mag output intermittently output zero's
+* Fixed calibration bug where X & Y axis were swapped
+* Added support for hexa configurations
+ * Look at the file Motors.h to view how to connect the motors
+* This version is only compatible with the AeroQuad v2.7.1 Configurator
+ * Please note support for > 4 motors not directly supported within v2.7.1 Configurator
+ * To view motor data, use Serial Monitor to send '=' command
+* Special thanks to Jihlein for producing this version and to ala42 for his bug fixes!
+
+Version 2.5 Release Notes (11/30/2011)
+----------------------------------------
+* Added support for the new v2.1 AeroQuad Shield with HMC5883L
+* Added support for mounting an HMC5883L upside down on v2.0 AeroQuad Shield
+* Added support for octo configurations (thanks Jihlein!)
+* This version is only compatible with the AeroQuad v2.7.1 Configurator
+
+ Version 2.5 Beta 1 Release Notes (7/31/2011)
+----------------------------------------
+ * Fixed various 8 channel transmitter channel bugs (special thanks to Ala42!)
+ * Added safety procedure for ESC calibration (prevent random full throttles during PID updates)
+ * Please keep common sense safety practices in place, remove props or remove battery power when necessary
+ * Optmized SerialCom.pde (removed unused commands)
+
+Version 2.4.3 Release Notes (7/24/2011)
+----------------------------------------
+ * Fixed duplicate altitude hold call in timing executive
+ * Added support for 8 channel receiver for Mega (thanks Moeffe)
+ * Added telemetry response to tell Configurator how many receiver channels and motor commands are available
+
+Version 2.4.2 Release Notes (6/29/2011)
+----------------------------------------
+ * Fixed EEPROM issue that affects altitude hold (thanks Aadamson)
+ * Greatly improved altitude hold algorithm (thanks Aadamson)
+ * Updated incorrect sign issue with v1.7 shield
+ * Fixed Issue 114: Processor specific Motors_PWMtimer class is not surrounded by ifdef
+
+Version 2.4.1 Release Notes (6/5/2011)
+----------------------------------------
+ * Wii bug fixes (thanks aadamson/jihlein) - please note that the Wii sensor orientations now follow the MultiWii convention
+ * Video On Screen Display support (thanks Alamo)
+ * CHR6DM compilation bug fixes (thanks lokling)
+
+Version 2.4 Release Notes (4/2/2011)
+----------------------------------------
+ * Added ARG/MARG flight angle estimation routines
+ * Improved timing executive, reduced main flight loop to 100Hz
+ * Stable/Attitude Mode has highly improved auto level capability
+ * All these changes have been made by jihlein and aadamson, THANKS!
+
+ Version 2.3 Release Notes (3/17/2011)
+----------------------------------------
+ * Implemented common SI units for sensors
+ * Implemented common DCM gains for all hardware platforms
+ * Calculate heading using Compass & DCM
+ * Acro Mode utilizes SI units only for common starting gains compared with other hardware platorms
+ * New altitude hold updates
+ * initialized PID with hold altitude as last postion
+ * created a deadband in the throttle stick when in altitude hold of 250 step (configurable in aeroquad.h), this also is the extents of the PANIC alarm as noted below.
+ * Added a PANIC mode, where if you move the throttle greater than 250 steps, it will automatically turn off Altitude hold and the throttle will function as it normally does, to turn back on altitude hold, you have to turn it off and back on again, allow for a get out of altitude hold without having to find the switch. This PANIC can either be UP or DOWN throttle.
+ * Added a bump up or down to altitude hold. Once you have Altitude hold enabled, and you are in the throttle dead band, you can nudge the altitude up or down, by moving the throttle slightly up or slightly down and then back to the middle. Scaled the climb or descent to be really slow. Throttle increase is based upon altitude increase and constrained to no more than +/- 50 units.
+
+Version 2.2 Release Notes (2/6/2011)
+----------------------------------------
+
+ * Fixed correct scaling for Kd for all flight modes (thanks to Ziojos & Honk). Makes it easier to find the right PID gains to remove oscillations during flight. PID Tuning Guide is updated with best values to use.
+ * Added experimental ArduPirate Stable Mode (thanks to Kenny9999)
+ * Started common SI units for major sensors to work with DCM (thanks to Kenny9999)
+ * Addressed issues 82-100 in Google Code Issue Tracker (http://code.google.com/p/aeroquad/issues/list)
+
+Version 2.1 Release Notes (1/20/2011)
+----------------------------------------
+
+ * Added support for battery monitor for AeroQuad v2.0 Shield
+ * Initialization bug fix for receiver code
+ * Fixed issues 64-81 in Google Code Issue Tracker (http://code.google.com/p/aeroquad/issues/list)
+
+Version 2.1.2 Beta Release Notes (12/22/2010)
+----------------------------------------
+
+ * Fixed PWM timer class to work with Uno, special thanks to CupOfTea (implementation) and Ala42 (debugging)!
+ * Implemented PWM timer class for Mega (thanks CupOfTea!)
+
+Version 2.1.1 Beta Release Notes (12/20/2010)
+----------------------------------------
+
+ * Fixed issues 55-63 in Google Code Issue Tracker (http://code.google.com/p/aeroquad/issues/list)
+ * Added support for DCM with Uno and v1.8 Shield for improved Stable Mode performance, special thanks to Ala42 and Aadamson for all their optimization work
+ * Added experimental camera stabilization code (thanks CupOfTea)
+
+Version 2.1 Beta Release Notes (12/4/2010)
+----------------------------------------
+
+ * Has only been flight tested with Arduino Mega 2560 using v2.0 Shield
+ * Bench tested configurations: Uno with v1.8 Shield, Duemilanove with v1.8 Shield, Duemilanove with v1.7 Shield
+ * This has many changes and optimization improvements implemented, please be careful flying with this version as this is still a work in progress
+ * Full documentation on all changes will be provided at full release
+ * Many improvements by Lokling and Honk
+
+Version 2.0.1 Release Notes (9/19/2010)
+----------------------------------------
+
+This is a bug fix release which resolves reported issues:
+
+ * [#30](http://code.google.com/p/aeroquad/issues/detail?id=30&can=1) added serial com commands to report hardware platform and motor configuration to adjust scales
+ * [#31](http://code.google.com/p/aeroquad/issues/detail?id=31&can=1) by adding serial command to report motor config, can now label Configurator correctly
+ * [#32](http://code.google.com/p/aeroquad/issues/detail?id=32&can=1) fixed wrong referenced array element
+
+Additionally fixed incorrect sensor orientation for v1.7 Shield with Duemilanove, and Wii for Duemilanove and Mega, and APM with APM sensor shield. Added #defines for Wii for Mega. Solved DCM overflow issues for APM when performing calibration or writing to EEPROM. Flight tested ArduCopter hardware, v2.0 Shield with Mega, v1.8 Shield with Duemilanove, v1.7 Shield with Duemilanove, v1.8 Shield using Wii sensors with Duemilanove. Updated default PID values for v2.0 shield using 30.5cm motor to motor configuration at 1.2kg.
+
+Version 2.0 Release Notes (9/6/2010)
+----------------------------------------
+
+This is a major architecture change from the v1.x flight software release. Major hardware and algorithm components are now implemented as C++ classes to allow common flight software support. Improved Stable Mode implemented. Hardware support for new v1.8 and v2.0 AeroQuad Shields using ITG-3200 gyros and BMA-180 accelerometers. Hardware support for Wii sensors, ArduCopter (APM and Oilpan) and Multipilot (all new platforms still need flight testing).
+
+Flight software configuration support for multiple hardware has changed. Look for the lines listed below at the start of AeroQuad.pde and uncomment the appropriate selection:
+
+ /****************************************************************************
+ ************************* Hardware Configuration ***************************
+ ****************************************************************************/
+ // Select which hardware you wish to use with the AeroQuad Flight Software
+
+ //#define AeroQuad_v1 // Arduino 2009 with AeroQuad Shield v1.7 and below
+ #define AeroQuad_v18 // Arduino 2009 with AeroQuad Shield v1.8
+ //#define AeroQuad_Wii // Arduino 2009 with Wii Sensors
+ //#define AeroQuadMega_v1 // Arduino Mega with AeroQuad Shield v1.7 and below
+ //#define AeroQuadMega_v2 // Arduino Mega with AeroQuad Shield v2.x
+ //#define AeroQuadMega_Wii // Arduino Mega with Wii Sensors (needs debug)
+ //#define ArduCopter // ArduPilot Mega (APM) with APM Sensor Board
+ //#define Multipilot // Multipilot board with Lys344 and ADXL 610 Gyro
+ //#define MultipilotI2C // Active Multipilot I2C and Mixertable
+
+Review the rest of the #defines also to match the unique setup of you multicopter.
+
+Version 1.7.1 Release Notes (3/24/2010)
+----------------------------------------
+
+Fixed bug for Arduino Mega users. #define Mega_AQ1x was not defined before #include "Receiver.h". It accidentally caused the receiver pin assignments to use the Duemilanove assignments instead of the Mega.
+
+Version 1.7 Release Notes (3/21/2010)
+----------------------------------------
+
+This release allows users to specific which voltage is used for aref, specifically for compatibility with AeroQuad v1.7 shields. Updated accelerometer calibration [here][1] to accommodate user definable aref and to best estimate Z axis zero position. Fixed heading hold reference to aref and optimized motor to gyro rate conversion for motor control PID. The new aref update is configured through the AeroQuad Configurator v2.3. Tested this version against Arduino 0018. Be sure to update your HardwareSerial.cpp found [here][2] if you are using XBee for wireless communication.
+
+Version 1.6 Release Notes (3/5/2010)
+----------------------------------------
+
+This release fixes a yaw bug that exhibits itself with the new capacitors installed which allows the user to use higher PID values. Also the comments were fixed to reflect usage of IDG500 or IXZ500 gyros. If the user does not select the correct gyro, the yaw axis may become inverted. Started implementing certain functions using classes (C++). The FlightAngle class defines the algorithm to use for angle estimation, the Motors class defines how PWM works and the Filter class allows multiple filter objects to be called to reduce the number of global variables needed and to encapsulate and retain the data needed for those filters to work.
+
+Version 1.5 Release Notes
+----------------------------------------
+
+This is a maintenance release for users of an Arduino Mega with an AeroQuad Shield v1.5 which provides receiver support. There is a bug in the Arduino core code which doesn't allow the proper PCINT assignments to PCINT 8-23. This release will hardcode AI pins 8-13 (PCINT 16-21) for use as receiver pins. To enable this capability, please uncomment #define Mega_AQ1x located in AeroQuad.pde.
+
+Place jumper wires as indicated below to make your AeroQuad Shield v1.5 receiver pins work with an Arduino Mega:
+
+ * Roll (Aileron) Channel, place jumper between AQ Shield pin 2 and Mega AI13
+ * Pitch (Elevator) Channel, place jumper between AQ Shield pin 5 and Mega AI11
+ * Yaw (Rudder) Channel, place jumper between AQ Shield pin 6 and Mega AI10
+ * Throttle Channel, place jumper between AQ Shield pin 4 and Mega AI12
+ * Mode (Gear) Channel, place jumper between AQ Shield pin 7 and Mega AI9
+ * Aux Channel, place jumper between AQ Shield 8 and Mega AI8
+
+Version 1.4 Release Notes
+----------------------------------------
+
+Warning! If you are a previous AeroQuad user and are using the Sparkfun 5DOF with the original IDG300 gyros, please review AeroQuad.pde and uncomment the line: #define OriginalIMU. Failure to do so will result in unstable flight. When Sparkfun updated the 5DOF IMU to use the IDG500, the roll/pitch gyro axes were inverted. The default AeroQuad Flight Software behavior is to assume the user is using the latest Sparkfun 5DOF IMU to make it easier for new users.
+
+Many of the improvements in v1.4 are geared towards the new features of the AeroQuad Configurator v2.0 and include the Spectrum Analyzer, Serial Monitor, manual input motor commands for initial checkout. A basic heading hold has also been implemented (turned off by default) using the yaw gyro.
+
+The camera stabilization feature is operational but still not optimal. There is an incompatibility with PCINT for reading receiver output and the Arduino 0017 Servo library. There is an intermittent jitter that occurs during reading of receiver output. Using analogWrite() works well, but there are not enough compatible pins on the Arduino Duemilanove to support this. Therefore further development will be pushed to the Arduino Mega.
+
+The heading hold feature is also operational but not optimal. The IDG gyros exhibit some drift during flight, which will cause the heading hold to eventually also drift. This can be alleviated by landing the AeroQuad, disarm motor output, and then perform a manual sensor calibration (TX left stick to the lower left, TX right stick to the lower right). The user will then be able to return to flight. This feature will be optimized during Arduino Mega development since it is planned to implement heading hold with a magnetometer for that platform.
+
+With the updated Servo library of Arduino 0017, the older ServoTimer2 library will not be used for future versions of the AeroQuad Flight Software.
+
+Version 1.3.2 Release Notes
+----------------------------------------
+
+This version provides additional communication messages for the Configurator to make the new calibration procedures more robust. New support added to allow Configurator to auto-reconnect to the AeroQuad (via USB or Wireless) for more convenience to the user. The Pin Change Interrupt (PCINT) code has been improved to work better for Futaba transmitters. The variable declaration section in the main AeroQuad.pde sketch has been organized into separate header files for easier maintainability into the future. The new default EEPROM values now include a suggested setting for yaw to allow a smoother yaw transition (in the past it would cause the quad to pop up and down a bit). The main loop is now organized into different timed loops, to make sure the sampling of the sensors and control algorithm execution are now performed at regular timed intervals (500Hz).
+
+If you'd like to maintain as much PWM resolution as possible for PWM Motor Control, please install the ServoTimer2 library found at:
+[http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1204020386/75][3]. To compile the AeroQuad sketch to use the ServoTimer2 library, the ServoTimer2 folder found in this distribution must be copied to ..\Arduino-00xx\hardware\libraries. To verify the library has been successfully installed, open the Arduino IDE and go to Sketch->Import Library. You should see ServoTimer2 as one of the items to select (you don't need to select it at this time). The last step is to configure the #define statements for ServoTimer2 in the AeroQuad.pde sketch.
+
+The default #define statement for PWM Motor Control is AnalogWrite. This will provide an update rate to the motors at 490Hz. No modification to the code, or installation of the ServoTimer2 library is necessary for this default.
+
+Version 1.3.1 Release Notes
+----------------------------------------
+
+This version allows the user to calibrate a transmitter in either Airplane or Helicopter Mode. There is also a calibration for ESC's and the ability for the user to return EEPROM values to a default value (which is also useful for first time setup). To use these features, you must download the AeroQuad Configurator v1.3.1 or greater. The transmitter calibration is meant to fix the situation where the trims could potentially move the transmitter beyond the 1000-2000 ms PWM pulse width range the AeroQuad is expecting. This had resulted in a non-response from the AeroQuad when moving the transmitter stick to an extreme position.
+
+Version 1.2 Release Notes
+----------------------------------------
+
+This version incorporates the use of the Pin Change Interrupts (PCINT) to read output from an R/C receiver. This removes the need to know the channel order of the receiver used. This PCINT method has been tested with:
+
+ * Spektrum DX7 w/ AR6100, 6200 and AR7000
+ * Futaba T6EXHP w/ R146iP
+ * Airtronics RD8000 w/ 92778
+
+The PCINT pins are unfortunately different between the Arduino Duemilanove and Arduino Mega. Therefore Version 1.2 is not directly compatible with the Mega. There are plans for compatibility with future releases, but for now the Mega is only compatible with Version 1.0 of the AeroQuad flight software.
+
+**New v1.2 features:**
+
+ * Stable Mode (auto level) is disabled by default. To enable remove the comment of the appropriate #define statement in AeroQuad.pde. This was done to remove prevent confusion by new users.
+ * If any critical flight parameters are zero, it is automatically filled in with a typical value.
+ * PCINT receiver code updated for efficiency
+ * Auto calibration of sensors at powerup disabled by default. To enable, remove the comment of the appropriate #define statement in AeroQuad.pde.
+ * Manual calibration of sensors can be performed by moving left transmitter stick to the lower left, and the right transmitter stick to the lower right corners.
+
+Version 1.1 Release Notes
+----------------------------------------
+
+This version of the code now uses analogWrite() to efficiently write PWM commands to the ESC's. The tradeoff is that we can only achieve 128 steps of resolution. The Turnigy ESC's specified in the parts list have been measured to only have 128 steps of resolution, so if you are using this ESC, there shouldn't be any issues. Also, if you've built a previous MikroQuad or AeroQuad you will be required to update wiring in your shield per the AeroQuad website instructions.
+
+**New v1.1 features:**
+
+ * 400Hz update rate to ESC's/Motors
+ * Combined user configurable values into single tab in Configurator
+
+Happy flying!
+[info@AeroQuad.com](mailto:info@AeroQuad.com)
+
+
+ [1]: http://carancho.com/AeroQuad/forum/index.php?topic=290.msg2735#msg2735
+ [2]: http://carancho.com/AeroQuad/forum/index.php?topic=85.0
+ [3]: http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1204020386/75
\ No newline at end of file