This commit is contained in:
Chris Anderson 2012-01-27 19:58:46 -08:00
commit b37ca7cccd
70 changed files with 896 additions and 1505 deletions

View File

@ -69,6 +69,7 @@ http://code.google.com/p/ardupilot-mega/downloads/list
#include <AP_TimerProcess.h> // TimerProcess is the scheduler for MPU6000 reads. #include <AP_TimerProcess.h> // TimerProcess is the scheduler for MPU6000 reads.
#include <AP_DCM.h> // ArduPilot Mega DCM Library #include <AP_DCM.h> // ArduPilot Mega DCM Library
#include <APM_PI.h> // PI library #include <APM_PI.h> // PI library
#include <PID.h> // PID library
#include <RC_Channel.h> // RC Channel Library #include <RC_Channel.h> // RC Channel Library
#include <AP_RangeFinder.h> // Range finder library #include <AP_RangeFinder.h> // Range finder library
#include <AP_OpticalFlow.h> // Optical Flow library #include <AP_OpticalFlow.h> // Optical Flow library
@ -291,7 +292,8 @@ static const char* flight_mode_strings[] = {
"RTL", "RTL",
"CIRCLE", "CIRCLE",
"POSITION", "POSITION",
"LAND"}; "LAND",
"OF_LOITER"};
/* Radio values /* Radio values
Channel assignments Channel assignments
@ -1439,15 +1441,9 @@ void update_roll_pitch_mode(void)
if(do_simple && new_radio_frame){ if(do_simple && new_radio_frame){
update_simple_mode(); update_simple_mode();
} }
// mix in user control with optical flow
// in this mode, nav_roll and nav_pitch = the iterm
#if WIND_COMP_STAB == 1
g.rc_1.servo_out = get_stabilize_roll(get_of_roll(g.rc_1.control_in + nav_roll));
g.rc_2.servo_out = get_stabilize_pitch(get_of_pitch(g.rc_2.control_in + nav_pitch));
#else
g.rc_1.servo_out = get_stabilize_roll(get_of_roll(g.rc_1.control_in)); g.rc_1.servo_out = get_stabilize_roll(get_of_roll(g.rc_1.control_in));
g.rc_2.servo_out = get_stabilize_pitch(get_of_pitch(g.rc_2.control_in)); g.rc_2.servo_out = get_stabilize_pitch(get_of_pitch(g.rc_2.control_in));
#endif
break; break;
} }
@ -1989,17 +1985,22 @@ static void tuning(){
break; break;
case CH6_OPTFLOW_KP: case CH6_OPTFLOW_KP:
g.rc_6.set_range(0,10000); // 0 to 10 g.rc_6.set_range(0,5000); // 0 to 5
g.pi_optflow_roll.kP(tuning_value); g.pi_optflow_roll.kP(tuning_value);
g.pi_optflow_pitch.kP(tuning_value); g.pi_optflow_pitch.kP(tuning_value);
break; break;
case CH6_OPTFLOW_KI: case CH6_OPTFLOW_KI:
g.rc_6.set_range(0,100); // 0 to 0.1 g.rc_6.set_range(0,10000); // 0 to 10
g.pi_optflow_roll.kI(tuning_value); g.pi_optflow_roll.kI(tuning_value);
g.pi_optflow_pitch.kI(tuning_value); g.pi_optflow_pitch.kI(tuning_value);
break; break;
case CH6_OPTFLOW_KD:
g.rc_6.set_range(0,200); // 0 to 0.2
g.pi_optflow_roll.kD(tuning_value);
g.pi_optflow_pitch.kD(tuning_value);
break;
} }
} }

View File

@ -258,6 +258,8 @@ static void reset_optflow_I(void)
{ {
g.pi_optflow_roll.reset_I(); g.pi_optflow_roll.reset_I();
g.pi_optflow_pitch.reset_I(); g.pi_optflow_pitch.reset_I();
of_roll = 0;
of_pitch = 0;
} }
static void reset_wind_I(void) static void reset_wind_I(void)
@ -462,34 +464,35 @@ static void init_z_damper()
} }
#endif #endif
// calculate modified roll/pitch depending upon optical flow values // calculate modified roll/pitch depending upon optical flow calculated position
static int32_t static int32_t
get_of_roll(int32_t control_roll) get_of_roll(int32_t control_roll)
{ {
#ifdef OPTFLOW_ENABLED #ifdef OPTFLOW_ENABLED
//static int32_t of_roll = 0; // we use global variable to make logging easier static float tot_x_cm = 0; // total distance from target
static unsigned long last_of_roll_update = 0; static unsigned long last_of_roll_update = 0;
static float prev_value = 0; int32_t new_roll = 0;
float x_cm;
// check if new optflow data available // check if new optflow data available
if( optflow.last_update != last_of_roll_update) { if( optflow.last_update != last_of_roll_update) {
last_of_roll_update = optflow.last_update; last_of_roll_update = optflow.last_update;
// filter movement // add new distance moved
x_cm = (optflow.x_cm + prev_value) / 2.0 * 50.0; tot_x_cm += optflow.x_cm;
// only stop roll if caller isn't modifying roll // only stop roll if caller isn't modifying roll
if( control_roll == 0 && current_loc.alt < 1500) { if( control_roll == 0 && current_loc.alt < 1500) {
of_roll = g.pi_optflow_roll.get_pi(-x_cm, 1.0); // we could use the last update time to calculate the time change new_roll = g.pi_optflow_roll.get_pid(-tot_x_cm, 1.0, 1.0); // we could use the last update time to calculate the time change
}else{ }else{
g.pi_optflow_roll.reset_I(); g.pi_optflow_roll.reset_I();
prev_value = 0; tot_x_cm = 0;
} }
// limit amount of change and maximum angle
of_roll = constrain(new_roll, (of_roll-20), (of_roll+20));
} }
// limit maximum angle
of_roll = constrain(of_roll, -1000, 1000);
// limit max angle
of_roll = constrain(of_roll, -1000, 1000);
return control_roll+of_roll; return control_roll+of_roll;
#else #else
return control_roll; return control_roll;
@ -500,27 +503,30 @@ static int32_t
get_of_pitch(int32_t control_pitch) get_of_pitch(int32_t control_pitch)
{ {
#ifdef OPTFLOW_ENABLED #ifdef OPTFLOW_ENABLED
//static int32_t of_pitch = 0; // we use global variable to make logging easier static float tot_y_cm = 0; // total distance from target
static unsigned long last_of_pitch_update = 0; static unsigned long last_of_pitch_update = 0;
static float prev_value = 0; int32_t new_pitch = 0;
float y_cm;
// check if new optflow data available // check if new optflow data available
if( optflow.last_update != last_of_pitch_update ) { if( optflow.last_update != last_of_pitch_update ) {
last_of_pitch_update = optflow.last_update; last_of_pitch_update = optflow.last_update;
// filter movement // add new distance moved
y_cm = (optflow.y_cm + prev_value) / 2.0 * 50.0; tot_y_cm += optflow.y_cm;
// only stop roll if caller isn't modifying roll // only stop roll if caller isn't modifying pitch
if( control_pitch == 0 && current_loc.alt < 1500 ) { if( control_pitch == 0 && current_loc.alt < 1500 ) {
of_pitch = g.pi_optflow_pitch.get_pi(y_cm, 1.0); // we could use the last update time to calculate the time change new_pitch = g.pi_optflow_pitch.get_pid(tot_y_cm, 1.0, 1.0); // we could use the last update time to calculate the time change
}else{ }else{
tot_y_cm = 0;
g.pi_optflow_pitch.reset_I(); g.pi_optflow_pitch.reset_I();
prev_value = 0;
} }
// limit amount of change
of_pitch = constrain(new_pitch, (of_pitch-20), (of_pitch+20));
} }
// limit maximum angle
// limit max angle
of_pitch = constrain(of_pitch, -1000, 1000); of_pitch = constrain(of_pitch, -1000, 1000);
return control_pitch+of_pitch; return control_pitch+of_pitch;
#else #else

View File

@ -309,8 +309,8 @@ public:
APM_PI pi_acro_roll; APM_PI pi_acro_roll;
APM_PI pi_acro_pitch; APM_PI pi_acro_pitch;
APM_PI pi_optflow_roll; PID pi_optflow_roll;
APM_PI pi_optflow_pitch; PID pi_optflow_pitch;
uint8_t junk; uint8_t junk;
@ -435,8 +435,8 @@ public:
pi_acro_roll (k_param_pi_acro_roll, PSTR("ACRO_RLL_"), ACRO_ROLL_P, ACRO_ROLL_I, ACRO_ROLL_IMAX * 100), pi_acro_roll (k_param_pi_acro_roll, PSTR("ACRO_RLL_"), ACRO_ROLL_P, ACRO_ROLL_I, ACRO_ROLL_IMAX * 100),
pi_acro_pitch (k_param_pi_acro_pitch, PSTR("ACRO_PIT_"), ACRO_PITCH_P, ACRO_PITCH_I, ACRO_PITCH_IMAX * 100), pi_acro_pitch (k_param_pi_acro_pitch, PSTR("ACRO_PIT_"), ACRO_PITCH_P, ACRO_PITCH_I, ACRO_PITCH_IMAX * 100),
pi_optflow_roll (k_param_pi_optflow_roll, PSTR("OF_RLL_"), OPTFLOW_ROLL_P, OPTFLOW_ROLL_I, OPTFLOW_IMAX * 100), pi_optflow_roll (k_param_pi_optflow_roll, PSTR("OF_RLL_"), OPTFLOW_ROLL_P, OPTFLOW_ROLL_I, OPTFLOW_ROLL_D, OPTFLOW_IMAX * 100),
pi_optflow_pitch (k_param_pi_optflow_pitch, PSTR("OF_PIT_"), OPTFLOW_PITCH_P, OPTFLOW_PITCH_I, OPTFLOW_IMAX * 100), pi_optflow_pitch (k_param_pi_optflow_pitch, PSTR("OF_PIT_"), OPTFLOW_PITCH_P, OPTFLOW_PITCH_I, OPTFLOW_PITCH_D, OPTFLOW_IMAX * 100),
junk(0) // XXX just so that we can add things without worrying about the trailing comma junk(0) // XXX just so that we can add things without worrying about the trailing comma
{ {

View File

@ -176,7 +176,7 @@
# endif # endif
#elif CONFIG_SONAR_SOURCE == SONAR_SOURCE_ANALOG_PIN #elif CONFIG_SONAR_SOURCE == SONAR_SOURCE_ANALOG_PIN
# ifndef CONFIG_SONAR_SOURCE_ANALOG_PIN # ifndef CONFIG_SONAR_SOURCE_ANALOG_PIN
# define CONFIG_SONAR_SOURCE_ANALOG_PIN A1 # define CONFIG_SONAR_SOURCE_ANALOG_PIN A0
# endif # endif
#else #else
# warning Invalid value for CONFIG_SONAR_SOURCE, disabling sonar # warning Invalid value for CONFIG_SONAR_SOURCE, disabling sonar
@ -313,21 +313,30 @@
#ifndef OPTFLOW_ORIENTATION #ifndef OPTFLOW_ORIENTATION
# define OPTFLOW_ORIENTATION AP_OPTICALFLOW_ADNS3080_PINS_FORWARD # define OPTFLOW_ORIENTATION AP_OPTICALFLOW_ADNS3080_PINS_FORWARD
#endif #endif
#ifndef OPTFLOW_RESOLUTION
# define OPTFLOW_RESOLUTION ADNS3080_RESOLUTION_1600
#endif
#ifndef OPTFLOW_FOV #ifndef OPTFLOW_FOV
# define OPTFLOW_FOV AP_OPTICALFLOW_ADNS3080_08_FOV # define OPTFLOW_FOV AP_OPTICALFLOW_ADNS3080_08_FOV
#endif #endif
// optical flow based loiter PI values // optical flow based loiter PI values
#ifndef OPTFLOW_ROLL_P #ifndef OPTFLOW_ROLL_P
#define OPTFLOW_ROLL_P 6.4 #define OPTFLOW_ROLL_P 2.5
#endif #endif
#ifndef OPTFLOW_ROLL_I #ifndef OPTFLOW_ROLL_I
#define OPTFLOW_ROLL_I 0.068 #define OPTFLOW_ROLL_I 6.2
#endif
#ifndef OPTFLOW_ROLL_D
#define OPTFLOW_ROLL_D 0.12
#endif #endif
#ifndef OPTFLOW_PITCH_P #ifndef OPTFLOW_PITCH_P
#define OPTFLOW_PITCH_P 6.4 #define OPTFLOW_PITCH_P 2.5
#endif #endif
#ifndef OPTFLOW_PITCH_I #ifndef OPTFLOW_PITCH_I
#define OPTFLOW_PITCH_I 0.068 #define OPTFLOW_PITCH_I 6.2
#endif
#ifndef OPTFLOW_PITCH_D
#define OPTFLOW_PITCH_D 0.12
#endif #endif
#ifndef OPTFLOW_IMAX #ifndef OPTFLOW_IMAX
#define OPTFLOW_IMAX 4 #define OPTFLOW_IMAX 4
@ -494,6 +503,18 @@
# define SUPER_SIMPLE DISABLED # define SUPER_SIMPLE DISABLED
#endif #endif
// LOITER Mode
#ifndef OF_LOITER_YAW
# define OF_LOITER_YAW YAW_HOLD
#endif
#ifndef OF_LOITER_RP
# define OF_LOITER_RP ROLL_PITCH_STABLE_OF
#endif
#ifndef OF_LOITER_THR
# define OF_LOITER_THR THROTTLE_HOLD
#endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// Attitude Control // Attitude Control

View File

@ -49,8 +49,7 @@
// //
// //
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 #if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
/* TODO find out correct channel for APM2 TRI_YAW */ # define CH_TRI_YAW CH_7
# define CH_TRI_YAW (-1)
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1 #elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
# define CH_TRI_YAW CH_7 # define CH_TRI_YAW CH_7
#endif #endif

View File

@ -122,7 +122,8 @@
#define CIRCLE 7 // AUTO control #define CIRCLE 7 // AUTO control
#define POSITION 8 // AUTO control #define POSITION 8 // AUTO control
#define LAND 9 // AUTO control #define LAND 9 // AUTO control
#define NUM_MODES 10 #define OF_LOITER 10 // Hold a single location using optical flow sensor
#define NUM_MODES 11
#define INITIALISING 9 // in startup routines #define INITIALISING 9 // in startup routines
@ -163,6 +164,7 @@
// optical flow controller // optical flow controller
#define CH6_OPTFLOW_KP 17 #define CH6_OPTFLOW_KP 17
#define CH6_OPTFLOW_KI 18 #define CH6_OPTFLOW_KI 18
#define CH6_OPTFLOW_KD 19
// nav byte mask // nav byte mask

View File

@ -238,6 +238,18 @@ static void init_motors_out()
#endif #endif
} }
static void motors_output_enable()
{
APM_RC.enable_out(CH_1);
APM_RC.enable_out(CH_2);
APM_RC.enable_out(CH_3);
APM_RC.enable_out(CH_4);
APM_RC.enable_out(CH_5);
APM_RC.enable_out(CH_6);
APM_RC.enable_out(CH_7);
APM_RC.enable_out(CH_8);
}
// these are not really motors, they're servos but we don't rename the function because it fits with the rest of the code better // these are not really motors, they're servos but we don't rename the function because it fits with the rest of the code better
static void output_motors_armed() static void output_motors_armed()
{ {

View File

@ -13,6 +13,7 @@ static void motors_output_enable()
APM_RC.enable_out(MOT_1); APM_RC.enable_out(MOT_1);
APM_RC.enable_out(MOT_2); APM_RC.enable_out(MOT_2);
APM_RC.enable_out(MOT_4); APM_RC.enable_out(MOT_4);
APM_RC.enable_out(CH_TRI_YAW);
} }

View File

@ -113,6 +113,10 @@ void output_min()
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min); APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min); APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
#if FRAME_CONFIG == TRI_FRAME
APM_RC.OutputCh(CH_TRI_YAW, g.rc_4.radio_trim); // Yaw servo middle position
#endif
#if FRAME_CONFIG == OCTA_FRAME #if FRAME_CONFIG == OCTA_FRAME
APM_RC.OutputCh(MOT_7, g.rc_3.radio_min); APM_RC.OutputCh(MOT_7, g.rc_3.radio_min);
APM_RC.OutputCh(MOT_8, g.rc_3.radio_min); APM_RC.OutputCh(MOT_8, g.rc_3.radio_min);

View File

@ -92,6 +92,8 @@ static void init_optflow()
SendDebug("\nFailed to Init OptFlow "); SendDebug("\nFailed to Init OptFlow ");
} }
optflow.set_orientation(OPTFLOW_ORIENTATION); // set optical flow sensor's orientation on aircraft optflow.set_orientation(OPTFLOW_ORIENTATION); // set optical flow sensor's orientation on aircraft
optflow.set_frame_rate(2000); // set minimum update rate (which should lead to maximum low light performance
optflow.set_resolution(OPTFLOW_RESOLUTION); // set optical flow sensor's resolution
optflow.set_field_of_view(OPTFLOW_FOV); // set optical flow sensor's field of view optflow.set_field_of_view(OPTFLOW_FOV); // set optical flow sensor's field of view
// setup timed read of sensor // setup timed read of sensor
//timer_scheduler.register_process(&AP_OpticalFlow::read); //timer_scheduler.register_process(&AP_OpticalFlow::read);

View File

@ -408,13 +408,13 @@ static void set_mode(byte mode)
// if we don't have GPS lock // if we don't have GPS lock
if(home_is_set == false){ if(home_is_set == false){
// our max mode should be // our max mode should be
if (mode > ALT_HOLD) if (mode > ALT_HOLD && mode != OF_LOITER)
mode = STABILIZE; mode = STABILIZE;
} }
// nothing but Loiter for OptFlow only // nothing but OF_LOITER for OptFlow only
if (g.optflow_enabled && GPS_enabled == false){ if (g.optflow_enabled && GPS_enabled == false){
if (mode > ALT_HOLD && mode != LOITER) if (mode > ALT_HOLD && mode != OF_LOITER)
mode = STABILIZE; mode = STABILIZE;
} }
@ -520,6 +520,13 @@ static void set_mode(byte mode)
do_RTL(); do_RTL();
break; break;
case OF_LOITER:
yaw_mode = OF_LOITER_YAW;
roll_pitch_mode = OF_LOITER_RP;
throttle_mode = OF_LOITER_THR;
set_next_WP(&current_loc);
break;
default: default:
break; break;
} }

View File

@ -253,6 +253,9 @@
<Compile Include="Controls\XorPlus.Designer.cs"> <Compile Include="Controls\XorPlus.Designer.cs">
<DependentUpon>XorPlus.cs</DependentUpon> <DependentUpon>XorPlus.cs</DependentUpon>
</Compile> </Compile>
<Compile Include="GCSViews\Firmware.Designer.cs">
<DependentUpon>Firmware.cs</DependentUpon>
</Compile>
<Compile Include="HIL\Utils.cs" /> <Compile Include="HIL\Utils.cs" />
<Compile Include="ResEdit.cs"> <Compile Include="ResEdit.cs">
<SubType>Form</SubType> <SubType>Form</SubType>
@ -652,9 +655,6 @@
<EmbeddedResource Include="GCSViews\Terminal.zh-Hans.resx"> <EmbeddedResource Include="GCSViews\Terminal.zh-Hans.resx">
<DependentUpon>Terminal.cs</DependentUpon> <DependentUpon>Terminal.cs</DependentUpon>
</EmbeddedResource> </EmbeddedResource>
<EmbeddedResource Include="HUD.resx">
<DependentUpon>HUD.cs</DependentUpon>
</EmbeddedResource>
<EmbeddedResource Include="JoystickSetup.resx"> <EmbeddedResource Include="JoystickSetup.resx">
<DependentUpon>JoystickSetup.cs</DependentUpon> <DependentUpon>JoystickSetup.cs</DependentUpon>
<SubType>Designer</SubType> <SubType>Designer</SubType>
@ -733,9 +733,6 @@
<None Include="arducopter-xplane.zip"> <None Include="arducopter-xplane.zip">
<CopyToOutputDirectory>Always</CopyToOutputDirectory> <CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None> </None>
<None Include="defines.h">
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None>
<None Include="m3u\networklink.kml"> <None Include="m3u\networklink.kml">
<CopyToOutputDirectory>Always</CopyToOutputDirectory> <CopyToOutputDirectory>Always</CopyToOutputDirectory>
</None> </None>

View File

@ -39,6 +39,9 @@
| System.Windows.Forms.AnchorStyles.Left) | System.Windows.Forms.AnchorStyles.Left)
| System.Windows.Forms.AnchorStyles.Right))); | System.Windows.Forms.AnchorStyles.Right)));
this.pictureBox1.Cursor = System.Windows.Forms.Cursors.Hand; this.pictureBox1.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBox1.ErrorImage = global::ArdupilotMega.Properties.Resources.bg;
this.pictureBox1.Image = global::ArdupilotMega.Properties.Resources.bg;
this.pictureBox1.InitialImage = global::ArdupilotMega.Properties.Resources.bg;
this.pictureBox1.Location = new System.Drawing.Point(0, 0); this.pictureBox1.Location = new System.Drawing.Point(0, 0);
this.pictureBox1.Name = "pictureBox1"; this.pictureBox1.Name = "pictureBox1";
this.pictureBox1.Size = new System.Drawing.Size(170, 155); this.pictureBox1.Size = new System.Drawing.Size(170, 155);
@ -55,6 +58,7 @@
this.label1.Name = "label1"; this.label1.Name = "label1";
this.label1.Size = new System.Drawing.Size(170, 13); this.label1.Size = new System.Drawing.Size(170, 13);
this.label1.TabIndex = 1; this.label1.TabIndex = 1;
this.label1.Text = "None";
this.label1.TextAlign = System.Drawing.ContentAlignment.MiddleCenter; this.label1.TextAlign = System.Drawing.ContentAlignment.MiddleCenter;
// //
// ImageLabel // ImageLabel

View File

@ -98,9 +98,16 @@ namespace ArdupilotMega
public float ch3percent { public float ch3percent {
get { get {
try try
{
if (MainV2.comPort.param.ContainsKey("RC3_MIN"))
{ {
return (int)((ch3out - float.Parse(MainV2.comPort.param["RC3_MIN"].ToString())) / (float.Parse(MainV2.comPort.param["RC3_MAX"].ToString()) - float.Parse(MainV2.comPort.param["RC3_MIN"].ToString())) * 100); return (int)((ch3out - float.Parse(MainV2.comPort.param["RC3_MIN"].ToString())) / (float.Parse(MainV2.comPort.param["RC3_MAX"].ToString()) - float.Parse(MainV2.comPort.param["RC3_MIN"].ToString())) * 100);
} }
else
{
return 0;
}
}
catch { catch {
return 0; return 0;
} }
@ -141,6 +148,24 @@ namespace ArdupilotMega
public float battery_remaining { get { return _battery_remaining; } set { _battery_remaining = value / 1000; if (_battery_remaining < 0 || _battery_remaining > 100) _battery_remaining = 0; } } public float battery_remaining { get { return _battery_remaining; } set { _battery_remaining = value / 1000; if (_battery_remaining < 0 || _battery_remaining > 100) _battery_remaining = 0; } }
private float _battery_remaining; private float _battery_remaining;
// pressure
public float press_abs { get; set; }
public int press_temp { get; set; }
// sensor offsets
public int mag_ofs_x { get; set; }
public int mag_ofs_y { get; set; }
public int mag_ofs_z { get; set; }
public float mag_declination { get; set; }
public int raw_press { get; set; }
public int raw_temp { get; set; }
public float gyro_cal_x { get; set; }
public float gyro_cal_y { get; set; }
public float gyro_cal_z { get; set; }
public float accel_cal_x { get; set; }
public float accel_cal_y { get; set; }
public float accel_cal_z { get; set; }
// HIL // HIL
public int hilch1 { get; set; } public int hilch1 { get; set; }
public int hilch2 { get; set; } public int hilch2 { get; set; }
@ -190,6 +215,7 @@ namespace ArdupilotMega
ratestatus = 1; ratestatus = 1;
ratesensors = 3; ratesensors = 3;
raterc = 3; raterc = 3;
datetime = DateTime.MinValue;
} }
const float rad2deg = (float)(180 / Math.PI); const float rad2deg = (float)(180 / Math.PI);
@ -229,6 +255,7 @@ namespace ArdupilotMega
int ind = logdata.IndexOf('\0'); int ind = logdata.IndexOf('\0');
if (ind != -1) if (ind != -1)
logdata = logdata.Substring(0, ind); logdata = logdata.Substring(0, ind);
if (messages.Count > 5) if (messages.Count > 5)
{ {
messages.RemoveAt(0); messages.RemoveAt(0);
@ -519,6 +546,51 @@ namespace ArdupilotMega
//MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] = null; //MAVLink.packets[ArdupilotMega.MAVLink.MAVLINK_MSG_ID_SYS_STATUS] = null;
} }
#endif #endif
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_PRESSURE] != null)
{
var pres = new ArdupilotMega.MAVLink.__mavlink_scaled_pressure_t();
object temp = pres;
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SCALED_PRESSURE], ref temp, 6);
pres = (MAVLink.__mavlink_scaled_pressure_t)(temp);
press_abs = pres.press_abs;
press_temp = pres.temperature;
}
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SENSOR_OFFSETS] != null)
{
var sensofs = new ArdupilotMega.MAVLink.__mavlink_sensor_offsets_t();
object temp = sensofs;
MAVLink.ByteArrayToStructure(mavinterface.packets[MAVLink.MAVLINK_MSG_ID_SENSOR_OFFSETS], ref temp, 6);
sensofs = (MAVLink.__mavlink_sensor_offsets_t)(temp);
mag_ofs_x = sensofs.mag_ofs_x;
mag_ofs_y = sensofs.mag_ofs_y;
mag_ofs_z = sensofs.mag_ofs_z;
mag_declination = sensofs.mag_declination;
raw_press = sensofs.raw_press;
raw_temp = sensofs.raw_temp;
gyro_cal_x = sensofs.gyro_cal_x;
gyro_cal_y = sensofs.gyro_cal_y;
gyro_cal_z = sensofs.gyro_cal_z;
accel_cal_x = sensofs.accel_cal_x;
accel_cal_y = sensofs.accel_cal_y;
accel_cal_z = sensofs.accel_cal_z;
}
if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] != null) if (mavinterface.packets[MAVLink.MAVLINK_MSG_ID_ATTITUDE] != null)
{ {
var att = new ArdupilotMega.MAVLink.__mavlink_attitude_t(); var att = new ArdupilotMega.MAVLink.__mavlink_attitude_t();
@ -819,6 +891,7 @@ namespace ArdupilotMega
{ {
if (bs != null) if (bs != null)
{ {
//System.Diagnostics.Debug.WriteLine(DateTime.Now.Millisecond);
//Console.WriteLine(DateTime.Now.Millisecond); //Console.WriteLine(DateTime.Now.Millisecond);
bs.DataSource = this; bs.DataSource = this;
//Console.WriteLine(DateTime.Now.Millisecond + " 1 " + updatenow); //Console.WriteLine(DateTime.Now.Millisecond + " 1 " + updatenow);

View File

@ -0,0 +1,249 @@
using System;
using System.Collections.Generic;
using System.ComponentModel;
using System.Data;
using System.Drawing;
using System.Text;
using System.Windows.Forms;
using System.Text.RegularExpressions;
using System.IO.Ports;
using System.IO;
using System.Runtime.InteropServices;
using System.Xml;
using System.Net;
namespace ArdupilotMega.GCSViews
{
partial class Firmware : MyUserControl
{
/// <summary>
/// Required designer variable.
/// </summary>
private System.ComponentModel.IContainer components = null;
/// <summary>
/// Clean up any resources being used.
/// </summary>
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
protected override void Dispose(bool disposing)
{
if (disposing && (components != null))
{
components.Dispose();
}
base.Dispose(disposing);
}
private ImageLabel pictureBoxAPM;
private ImageLabel pictureBoxQuad;
private ImageLabel pictureBoxHexa;
private ImageLabel pictureBoxTri;
private ImageLabel pictureBoxY6;
private System.Windows.Forms.Label lbl_status;
private System.Windows.Forms.ProgressBar progress;
private System.Windows.Forms.Label label2;
private ImageLabel pictureBoxHeli;
private MyButton BUT_setup;
private PictureBox pictureBoxHilimage;
private PictureBox pictureBoxAPHil;
private PictureBox pictureBoxACHil;
private PictureBox pictureBoxACHHil;
private ImageLabel pictureBoxOcta;
private Label label1;
private ImageLabel pictureBoxOctav;
private void InitializeComponent()
{
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Firmware));
this.pictureBoxAPM = new ArdupilotMega.ImageLabel();
this.pictureBoxQuad = new ArdupilotMega.ImageLabel();
this.pictureBoxHexa = new ArdupilotMega.ImageLabel();
this.pictureBoxTri = new ArdupilotMega.ImageLabel();
this.pictureBoxY6 = new ArdupilotMega.ImageLabel();
this.lbl_status = new System.Windows.Forms.Label();
this.progress = new System.Windows.Forms.ProgressBar();
this.label2 = new System.Windows.Forms.Label();
this.pictureBoxHeli = new ArdupilotMega.ImageLabel();
this.BUT_setup = new ArdupilotMega.MyButton();
this.pictureBoxHilimage = new System.Windows.Forms.PictureBox();
this.pictureBoxAPHil = new System.Windows.Forms.PictureBox();
this.pictureBoxACHil = new System.Windows.Forms.PictureBox();
this.pictureBoxACHHil = new System.Windows.Forms.PictureBox();
this.pictureBoxOcta = new ArdupilotMega.ImageLabel();
this.pictureBoxOctav = new ArdupilotMega.ImageLabel();
this.label1 = new System.Windows.Forms.Label();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxHilimage)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxAPHil)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxACHil)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxACHHil)).BeginInit();
this.SuspendLayout();
//
// pictureBoxAPM
//
this.pictureBoxAPM.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxAPM.Image = null;
resources.ApplyResources(this.pictureBoxAPM, "pictureBoxAPM");
this.pictureBoxAPM.Name = "pictureBoxAPM";
this.pictureBoxAPM.TabStop = false;
this.pictureBoxAPM.Click += new System.EventHandler(this.pictureBoxAPM_Click);
//
// pictureBoxQuad
//
this.pictureBoxQuad.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxQuad.Image = null;
resources.ApplyResources(this.pictureBoxQuad, "pictureBoxQuad");
this.pictureBoxQuad.Name = "pictureBoxQuad";
this.pictureBoxQuad.TabStop = false;
this.pictureBoxQuad.Click += new System.EventHandler(this.pictureBoxQuad_Click);
//
// pictureBoxHexa
//
this.pictureBoxHexa.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxHexa.Image = null;
resources.ApplyResources(this.pictureBoxHexa, "pictureBoxHexa");
this.pictureBoxHexa.Name = "pictureBoxHexa";
this.pictureBoxHexa.TabStop = false;
this.pictureBoxHexa.Click += new System.EventHandler(this.pictureBoxHexa_Click);
//
// pictureBoxTri
//
this.pictureBoxTri.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxTri.Image = null;
resources.ApplyResources(this.pictureBoxTri, "pictureBoxTri");
this.pictureBoxTri.Name = "pictureBoxTri";
this.pictureBoxTri.TabStop = false;
this.pictureBoxTri.Click += new System.EventHandler(this.pictureBoxTri_Click);
//
// pictureBoxY6
//
this.pictureBoxY6.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxY6.Image = null;
resources.ApplyResources(this.pictureBoxY6, "pictureBoxY6");
this.pictureBoxY6.Name = "pictureBoxY6";
this.pictureBoxY6.TabStop = false;
this.pictureBoxY6.Click += new System.EventHandler(this.pictureBoxY6_Click);
//
// lbl_status
//
resources.ApplyResources(this.lbl_status, "lbl_status");
this.lbl_status.Name = "lbl_status";
//
// progress
//
resources.ApplyResources(this.progress, "progress");
this.progress.Name = "progress";
this.progress.Step = 1;
//
// label2
//
resources.ApplyResources(this.label2, "label2");
this.label2.Name = "label2";
//
// pictureBoxHeli
//
this.pictureBoxHeli.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxHeli.Image = null;
resources.ApplyResources(this.pictureBoxHeli, "pictureBoxHeli");
this.pictureBoxHeli.Name = "pictureBoxHeli";
this.pictureBoxHeli.TabStop = false;
this.pictureBoxHeli.Click += new System.EventHandler(this.pictureBoxHeli_Click);
//
// BUT_setup
//
resources.ApplyResources(this.BUT_setup, "BUT_setup");
this.BUT_setup.Name = "BUT_setup";
this.BUT_setup.UseVisualStyleBackColor = true;
this.BUT_setup.Click += new System.EventHandler(this.BUT_setup_Click);
//
// pictureBoxHilimage
//
this.pictureBoxHilimage.Image = global::ArdupilotMega.Properties.Resources.hil;
resources.ApplyResources(this.pictureBoxHilimage, "pictureBoxHilimage");
this.pictureBoxHilimage.Name = "pictureBoxHilimage";
this.pictureBoxHilimage.TabStop = false;
//
// pictureBoxAPHil
//
this.pictureBoxAPHil.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxAPHil.Image = global::ArdupilotMega.Properties.Resources.hilplane;
resources.ApplyResources(this.pictureBoxAPHil, "pictureBoxAPHil");
this.pictureBoxAPHil.Name = "pictureBoxAPHil";
this.pictureBoxAPHil.TabStop = false;
this.pictureBoxAPHil.Click += new System.EventHandler(this.pictureBoxAPHil_Click);
//
// pictureBoxACHil
//
this.pictureBoxACHil.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxACHil.Image = global::ArdupilotMega.Properties.Resources.hilquad;
resources.ApplyResources(this.pictureBoxACHil, "pictureBoxACHil");
this.pictureBoxACHil.Name = "pictureBoxACHil";
this.pictureBoxACHil.TabStop = false;
this.pictureBoxACHil.Click += new System.EventHandler(this.pictureBoxACHil_Click);
//
// pictureBoxACHHil
//
this.pictureBoxACHHil.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxACHHil.Image = global::ArdupilotMega.Properties.Resources.hilheli;
resources.ApplyResources(this.pictureBoxACHHil, "pictureBoxACHHil");
this.pictureBoxACHHil.Name = "pictureBoxACHHil";
this.pictureBoxACHHil.TabStop = false;
this.pictureBoxACHHil.Click += new System.EventHandler(this.pictureBoxACHHil_Click);
//
// pictureBoxOcta
//
this.pictureBoxOcta.Image = null;
resources.ApplyResources(this.pictureBoxOcta, "pictureBoxOcta");
this.pictureBoxOcta.Name = "pictureBoxOcta";
this.pictureBoxOcta.TabStop = false;
this.pictureBoxOcta.Click += new System.EventHandler(this.pictureBoxOcta_Click);
//
// pictureBoxOctav
//
this.pictureBoxOctav.Image = null;
resources.ApplyResources(this.pictureBoxOctav, "pictureBoxOctav");
this.pictureBoxOctav.Name = "pictureBoxOctav";
this.pictureBoxOctav.TabStop = false;
this.pictureBoxOctav.Click += new System.EventHandler(this.pictureBoxOctav_Click);
//
// label1
//
resources.ApplyResources(this.label1, "label1");
this.label1.Name = "label1";
//
// Firmware
//
resources.ApplyResources(this, "$this");
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.Controls.Add(this.label1);
this.Controls.Add(this.BUT_setup);
this.Controls.Add(this.label2);
this.Controls.Add(this.lbl_status);
this.Controls.Add(this.progress);
this.Controls.Add(this.pictureBoxACHHil);
this.Controls.Add(this.pictureBoxACHil);
this.Controls.Add(this.pictureBoxAPHil);
this.Controls.Add(this.pictureBoxHilimage);
this.Controls.Add(this.pictureBoxOctav);
this.Controls.Add(this.pictureBoxOcta);
this.Controls.Add(this.pictureBoxHeli);
this.Controls.Add(this.pictureBoxY6);
this.Controls.Add(this.pictureBoxTri);
this.Controls.Add(this.pictureBoxHexa);
this.Controls.Add(this.pictureBoxQuad);
this.Controls.Add(this.pictureBoxAPM);
this.MinimumSize = new System.Drawing.Size(1008, 461);
this.Name = "Firmware";
this.Load += new System.EventHandler(this.Firmware_Load);
((System.ComponentModel.ISupportInitialize)(this.pictureBoxHilimage)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxAPHil)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxACHil)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxACHHil)).EndInit();
this.ResumeLayout(false);
this.PerformLayout();
}
}
}

View File

@ -14,230 +14,11 @@ using System.Net;
namespace ArdupilotMega.GCSViews namespace ArdupilotMega.GCSViews
{ {
class Firmware : MyUserControl partial class Firmware : MyUserControl
{ {
private ImageLabel pictureBoxAPM;
private ImageLabel pictureBoxQuad;
private ImageLabel pictureBoxHexa;
private ImageLabel pictureBoxTri;
private ImageLabel pictureBoxY6;
private System.Windows.Forms.Label lbl_status;
private System.Windows.Forms.ProgressBar progress;
private System.Windows.Forms.Label label2;
private ImageLabel pictureBoxHeli;
private MyButton BUT_setup;
private PictureBox pictureBoxHilimage;
private PictureBox pictureBoxAPHil;
private PictureBox pictureBoxACHil;
private PictureBox pictureBoxACHHil;
private ImageLabel pictureBoxOcta;
private Label label1;
private ImageLabel pictureBoxOctav;
private void InitializeComponent()
{
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Firmware));
this.pictureBoxAPM = new ArdupilotMega.ImageLabel();
this.pictureBoxQuad = new ArdupilotMega.ImageLabel();
this.pictureBoxHexa = new ArdupilotMega.ImageLabel();
this.pictureBoxTri = new ArdupilotMega.ImageLabel();
this.pictureBoxY6 = new ArdupilotMega.ImageLabel();
this.lbl_status = new System.Windows.Forms.Label();
this.progress = new System.Windows.Forms.ProgressBar();
this.label2 = new System.Windows.Forms.Label();
this.pictureBoxHeli = new ArdupilotMega.ImageLabel();
this.BUT_setup = new ArdupilotMega.MyButton();
this.pictureBoxHilimage = new System.Windows.Forms.PictureBox();
this.pictureBoxAPHil = new System.Windows.Forms.PictureBox();
this.pictureBoxACHil = new System.Windows.Forms.PictureBox();
this.pictureBoxACHHil = new System.Windows.Forms.PictureBox();
this.pictureBoxOcta = new ArdupilotMega.ImageLabel();
this.pictureBoxOctav = new ArdupilotMega.ImageLabel();
this.label1 = new System.Windows.Forms.Label();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxHilimage)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxAPHil)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxACHil)).BeginInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxACHHil)).BeginInit();
this.SuspendLayout();
//
// pictureBoxAPM
//
this.pictureBoxAPM.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxAPM.Image = global::ArdupilotMega.Properties.Resources.APM_airframes_001;
resources.ApplyResources(this.pictureBoxAPM, "pictureBoxAPM");
this.pictureBoxAPM.Name = "pictureBoxAPM";
this.pictureBoxAPM.TabStop = false;
this.pictureBoxAPM.Click += new System.EventHandler(this.pictureBoxAPM_Click);
//
// pictureBoxQuad
//
this.pictureBoxQuad.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxQuad.Image = ((System.Drawing.Image)(resources.GetObject("pictureBoxQuad.Image")));
resources.ApplyResources(this.pictureBoxQuad, "pictureBoxQuad");
this.pictureBoxQuad.Name = "pictureBoxQuad";
this.pictureBoxQuad.TabStop = false;
this.pictureBoxQuad.Click += new System.EventHandler(this.pictureBoxQuad_Click);
//
// pictureBoxHexa
//
this.pictureBoxHexa.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxHexa.Image = global::ArdupilotMega.Properties.Resources.hexa;
resources.ApplyResources(this.pictureBoxHexa, "pictureBoxHexa");
this.pictureBoxHexa.Name = "pictureBoxHexa";
this.pictureBoxHexa.TabStop = false;
this.pictureBoxHexa.Click += new System.EventHandler(this.pictureBoxHexa_Click);
//
// pictureBoxTri
//
this.pictureBoxTri.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxTri.Image = global::ArdupilotMega.Properties.Resources.tri;
resources.ApplyResources(this.pictureBoxTri, "pictureBoxTri");
this.pictureBoxTri.Name = "pictureBoxTri";
this.pictureBoxTri.TabStop = false;
this.pictureBoxTri.Click += new System.EventHandler(this.pictureBoxTri_Click);
//
// pictureBoxY6
//
this.pictureBoxY6.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxY6.Image = global::ArdupilotMega.Properties.Resources.y6;
resources.ApplyResources(this.pictureBoxY6, "pictureBoxY6");
this.pictureBoxY6.Name = "pictureBoxY6";
this.pictureBoxY6.TabStop = false;
this.pictureBoxY6.Click += new System.EventHandler(this.pictureBoxY6_Click);
//
// lbl_status
//
resources.ApplyResources(this.lbl_status, "lbl_status");
this.lbl_status.Name = "lbl_status";
//
// progress
//
resources.ApplyResources(this.progress, "progress");
this.progress.Name = "progress";
this.progress.Step = 1;
//
// label2
//
resources.ApplyResources(this.label2, "label2");
this.label2.Name = "label2";
//
// pictureBoxHeli
//
this.pictureBoxHeli.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxHeli.Image = global::ArdupilotMega.Properties.Resources.APM_airframes_08;
resources.ApplyResources(this.pictureBoxHeli, "pictureBoxHeli");
this.pictureBoxHeli.Name = "pictureBoxHeli";
this.pictureBoxHeli.TabStop = false;
this.pictureBoxHeli.Click += new System.EventHandler(this.pictureBoxHeli_Click);
//
// BUT_setup
//
resources.ApplyResources(this.BUT_setup, "BUT_setup");
this.BUT_setup.Name = "BUT_setup";
this.BUT_setup.UseVisualStyleBackColor = true;
this.BUT_setup.Click += new System.EventHandler(this.BUT_setup_Click);
//
// pictureBoxHilimage
//
this.pictureBoxHilimage.Image = global::ArdupilotMega.Properties.Resources.hil;
resources.ApplyResources(this.pictureBoxHilimage, "pictureBoxHilimage");
this.pictureBoxHilimage.Name = "pictureBoxHilimage";
this.pictureBoxHilimage.TabStop = false;
//
// pictureBoxAPHil
//
this.pictureBoxAPHil.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxAPHil.Image = global::ArdupilotMega.Properties.Resources.hilplane;
resources.ApplyResources(this.pictureBoxAPHil, "pictureBoxAPHil");
this.pictureBoxAPHil.Name = "pictureBoxAPHil";
this.pictureBoxAPHil.TabStop = false;
this.pictureBoxAPHil.Click += new System.EventHandler(this.pictureBoxAPHil_Click);
//
// pictureBoxACHil
//
this.pictureBoxACHil.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxACHil.Image = global::ArdupilotMega.Properties.Resources.hilquad;
resources.ApplyResources(this.pictureBoxACHil, "pictureBoxACHil");
this.pictureBoxACHil.Name = "pictureBoxACHil";
this.pictureBoxACHil.TabStop = false;
this.pictureBoxACHil.Click += new System.EventHandler(this.pictureBoxACHil_Click);
//
// pictureBoxACHHil
//
this.pictureBoxACHHil.Cursor = System.Windows.Forms.Cursors.Hand;
this.pictureBoxACHHil.Image = global::ArdupilotMega.Properties.Resources.hilheli;
resources.ApplyResources(this.pictureBoxACHHil, "pictureBoxACHHil");
this.pictureBoxACHHil.Name = "pictureBoxACHHil";
this.pictureBoxACHHil.TabStop = false;
this.pictureBoxACHHil.Click += new System.EventHandler(this.pictureBoxACHHil_Click);
//
// pictureBoxOcta
//
this.pictureBoxOcta.Image = global::ArdupilotMega.Properties.Resources.octo;
resources.ApplyResources(this.pictureBoxOcta, "pictureBoxOcta");
this.pictureBoxOcta.Name = "pictureBoxOcta";
this.pictureBoxOcta.TabStop = false;
this.pictureBoxOcta.Click += new System.EventHandler(this.pictureBoxOcta_Click);
//
// pictureBoxOctav
//
this.pictureBoxOctav.Image = global::ArdupilotMega.Properties.Resources.octov;
resources.ApplyResources(this.pictureBoxOctav, "pictureBoxOctav");
this.pictureBoxOctav.Name = "pictureBoxOctav";
this.pictureBoxOctav.TabStop = false;
this.pictureBoxOctav.Click += new System.EventHandler(this.pictureBoxOctav_Click);
//
// label1
//
resources.ApplyResources(this.label1, "label1");
this.label1.Name = "label1";
//
// Firmware
//
resources.ApplyResources(this, "$this");
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.Controls.Add(this.label1);
this.Controls.Add(this.pictureBoxOctav);
this.Controls.Add(this.pictureBoxOcta);
this.Controls.Add(this.pictureBoxACHHil);
this.Controls.Add(this.pictureBoxACHil);
this.Controls.Add(this.pictureBoxAPHil);
this.Controls.Add(this.pictureBoxHilimage);
this.Controls.Add(this.BUT_setup);
this.Controls.Add(this.pictureBoxHeli);
this.Controls.Add(this.label2);
this.Controls.Add(this.lbl_status);
this.Controls.Add(this.progress);
this.Controls.Add(this.pictureBoxY6);
this.Controls.Add(this.pictureBoxTri);
this.Controls.Add(this.pictureBoxHexa);
this.Controls.Add(this.pictureBoxQuad);
this.Controls.Add(this.pictureBoxAPM);
this.MinimumSize = new System.Drawing.Size(1008, 461);
this.Name = "Firmware";
this.Load += new System.EventHandler(this.FirmwareVisual_Load);
((System.ComponentModel.ISupportInitialize)(this.pictureBoxHilimage)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxAPHil)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxACHil)).EndInit();
((System.ComponentModel.ISupportInitialize)(this.pictureBoxACHHil)).EndInit();
this.ResumeLayout(false);
this.PerformLayout();
}
protected override bool ProcessCmdKey(ref Message msg, Keys keyData) protected override bool ProcessCmdKey(ref Message msg, Keys keyData)
{ {
if (keyData == (Keys.Control | Keys.B))
{
findfirmware("AP-trunk");
return true;
}
if (keyData == (Keys.Control | Keys.A))
{
findfirmware("AC2-QUADHIL");
return true;
}
if (keyData == (Keys.Control | Keys.C)) if (keyData == (Keys.Control | Keys.C))
{ {
OpenFileDialog fd = new OpenFileDialog(); OpenFileDialog fd = new OpenFileDialog();
@ -265,26 +46,31 @@ namespace ArdupilotMega.GCSViews
public int k_format_version; public int k_format_version;
} }
public enum FRAMETYPES
{
NONE,
TRI,
QUAD,
HEXA,
Y6,
APM,
APMHIL,
HELI
}
public Firmware() public Firmware()
{ {
InitializeComponent(); InitializeComponent();
WebRequest.DefaultWebProxy.Credentials = System.Net.CredentialCache.DefaultCredentials; WebRequest.DefaultWebProxy.Credentials = System.Net.CredentialCache.DefaultCredentials;
this.pictureBoxAPM.Image = ArdupilotMega.Properties.Resources.APM_airframes_001;
this.pictureBoxQuad.Image = ArdupilotMega.Properties.Resources.quad;
this.pictureBoxHexa.Image = ArdupilotMega.Properties.Resources.hexa;
this.pictureBoxTri.Image = ArdupilotMega.Properties.Resources.tri;
this.pictureBoxY6.Image = ArdupilotMega.Properties.Resources.y6;
this.pictureBoxHeli.Image = ArdupilotMega.Properties.Resources.APM_airframes_08;
this.pictureBoxHilimage.Image = ArdupilotMega.Properties.Resources.hil;
this.pictureBoxAPHil.Image = ArdupilotMega.Properties.Resources.hilplane;
this.pictureBoxACHil.Image = ArdupilotMega.Properties.Resources.hilquad;
this.pictureBoxACHHil.Image = ArdupilotMega.Properties.Resources.hilheli;
this.pictureBoxOcta.Image = ArdupilotMega.Properties.Resources.octo;
this.pictureBoxOctav.Image = ArdupilotMega.Properties.Resources.octov;
} }
private void FirmwareVisual_Load(object sender, EventArgs e) internal void Firmware_Load(object sender, EventArgs e)
{ {
Console.WriteLine("FW load");
string url = ""; string url = "";
string url2560 = ""; string url2560 = "";
string url2560_2 = ""; string url2560_2 = "";
@ -292,6 +78,8 @@ namespace ArdupilotMega.GCSViews
string desc = ""; string desc = "";
int k_format_version = 0; int k_format_version = 0;
softwares.Clear();
software temp = new software(); software temp = new software();
try try
@ -357,6 +145,7 @@ namespace ArdupilotMega.GCSViews
} }
catch (Exception ex) { MessageBox.Show("Failed to get Firmware List : " + ex.Message); } catch (Exception ex) { MessageBox.Show("Failed to get Firmware List : " + ex.Message); }
Console.WriteLine("FW load done");
} }
void updateDisplayName(software temp) void updateDisplayName(software temp)
@ -435,7 +224,7 @@ namespace ArdupilotMega.GCSViews
} }
return; return;
} }
else if (items.Count == 2) else if (items.Count == 2 && false)
{ {
XorPlus select = new XorPlus(); XorPlus select = new XorPlus();
MainV2.fixtheme(select); MainV2.fixtheme(select);

View File

@ -144,634 +144,6 @@
<data name="&gt;&gt;pictureBoxAPM.ZOrder" xml:space="preserve"> <data name="&gt;&gt;pictureBoxAPM.ZOrder" xml:space="preserve">
<value>16</value> <value>16</value>
</data> </data>
<data name="pictureBoxQuad.Image" type="System.Drawing.Bitmap, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
<value>
iVBORw0KGgoAAAANSUhEUgAAAnEAAAJxCAYAAAAtjeQ4AAAAAXNSR0IArs4c6QAAAARnQU1BAACxjwv8
YQUAAAAJcEhZcwAAFxEAABcRAcom8z8AAAAZdEVYdFNvZnR3YXJlAEFkb2JlIEltYWdlUmVhZHlxyWU8
AACRnUlEQVR4Xu29TY9lx3WuyZ+Q/0D5B3yRc8NATg30IGc24ElOPPGkE/DIgAel2e2RcmAYFxDUSBu4
hC+ghuhGU22ojb6lFnVNSRRuyVKXRZlg8wolumxSMsmqrGLlxzm936iIo6hd5+TZETv23vHxbOC4ZOb+
jPWutd5Ya8WKN9br9Rv8GAMwAAbAABgAA2AADJSFAQgcJBYMgAEwAAbAABgAAwViAKEVKDRmSmXNlJAX
8gIDYAAMgIEpMACJg8SBATAABsAAGAADYKBADCC0AoU2BZvnnswSwQAYAANgAAyUhQFIHCQODIABMAAG
wAAYAAMFYgChFSg0ZkplzZSQF/ICA2AADICBKTAAiYPEgQEwAAbAABgAA2CgQAwgtAKFNgWb557MEsEA
GAADYAAMlIUBSBwkDgyAATAABsAAGAADBWIAoRUoNGZKZc2UkBfyAgNgAAyAgSkwAImDxIEBMAAGwAAY
AANgoEAMILQChTYFm+eezBLBABgAA2AADJSFAUgcJA4MgAEwAAbAABgAAwViAKEVKDRmSmXNlJAX8gID
YAAMgIEpMACJg8SBATAABsAAGAADYKBADCC0AoU2BZvnnswSwQAYAANgAAyUhQFIHCQODIABMAAGwAAY
AAMFYgChFSg0ZkplzZSQF/ICA2AADICBKTAAiYPEgQEwAAbAABgAA2CgQAwgtAKFNgWb557MEsEAGAAD
YAAMlIUBSBwkDgyAATAABsAAGAADBWIAoRUoNGZKZc2UkBfyAgNgAAyAgSkwAImDxIEBMAAGwAAYAANg
oEAMILQChTYFm+eezBLBABgAA2AADJSFAUgcJA4MgAEwAAbAABgAAwViAKEVKDRmSmXNlJAX8gIDYAAM
gIEpMACJg8SBATAABsAAGAADYKBADCC0AoU2BZvnnswSwQAYAANgAAyUhQFIHCQODIABMAAGwAAYAAMF
YgChFSg0ZkplzZSQF/ICA2AADICBKTAAiYPEgQEwAAbAABgAA2CgQAwgtAKFNgWb557MEsEAGAADYAAM
lIUBSBwkDgyAATAABsAAGAADBWIAoRUoNGZKZc2UkBfyAgNgAAyAgSkwAImDxIEBMAAGwAAYAANgoEAM
ILQChTYFm+eezBLBABgAA2AADJSFAUgcJA4MgAEwAAbAABgAAwViAKEVKDRmSmXNlJBXcnkddGN6bH/3
un/d7373v++/uP7ivedXv36w7Xe7un5H53S/C++6E3uvQ2SVXFb4GHwMGJgQAwzuhIOLQ8AhgIHRGBBZ
OxPpEjnr/t15fPL04fpXn7076Nfda+d9Xtw8+aD741uW5IngQe6wk/hKMJAlBrJ8KRzfaMeHXDE4JWJA
ZOlUhO3q5vL9PssSQfunx99c//Cjr62//bM/Xn/rJ3+w/vr3f2f9F9/9yqif7qPf9z74qrm3nvPF80ev
PP769vljS+xEKI+wUdgoMAAGcsBAiYaed4aggIF6MCBCdN4nbSJSjqz91Q9+dxRJiyV5Iogid3qPDz/9
ztqP3nVp2ac2JSvSqfQumGQMwAAYmB0Dsz8QY4exBwPNY0ApyouOCF26cJdSoSJLIk2xpGuO6/7mx79v
InYidf5xc/vibRtFhNDhyPGrYGA2DMz2IBx3844brLVt2JQqPe/IzseO/IgI/f3P/3S9VKQtBelTWlcp
Xj9K16Ve3+y+UUQVzDMGYAAMTIqBSW+OEcOIg4HmMXBqV4Qa7qaIm4hbilq2FCQs5T0coXMk1RLWe6Rb
m9cB/CxEbjIMTHZjnDeGCww0iwGlFM/sYgATpXrw6BtFR9xCyJ4IqoiqCKt3XHT/W9FIbC5jAAbAQDIM
JLsRxgnjDAaax4DI2z1b9G9WeIrMhBCg2s5VjZ/Sre6wqVbIHE4c3wsGkmAgyU1w3s07b3DUtkF6hbxp
ZWnuCxTmJouq+4PMYSfxlWAgNQZwvm07X+SP/MdiQDVvardh+qtB3u7uWdcnc92wKc0qEjxWDlzPGIKB
BjGA0BsUOg4Dh5kAA8cdeTMdcZU2hbyFNRz2yZxttaIFENhjxgAMgIEgDASdjJHByIKB5jFwYHuimQUL
6pk2d2qypueJ/CqCqcOS4mN0rHkdwy9D5AZjYPCJGBYMCxhoHgNnLnWq1aY5tglxuyy4rbT6/6pZb44k
UAtAvF5z56RYm9c1fDNEbhAGBp2E88aggIGmMXDger0tnToVCVM/NrcV1rZ9Tr22Hnf+T5EmXe+2+FJU
MdV+rDFEUQTU7QRhe8wRlcOR46PBwJ0YACAABAyAgbswcOKibyJOMeQk9hrVjSlCpaifSzn6rEzv1RGx
97r/9pZam3g/kZ9dv1PvPG399c6Lmycf9NmeyKpWk4rYzR29E0ntReXQUXQUDICBrRgAGAADDICBXRhQ
Wm/WhQuKhIm09Rrlrq9vn6lwTO8jEjZVhOqou/eJSJ7Inb+3q0iVSN1cu030onLqGnxINLzpaDh2GjsN
icMIYgTBwCAMHHbpPLPdgNJ7U9e+bdt/1D5f0bWpCNtQpyhid6bFHD6pc/u+Tj02igTqsM8WwRz63pzH
WIGBBjCAkBsQMoYfxxeAAbUOMX3fplx5qlSp0rNKW7rDrnpVpO0g4H3ntmEiUkrDXrr3VoRuyhYrSud6
46Ro5NzfzPMYczCQKQYQTKaCwVDjqBbAgAiUqceaqg5MZMcV7+tZNuKWO3HbZSdP7DZahs+5bcamiM7p
nq4u0JLdnIkufgW/AgZmwgADPdNAL+CQkS2yDcHAhYiIatGmICGqJduQkNXVM0Wzup9SlSHvmOu5IlRK
uX7sSLCijFOMo+oFPfILkasDP7nimvcqAF8IqQAhVeLowFqmWHPRJKUFUxMPRd5cKtCmae9lni4di9NT
uwjDRDSnIHMixJbIiTTWQoTHjjvXZ2pf8F/TTlQBPsAHA+1iQP3ffipCIAIX2wpk23W9nQhUY1c7eevr
0bFP5kS8Uo6vaUNy82S1Wt08gchN6yQhIYxvzhjAgbfrwJF927LfELiU/d8UyRMhNJGil2nT1shbX6/U
Z8+s3lCqOuUCCNUtisjZcSYi17Y+Y88blT+Cb1TwOc8seLfJZ74bApcyQqTVrK5JrU3RUrP1W/uiLcvM
itaUW5YZItelbSFyk+sMvhJfmSUGsnwpnDgGCQxMhoHkBE7tQtjEfZC8DuzK0qQNlCFyg8YeXwcJqxID
VX4UBACjBga2Y8DVwKWKwLnaLJM/fZk6xabsH4PNVmaponKOyFEjB/7QwbYwgMHdb3AZI8aoCgy4Vagp
auBeqX172VqDmqwwPdlE5VQrl6Ivn6uRs0TuEGfeljNH3m3KuwrnBHjbBC9yD5L7RapVqEqfur1NqX0L
ksE2e3uqejYtUEgRHdXCCR1XN5fvd/9QkxhGrPGHjFdxGCjuhXHco50GMm/PUJ2mInAiCW7xQndP3Rc8
jR+DI0u6zKKHsa1IXB+5LnX+DvIBn2CgbgxggMcbYMaQMcwZA8cicCl2YnDkgLqrSZzCJr2aoumyUub2
UAQ2Z3zybsgHDIzAAIM3YvAwjjiHzDFwqF0SFDkbuxMD2z3NhnWT9k5Bul2/PiKms8kOf4o/nR0Dsz8w
c6fHeKCE1WDAbi4/umjekQGbnqPOanodMenvsUROxN3VLrLwBCKH760TA9U4LABaJ0CRa7Rcz0UE1IB3
TI2VI3B2AQP2YnoC58Y4CZHTIhSzq8PLFcQQ8Pnkh64w1rNgYJaH4IijHTHywRDEYOBEBO7DT7+ThMB1
t6KuahkcJiFy6uWnwzYajsET1ywjf8adcd+Lgb0nQMAgYGCgKAxoR4anXzx/NKoOzqungsAt60iSEDlX
00h9XFG6jH9eVveKGP8iXhISgeEBA8MwYOvWRm207hw+KdRhYz4DNkcTOVcfZ/dvPZzhnfEtEBAwMAMG
GOQZBhmDmY0zrB3vZ0qbjdmRgR5j2WLVELkxKXLt6KCD/nHZyrh2+8T3TcA3GNQJBhXShpFcAAMmjarV
iLELGVy3f7uqlSL4/GzDuUiYUt2xMvb6x4kUYv8ZAzBQOAYQYOECxBDjiIQBW7QenUbtbaAOgcvULrj9
b2O36FJaVfWSIvysVsV24D/KxwAkLlNjjXKVr1wzyvBYEZrYLZtcvZT28OxuczTje2N/wu2PdnZ4KHmL
eMdE5FzEtbuFInvIgDEAAwVjAOEVLDwMMA5IGOiiKo/G7MpAZ//icGR24hizAlm1dfaAtOMD4AEFYwDh
FSw8SFxxzncKfTMF77FNfd1Chu4WF+CpKDydSO6xCx1cE2AWORQl8ynsB/csnAMgwMIFiONt2ghvesLF
pNWcI7+6uXyf+qgicWQWOsQSeG+Rg9Lx+ALGAAwUiAGEVqDQMLg4HIuBe3LiqnGKIXG/+uxdUmqF67/q
47Stlgh5KAZUC6k0vNLx2BRsChgoEwOQuMKNOIpXpuIlkJuicJciYqHOW+cremMPEUHsQLljoJq2dQIc
KC0PDhgDMFAYBhBYYQLD0OJoxkbhXATGrnLEBpRvA0xEVnukxhB623KEaFz5OECXG5QhQm9Q6BDB4omg
qYWLjb54q1GphapD/9V25OPYFcre4haicXXgAb/ekBwRdkPChrwVT96cvp7F1sJ5PcJYjVqX7pvVqjFb
rrnI7PXtMxVJ4hMYAzBQEAYQVkHCwsDiYISBrmv/Y6XAYlJnit7ZTdAPwFNdeLLtQtYxixxYqVoXFtDt
duQJiYPEgYGyMKCU1zpm2yXVTLGYoWrjfij5xuytqmicDrutFzahLJuAvBqWF8JvWPjM1spz6Ep5qfYp
JgrHnpnlyTtCR5Umj4rGebWSIoP4BsYADBSAAYRUgJAwqDgUiwETaYnZI5Xi9WYwFB2N016sRGqbwQm+
vxLfjyArESRErwnjex4bZfnk6UPVwj0FJ03gJDoaJ5xopSs4aQIn+P8K/D9CrECIGNw2DK4WNMjJhqZS
vRWp98BKE1iJjsZ5TaCPwUoTWIEDFM4BEGDhAsTQNmNoTQuJmAUN2iT9ZnX1rLucFamN6HsXTXtb23Fp
wUII6XcLHDqsKJqHf2AMwEDmGEBAmQsIQ4ojsRgwKbJQp6x2E/bAKbel64qkme3VQkiczhXpt21o8A9t
YQZ5FyhvhFag0CB27RE7OVU511CHrEUQ9mDFYWO6ro3tY/oJeotgFP3FRzAGYCBjDCCcjIWDAcWBWAyY
qEpMKlVOnE78zeLoTLhRTWQI+fdSqlpIg49gDMBAxhhAOBkLBwOKA7EYMKtSQ1OpXnPfU7DUJJZUAxnV
/Fc7e7BKtUnMwAkK4wQIrDCB4YzbM6xXN5fvx6xK9Zq3sqChUT03CxwimkN7q1SPsDnt2RxkXo7MIXGN
GneUtBglVS1b1Mbmct5y4g3IWiRV9Vv3ut9bSh8/v/r1A/frxuE9/Xf7d53XEqlVFHatqGxIStVr/KuU
LH6CMQADmWIAwWQqGAwnjsNiwDjh0LqmBlKpImKnlqRqiMwh4qpUYP+n2kD/6K57qOsbIHTRKdWGJgH4
QfxgsRgo9sUhOZCcRjBwIfIREkXRud6q1NqiTvqee3b3CUPalDYWad1XM6i/6zyNjSN1tpWGIni1jdPG
tovoxqxSpdUINrYRG1s0Dyr65QEYRqZ2DKgeTlGlUBJX6arUE0feNCYxq3X9cRSh03102PvWmjrUd62V
Ig3BEXVx2Nfa7WsN3weJI4wMBvLFgEmF/fCjrwU5X6/BryJMNcj3wKVNRU5D67v2ERelql1kzj6ntqjc
kXAU2vjXq4tT2rkGHPENyLE6DFT3QRgbjG1FGDiW8+2TFqUP76qR85q16vrSdfxQ0UiNg757X8p0H2G7
6+8uBW1ba4j4lD52m/dXpDGmWbQJU67X5zWNBd9SD66R5fqNaowUwkQxK8SAImlrRdYc+XCb2d+VYvXq
4UrX76PV6uaJxmBs6nQoudNztOeofW5NRO6tmFYjwpld3Vs6lnj/iiYlFdr6aHxGX8ggQprAwOQYuOg7
XvWLc8cuYqNzKtil4UBESoQqdGXuUMK26zylESskcqYuzp8QDBmniiYE+DpIXJUYqPKjIBeTkwtwM4NB
VATEj7h5adKuEP/K1HFtSy9WkAJTDZxhq6nr34YQF53jiJxN5dZQI7c1Nb9vPLzFDYfYVewqGMgPAzjj
GZwxwM8P+IXIxLTDkKMVWVNU7nZ1Y1KL17fPVyI5/UUPLt3a/ankYnTVYM2WQt1FZBxprqhhcvAiGQ9P
NdRX4u/wd9VhoLoPKsQ5M+4Yk30YUPRn43RF1nR82qVKRTr0/4vQ9VNkFSxqMBGjmCL8fVGlmL976cST
0m1LR/wfh7ar8VY6Kx27D7P8nTECAzNjgAGfecAxhDiCgRgwZEaREOdIRdr8+rB/f/ahIXE+4XFkb+Az
stP/bhXlI0Ucp1yFGkLm9B4ve+49f9yNadFp1W5s34nZg9eA7OWWZtnhhXdCJq1jAKXEMIGBPDGwIXEi
aTo++OTbr/SL81JdG3Kncy3hKFGuSgEH9zMLIWUx53rRzdKjUSJiQT0HNV62h9791p0l3w9hzBEDJRp6
3jlP0oFc0srFOFxvD9StKwt/8a9/a9KqLsKidFmpK1MVhYvZHiqGmIVe40XjSsa5wVRolJM2I5CXHMkL
7/QSlyUbJN49LWlgPPMaT+NwRR5E0kTWthEPOeSb2y9NpM70OOtSkd1xUaCBO8oxCufG3IvGlVwbt4nu
hpDYlxMDk07GRjAGYCAzDCCQzASCocRRWAycG2bWHR1JW90VPRHBENGzBE6XlFi/ZL43NEoUQkbGnKv3
skeJBNnZ+SgSV3qdJTYVm1ozBiBxkDgwkCcGVINk+sEN2TtVq1a9ozgSp62uQldOjiFlMdeq3rBL+V4W
4BBMVHPXEbqHqkfi+rcU8cZ+MAZgYEEMMPgLDj4GEAdwBwYMibu+uRwUnVJzWtdypLvstDBsHepbh5DV
GPKV6hqv8a1IUu6200Q2RTw1rv4vdAcMne9f/7JfoSGzBwWMQ+5y4v3y16WsZZT1y2EgsncU4Gc6A/Tz
zlEGrdR8+C//xUVK/rww3YlK86UiZ0PvU1gj5QNtep96oYi30Ka4aG9hOoFtnc62VjW2VX0MSgrpqwUD
q/Xti6df/ktQO4jf7upw/WlhURIRgkERx6GEa6rzLEsuhcAoIps0wllLz7xa7ATfgc+DxMH2wUB+GDCk
ZtcG93cRlP/rn/5nF40rhWgIf+Z7pyJeKe9rB7eYWjA1+NU7h258v23MvBW6paXrsXH52ThkkkgmDGSi
gWRGxIwoEQZMGiyms75zvFogYI8SareKInF2bO8nkvUc9vdQWBi7aMSL8j4q6NvnGF+egQ9dFAOLPhxj
APEBA69hwESlQovP/ciJoi4vbp6sbBSmBB0vJhJXIInbkGTVs8VGJb0VqifoLHYbDOSDgRIMPO/ITKcV
DBzerK6ejY2ayFF7TreE1FcxJE4R0u4oKRIn3TlQC5fYPWlNFK6bFJS6EwiEIx/CgSzSy6IV58h3QgRL
wMCFGILahcRGTPzrXu72cP1UTjxz41kMibNpar1vCXjy3/FY7/7g0TeCsaVr7KF7lPbdvC8yqxoDVX8c
BgeDWxAGTO3SPz3+ZrCT3UX4vJYYIoc56/pZSvKaggDv2uKsYBL3RheNM8WSIZMEpeZ1dJOBzzLHUM74
5t3ytj9Fy6fol8eoZO2YwVaA4Uq5itAnIGr2WkAUxUSJxtRsTUXc/Pt6pLjUiNQfqvdgyKIZTSrsIQKI
TjMGYCAzDCCQzASCoWzSURgS0z9CdzC4Y3ukbv/VFyrmylnfo1J9c5A39wxvfHNPT++Ss0lb6xiy9ZYi
dt5xP3P85Ixt3i1v21O0fIp+eYxK1k4ZbA03XCcdluVg/V9wk1avm77Sp/376f9XyjZLuahoPvXuAqkJ
niJYVzeX7+c6hgPey5A47cc7ZJGD16pGl7014P5ZYov3zlPnkUsauaB0mTo1AJ4G4AWPY3BkqvB035mY
Qki9VmqSdtf9XG1Y94rnBWPKkLhPX66wvbP+0sOSC8bpWvwFYwAGMsMAAslMIBhKHIUw8Pzq1w9CW414
jleRvdJ0W1HCpAs7UpI8b4VmttHMATK/r2iinybd1Y9Q2Ltd3ax/8a9/C4krT5dK033edwTGGLwRgzfA
aDK+jG8UBrTQIZTEibTYo8ioyfXt8zf1/im2iEpJ4FyftIKaJ2/FnD8xEDkTSduWwnbba92sXviET5HS
KCxzHeMGBqbDAEqJYQIDeWLgQnVLoWTEkjjVxJUo1yyjcRX1Sduk6EVMO9Js4NJfQCNid3P75frHv/xL
s3OIPY4LxVSJesA7l2m/FpHbIg/FGBTpYMHKvIbF1C+FkjhF7wrvrC8COmrbsdAxu+t8l3rsVve+Xbjd
OugTNq1QVTROuzG46KeLwj2/+o3Bnrfp/VHh34/9mtd+Md4zjTcDPdNAYwAhroEYOJXTDS30V18vu0tD
qbp9oPdXNEjRopSELPReer5qyLr3uexEUXItnLCgSNpr5Pjpi381gTaR/99ucn+z6dnntVUpFU+8Nz6u
agxU/XGBTpOxQNlzwoBxuqENcD2nWzLpOHHEIpR4pTzfa3QrQp0TNmLe5Uxj2q839FehupYiv+66qLhx
VLPoLu36uILvjxkzrikf99XLsPoPxPgU73xaxehr6a8hBKXwFaq+rE06OeU2ZEPGz53jETild2vA4M4a
y3/5/EemBk6H/vWJno1EvlPJGNQgR76hDn1MJsdkN0LJqzD04CEjA6EIiCIhIeRDKTF7iASVLk8RqNmJ
nCNwdrVs6WNo3l9Y2rXa2euBt/7gk2+/greKsFSFHCvQaeSQ2C4zoIkHFCUrnjhkoxNqaRGzi4GiJ4Uv
bvBlYIicvmnqGjnd36UUayJw3fDtjepqBa6icP4Ye1HdGtLJ2eg1PgIfkRIDABsSBwbyxYBJKYaSF68l
Ri2yPdM4qOVKaI3g0CimCIvuX2nk6UTftauxr8ZIGNNKVH+8tHrVHkcpnQ73gsSAgXQYqMXI8x35EhFk
Ey+bvc53G0nx9lDV9bWM/3HX5uNjkQpFy+4iJEOJm85TKtFF3+yq3uOKxszJ3kQzQ8ZF53p1gbVgiO+o
xx4gSytLBgJQg4F8MbA3DbbNMXt1ceeVERKNx72b1dUzR+YUPQqNVGrMRHR7G7xrrHT/6vRB5Ddm9w+l
8itKy1cn1xqxyjeF2x+AXaHRRhHCFSHXMYt1wKohs5GrGnX8UGTO9m8zGb9QkqJr7PUib7pfjeOkb1Iq
dK3UaEgkzlvscK/isalV5nxXvfr8mmwRdkPCxhgX6aijUmEN1TMpZXw/NF1omF9HBBvQiTN9aOh+tN5O
DccNjBF+ED9YLAaKfXEMS5GEBLyFG0uRlOCC/sYiKSJjQZGmVkhcF419qKhsSBSOejhsK/61HAzgVMOd
KmPGmM2JAdVpbTYuD3HGladUfRlA4rbrZFQqVRhTPVwF+8XOqac8C7+wCAYWeSgsvxyWj6yWl5WiKTH9
4hpKqULitjvQ85hUqvbrtYdSsfgIxgAMZIwBhJOxcDCgOBCLAVPXJOcaEonzUqqqq6tZ1yFxW+Srlimh
Cz6EL6/P4GHluKlZJ/i2um3eRr4IuhFBY4yLJjFyplEpVW3bZVtyKC1bq75D4l6X7akw02/gO2QSYFOp
DyvGS616wHfVa+N2yhahNyh0jHN5ZCY2peo1/pVTr1XfIXE92WrLNu1AMYS0+eeQSq1WR2rV/ea/q/kB
qNixIdu6SEtUStUrUtduB7ViAhL3qmyPFIX74UdfCyZxpFKr1ZFadb/572p+ACp2bMi2LtJiUqraCik0
uuL1/Ko1GgeJ87B+ffv8zZgFDY7ws0sDRA6/WA4GcPR1OXrkWbE81fIhJkUm56zrlJKt1DhD4n6L+2iy
30jqHRtZsY2s1L7diVkADaDBQDkYiC5WV2rNHicVGjpInMXwmCicFsHYrcgOKsQIdq4cO4esAmTFYAUM
FoatnBBzrbLqnPTjmA782iRe0bjOST+qcGwgcS/tWHQUrqF2NPg8fF5VGKjqYyp0TsgHg9PHgCEs3/rJ
HwTXxnnNf2urjYPEdXqiFamxtXAsaGCCiv8sEwOQBEgCGCgLA0p1RS1wcIXragLb3aKmlBkkbr0+Fi5E
xkIXvpgo7c2TlSWB2IOy7AHyalxeAKBxADD7KnL2dREbcfGK10V8atH/5kmc0uRKl4uQhZI4r15SRLAW
TPAdyLIJDDTxkRgmDHNlGIiufZKD11ZM9jiqZFxaJ3Hm+2N2Z3C1krQVwUZWYgua4zTNfTBAxVjVgIEx
qxBVxK70WUWOu2USd6ht1WL2SBWhr3zVMv6NaFz1GKj+A2tw2HwDxHMLBkZF4zznfVYBvpolcW4xg7bL
Ck2jEoXDrlSg+81zmOYHABBjyArGgKmNi3HgcvhqVVJJWrVVEme+O2Z7rV4Ujlo4IlZwgUIxgOAKFVzB
xAPMpcOcicbFptJcWtXu5HBQMKZaJHGqZxwte1akMoktWO/xJZ0vYRDSOVTGkrFcAgOGwGjVaWg6Ted7
+6oqqrfE+6d4Zmsk7qAj3h+rrlFEPEbu2oO3kihsCvxwj3J1v3nZNT8ABTsuZIfhEQYO1Pfti+ePopy5
CIDn0E8L1YemSJz20B1D3NUo2h4lE3fsH/YPDBCJKzbyAHgxYD4GRL6ia6NU4K76OK1y7G6jNF1p+GqJ
xJlvjWnq6yJ2knWFDZ9LwyzvW56dyVJmWb5UgU6EcUQhF8XAmFWKcu5aHKFmsavVzRNF9wrTwVZInCHr
sTWQvcUMZ4XJeFH9YqyKm9g1g5dmPhQlRAkrx8CofmFy8C7NVuBChxZI3JEipYqixezK4Ii6SCCLGbCF
ldvCpnhNUx8LcDFelWPAkJnYlhP+QofO0f+0oLGqncQdKf2pSGlsOxnXUqa7z2Un18OCZIuPIssBBu7A
AIODgoCBijAwNq0qZ/+9D75q6t7trhAl4KNmEnekFLdWoo4hcJU1dy4Bk7xjRXY150kPQANoYKAuDBwq
2jIm7eavWC2EyNVK4pIQOJcmJ41KJiJnMsK7xeETB16XA0eeyFMYMAXwah0S00PMXeNajxRA5GokcUkI
nOrn1H6G1ahxDhJiwbjljgGcPk4fDFSIAUu8TDPfFETORnFyXbVaG4lLQuAkd61ktcdJ7s6I94MwgYFw
DODAK3TgKEK4IlQ4Zurq/3BsLZXflsIudsiRyNVE4o61CjWl3Dpsn1eIb3wXvgsM0OwXZ49xrxoDWtV4
qVWNsW0pXBTPbc+l7Z46zBxlhptaSJxJg49dhdpbZfxOZrLC8UK+wEBCDDCYCQcTY1k1ISpVV45FDMYu
dBAx0P6sihDZNhU5pedqIHEXqeRkGjd3crq6uXy/u2eOkdNSdYn3xl9mh4HsXggiBBECA8kxkGShg2sY
q0J5e+SSpiuZxGnvW/XkMwtRxkZM/+oHv2sieXYhQ24RU/wNJAgMJMYAA5p4QCEgyQkIGE2DURPpGbti
VUROROPDT79jeJxd8HC4MO5LJXEnlmyZ3nxjFqA4uSjiag8IXBq9wf4wjlljIOuXW9gxMDYob1UYcCtW
UxC53oIH7QKwZHq1NBKnFKeimKb9h/q4JSZwirxWhV2+B3mCge0YQNExdmCgIQw4Ipci8tNPr3aLHt7u
DO0SUbmSSNyxXRxioplj06dbInAQuIb0GWIDucWBo/BgoC0MbGqwxvaQc9EjEZEHj77h0quKyp3N7FxK
IHEHjkCrZk2LRMZG3yBwOPCZ9QxfkaGvQCgZCgXFxDhPjIFXiulTkAkXlXM1WepR133D8cTf4exX7iTu
nl3Rm2Txgk+evRo4InDYcvx5gxhA6A0KfSbHCrbyxpaInHqIJVns4BNBpWoVbfIWPkxdZJ8riTt1qVOR
rRS1bxA4JnjYbzDgYwBHm7ejRT7IZ1IMpF7s4JOMH370NbdScm2fMxWZy43EnXYE2fRh0cKFVGlrN7bq
A+e1eSECh42Y1EZAGvMmjQgfAwAGwMCFCEeKhsD91Kz6lmk1rDts9C91mjUHEnfQfeMm8jYFedPYKpqn
KKe25uqed4KDzdvBIh/kMzUGcOA4cDAABoQBLUYwER5FelLVybn7iMxp8YN2ErBpVkWq9EyRn7EYXJLE
Kbp47mrepiJv/lZaq9XNk+6ZU0U1x8qC68fjmTFkDAdjYPCJCQwtzwKYYCBvDJy4zddTrZ7sk0GtZFXN
nJcOXNvWJGOiSnOTuEMRULt4wwQZ1S5kqjHTGLpopn2mno8uMQZgAAy8AQgAARgAAz4GjlwxviJnqSNy
/v2UGhQ58RZBXFpCdxoYoZuDxCny9QpxExFV3Z+ijFONk+7tVqDausIUkUt0Hp0HA5VgAEFWIkhm5kQm
EmLgwJIpQyCmJCmO/CiK5RM6RbfsBu7ntvbrrujTFCTOkLbud9GRp8eupk/ETeR2ipRznwhqTBzBte+C
vcZegwEw8AoGAASAAANgYBcGRGJMHVvqFZZ3Ra4UoRNR8nqgGQ6lfUbtwgiRNkXrjrufyN0YEieypvvo
HufXt8/edYTNfHu3iECpUqWA5yCzroGvlz79uHsNvSN6yhiAATDwGgYABaAAA2DgLgwovWp2VReZmYvI
9NOuSlvq+X1i5xOuX3327nrIb989RCBFWueItvXJrAisqxckfQpxhbyDgX0YwIHjwMEAGNiHgQNFqVxU
LtW+q2PqyESwRHj0LiJ4Il5DCJw7R9foJ7Km+yxBTv3v14IPF31TxNGmkPfJhb+ju2CgcQwAgMYBsI/l
83dmgh4GtHm7icqJDC0RqRpD/HK9VkTS1b4RfUPfsLlgIAQDkDhIHBgAA6EYeGUv0KWjWLmSs33vpQig
S+3aHR5UmxcqC85nzMBAwxhA+A0LH4eBwxyBgUO3ZZcWPig1qZTgPuLC379iUreKZOqwqVMtqsAWMwZg
AAwEYyD4AowNxhYMgAE/xWpXjJqUIGTuKzuJbH8LMltnqHpD7DBjAAbAQBQGoi7C6GB0wQAY6GHg2LXn
cGSONOtLQqe0qVbWesdF978P0SF0CAyAgbEYgMTB/sEAGEiJgWMXmRNp0YrLVhdAaMGCS5taAgd5Q9dS
6hr3Ak9suzWWBXM9MykwsBUDXWTu+Zsu+qQCfpGa2uvmFH1UuxNvKzG1C1HNG2lTHC6kCwwkx0DyG+LQ
IDVgAAx4GFDa8J7bj1WkTqnFmgidiJv61flNhG1q+RRdQBfAABiYEgOQOGYGYAAMzIWB486YXXTp1ksX
oXOErrT6OaWI+8TNElVF3ah3Q6fm0ime0zjWAEDjAJhyhsC9mYHegYGTPqFTJEupSG38nlvaVaRN0UPV
+Hmb0q8tcTvvvuUIvIN3MAAG5sYAJA4SBwbAwNIYUIROKVezG4Q7tIeoInVqWzLn1lgibCKSeq4WJvik
TVHE7j3f7t7xjIgbDntuh83zwFwfA0sbb54PgQADYMDHgBYAGFKnVa62Ga7P7TZ7pPb3PxXR02/Xalj3
d/dvf99Vt/G8/7BuccZjRQwtaSPaBlaxV2AgKwxk9TLMMphlgAEwsAUDqjEzxK77nYvcdbtEfPAKsxv5
/zy/+vWD7hb37TNO7fOwjzhsMAAGssZA1i+HQ8ehgwEwMAAD/0kcrh9hc5E6969SpO4cy/lUy4YNZAzA
ABgoFgPFvjjGF+cDBsCAxYAidEH7tloSp+uwgYwBGAADxWKg2BfH+OJ8wAAYgMSBAewAGGgZA5A4ZiBg
AAyUjgEicWC4dAzz/mA4CgNRF7XMevl2Zn1gIDsMQOJwgPgyMNAkBpr8aJxwdk4YHGKAx2AAEgd+xuCH
a8FPsRgo9sUhYhAxMAAGqIkDA9gBMNAyBiBxzEDAABgoHQNE4sBw6Rjm/cFwFAaiLmqZ9fLtzPrAQHYY
gMThAPFlYKBJDDT50Tjh7JwwOMQAj8EAJA78jMEP14KfYjFQ7ItDxCBiYAAMUBMHBrADYKBlDEDimIGA
ATBQOgaIxIHh0jHM+4PhKAxEXdQy6+XbmfWBgewwAInDAeLLwECTGGjyo3HC2TlhcIgBHoMBSBz4GYMf
rgU/xWKg2BeHiEHEwAAYoCYODGAHwEDLGIDEMQMBA2CgdAwQiQPDpWOY9wfDURiIuqhl1su3M+sDA9lh
ABKHA8SXgYEmMdDkR+OEs3PC4BADPAYDkDjwMwY/XAt+isVAsS8OEYOIgQEwQE0cGMAOgIGWMQCJYwYC
BsBA6RggEgeGS8cw7w+GozAQdVHLrJdvZ9YHBrLDACQOB4gvAwNNYqDJj8YJGyd83P1OGIvsCAk6Ge6M
IHHhYwbO2hyzg87mn2P367H7KHJ7inx4dbt+p1NiHXJ+YIAxKB0DkDgwXDqGp35/kbd7ne2/tLZ/6udx
/5l0koGeaaAzIEuH3TtcWAV2/0Di2pF/zboOiQPHNeN77LedPrtZPZbR/+xq5Wz/2HtyfSY6hyAyEcSE
JM/MwF7crp9Jey8+erE+/D8/g8TVL/eWdBsSB55bwvvQbz25Xq0fydh/dHm7PvmHJ+t7D59D4irTlaFg
4LwyBX+vU+Kn0tr7n1yvj/7+8/Ub/9tvzI90KmnkCScOc9sLSFyZ9mlunLTyvOPLm9W7jrydvvd0Y/ch
cfXZ/VZAXdt3Krp23P1ObF2bnNi5uJrq3W5W6188v1m9kBI/+Oxmffz/fLFR4h6JM1zukxerB7ZOTulW
3evU3l/PqW3s+J76ZAqJq0+m6Ol2mcru63fm2f77sv3Xt+sfdZN2k2b5/Gq1EmE7+N///RXb75G4tVKs
XXr1PV3r3Uv3PsTul+P3UJS8jZ8ja3JSF1bhXBRt67+dEptD4XN/BubIm/tXyqzf+T9/aaJ0+nn1Ept7
K5JnCZ7eQaQRYpc3ZlrUaUgcmKwN90d2Mn0u++tq2u40/vaPsul98ubsvib0zva/9fGVsfvyFdsO628U
HNCkXu9T2xhX8T1VfERF4NIMSApz8fR69b6vWCJYUjgpqJRQyqif6hwef7laO/Km885+cvla5K1P4u76
/5V2dfUTUvS+kn95u/5Y7wipw6hlonuQOBxs6b5MEbB7Lg3q235lU2SHZfc1MZfdl41+85cm2bI5XL1z
iK33z1WttO4t/+Em9/79tbK1s/1vd/9NUUBIXSY6Vzrwa3h/Ke95n7SJsElpRaakXH3F1H/7zr9erzvF
MofI27bweaxC96/TzM7N4vRu/tEp9kOr2IThM1HsTMjVXPoJiQN3c2Et1XNkK88sKdqYUxE2kTGRNb+G
2bfH//H9L9fddZuJe7/eOZXNd/fRe4jY6b38Cb2dzCtSpwxNqnHhPoFjyYAFDlgisAr0F17PHlO75iJs
dymhyJRmSf0Z2K7weWqF9u8ngql36Sk2hG4ZTLWsy5A4MFcC/h1xk400h2ynI237bLjs7acvVuvnNy+v
FXnbVu88pc3XvR2p8yfz1pcpO6OgRAmyqOYdq/mQAoAjBT73axsUIteMa5/yOqX8k/9+aWZgXbsQc4wN
n6dUdin2FkKn0LvSw+CMMZgSA5A48DUlvsbc+0A20GYrNsRNtnJXpK1vl3Xezz6/2UTe9tU7p7Tr++4l
3yUfJl/mDhuhk06SmZlBL8eAk2uHCejUr3PQ7CWEuEmJNNvy696WmoHtU2g//C4j5RZK2DYnUmoZNHDD
GKTGACQOTKXG1Nj7icBcuP6cIl4hxE22VATpm4+u1s+9kpm7FqsNtc9Tnaf3VdpVWSV3dEGLN4nOTevz
xgKV67cbT5GVe36XbCnwttq2fQqlaJt/5KzE275F79uroVPInRkaTjel7YDEgaeUeBpzr2NvW0MToVIa
dJ+d7/9ddlNZF3fIhg7N2IQ+a4rzFT30fZcNZJCVmUBPx4CVa18XiCFvrsFuirC3onDvfPrbhQSfX7/s
/zOF4k15T32Hr9R2hgaZm0CpG4x2QuLA0dL+aJMyVQYidtLubLBf++zKZ0TkYgIBU9r1fffWd8hfeVkZ
7SABmUuor0sDv5bnG/LmFipMke7UzOzjLq7uQusiiEsUte5T2n1/lxHqRReJzCVU6AYJnGwIJA4MLeVL
jl292xQdAmQva5jEu9o5twjObgd23Ki9SorVpDdrVCBn/tZWUxIrN6vpdmNYub5wIkQlhdkdydtC5uSI
RYbBJGMQigFIHJgJxczY8zdp0ynIW38yLL+iSbzfzH1KX7NvMj7m76qbc5E5m3o+wu7H+72xQG75+mN/
c+E5FUoE6O3Hv10NlKLB7xilHHOtaidczZwlw4TaccihdgUSB2ZCMRN7viaayh7s3NpqjD3cd60IUFeK
siFzpU7iXUBC24PZuj+NKZP4CD2OBXLL1x24Bo1LkycRxw+e3m5ajkzd9HGfgRnzd32LC7Xb2dkhs7P4
2VljYweJizD+jWEkhc86cyUzS7Z3EgHyd2tY2g+NsfsKSLj2JEzi4+x9CmC3dI9N6vSu/enGgDrmWreS
ye3eMOTd3G4QbvuumOdOcY2/QbOtdWoJX3xrHBmBxMWNG3gbNm5HbsWp2mfMmXW5y8Yqi6H3cQsf9L/3
9Z5z22o5u59LKQ6T+DgCp4kYSjxMiQ9yUWKBXaRNZMdtYOxvXO+InKJady1tf6Vviff/KJqnWabbPWIJ
Je+lWH9KS5J4BW8k2gKJG2bHsPfh43Tmp06nmLgOuafb11R2WfZZdtrvx6Z3HDKJ702SN5Zf99q31eOQ
9xx7jns/G/GktGYAXlHq/YN04hYuzN3aQ4orwqbIWl9hpX3qQ2f776ieQI5MPwH/z7vZ2ac6Z9eydK8O
4bj73yf22gvdz32v03A9W+8gUjgnqVP9hzVO+h8o9H6stqrPkDiwkRr7h/7Efe7WHv4+1f4k3dnk7r+9
J/Pu2X3pwB92pT7v6hxds20S75E42X39jN/Qt/q7Cbl7KFAgO7wvwjeWvPnXuwij3sGWLh00MhmNwnDU
RQ0N6LmANGc7j237keodLFnT+4jMSPn2yU7AN85NR5+Auv98x30Ou78ZcufvOKHrROqk2HMYNl+hbW85
FHq/7Pdho7a/Q+LAREpMzz5xly2VTe01RjcT9c7kapJ+Zu3+EPunticfy1b3J/EeibtrvORf9Ly3/Am9
2+c1pnlxKMnz++TZbzka4PNSYqCYexXzojML8ND1/tFMZOrok5RCIXJ/xmWJk5zTEMJ2lxw39Rw+GR1A
4rbdU6Tu3BmIuQidxt/1lrNyQaFx2j4+IXHgIZUv00TZTNynjj454uZnWaxtFWmTrR1C2HZ9t641euEm
8W5FqP1PIeMle3vmFvTpevkq2eSpx0i+0VvBejozDwgZo8XOXezBGQtDrUOeCqiaGYXOIIaeLwW+Y8P4
Mcq7S6an7ru8zYql5LEYkGLf8wld7BYzQ8dMqWUptK2XGEtuY7+b6+IxM9XYQeLyk8lUsp7qvpu656kn
7v2tCO3E9Kyzp1NMTjdpYRFTz/bHjqN8k3aneNsRRN1XvnKqYId8pUd0RXBj373K66r8qBFCFtM3s4yp
ZhiqdfAUyaVJ9dwpiFtfvnrGuVM+O1NLgQEZn1c2e5ahmkKpJRcvYsnMDIMm/ELiwMEYO3b09Hr1votY
DZ1UhpwnIuJvP2XTpLLFUxC3bWOxmcRHROJ2ja38iTo2aCstM8GeqvWKn42xtYpz+MsxmJrt2tkeNIJY
zfWOYviG8U9BPkRq3GyiW3TwTKSn+x0uNC5uqxg5v5Tj62Zpph5jqk7mkg8zs6RyS4mBJe4FiUurx0vI
cKlnqtzkUgRENjqEmA05t78zjSUgS00+/Ul86vGWT9lE56Yic66mz5Lupfxn6rEbdb9RFycmAIu9iy2Y
Nzn+1AROOX1vvzilaeVwcplFTKkEr2wInTo17c/MrPwWw08telDwd0DiIHEx+i8yNUnmpU/erI06ykTH
prT7urcJiOiYgsyJbOvoNq54MmMkMwZfs1wzy0MyAe62bz3oQsHqQ2bANmRmNfQcpU3ZTspEi17Zniz1
yiZvwYNmgbmQ49b1au7vh8RB4kIxZwicIvopV9n7qyodj1kw4xI6JinPf4XMKYKWMkAi/6roqa3zzoUc
pxy/wfcafGLGRCz2GzYELmX/t17uXv3Ncoq8xY5ViutOXR+iXb3rhhLk/nmOyFlCDpFry6EfrVY3mpGv
/+K7Xxn80/n2uqYdQIV2fYit2hC4lMRCEaLexu5TRryGfGcO52wWVuzqXRdr9119tC1PalaPcxDyEu+w
IXAp6yCUMvSK7i+IDL1WtyWCZaImmkWlJM8uxA6Ra6pWzhC4FzdPVt/6yR8MJnAiezpf10HkmsKLfE1y
AtfbYUZF/seNkuO7fPnO3nWxJE7XQeTa3HYrOYFTON6lTu1ycZT47mjQK3sRploJ7IicLR5eYnLAM+eL
Am4I3N/8+PeDCJyL2Ok6iFxTJC45gXOF9jYapAkqNmD3GLwyiU9VJ906kWsOcK4GLlUEzvUus/UPKHGY
ETuT8VNULpVCq/eeDhY7VO1Mjm5WV89eXH+xjiVwrxC57j66H0XSVWMmKYHze5fZSSOp0+G2/yh1M30R
OfmRFhc7NEXi3CrUFISht4uAWmo0m5MfOfvcKHSq1cGuRk7rVUa+W1P6UchYJSNwELmqSZuvu0kJXG8X
gbNC9CZHW3auCXeq3TEckbMN6BX1y/Gbk79T8htmPHBy6ElWofr7eVqi0AxgJpSvkY9Wi6VIr3pEDiNb
jzEzzjhFBK6/CMKkVruInD30nJZsY83feqRov4hCikUMLtLPfp7J9GOzT22K7JgItg4b6WvCL9esvK/N
xFK0EdHSZnYMSKbAffyduvSqxnlMwauu9RoC45TLJyWGwH3x/NHoFOquVawicp88fQiRKx8rzq4cKr2W
YgceEUCv7pl2RmkxstmrPIWPdrXRtvlw9Ryn+g/sLPKxi/CMnYnRZHAy8ubjsEuXmSaO67EzM7ezQ+tL
0CuIKhkCJ4L19e//TtQihqHtR3R/iNwsej617zlwdVdjI/u9zMu9CvRp6rGPuf+BK3dKsXeti5h2slLK
NuZ9irmmmBeNFMShmgFqJjaWwHlhdE3VmwjTRo55CkxtDPDYNiSt1kksKLsU8n8tij4HgXNEDyJXvtNz
hGDsRLC38pGI/vSESKQryfaX3h7lJxXZw9fsa2qDm9X9Us3EXH0VG+/OatyT7abh1UkoDZIVRnmfO+Ux
WwSuH6mDyBWtJ2ciAmNTc24CyK4As2PB6P3YfcwVuFEtpPbG7W53VKutrdmhGUY/diWqI3C0rJhdkQ02
/X1tx9TIeeF1GfiacV/LtyltNUsKdVeqtUfkqk/LVKIXctaGAIyxF24FaostKzLBQRIi52VilEGrxTa+
8h1VflQnLIVP1wqnjlFkWlXkAfpURM5b6FDtrKwSQ3WxNIHbkVrVe9VqM2v4LpVhfKzymTH7oWpRlQ4I
3OJYT0LkFMixR5UTsRoUt/8NSsM9HbukHAK3uAK/IldH5BRRiyXmMuxqCPn0evV+p9QHOOS8ZCx5XN8+
f1MG958ef3PSBQxDFzq48/Q+Ouz71Wg3i/8muxpxrSharI1ouWlspvYwCZHz6uOOM/3OaP2LvjDXgbB1
a+sxLSro+p+fcxfenGzHFCu7Fcbd/aqcleWqlwPe6yBXAreDyDEJyCsqabIvYyZ5ELg87X4n1tFETvVx
itDW2Ai4NhJ3JkUes6KR/TezVWRhdbPYYcxsu+ZZ2QCylKPOH9yurn+aYwSuH7FzETn7vhC5PIjc6OyL
c/K0I8rW/hsiN2axilvgVtsEPkeDHvtORpHHFLS6WoiWuj0X6PRN3YvSorH9n7xZWbXFrgXJ9eDm9oXp
sPv3P//TrFKou1Kuek8d9r0hcgsTOZdGjc2+uH6SRqgv+4rG+iCum3bsTK3smGhrjRP4akA3VpFVL6Vw
qy1mxTBPq4xjcXekZeNj6h69Ytd7GO3FnNbh1c2l6hOLIXCO2DkiZ9//EAwthiGRrlERGs+xK9oz1jZx
/YRj6Px8bEmNm8B3AZ9Htci6FsAZRY5l6L2Z2FEtwq38O0wNjLbCiS1i1rW2hxBOeELDuwOHR6vVjdmZ
o5QIXD8y54ic/Q7sxvwYekPOeEwz99pXLlboAw60MG1MJsari65iAl8FiRuryN5KVGZiCxjiEYZGShhd
A6l0rA56AM4efTjqasqevrh5stJ+paErRXM6X++v79D3dFCCyM1rP4z+x0ZlXPmMXTBVhS8cYUtL+v4j
1S6OaQbsTeCLz7qVJLhd7yriFd3U1xU74shnd+RJsOdWrMbWx3kEnlqYeRzw8c3q6tmL6y8m28h+bpJn
iFz3PfquzhSBo3lwdKAoemwk3nXzt7sxFO/IGyFvvs8wfj82++YIvDLxpY9dEke64CBsViXFpNRc37Aa
lx0vKJO5MWX2x42tj5MxV2ie2fgsJN4Y3poInCOMjsiZ0O7Llghz60FrzzvXQMcuZmhlX82acTi2Dt6b
wBddTlO64ptweqwiaxZnD9IgZTudkzGzMrWksQdRlOlwYAjcnBvZzx2RY7/V2YirnG70jjy1tpqombDt
+LZRrWUUxNFRehauZBJnBBgbTmd14mwGdxaMjZmVuRVLlzerdxs0hHPI56x2Ardjmy599xzj29ozlAKL
2lqr5qavjWJt1AS+hmhcycofHYWjT1iVjsXUyMT2CSQaNxkmjMOtOQLXj/j1InLF19xkRg5MFC626Ss1
sJPp+WJcYswEvoZo3GIDP9IwjIrCocj1KbLFk4n4KMoaWiNJNC49JnLfRmvqdCv7rabHlPhbbBSupmL2
kf6zVL+/671HTeBLj8aVKkzjrGNq4Zwil54HR4m3OwjtthHbN4poXDqn2zqB27Hfaqn2Npf3PhgThVOU
ntWo6XQ8Mx9kOEFMuxkXjbMThFywPvg9Bp+Yk8A6AvZYqxFDoy06XzV0dn88GYQiv5/3vlNux1LmmKXn
isbpgOAn0Yv1h59+p+gecKkidRoHe2Bvxtnc6BIar8ErdYrjZJAthsf0i/WiccXxgmwFcgdROY1l3N6q
JBmDEr+ddx4gN9c7TjOsUKJfemg9I1yvf/jR1yYhcf/lx//T+m//8Y+S/f76B783yXs6EqhxgMSNt7dj
FrJp0m9bSWFDB9jQjOxIiLxOpGfKqITafS/VXhw3CBmgLM6Vg1a6LFRIOl+KTDh9vDEtQMEPY9MubhcH
2YICvjMLndwxTpOQuP/24X90hCjZvz/7+D9D4vJ37NGTd68Tge6Rs87wbiPlow4DseU0SreXSPRLA41x
zjGpstr2S8MY3W2MbUo0qg1BqcqcGSYmIXG//M33kpE3dyPdM1XqdNt9iMSNJ07OOY+YvFez4Xlmep4b
hzDlNDHROI8jKKKX23ftfJ9iXtQO6rkEFJMmUy0cUbhygJlAiVIQ/qKUOcGYpbQHkLjvfsWQQ0jcaLuT
QpeJwhVETMbYsthoXKk10SmN9uT3Uqgzpg9YyfnuMWBu/Vql3rWllpQzZAbvlLkbv4vWx3DE9xdD4n78
y78kEpe3g4+evNsSGqJwecs3NXeITr2XuMAh9eBNeT9FRaKWEGufPFakjp4NTynbqe5tQusxfeOEGTUP
HkFipvqmUu47C4n753/7P9b/9Rd/tv769//DpERsTLqVSNw42xM7efcWshGFa4vEvSHMxHSwKBEzpTgE
vaeiIuvQqErpPWAgEeMcgJadj1RmUqpxDmASEqdFCNuOL68/W+tvf/fwT7Ijc5C4UTp8FDsRUwmNnYgd
YEdHyaAknuDe9Uy4ieklq4URdheIIr67iJeUAkoZFR0JSYvpXK+Bq4xBMd/LuyaTVbQyKxVLSjVaDpOQ
OLUXEWG763CETueOiaCluhYSF40h2euoVKo3edf12P32xkDEPWp7ttJSqqWA28zGYrox2/5AD1HkZg1Z
tDKTUh2FmUlInIiVUqdKoQ5Zqfr58/+xVs3bkoQOEhePo9hUqjd5P8T2x49/yWPnOhSEZu9KS6mWQuKi
ZmOlCaNkhcn53RUaV1QtNIrrLTlXbV0pupLLe05G4vwImRr1qnecyNq+49+e/KM5d+rmvv0IHiQuWndE
wKJqWpm8R495LvYjxXuoFCYq+GNtiUq4UrzHpPeY9OapBuDp9er9mFWppYVFE42XDJ/Ae8/+3ur+vW/T
gu6/iZQoQlWE/BO8Z5Qye6tUScmEY2UWEucTJu3ioLq4felWGWhF8eZaEAGJi7YzZ5KVGnCHTMC8ht26
vhUbJ3suu+5svAiI7L5+7r/JDso/tDIm0WVYysLYlmTZj1X2L2hBF9W8r7QCxRHKJeW8uF1dP+1HI754
/mj9q8/eXb+4/qL/p/XN7QulmWXoqlds1VSK1Ic4A51rG/+Sjg83/LOTOJ/QiaBp5eqQQ9G5VPVvNPtN
RxAUQY9ZlKRm8Pao3a7p+86sHX8F6rL3svuy//3D+gmRPPmNEjjAmHfUdwYviPR2+TjKfYzGDM5c155K
CKGrTLzecLp+rned+zmnnQJ/7JRUG21/74Ovrr/1kz/Y6ZT+6ge/u/72z/54/eDRN9afPBU3eXl093lb
w1zrWKk+Ima7Ns8haKY7t3xLft6iJM6RKZduVSp118GODXniOnbi1UAq9djaawNp2XHZc9l12fddExL5
BfkH+QnP7st/1OwjRVSDU6olRXNLcBLnEkJoBKVy53viyJtmWlLMr3//d6KiCX/z499f/9Pjb65f3DzR
SkxH5mqcwUZNBry6yhZmrSntQRYkzl8IsSvNConLksQpAlK1842YFB468iZ7Lbst+x0TRZa/kN9wkTrr
T6q0cbGTAU36u+OtCDmltKN777X3hKU/QPVw6vcTSuIqTYMdXN8+f1PIUrj873/+p1EKvE3ppdQyCjq6
cLua3Nam0IqkBe+769XF3VtaFwp7/qIkzq1gHZJS1TkxjnDoNdTERZHEM+lr6BaLJaXBAvX5xNplY6dj
J+3bMCs/4sptrH+pKuugtHxMFkZ1cV0G53GgnGbnVLM/MGJAguvhvB5BNTnew6uby/dl2BQOT6nEvmIr
5O7VUSgKWgJGBr1j7AIZpWe0hVdNYzHDtyxC4tTsd+jiBumS0qxaEDGUkMWcB4mLsiFv1ex4A/XPZKNk
l+8qlYnBprvGn8RbP1NTNsZMCEIXyJTSpmaQ8wsEXMp7HmvwldIKicRV2BriaLW6eaKxSBl926X0UmhX
N2FnZilluuS9olLzWhBRykqlBXW1L9fZSJx6wIUStzlbjUDiwkmcIiAxGRibArvISA9G2TuXeUkdfdtl
++VfdFh/o5T2qPfP5HqTmg/dftGrq886K5W7gKJC6l49XO7fN+T9DIFTDURs/UPsDM2lVysiclLG4EUy
pczIMjGYDtOTkjgRNzXxHdIfzkXc5iRuvs5B4qKIQHAGxitGP81MF4bY+dfO8QlcrA2PuU5+Rv6mJiIX
s+NTKaU0UeCaUUE0owqKwilipxnc5c3q3Rnfc6pxPHAp1LkJnFN+R+S6sawhtaoUQbBz8GZkigxPJeva
7jsJiVOt25CdGiRnEbyliBskbpSeRGVgKquHM1kD2d8YIjb2GvkbHdb/HJRu91QOE9OuRtd0x1s5f3/W
jqMLjb8XE1I36KuAdLiVSHOkUO9Sem9JetZh5SGKprRo6B68pczIhnz/jOdMQuJEyu46cthmix0bRhE4
+SSTgQmtYfKau2ft1wbooMkYqM/bWDI25nqXWrV+qPQxvacxDd2CS/yj2+3ngwEyW2x8FnvwwEEJ3sC2
opC6UWT1/xmjiCmuVY2cimptk8iiZ2WakcXs/lHLxGCg3qWwC5OQuG1RuByJG5G4UUTOONyQOuiKMjAH
srOyt1MtXgvxCfI/9ih9Aj+2lCaFTZzkHpPcNJGjEFkITn15fb1KTn1lpchSeq2KqoTItOwg5tT3WUic
2oMoOjfmx+rUUYRrCkzdb3iiZdKoU61CDSFwL3ssVjOBP9K4hi5u8FL0h4l4TXJ9SX7DhB8qEha8MtUr
Qs/52/a9myEa6sAdqnRTnu+lVbMF9AD8nWpsQ1M1CquX0DNowPfvw16qv89C4tzMYsy/9InLi8R98mL1
ILSMppK2UrKrpjPAlHY89N7eBF5+KZV9WOI+wUGhEuqhlxjIoc80JC50u62SNq7doRAmCrd0PcQ2RdeW
Lva4KFiZo3BVyeRgqO6lOK8YEseODdk55uCm3CU42wE2U3b1zq2zQglYqvPlj0ovp1FtW+jkoIQ2IymM
9VT3MNGomEJELYgYoDBTvffY+5pI0dKLGXYpv2aJtnP4QaFjbGa7oWF1SFywo5+ExA3ZgSE0KgeJC5bt
WBu37/rgiInXG/SoULukyftlblE45weUFbKH/NM++WX5d9VDh5I41VraI9soZJaDbUFiSFxocWsJS4Lv
UgKtBNIWKKlmUKnv4ymzZo2SUYm/YCfh1VqW/N1zymoSEqf+cCJyIl6pfv/1F382qb55feLmHP9Sn3U+
cpJV6nebKFxuJTS+/5Bf6vrHfadUEte990XMLiCQuHjWHkXich/wPQqg6NZivYGGEj63z15oxCOn89UQ
OmSC4IXVc/qMrN9F5GUopmo+zyNxWcsrp5cLLaPxIuU5fUbQu+Q8eZd+ej1DS83CRHGK3HcByTkSN2aF
Urahzz0k7iT32VgNzvaff/P/mobQMSQul1VjNciBb/gKJLcjBz4OXBF9KImTPj968v8xnr3xTKljXhZG
fipn7rDr3aJInLDVHfdz/eacBXE/1NFWsELJgCyH/kAplT+3e3347z+BxE1o7HOTN+9TDlkcQ+I0OUPW
08lafqnwTJfq+aI6E0DiIlh7zG4NFaxQeiv3kHoNRlIrrWInCKQIp3MSodhSf7f+xvf/9uQfzX/76x/8
Hg69QKLudgmIaQGU44r+UEznfr4tpXkr16jUnvc6FomLifKq7U2u35xtJC6mV1DpJO769tm7GKLpSUIM
iXOrlCBx08tniCPbt/2WjPWPf/mXELnCiJyrHwwpdXC7NWA7p9dNjbH8VK6EBhIXETGbSpgtkrjnV79+
gCGaxxCFRuIgcdPLZQh50zl/9/BPBheMi+wNvS/nLS9jSNzyMrhLD+Sf5Kem8vsT35dI3MQD/EpUEBKX
tzKX7PCIxJWNLe2VGnKQWi1H3pC4vGUFictvQQfp1Iyij0Ti5jFgkLh5xnkKor8tCqc6OLd36rZmwKqR
m+JduGd6HEHi0o9pSpxC4iBxg0lji5E4auLmMWCQuHnGOaXzcPfq18Jta9SrhsBfXn+2Cdbpf0/xLtwz
PY4gcenHNCVOqYmDxEHi7o78sTp1hkLsX/77j4JXp2q1nI5ct0NLaahzvpcfaVMEbte7itz5x9e//x8g
cjPo1ljsOBKndlEhixtU40o98fQEsNXVqTlv5TmYVM1ZD2efFdwnzjna7nr1g8n52+5sRkifuGmNEc1+
px3fsY78ruu11ZY77lq0INLmH2pHMuV7ce80mBrTJ079H5FDGjlsG8cK+sSZPqwx+7F3l9HsN4JUBZO4
EjarHbIEOuf982owkursHro61bWvYceG6ZzEEGwNJXG6FyRuWVkNkWf/nDEkjma/08q71R0bHnx2I1MC
iYsgcVVuVrtnHNg7NWTZ4YhztddiSLqGvVPDB3uKnnolkjj2Tg3HTmhDVu2FXPqRe6P3VvdOtbjKdivP
nFOOUfuc5b5Z7T4ye3P74u2cldmbjV103yIZlfhbh5K4s59cOh9xXug3zy2n9dQkToTOrUrd9q/v1LVC
dde5U6daPRI3twxKfJ7syvrkH54ETbKkz56zLfa7c87CyC/JP+3zYRn//a2PLm+DcFVCdq86Eqc02dXt
+p2MgbRvzFXPl20BvYqHb1fXYjSKGu77lhz/fqTxPX3vaZAye04ix2/K8Z0mJ3GpIi9aLBGT+ht6jUfi
cpRTju8UPMny9POwULt0ILv64affmRSLQzHbP89thybTWej4vhGzlafq54jExTv6Ew1eaFhdJO7zq9UH
pQJN5KhT5qc5rrT6qx/8rgO0Zss5Gv8h73QcgysvXTPkGZzTDfLUkbhUJE4RvVjnNuQ6SFywrQgmcaVv
uWjtqYlCys4OwdWc59jJ+9OCJ+9vXK/WT9/6+Cpo8l4CrnJ2NlHOtpKIidIB69xC61Jke5Q62xXezdjG
tDDIeRPkDEk1JM629IDEhZG4Zzerx6ELjyroTCDbJLu6zi0a55XQyHbmzBn2vVvw5EBpfXuIj+y7/yJ/
X+ShAwfDAFq1SCEF6F7tktJmOX/fXe9monFfPH+0zqXdiFs11o3pecHjqjHX+wdhSvjLfYVShjKZhMSp
ka8iZyl/2xoGp4xyQOLC7PDlzerdUBJXQu3SQB019imXVfDyP/JD8kclR+G6dzdBoRG1lgcD5Tc755j9
gYEDEcycvfDnSeCzchsLvf/6waNvLB5alyKrqLUCRX6jcQcxJ8YnIXEpydVc94LEhZG4MROtwuuhpZ9Z
TeDlf+xRuj891XcoYhsSFLr46IX7/jltZ9Czgk6emxSpti10RlZCIeLQcbQrgRZf5OClUbMNKQ8dU2mk
FDNEkb1UzVnAc7LWrRm+oxgSN/VuDpC4YBKntF1wU1bVOykVOwO2p9ZtEzVaui7aLWYofEWqk1VUBkb8
I+fdGoT1qcE49v5RS4K1jLiCGZmZlV3dXL4vhf6bH//+IhE5rzeQDOtYeS59/ZHGMnRlagl1ERnKJlsS
J9KmFKrbwovVqdnptSExoYvaKlih6ttHQ2Rlf+eKGPvPkb/RYf1PtqnEoXZvZAbmYuhzljhvaae67/lR
MzJFWjoSpzYY++5fwt+PVqubJy9unqzmrpNwBO769vmblYylImnBIfVKFsvMjfXsSNzfPfyTtfrFfXn9
mXFQ7mB1anZ28lCyCe3lWFEpjdFVa3dnJ3LyM/I38jsyl5XY/rU6DIRkYLT4zR5ZZ2DmNuyhzzuJmZFV
srjBHytD5DQWc2zArho4rZDSURGB03hG7QKikHolaZpQ/RtzfhYkbhdxg8RlR9xewZraQYSWPXilNOeV
EI8NkZM9nmORm0uhVkbgTGQ3dFFDKRmYMUZ6jmujZmSV1jAddrUJDwXGKRVaszCtRrJHNcZQRl1ELLRP
kGZudheQt2pxDDN9x2IkTitYf/zLv3wt4vZK+I1I3Bz2O/oZKoeJ6a6vVeRPr1cqQYl+dobXyg4buzxV
NsafuFs/I99byxiajF5oW6lSMjDZC2mM4/3ydl3yFiHbZHOgaJIAqdWiKaNyajDp0qd2FaqioNnjI+Ad
lRYIbllTSkg9YBzmkumsJM4Rt8+f/49dXO21/660qurhdO2UdUcsbIiyI8bxKroWkgLzmnLLVs6F9Tme
c2LtsrHTKRsCy4/In9hD/qWqset4wEOR+xAc6VxlYEqYEMwBvrHPeEuRkFABVFYX1x/D406hTbhMs7Pv
ffDV6FC7Cli9xQsufVqVEltjfhYzG9MiCHuIBI7FckvXT07i/voHv2f2Qw0lbqqLU5p1SuLm3xsSF6U3
mkQGp8C8urjTCvX1wNXJaWxkt2MXvCnyJr/hsi7WnxzXOGYaq9B6OK/voKKgWdvtrF/Od76h/V0851tb
RMmX2akjcwKq0qxSTIXcd9VPaAanDtzq/+OlTd3GxjUqsRkvzcZi0jOVTwam1P9JSJxWloq4/duTfxwc
cfNPnHoRwzZiCImLcoKaSEY5X1v+oIjSlPhe8t7Hrv2Um8jLnsuu74rQyR/IL8g/uHpnXWv9R42E18lH
3xa80rmkycCSQBz6bEVAgtNgXpFrzcrsxlDk66KbpalH0iuHwuRen7dX/mZrHxShOqzY4GmM9H1RDkHE
r8K0/FDdG3PeJCROUbQhh6JzqotTqlSkzx2QuHKITWwarKGJl+zamauV7uuF7L6XJt382foJ+cVqJ+3O
n8l2x2TySkrLjzHSs10bs3GtwqEqYq+o1cjQ8ZZiK/p4z/6krPfFYez/L9Im5T2onLj546VvDm4tUukC
maE4GnveJCROJGzX4RM3PyIGiSuHuPVskmxWcF1cI1mYvn7Knsuuy9bJ9mvsZPdl/50vkF+Qfxir26Vc
rzEJbu7utlksoR5OsixFGAJicF1co8pcikxne8/YVKrXqqYlw5dKLrOQOKVVRdLuWpwAiSvWaYuUBDfn
Vham2+1n1S2Kq6W/ZSqdbO0+p8JPaGsRbzGbiHD2Y5b9C9pBjBKGS6mizPkDcUJlOZIihzYOdbOxjgB+
POG7laJ/Me85C4mTbLXCVERNCx221aRB4srVf2VSYtoCeXteKhoTg1+uKXzcYifvpS1mKwWo0WFRlLl5
A6bZVHCPoNJmYxk6qtlInOTrDheZ8wkdJK5oG3ChqFpodwKvMP0sQ90oxe+W/J7Rk/fSyrCKEVJsgSLK
XLQBH4vPA83k1e8n1AlUuOvH2LEMvX4SEve3//hHg1emuho5fzEECxuKswcnMSkx6bsWJXX11GrFFIpd
zi9/zC5iJu8lLogsCaxRKVWnzKTFmjRk0ZhRc0gwMwozk5A4ly51PeJCW43o/Ln6w7nn0GJkFI7eiE2p
ehMx1daV5Ot413HyOnhxu34Wk4b3UqnFYKYksESnVD3ByKmX9M286wh5iYTF9IYjlZpERyYlcT4RE6FT
O5GhTX+1U8OcDX8hcaPxZKIqobs3uAUO2sILuz9aBiX5onvCi7JwoRmYEifvJQlGe19qtVGUMqtXzOXN
6l2UuRllNlE4EfhQRfZ6BB2Cl2i8zEbifEIXuv2WCJ1q5qaMzkHiojHk/JNJqaLLo8exKH8faXsP1JIs
poSm1Ml7aUKNVmZvM9tiwqSRIC5NppO8r2phYqJwbsN7CP9oh7EIiesTOkXcRNTuOqauk4PEjcaSdlz5
OGb/S+eY6VAwXgaF+CMThWuJ8E/iQKcUdqwyK7RONK4ZRY6OwpF6T4aRxUmcT+i0V+ouQgeJSybzKf2J
cc6h2y9qUuZ1KCCyPqI8ZUq/nujeJgo3ZvJeYup9SqWb6t7R+W4vGqeI3lTvx30XHtvYWjgZfIXhZQjA
x2j9yIrEbSN0LjoHiRst6zlsnghYVPd9F40r0UFjh4KwGc0NSp68z6F8qZ9xIGWOWXnionEsOw9SjNTy
m/p+0eF0rx2N7jH1e9Z+/2xJnCN0X//+f1grQnfXbg8pauVIp6bRpdiaaE3OvDpXymnqtG2HWpEaUwtX
egeLUh3JhYicZlihRese4z7DUacxrhmNo+kLF1M700u7aKJQqm7k8t7Zk7gUBG3IPSBxyXRJBCxq9xU3
gVcXf3Q7mTxysTWbRY8xK1JL7yWbjRACFSs6tO62U5Kz756Js66IrLiZeowieyuTNEEoVS9yem9I3He/
Yla9QuLS6ZMWHKm2ObTdiOy+1zeOCXxdNs6Qe9U+hgZ1eiU0RfKBnIx+0Ls4hx0TjXPMW7tA4LDTGdiF
x3KUIlP8nBwHkDhIXJBNH2g/oqNxTOCT6/gU8g2+p8qjYol9DSU0wQM2UNHmuO+oaJxXI3GS0TfNMW41
PuNAixliFZko3CTGHRIHiZvE1oyJxjGBn0TXJ5HzQL98T1G4mJYiNUThNEZLDv7oZ4+Jxikcb/fW00rE
IsOoA0E+epwLeM65FPnkH55Eh9N1vcosC/jWUuQJiYPETYXVUdE4JvDVELkjGe3YxQzyF/YQEZwKq5Pf
d/IHTDw4o6JxzMrKBa6HK0VSo1YraybmhdNFBEvXh5zeHxIHiZsMj2oX8vnVahVTG+cm8LYumolbmXbP
ZF+EgZiSKrci1baTKjqIM5mSzegQL+TEY4rZe0vPT2d85xrGPYdv2DR3jDHm1MhMSlohcZC4KW2EicbF
FrOrabAOesdNagMmk7/LwsVmX7xFLsX7/ckGeUZCNKqthJy/WlKox0z3zgrP1jAmTXxDN4v66RgC77Wb
KTqcnilmIXGQuEntkHPkMbs4aALnNX9H/8vyeyJe0QS+tnYzkyrZjM5FSmiWkMcsMZYRUFj26fXq/e42
RYdWZxzzpbFjIrCxMqfx8+STFUgcJG5qG3GolGhsTZQrbLd1USrLmPp9uf/4MVagxQReYrMvXicCRXOL
l0nxH+CEMGaZsZTZRWUIrxcB6lEzsV5j3yoUOUNjBImDxM3hX0ZN4Hv1cWRi8iY1Bzer9RN1IYitg6ux
Dn4OJZvrGaZGImY7Lhe988LrivLM9d48J2ysjZzHzMScItt0DOMfNv5DxwsSB4kbipVR52kXhtj2QrL9
LhOjQnkyMdn6PS1k0G4b0fXvNS1m8PnJKOXJkOicS8ixxY69CI2iPbWNT+nfc6TaxTEGm9Yys2EaEgeJ
m8vejJ7Au3YTts72ANs/m50YhBGbIYvuB1fzIsZBA1gQoEc1fZWg3UIHWycBkcuHyB4plK7axdhC5h5J
PykI1yXqKSQOEjcnbs0EPrbpKyU1eZE23za7BSzKlMXUvPutpGosl5pTyeZ61uhZGUQuO4VOQuDcbJs0
6izyhcRB4uay+XrOgRamjekb5q9YxUbMYiP24sMRuNhWMi4wU3Nj/72DWGi0wszKYlcuEpHLQ4Et9pIQ
OBXCKg1L3ctssoXEQeLm9i9Hrl42NmLjR+shcrPZiq04SUHgJE/VydujyuzL3Eo22/NcEeSY1BsRuWWV
uFO8JATONfW1iixDPxsOG37W+ovnj9a/+uzd2X5/YUnTkH/nfC+Ngz3A3fS6d6ax1tZaELly7VwqAuc1
9VVgp0r9q/KjrLBMDyGFUWP7yRCRWxT0R9oSZWwNXK8OTga+Zsxn823Xt8/efX716wdz/K5vnz+W4x5C
3tw5Ol/XzfF+eobGA+zNo3vdBP5tyXfMAjffbrDYYR65Wf1Q8/53JL8xKVS36lj3sQGdbGxjajtQ7YfZ
gVL4NHqDXDeT60XkqmX0qcE14n6nbhXqmEiqX6xMamRWQzy3XbkXQ+K6a3Td3O/K86Yf882+mmPth4vk
WCJwAF4m1ZdNG5Exixhc8EXlM3Zv1MOa5daCQTEGfmx4XUTO5dYtIUChpzHGRl7qAzfWALv9ETHAkxre
HGwIJG4aXcxBtrHvYNoRjekn6SbxrhG8Vsd3polyjGmwZkpnZPvHrDDekj07rpnA6dtiFaSo61x4fSw4
/BC7JQZVM/yZwa9ZmEmDaBudMSlwF0rXTMwaBuQ0jeHNxQ5A4uqWbyzOTt2EcEx9nGtRIXti99jWfWPf
ieteHzsjJ42vGrGPlZW3kKEJObUCqE2YdmydhJ+is6HaExR6tEE7sqtGR0dM/SXl1uAyc67f4UDi6pdx
rK86S1Ff5SaGiuzZ46L7l2zMONwduAUMGtfYrbR80uftiyr5xGKmqOuKetmRQklWJ+EUWosm7HGOQkcr
jHHAWsCQgmD36hch2G0YMkhcG3KO9Vdy6KML5d0E0REFm41hkhiHvc3EXeM5NvMi2ahkSkdr9c+xSlHq
dclaVjiFdqFbFDqYxGn1sFmFpPRpilkYLWGCZVCqHvffGxIX50hrkf/e73ARn7G10X6dnCaedhKvaN/e
d+CczRglnbj72bEad2TYh5sWgbfZf3Ns4fwOhRZACbPfbdSMEusYuwppxwri033A5+9VOR1IHCRiry9L
sf+mn7rTxNOlVy9vVmohQ1TubhwedyVIpmliqol7r7zppy363r3Ar9TZJSdyUmgBU4et7yKV97pCv6LE
qUg0EbiqCFmMTYLEQeKG4ObA9nwbvQLSJ3OaiHpROSbxr2Px0EVCtXhhzE5K/UUPbuVwy738hgC/1nOS
EzkBTHVdrlbOzvyYna3Xm9SplDjFKmEicM0TN98uQeIgcUP91IbIjW0m24/KuUm8XfBGNuBlRuqeXWBm
ahJT1L65cRd51tEygVOQbSjwaz1vUyOXYmmzTywcwLxCy8NKo5p3YWMzA3Op05RKrEiet1oMo9muI4fE
tSv7GN+0aWeUksj1J/E2ddiiXTLkzZJZk6FK6V/9Vl82UNJ0+VKMAtR2TbImg/1Qr1Ks3pJn8ZiL7jcl
mcsl6nfkwufmo7sZWIqFC/74isApqmePFg1lbXo45nsgcZC4YPz4+3OmnFzKTill6OzTDGQuF7v/CnlT
Rio1eZOcnE9tbRXqriBQMPArjSYdPL1evZ+y0L4favfJnG1qezzBWOoTzhcs7jy1Bb6GW01B3lwhq2pQ
7EwvFwOGLi1HJCBxy4196bjXxNpE9FMTOd1PGRlH5myt9NkE9vm+7Y4whU8ZIl8FJi5c2lRjmbJkZkfp
jOQ25N2qP6f6DwwQ9Csb76ZWaAHRReZcEewESu1qBJ52/2Ou6JRI1LkLnctgyXCljrz16yAs6YbAYchk
wyBx4GCML5OtNGQr1WKrbQX4rlbakh2RkFT2675LScw4iVfU7dSSR/N4tdtKHXlz40jmZTdhHQP8Wq/d
zMymIiIiiAq3e82CtaJVW07JmEg5YsfWKFJvYYVmSbH323WdjM89F72UAqvuYYrZlz8Lcz35qINILs/U
+Jj7fpC49Do+twyXft5xZ1cuNcGe0o6J5HjbQrlOBucjCd19Rb/cfSdcWOGIm9keUYd8zZSTdpea1rPs
dx1P4M+Wxt6o54+6uOLBNDOzVLsI9Gdl/doupR29+q61TUmeRSj2pu+av7DCRirGkEMRQY3JRVeH8Ngp
sAyHyOhUZNeNkwyfR3jlsMEtY+BjABIHHlLYBO0i8FD2LfVKym310rKd3sIsn9CdBNq4+5pE6xm+rUzU
HUGk6Z4fcZOv0vik2GHnLt+oYEevmf4UAYkUuFn0Hos+PBCoc7/rK/t5TpFe7QNYSqGO4n6ETrMPG6WT
o5JC3UXGXmmeG9m7Tvc3itsnbS7iNgdx27KMXCniUOM2N2Z43jJkAhK3zLjXiPdX9vOcKr3ar5nuEzrZ
WjuZP7d27y4CsyFxfbtpJ9zSjyGTeNl9TdbP/dpm3UM+Sb5pauK2Y+KuMagRa0m+KclNKh7gzVJ0zZjm
UGi/BkCKrZmIH6WTQikaZmdZUk5H7qSAW3dAkOK5e3STKHUW/0N7nbv+/icvVg9chM39q2s0w1NUb6pa
h10zMb99iP1WZmEYsl32ChIHNlL7slOlV2ULUzanvSvypL8pWOAm836UzrPJ72lybe23CJfs/gMXidvV
u64z5Z925/25Psez/W+JrPnZFfccPVukTanlqTMt/THx+r8xcR+g16mBX+v9NgotgM0RldsWfpdy6/ki
dtsUfBeJc8bhP//yRZ+nmf9f95IRkNI6wja34vrf65TYGlEZnVpxxXelkS0kLs04gsdXx/HQ7fAg+zjn
JN63h5pAi0gqhan36E/qZcO3kTh3jz/60dOt17hJuvyJbK4I21LfuCMVPCR62Dxmmx+AAIKw2XVgiv43
+2Zou/4uQikl109KuC9iJiX9+ZPb9fObl3xuSePU/ya9uyOnRN8grgG6CYmDxE3pywy+7pokx9rvMdc5
u6/J/b7FGPIT/2tHAju7ao7U21+N+Q6/99uEizKmxMei91704QFGOqf3PHXtNDSDWTJiNUZx/uxnz1RI
u+6Wu5tj6kLeu97Vb4psx5boG045ROchceAlBC8x52Y5iQ/1Aa5MpbOzmyzMvol/6DNCzvebItvab6Jv
gbocA2aueVkkei4t0ArWpVKsIcqy7VzNgL756GpD5D6/fvktY+879HrXDNPbPFq1HihxoBIXOhlKaUcg
cWAmJZ7uutdmEp9TFmOozXXniTw9v1mpbYc55g5I+KtoF25UPBduJnvOZDduxLEc2bRfVuHpUIWWQj3+
crUhc1Oni/udzBMthQfL7TpySFy7sl9C7zXR3KRYp9qZJtSOh54vO/xmr0566oCEfI3Irw5Sp2lKZpZQ
gBqfeWz3xzNLsVWfsMTih1Al3rYqqFuppO2szCFlS5ku7pM3u4z9uBHCXyPuc/kmSBwkbgksHqoS5aW1
nG6bwbF2fd/1Ilbvd3XSzu47H7bvupC/byFv0lmyLgn0dgng1/xMhdofSaHd9lOlkTmRtnc+fTlTcodW
rY75Dt1T93BpU0veTiBvaWZijCPbboGBRXXp0G7GviFzS9aZhZCrfleAzjavXJ20JvFjv0MBDdf31Ebe
IG8JiJuv7zUTqiW/7bWN4Jdcuh2q1CJs7/7mZjMzEyHdt/pp2zO0asrfYsamTYm8JVZiHDgkDgwsSuKc
r3klMjfVRvCh9jzkfNl5/1CqOOR6nesm7a4Viu1Dd0bkbRqMLkl0Wnj2sT9Dc9tUjYlqhSpU6Plu1Wps
FE5k1d91wvZ6U8pBBq4FmfON88uZdOr8Yw7Od4+5qZlzTXRFZmQTc57IK+L2s89vNnXRoVE4+TQRQL9/
qZ20n2L3p/V7KOI8xk8ERvvPfezIkSJUOdXO6V0+ffHb1Uoh9XB94qZvtClTKTB1D/NgrGVdhsSBsVzx
f2pbZxjT77avyoXQKWqmDgWuHi4k66Jr5Tf8bIv1cedM2qclbqRTlzV4SideuC1dpNgiTFryvYRiuwa7
z22/OBmZffvjOeVVqN3f59UuFVfYnKjbshjL1aFN9V6QOPA2FbZS3Vc28czfSH7u/Uj9rEzsylT5C61g
7UXctD2Zsi0nRN3mI29urFMBlPvEGVGB/tyP0GkmpJnN1KROhFF1b66I1S3E2JZ+9bd98UmbCKidZULc
4uSP3qQZN0hcmnEEj/OM42uEzk3m3baHU5XcuA4BXY+4TReCXT3iNFl3Wz26tiAuk/T0evW+fFf3O4K4
zU/ciMTNo6ihBlHKoJna236Uzim3aipE7ESoxrT90LWuN5C/W4O/dddd+7PaNKmcpiKKod/I+YzZFBiA
xIGrKXA1xz0PbATrwp/Mu9Sr29dUZGpspkb+oyNfm4m7omm6r2y/I2u79me1pE3RtlMyLXn5vTlAyjPi
DKxInRTmvIuSvedmQP6/iopphqSfiJebxe3anUFEUIcjb9vu6f6binJtYaocpN6DGVecHMH/9OMGiZt+
jMHxPGPsSN092V+3OMK31W7jetl92XS3ef2uRWyqW3v07Hazb+pddl9/s/5GhE0ZFk3W9U7IP9MxQDCZ
CmaH0hxapZJyyXHdl8L5it7fNsuFz7/otgeTgnb/57Pun3d1bfd7y95H93IKC1krCxPosO2e/xff/cp6
6M86MuGe8WMMcseASJTIlCbTwqxqqt/55MXqgSNkInR9EufqnXXObReA6/75ubX7sv3nnu3XvSFrhepB
7uDl/cKAZWZlTpk1A3O9etgdAWddMWGRYxtM4ET0IHHoQ0X6cN8ncTt2R8CXhvnSYsarmBetSOGmHHND
4lTf4HXJ1g4SJ4wfTqtiDEDiKnVQFWM2pR8wJE71zqpp09GVzDyzkTZF8VI+i3tlNp4IJDOBjFS4TeTN
plgVfkfGjEHtGIDEgfHaMX7X96msxkWX9e9F9zvE9rfh+1oGfo3fruJV9eyRU2MGhmOrEePbvgkSB9Zb
wfq277wv5mbbPUHeGtOFloFf47efQ97amH0xy35FzpC4xhwX+H8N/8eMSZu2v0Yiwzdh0MFAWxiAxLUl
b/QbeYMBiwEGAmUAA2CgdAxA4sBw6Rjm/cFwFAaiLiJs22bYFrkj90wxAInDAeLLwECTGGjyozN1RMgC
IwQG4jAAiYsbN/DGuIGBwjGAAAsXIISU6BgYMKuxafaLLcOfgYHmMNDcB+PwID1goDoMQOJw3vgyMNAk
Bpr8aJx4dU4cHLdtwCFxbcsf/Uf+zWKg2Q+HyEHkwEA1GIDE4cTxZWCgSQw0+dE472qcN/jFcAsDkDhw
gC0AA01ioMmPhsRB4sBAVRiAxOHA8WVgoEkMNPnROPCqHDgYxnhD4sAAdgAMNImBJj8aEgeJAwNVYQAS
hwPHl4GBJjHQ5EfjwKty4GAY4w2JAwPYATDQJAaa/GhIHCQODFSFAUgcDhxfBgaaxECTH40Dr8qBg2GM
NyQODGAHwECTGGjyoyFxkDgwUBUGIHE4cHwZGGgSA01+NA68KgcOhjHekDgwgB0AA01ioMmPhsRB4sBA
VRiAxOHA8WVgoEkMNPnROPCqHDgYxnhD4sAAdgAMNImBJj8aEgeJAwNVYQAShwPHl4GBJjHQ5EfjwKty
4GAY4/2fOp1ef+snf2B+3/vgq+sffvS1rT93js7vjgtsAbYADICBkjGAA8QBggEwkDsGDjoje9z9zuxm
9/efX/36gSViSf65vn3++Pr22bvdzc7tM/S8w5KNO+8OOQED9WMgd+PN+0EwwEB7GDiyhO0tkas+S/vk
6cP1rz57d/3g0TdMtE2RNxdh079/8+PfX//Fd7/y2u/r3/+dV8779s/+eBOt0/306x+3q+un3e8dS+xO
un9FKMEkYwAGwEAWGMjiJTCKOAUw0DQGFPE6u7l98XZHmC4dkXpx/YUhViJqIly7yNk2wjbmvzmyp+f+
0+NvrkUa/aN7T/0HRewUrcOGMgZgAAwshoHFHozxw/iDgaYxoGjbeUeIPnYE6Yvnjwxp+vuf/+n6r37w
u1ujaWPI2ZhrRexEJBX980mdJZ2qrVOUDnvKGIABMDArBmZ9GEYOIw8GmsaAIm6vEDcRIqVD54qyjSFy
/rUidSKbH376nbUihjogdE1jG18KeVsEA4s8FEeOsQMDTWHg1C4aMGTHEbfcom1jCJ6idIoiusNGGO91
/z+LI3Du+FkwMBkGJrsxTropJw2OMFJ9DGgBwD0tDBCxUbRKqciaiNuuxROK0Pkp125xxpvUz2EP8Ylg
YAoM4HxxvmAADKTEgCJPqhEzhxYmiNSMiXKVeq1SxH50zkYjWQyBvqXUN+7VOJ4AQOMAmGJmwD2bnHG+
Qt5EXtTuo1QClvK9VT+nla6udg4y16R+4GvxtZNgYJKb4sQxUmCgGQwobbqJvIm81Z4yjSV4fTJn+88R
mcO544fBQDQGoi/ESTfjpMEIBmYXBlTzZvq6aZUm5O31BsO76uZMZO7myUpjZ2vmWACBnmFrwUAwBoIv
gLxB3sBA8xg47sjbI1fzRtp0GHnrEzpF5lzNnCXD99Ct5nULnwyRC8JA0MkYGAwMGGgaAwfaVcGtNm11
wUJsOnXXdVoA4bb8srtBkGLFkeObwcAgDAw6CcfdtOMGIxgTYeDEtQtRqxBFkVKTmZD7KXWrCKCIpFKT
+rn9T4f8qwiYu+6u/VZD3mnsuWp67BY/dON93v1Ub4j+MQZgAAzsxADgABxgAAzchYFN9E3bYi2ROlWk
SgRHxGvbJvWunYl6sw0hcHfdQ9+o+j4RPH3r3GRVz9PzdVzdXL7f/XMEkYPIggEwsAsDOHAcOBgAA7sw
cOT2Np0z+uZIm7+llSNqtj2HolRn3U9pR5Ec1ZIFRQbt/XSdFhToPqe6j1aMdgsNHrvn6V+RQ33/nARW
EUa38MF+K3qKnoIBMPAaBgAFoAADYGAbBkSSTHpPW0qNTRXuu17ETURJkbDfEjZDpi4swborIjWGxO3C
v1KZJ93v3EbEzGtpPEQuRbKmjtIpZex2frC1iHon9JUxAANgYIMBwAAYwAAY8DFwYFteGAIxZdsQ3btP
3GxhvwjkXaStj9kpSFz/GSJQitZduLYqipTN0dRYY6TDRkVDxgXdRrfBQOUYQMCVC5iZO5GLAAwcWhJl
6s/2Rc9i/67Inl+X5hG3w4B39W3XHCSubytPHNkVwVIEUXV7U0XnNGYijTerq2eWTGK7sd1gAAy8AQgA
ARgAA8LA0Wp180SEZKrWIbqvS5faaNZ597hY4rY0iXPPV4TuzPXNc9G5KSKYSjm79Cp1ckzOIic82PvK
7D0CrUygKDbGPQIDp4rwqN5LRCE2wrbrOn/fUEt2lJYU+Ullf5aIxG17dzVBfsfV9E2xBZkifR6Ru0g4
hqlkwX3S4ZqxZCz3YmDvCRiJZI6GsUYhc8SACJWJkKUmcL3Im1Ys6FlTjEEuJM5926Gfap1iZa/b6cE+
Z4ox5Z7TYJVxZVyTYiDpzSYy0LwjoAcD02DAEDhFdlLWcqkVh4sWeZG3KWWYG4nbkDkXmVOUUzVzKaOc
3pZdiv6ljGxOKSvuPY0uM66NjiuCb1TwEO5JIkIl6VNyAtfbC/TpjHVbuZI4h4djt2BE5DZlvzm3crUj
iz+FyDWv0yXZH941EfdgIBMNJKQIA1oQBpITOLN6sos22eNiZkKRO4lzdlYLIC41RilTrEpb64DIYYMK
skFwj0Tcg4FMNJAoDwa0EAwkJXD+NlG2j9nxAuNQComTvX1lG7NUdYiOyNmmwNh17DoYaAQDCLoRQS/g
WMFWfthKSuCUFsxkw/aSSJzTi5MucqaUs9mnNUWtHIsdmEhi59vDAI42P0eLTJDJFBg4SrmIQcTDpvBE
RJaIvvljVCKJ0/sfuoUPan6cYnGJI3LdvZXSngJH3JNxBQMZYQBhZCQMjC5OZyIMHKkWS1GzsU1o/fSp
JSAHE71ziG0qlcS5bzTvn6rNi0fkFHkNGUfOZbzAQGEYQGCFCQyjjFMKxMCBNnDXTgJj6696jWbPA99j
SltTOonT2Ci9eik5aZHImPRqT05LR0mnlDv3xn81j4HmByAjR4QsMEjJMeDSdWO30hIB9Orfcovw1EDi
JPsjuzhk9NZnInKSl10Ne4SdY/IHBurEQHKnAVDqBApyLVKuipaNLpw3BK6LEFlCkGNkpxYSJ3t8YFuF
mDYkYyJyTm62R10OaW/8DRNVMJAYAwxo4gGF7BRJdmrUgxMRuA8//c4oImBWoHYEbrW6eaJIUab4ronE
OSJn9mBVfdsYIudaj7A9F3YpU92t0fbO+k2zPgwQYUjAwCwY0KrHpyqUH7Pi0RGAzAmcbFhtJM7YZbf/
6lgix0KHWXQOX0pAZBEMLPJQHDlGBQxMhwFXBzdmIYNLxRVA4KolcamInFvoYNPhh+jedLrH2DK2c2MA
EsfsAQzUhYGzsXVwhRG4qkmcT+S+98FXo1OrkqkOW2+Hztel88izYXki/IaFP/eMgedNPktVzdpam6zH
1lG5Vah2N4Fca+D6dqvKdKqvL26xw5hVxiKB9tB4YfsZAzBQAQYQYgVCxCDjkIQBpVG1CCG2oa9Lu92s
rp5lvIhhm82qnsR18tCeqw9FwrTYJJaka2cIe5BWxfbj/yvAAEKsQIiQOEhch4HRaVTPwZ8WhqkWSJxs
9YFqFMc0bhbBt2lVrX7F/jMGYKBwDCDAwgWIIcYRybmraH1MGlU9yQpOtbVC4mSvjxQplaxjVx67fW+7
e5VG1vFX+Csw0MMAA4JSgIHyMXAxJs2mbZ50dOm6twudFLRE4qSvIl+jesip/YytezwoVObYrfLtFjJM
IEMGMcEgYgSJhi2IgeMxDl3pNaXn7HZPpTr01kic7LYh7rELHVRXV3DkFb+F3wIDFgMMBMoABgrGwNjF
DErL2eNoQSI6FoMtkjiz0GFMfRyLHJh8FqzzY21GNddX8yGAEYPUIAZMFE41TjGrFb3aqLPCx65FEmfq
4yT/2FpI1zvORvXwBQVP5grXX7A3AnsM3ojBQ3EgjktiwERirr+IKnD3mr/WsEqxVRIn+y0CHk3kvS25
DpfEMs/GloKBOAxA4iBxYKBMDJyOcd5KpVW0DVPLJG5Uf0DXcsTu04otKNMWILeG5YbwGxY+M5+4mU8O
4zYmCldh5/6mSZxLq4qYx6TVicaVawdysEW8w7L4gcRB4sBAeRiIroVTbzGlYLso3KOKjG/rJE46bMZA
7WJCiZyLxlEbt6wzrkgf8Skz+hQGe8bBRkkxkikwYFakRtbCeU19RQRr0X9I3MuGz0/V/y2UxOl8Lxp3
UBEuasE331GPrUouy+Q3xABU4xjBRp6GQwXoa5GxUGdd8ZZLkLiXWDV1kkqXh2KDvnHYbXx3mRjAUefp
qJELctmFgQs56phN7iuufYLEWX1Rmjw2SmsXuzzFmZfpzJFbm3KDLEAWwEA5GDjQvpkffvqd4EhL5XVP
kLjfYvgkdtWydn+whyJ62AXGAAwUgAGEVICQMKg4FIsBky6LKV6vOAq3KeoPSSFasiLyV50NdCuXQ8bD
nasoXsF76FYnyxrxyTeltTmAvkIjjpKkVZJcxlPOOaZwvYFeYETiXrVjhuzH7KvqLXxR7SX+gTEAA5lj
AAFlLiAMKY7EYiB6QYPnmI8qxRMkrmfHOsL/cQzh97biOqsUK/g8fF5VGKjqYzA6EJ6KMSCnupaTDU2T
2b5wNWyvtcteQeJed8zRqXeRP0V9K9Yl/B5ErhoMVPMhGBwIXM0YiE2lNlKsDol73SlHL4IhpYotrdmW
1vZtkDhmJGAgfwxEp1LVNqLbF/NxbYar9z2QuO0YvlD0NrQdDSlVSFzl9qIqn1fVxwA8jE+lGIhKpXpt
Rc4rHRdnvyBx20mcaiCjmv+SUsWWVm4zquE+1XwIgMPo1IoBtXyIKVL3NrpXJK9mXYfE7ZCvFjh88vRh
cB2ll1I9qBw7NesF31a33TPyRcgNCBkjXDyBMXtbhi5okPNupEAdErfbjikKG5xSVS9Ce5xgP4q3H/j5
iv08wq1YuBjfKozvsZxpaM8vL5WqVGzNei6ScV9jFEJyLUER+at5bPRt0SlVO0aqq6t9jPg+ZFwsBop9
cQwLhrURDJgo09e//ztBJMVLpcqJ16bnSg+fd/uEXrpwUehWZLrOXi+SUnW6OTalqkUxurZC/NSmD3xP
fTZusEwHn4giV+cIkX0Bin99++zdmJqmSh3wQWeHDKnVoW8MjVC6aJ3ShSJ+3qG0o+5fo17o24InAj/8
6GtueGodlxplzTfVqcM75YrAGxN4pU6qZhxH1cNVmAo7tlEhQ96+9ZM/CIpM7kq1Ku3syFwXmXvajdtJ
hTqibwrec1djbI8ax6Rmm8G3NeTXEXZDwq7QOdWOX6VCX4s2Kfp0V3q1Qudrom/aeUIRtJDat6Hnasy0
AtgeilzVhq21VpwOHQ+dJ4zZQ+Nf23jwPci0CgxU8REYGAxspRg4lRP1t9qSYxWZucshV5YGu9AYKPoW
WhcYQlgcaXFRua5B8ps1YSo2LS9i20Uoa96yDR8ImSsaA0W/fE1Glm+BiG7BgKll8smI179rZ9uIWnZp
sEQqKp0cSuD889XORUdlRM5EM0PHRaTWppnxFZAdMJAhBhBKhkKB0EHohAFFQPxFDW47pNvVjSEZImvb
nLIidd2hCFbJ+m0IbEx/vFCisu18R+QqGEeHAVMXF1pLWFlUt2R94N3LtmeTyW+yGxfuQBgXFGZxDGjP
U791hkibjsdf/Hfz7zanXEl/OEM4dpHUFCRtyD08Iqe09uJ4GPkOhxpTtZ4Z8u3+Kl4LteORzy99/Hj/
8nWgShlW+VEYm+IdDrh8aTDXioTIoboO+t0KTVMb9i+f/6hLc92YYnzfKXuLGkp1ugdK3+m7pq6B20dm
9HxFQm0/OZGg0nEZHNl00d/u22sgsqXLj/cvXweTyzD5DSswdIwJipIDBo5E4lwftJcbkn+5vv+LPzek
TRG369svVz7R038vPf3l6uBC0377CFns3x2J0f61pds2LW6IiW7aSNy90r+f9y9+EpKDXc7uHbJ7IRQN
RQMDBgOKpJkaJkfMnl/95pWom/777epq/eLmycpFrbwUYIm6bVJ+S9XB7SJ63mKSUqObDgsXqpcMJbSV
1FiWqA+8MwGFvRjYewIOFVIFBhbBwJkIjSJBcqKKwm3bneDyxScmUOKIjyItz69+/aBEmbkonKKMoURj
yvNNW5eOKFfQakPRtOCxFaYq+HZ8HYSoSgxU+VElOjDeeRGilDP+jcN1kbVPu9qsbURFkbqbLhrnCJ9q
uLrjfoF4yjIK58bci8bpPXPGzV3vduqiuyGkt+SJQcGyKhVjvPfM9oEBn3nAMSrFOsC5dcWQOB0iaXfV
iH3wybdNWtWtXu0u0bVzv+/Y520ijyEEY65zvVW/5wWOrZON0sHBbUY8AjtWxlxfnl4is8xlhoAyF1DB
DgNsjcOWomlKY5mWIneRFaX7tGrVO4ojcSq676+0nYugDX2OopxXN5fvF6CTRzYaKwz5vwfCSOjWZd5i
mf79isNZAbLDbo6zm82NX3MfjBIXF6FpFaOGxOnwt93aRTj+4cP/xdTN2aNE5xq8t+dQ8pXqvJJW/nak
3uTVRTwVofV/22or7xojne9fbxc66PaK7LWqn3w3ss8CA1m8BIYAQwgGXsVAF4H7kVKkISs1n3z5K0fi
/rCw8TRpvtAIUSpyNvQ+hfXgM2PqN4se+p13nefSyjW0XClMR/DVkMatGAAYAAMMZImB1WdywiErNX+7
Lde1tnYoSa5nQyOOKYhI7D2Uti4s0nmu903Zc89rYXNYGMZK0gfetSz7tai8Fn04RqAoRwtW5jMsJoqi
gvJQwvH+v37LEY2SUl1K/wZ/a+jYpDi/MBK32f0ixbd7kcgLbDe2GwzkgQEc83yOmbFmrAdhQEX+fgPf
EAdsepqZvnIvPu6M7EEhhrYYEqfFF92hesVBsszgvFO9sNu+LQRL/XNVF9etlH7W3Y4oXDnyLwWnvGck
phi4yIHLwDgjuzpldzLW6bp9Vrv7iByVgJNiSJxt41ISiXvDNuoNSs33CZwXhSsFUyXgnncswz5lLaes
X64QB8QYoojJMNA53EcpNn/3esaVEDWBxE2rQ0eaGMTsm+rInFa5dth8WlB0N5lO4oeKmAg2K+9mPxzF
RDEzxIBJfYW2gNiWInOrCAvZLqkYEmdr4s4zxM4+W27GOGYFsPBYWC3gvrHg79NOGhjfGceXwZ5xsAs0
/OBjPnwcdHuHPk7Z8NbrayZymLMsDcFQPd+Ymq05ri2YzBzc3F59GhPl1TVdD0J1k84ZQ7wb8mkSA01+
NMYIY5whBqIjJXeRFzngAtJgxyJHKVthTEHovLqw3EnxLrv+5xrnkFXP3/vgqy4K9/MMdQb/BXFrHgPN
DwCGCUKXAQbUCuJSq0oVPXO/UFKj8/3r9b/V7LWAFKDq9pKsoJyCvLl7eoRGNWYl2s4zbeOmY8guIG6l
8+3qRpfcL/SbS5QT71ymfi0it0UeijEo0gGAlekMi2qsXjtC20J4JGPb7fTfsiUfaokypvB+SvLm7i1C
LLJdsP0y0V4RuSFj7aXjIXHT6T52lbEdhYFRFxdszPhuFCd3DARHpgrbFqo//obI5loX5+3WcFGw3TMk
riPMhuSL9O8iv70onE6XfHLXGd4PGTWHgeY+GEOEIS4BA1rkELrvZeEkTlHCO4nFHNG2Xc/wVmielICf
He/4lmok9S1KkSp9v4s0u+21Pnv+kYvqigDiLxgDMJAZBhBIZgLBUOIohIHOwb43JOXlk44C9/Z8xf64
HnlLkrVdzxb5EbEuWT+1E4jDlCNnImv9b95scr+6Mi1J7AGJw1fAFzLEAELJUCglOwrePRkJva8Gq6GE
pnCHe5pjNM6Lwun9irWZWqXsoruK2nZbaBm49BfQuCjcL3/zPfM3exyX/O28e7m4RXZ3y65Yg4RgUcrK
MWDql0JJnO2s/06pY6No3F1pvtDxGHu+opsv+6SZvWhLt5ev1Fl+9Ov/26RV/cmCR9rMNl1eJA4SV778
S8cv778FgwwKigkG8sSAIXFypCFEROmywtN+IgumNUrId091rotKda9Uci2cdNyMq78biEub6r+7ldDC
z20XofvxL//SjL+3QvWgAhKLrcvT1iGXEXJh8EYMHkat+MhEzvg3Tje0V5zndHP+tn3vdt4nHFORtLvu
69KoXRTu7Qp03aSq+/3hhJduN4b1i5snK+97NwsePBK7T2b8HV8CBhbAAIO+wKBX4BDAzfS4OZTTvasN
xDYCUkn6q9si6sVDfX/MXp8pCJ/Ijo6rm8v3u39qiEIZYtwfG6WLn774V/OtOpRevf+LP9+cp8icFtlg
s5iwgoE8MYAznt4ZM8aMcSwGgrZIkoP2UmRnhRvdg9Xq5okiRKHRyLEkTgROz9XzuzE8KnwcDfa0MnXX
Qhlv4cZaq1b98VN9Yndc1DAGfEOeJAS5jJNLrHPhOogJGJgYAzFtRuSAreN9qwLjeGSJ1Cu1XGNJ2r4U
am0EzuLgzgnBv3z+IxOJ8wlzRRMCbNXEtqoCW1MsRop9cUAzjr0zfkWMnyIgwQX+dnuop5XI+NCmNNeq
z5pqRwfdVxvD67ArUauIwFkMmPpKf1FDn8iKvPV7xlWSmsfHQeCqxkDVH1eJE0NG7RqhrcXo+yJRFWzU
3se8auS0uMC0+0hdJycCo/taAqfn1FAD54/hPX1b6ErnShbJYD/btZ9NyL6Jj4TMFRF1AouvG1tFg4IX
N7ii/O7S0uvi+pg4UcNajYkK7u+KLO0juvq7yKDuo8PeV6S5OhxqkUhM42iNjY2CVjcmNcqZb6pPd4fI
FOWs0GgPETznlKHwHbm43LY10j6SoshSd22xTX/vwKeiZPccmVP9n8ZHhGxfqlV/13lKm7rIm72PIlW1
Rd+cbdd3BS+QEb7soZQ+foIxAAOZYgDBZCoYDCeOQxhQGlGEYx9p6//d6+9VKzmR7Tp1aVbHOETqFEHq
/+xiD3eaVp9+R9dXTN6cbTcp+dAUtLdzQ5XRSewr9rUWDEDiIHFgIG8MKCX6WpPWfaTOK0pvwQmLqB4r
Qtf93lI7jedXv37gfvr/9d/t308aIG4bnRbJFYHdh5f+3716uMNanB3fAXGrEQM48LwdOPJBPkcicaFN
f12rkUp2G0AP4vTApFJj0vGqoaMeDtJTI+mp7ZswjnHGkXFj3GbDgPZCVXowNJrSSEp1NjkUaPyjUqle
f7jzAr8ZPGCbm8JAUx+LQWJmWSgGLhRR2Ve43yd5Fa9SxW4NcNRalRpTT+nt4KAoMGPNGICBjDGAcDIW
DgYUB2IxoDquqJYadpWqmqCh622NgUnDq7YtNIJrm0Vfghl0BgzkjwEMe1uGHXkXKm+1GpFzDXXIXuNf
Ff4j/3bGwERvQxv8KtprD10PXhgDMJA5BhBQ5gLCkOJILAaiUqpyytoLlAUOTeHo4GZ19SyG9HupVEg/
vgF+UAAGEFIBQoLINeWAd+mknGrUKlVvgcMhWGoCS/eEFX8z+6ERXK1KtXvH4hvwDWCgAAwgpAKEhONt
wvHu1UU515jtk7zVhqTI6tf3A+1CEbOamVWp2Bl8TXkY2Os4EGp5QkVm1crMRFi06nRoZMWdRzSuWkz0
bbjBSMy+stqOzB5EbOsn+/j+SmSMICsRJMStCSct5xrVvJVoXBP4MFG4mLYirjl0pfvt4ufwc9VioNoP
g9Q04bSaw2/X+PdNEbnQnnFy0kTjqteJ6Fo4b0HDKbazepw0ZzdrxjTCZIYCBsrCgFngENP/y0XjiLZU
6aQPtSI1phZOBF/RO+0MUrOz49uqxH3z/qv5AUCxUezSMKBO/DGbmstZexubn5T23bzvbl11EdqYFam6
xh5njDH2EAyUhQFIXFlRGOSFvIQBpbyiitdN37jrL1wbiQMMdlkGe4e8THQ2ZqN7EXtF71RL190CPGBf
8DGFYQCBFSYwnG4VTne03nVO91FsAfu3f/bHLvKiGqrR78I9lh1DYUHEPKZO0ovCgQV0AVtQIAYQWoFC
w2ku6zQzGf/oaJyLvlgmd5TJ92CL4myRWcwQ01KEKBx2BN0vHwMYzjjDybgxbotjYEwERosc7HZcD0mj
FWvIRcBNOjS0b6DOJwpXrNwXtz2Qv3ywAxggI2CgXAxocULUSlU5ca+txDlGOR+jPFAWB9rBQ0Q8dJN7
R/iUjqcWrji5Y6/LtdeTyG6Smw40QjwbMIKBkRhQu5AxjlybpNtDhBB5FDIGbjWq6htjonDf++CrTu5K
yyN3xgAMFIoBBFeo4DC8OB6LAZNSExmLceYqhvciMofgqghcmXrI2NWo3gplpdLxAYwBGCgYAwivYOFh
gHFAFgMXcuoxPcJE/LQXqw71n6M+LntMGdL+ydOHUatRezt3HGNDspc3PhoffScGAAgAAQPlY2DUnpl+
fZxN04GJPDFxsFrdPFE7kdg6OLeYoSPsb0PgIHBgoHwMYKzzNNbIBbmEYsCk2GK243JpWG9vVRY65Ic/
LWRQpDQ64uq212IxQ/mOG/KFDB0GQh0F5+dn3JEJMjEYsHuimvRoTH2crvEWOlDwnhGunGxj+8H1tlxD
thnJFkIGIRuDAQgAygwG6sHAYefsL8fUS6noXdfbA2efATbcStQxUVaXRrVkEJ3PQK5jHDfXQvyIxKHE
GPI6MWDSqg8efSM6GgeRy8dBOAIXuxJVEbjeCuQDCEA+8kUWyGIsBnDkdTpy5NqwXG3R+jq2h5hz/ETk
lnUwKQhcL0V+MtZhcP2ymGD8Gf8+BnD2DTt7DEK1BmF0N3+I3LLYSEXgvKa+LFbB1uPvK8QAQq1QqJCz
ZR1wJuM/up8YRG4RHKldzDtKiY9JoW7p/4etx9aDgQoxgFArFGomJAJsLY8tUx83lgz0auQuwNdk5G7T
RmTMIgZHvtVPzrYTOURmk8kMO7e8nWtaBk1/PIYNw9YABkS6RvWPc6TA9ZGzkSIK5NM6ryM18pWsxrQR
2RI9PW4A4/ixtFhkPAsaT4RVkLAwxpDOGAyk6DHm+s4pQqSjWzzxcfePUrbYkPFjYCKmipzFbp3m9wX0
mjbTIma8bMA3Y5g1BrJ+ORwEDhIMJMHAwdXN5fsiCmMaATuioFWvL26erG5WV8+6W0IU4p3cgVvAoJXA
sVtp7SBwpL3j5YJfZOyKwUAxL4ozT+LMkXe7xunQ7LvZka8URE73cC1IbEsT0qth2Dqy0UxTs6i6w9hd
NvpRUva/xVbiL9vBAE49zPAyXoxXyRg4UqG70nYpiJyIh5oK67AF9Cc4j0HO455Ln47p5eeTPtXRWTlo
ZWvJGOXdkR8YCMAAgxUwWBhHnEMFGDhSGjQVkRORUB3XF88fuVq5t7v/QVRuu105dtG3X332bpL0qcbf
I3A/ZeyxURXYKHhJAC9hsAIGC+XAQFaCgeRErheVu+zG6aySsUphIw9d7ZvI89jVpzsicBA4bHkKrHKP
wnCEwAoTGI4RIpkIAy+JXKIaOUcsFJVztXJdilXhuZZTrIpI3rMLQJLVvvVr4LpxhsBhx/HljWIAwTcq
+EREAPyUjR/Tm0xELlVtliMYija5FOv17bN3O7wdN4Q5Q95sneBaqdMUNYjbVqHSs49JXUN6hb/Z4m8Y
lLKdMPJDfmMxsFklmTLN55rOqq+cUog6LJk7rdjpvELeFJFM0ffNJ29KW7s+cKxChcBVrEtj7Voz1zfz
oYAdgwcGdmJgs92TVpuObXXRv17EwydztrhfNXO1LIA46r7lwqVNFXlLHdncshPDBXjGpoEBMACJI5ID
BsCAMCAip5Wl6w8//U6SvmXbyKCfZn0ZnXv+ZqF1cyKgp92YPTRhRjtuqSNvbgyVjnURTT0X543zBgNg
QBjAgePAwQAY8DFwLkKierbUdVw+qRPZ8baHUp85rWhVdCnnhRCOuBmy68ZJUcYUuy3sioB+74OvmmfZ
GruWaguxTdgmMLAHAwwQSgIGwEAfAyciVVrwIAKROr3ar/FSdE7RP3fo2TYqqJSrUpVLYlSk6Z4fcVNE
TAR0qqibGx+lod242OcfLjwWS8qBZy+rB4x/puOPYDIVDMZ6UceNXnTkyRGXKdOr2widCJKXOjRROrsK
856N1E1F7ETYlKo8d3vNOmKpRQqqF5yauPmtWtzqXr0P9gB7AAbAwDYM4KwgcWAADNyFAZNeFamaolj/
riif0rmKBIrUeYRmE7Hr6ukeW3KnNKwInn6K3omM7fq58/Tv/e673nOtQDY37v6HFieItOmbU+xrGhLN
ZCsznDWEDQwMxQAOHAcOBsDAPgxstouaKyq3i/QoEqb0q+rQRLT086N2PhHb979FDHW9SKLuJ8I2ZR3g
PiLnb19G/zec+FAnznltY2Wf8ebvOHgwAAaEgQOb1jOkKXVPuX0EZ+jftcBAZGjXb+6o2pD39nu/2aig
UrroHWMABsDAXgzsPQFjgjEFA2DAw8Cx3U7LRLHmqhEbQoZKPEfpYhdJtIs5RJaxy4wBGAADgzAw6CSM
CkYVDICBHga0rZTagph05JQtNkokZ/veWalbV+dnF5Cohg97zBiAATAQhIGgkzEyGFkwAAY8DChqpEUF
5oDMfWVvOxZFLhXB1EHqFF3CnoKBsRiAxMH6wQAYGIuBQ7vzAmTuu9uJ3BbyptWxpE7RvbG6x/WNYwgA
NA6AsbMArmcm6WHgNTLXes2cv82YjbxB3rC5+F0wkAwDyW6EM8eZgwEwYDFw6KdZ1ShXZCbHlaH7atdi
/q76QPV6cwsW1M+uG48zIm/oBzYSDKTGACSOGQEYAANTYUDpQm1Z9bFfNzd30+AYIhZ6jQiqiKoIqzts
r7fT1Eab+0EEwAAYcBiYynhzX4gBGAADPgZO/Lo5t/9oyYROEbf+vq+WsJ53BlbRSHSAMQADYGBSDEx6
c4wYRhwMgIEeBhSdO7U90TZRK+0EoZ5pS+6YMCT6pho/7e7Qi7ip1YpW6R6Dd/AOBsDAnBiAxDFLAANg
YCkMGEInAuTvX6oonUidyJJI01K1dIq0KVLotvjaMM7uf1zdXL7f/aOI29GcBptnQRDAABjwMbCU8ea5
EAcwAAb6GBAh0gKAt+xigA1vcvucilApYue21RoSPbvrHBFE3cuRNfW6c33cdpA2kU6RT/DLGIABMLA4
BhZ/AYwhzgAMgIEdGFBd2Un3uydi9+LmyQc+sfL/t6J3Il9Dfn4qdNv9unu9Z9OjIpSkSHHU+EkwkC0G
sn0xHDuOHQyAgTvInciVI3gieapJu6/f86tfP9j2s+TMnGOJoa7TT/fSjwgbzhqfCAaKwkBRL4tTx6mD
ATAABsAAGAADYOAlBiBxzDrAABgAA2AADIABMFAgBhBagUJjBsIsFAyAATAABsAAGIDEQeLAABgAA2AA
DIABMFAgBhBagUJj9sXsCwyAATAABsAAGIDEQeLAABgAA2AADIABMFAgBhBagUJj9sXsCwyAATAABsAA
GIDEQeLAABgAA2AADIABMFAgBhBagUJj9sXsCwyAATAABsAAGIDEQeLAABgAA2AADIABMFAgBhBagUJj
9sXsCwyAATAABsAAGIDEQeLAABgAA2AADIABMFAgBhBagUJj9sXsCwyAATAABsAAGIDEQeLAABgAA2AA
DIABMFAgBhBagUJj9sXsCwyAATAABsAAGIDEQeLAABgAA2AADIABMFAgBhBagUJj9sXsCwyAATAABsAA
GIDEQeLAABgAA2AADIABMFAgBhBagUJj9sXsCwyAATAABsAAGIDEQeLAABgAA2AADIABMFAgBhBagUJj
9sXsCwyAATAABsAAGIDEQeLAABgAA2AADIABMFAgBhBagUJj9sXsCwyAATAABsAAGIDEQeLAABgAA2AA
DIABMFAgBhBagUJj9sXsCwyAATAABsAAGIDEQeLAABgAA2AADIABMFAgBhBagUJj9sXsCwyAATAABsAA
GIDEQeLAABgAA2AADIABMFAgBhBagUJj9sXsCwyAATAABsAAGIDEQeLAABgAA2AADIABMFAgBhBagUJj
9sXsCwyAATAABsAAGIDEQeLAABgAA2AADIABMFAgBhBagUJj9sXsCwyAATAABsAAGIDEQeLAABgAA2AA
DIABMFAgBhBagUJj9sXsCwyAATAABsAAGIDEQeLAABgAA2AADIABMFAgBhBagUJj9sXsCwyAATAABsAA
GIDEQeLAABgAA2AADIABMFAgBv5/FOw4h5UG/3QAAAAASUVORK5CYII=
</value>
</data>
<data name="pictureBoxQuad.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms"> <data name="pictureBoxQuad.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value> <value>NoControl</value>
</data> </data>
@ -896,7 +268,7 @@
<value>$this</value> <value>$this</value>
</data> </data>
<data name="&gt;&gt;lbl_status.ZOrder" xml:space="preserve"> <data name="&gt;&gt;lbl_status.ZOrder" xml:space="preserve">
<value>10</value> <value>3</value>
</data> </data>
<data name="progress.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms"> <data name="progress.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value> <value>NoControl</value>
@ -920,7 +292,7 @@
<value>$this</value> <value>$this</value>
</data> </data>
<data name="&gt;&gt;progress.ZOrder" xml:space="preserve"> <data name="&gt;&gt;progress.ZOrder" xml:space="preserve">
<value>11</value> <value>4</value>
</data> </data>
<data name="label2.AutoSize" type="System.Boolean, mscorlib"> <data name="label2.AutoSize" type="System.Boolean, mscorlib">
<value>True</value> <value>True</value>
@ -950,7 +322,7 @@
<value>$this</value> <value>$this</value>
</data> </data>
<data name="&gt;&gt;label2.ZOrder" xml:space="preserve"> <data name="&gt;&gt;label2.ZOrder" xml:space="preserve">
<value>9</value> <value>2</value>
</data> </data>
<data name="pictureBoxHeli.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms"> <data name="pictureBoxHeli.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value> <value>NoControl</value>
@ -974,7 +346,7 @@
<value>$this</value> <value>$this</value>
</data> </data>
<data name="&gt;&gt;pictureBoxHeli.ZOrder" xml:space="preserve"> <data name="&gt;&gt;pictureBoxHeli.ZOrder" xml:space="preserve">
<value>8</value> <value>11</value>
</data> </data>
<data name="BUT_setup.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms"> <data name="BUT_setup.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value> <value>NoControl</value>
@ -1001,7 +373,10 @@
<value>$this</value> <value>$this</value>
</data> </data>
<data name="&gt;&gt;BUT_setup.ZOrder" xml:space="preserve"> <data name="&gt;&gt;BUT_setup.ZOrder" xml:space="preserve">
<value>7</value> <value>1</value>
</data>
<data name="pictureBoxHilimage.ImageLocation" xml:space="preserve">
<value />
</data> </data>
<data name="pictureBoxHilimage.Location" type="System.Drawing.Point, System.Drawing"> <data name="pictureBoxHilimage.Location" type="System.Drawing.Point, System.Drawing">
<value>10, 362</value> <value>10, 362</value>
@ -1025,7 +400,7 @@
<value>$this</value> <value>$this</value>
</data> </data>
<data name="&gt;&gt;pictureBoxHilimage.ZOrder" xml:space="preserve"> <data name="&gt;&gt;pictureBoxHilimage.ZOrder" xml:space="preserve">
<value>6</value> <value>8</value>
</data> </data>
<data name="pictureBoxAPHil.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms"> <data name="pictureBoxAPHil.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value> <value>NoControl</value>
@ -1052,7 +427,7 @@
<value>$this</value> <value>$this</value>
</data> </data>
<data name="&gt;&gt;pictureBoxAPHil.ZOrder" xml:space="preserve"> <data name="&gt;&gt;pictureBoxAPHil.ZOrder" xml:space="preserve">
<value>5</value> <value>7</value>
</data> </data>
<data name="pictureBoxACHil.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms"> <data name="pictureBoxACHil.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value> <value>NoControl</value>
@ -1079,7 +454,7 @@
<value>$this</value> <value>$this</value>
</data> </data>
<data name="&gt;&gt;pictureBoxACHil.ZOrder" xml:space="preserve"> <data name="&gt;&gt;pictureBoxACHil.ZOrder" xml:space="preserve">
<value>4</value> <value>6</value>
</data> </data>
<data name="pictureBoxACHHil.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms"> <data name="pictureBoxACHHil.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
<value>NoControl</value> <value>NoControl</value>
@ -1106,7 +481,7 @@
<value>$this</value> <value>$this</value>
</data> </data>
<data name="&gt;&gt;pictureBoxACHHil.ZOrder" xml:space="preserve"> <data name="&gt;&gt;pictureBoxACHHil.ZOrder" xml:space="preserve">
<value>3</value> <value>5</value>
</data> </data>
<data name="pictureBoxOcta.Location" type="System.Drawing.Point, System.Drawing"> <data name="pictureBoxOcta.Location" type="System.Drawing.Point, System.Drawing">
<value>696, 176</value> <value>696, 176</value>
@ -1127,7 +502,7 @@
<value>$this</value> <value>$this</value>
</data> </data>
<data name="&gt;&gt;pictureBoxOcta.ZOrder" xml:space="preserve"> <data name="&gt;&gt;pictureBoxOcta.ZOrder" xml:space="preserve">
<value>2</value> <value>10</value>
</data> </data>
<data name="pictureBoxOctav.Location" type="System.Drawing.Point, System.Drawing"> <data name="pictureBoxOctav.Location" type="System.Drawing.Point, System.Drawing">
<value>696, 0</value> <value>696, 0</value>
@ -1148,7 +523,7 @@
<value>$this</value> <value>$this</value>
</data> </data>
<data name="&gt;&gt;pictureBoxOctav.ZOrder" xml:space="preserve"> <data name="&gt;&gt;pictureBoxOctav.ZOrder" xml:space="preserve">
<value>1</value> <value>9</value>
</data> </data>
<data name="label1.AutoSize" type="System.Boolean, mscorlib"> <data name="label1.AutoSize" type="System.Boolean, mscorlib">
<value>True</value> <value>True</value>

View File

@ -81,7 +81,9 @@ namespace ArdupilotMega.GCSViews
protected override void Dispose(bool disposing) protected override void Dispose(bool disposing)
{ {
threadrun = 0; threadrun = 0;
MainV2.comPort.logreadmode = false;
MainV2.config["FlightSplitter"] = MainH.SplitterDistance.ToString(); MainV2.config["FlightSplitter"] = MainH.SplitterDistance.ToString();
System.Threading.Thread.Sleep(100);
base.Dispose(disposing); base.Dispose(disposing);
} }
@ -295,7 +297,9 @@ namespace ArdupilotMega.GCSViews
if (MainV2.comPort.logreadmode && MainV2.comPort.logplaybackfile != null) if (MainV2.comPort.logreadmode && MainV2.comPort.logplaybackfile != null)
{ {
this.Invoke((System.Windows.Forms.MethodInvoker)delegate() if (threadrun == 0) { return; }
this.BeginInvoke((System.Windows.Forms.MethodInvoker)delegate()
{ {
try try
{ {
@ -319,7 +323,7 @@ namespace ArdupilotMega.GCSViews
int act = (int)(MainV2.comPort.lastlogread - logplayback).TotalMilliseconds; int act = (int)(MainV2.comPort.lastlogread - logplayback).TotalMilliseconds;
if (act > 9999 || act < 0) if (act > 9999 || act < 0)
act = 1; act = 0;
int ts = 0; int ts = 0;
try try
@ -330,6 +334,8 @@ namespace ArdupilotMega.GCSViews
if (ts > 0) if (ts > 0)
System.Threading.Thread.Sleep(ts); System.Threading.Thread.Sleep(ts);
if (threadrun == 0) { return; }
tracklast = tracklast.AddMilliseconds(ts - act); tracklast = tracklast.AddMilliseconds(ts - act);
tunning = tunning.AddMilliseconds(ts - act); tunning = tunning.AddMilliseconds(ts - act);
@ -1320,7 +1326,7 @@ namespace ArdupilotMega.GCSViews
Form selectform = new Form() Form selectform = new Form()
{ {
Name = "select", Name = "select",
Width = 750, Width = 50,
Height = 250, Height = 250,
Text = "Graph This" Text = "Graph This"
}; };
@ -1400,6 +1406,8 @@ namespace ArdupilotMega.GCSViews
{ {
x += 100; x += 100;
y = 10; y = 10;
selectform.Width = x + 100;
} }
} }
MainV2.fixtheme(selectform); MainV2.fixtheme(selectform);
@ -1596,6 +1604,16 @@ namespace ArdupilotMega.GCSViews
void ScriptStart() void ScriptStart()
{ {
string myscript = @" string myscript = @"
# cs.???? = currentstate, any variable on the status tab in the planner can be used.
# Script = options are
# Script.Sleep(ms)
# Script.ChangeParam(name,value)
# Script.GetParam(name)
# Script.ChangeMode(mode) - same as displayed in mode setup screen 'AUTO'
# Script.WaitFor(string,timeout)
# Script.SendRC(channel,pwm,sendnow)
#
print 'Start Script' print 'Start Script'
for chan in range(1,9): for chan in range(1,9):
Script.SendRC(chan,1500,False) Script.SendRC(chan,1500,False)

View File

@ -33,7 +33,7 @@ namespace ArdupilotMega.GCSViews
bool sethome = false; bool sethome = false;
bool polygongridmode = false; bool polygongridmode = false;
Hashtable param = new Hashtable(); Hashtable param = new Hashtable();
public static Hashtable hashdefines = new Hashtable();
public static List<PointLatLngAlt> pointlist = new List<PointLatLngAlt>(); // used to calc distance public static List<PointLatLngAlt> pointlist = new List<PointLatLngAlt>(); // used to calc distance
static public Object thisLock = new Object(); static public Object thisLock = new Object();
private TextBox textBox1; private TextBox textBox1;
@ -85,7 +85,7 @@ namespace ArdupilotMega.GCSViews
System.Diagnostics.Debug.WriteLine(matchs[i].Groups[1].Value.ToString() + " = " + matchs[i].Groups[2].Value.ToString() + " = " + num.ToString()); System.Diagnostics.Debug.WriteLine(matchs[i].Groups[1].Value.ToString() + " = " + matchs[i].Groups[2].Value.ToString() + " = " + num.ToString());
try try
{ {
hashdefines.Add(matchs[i].Groups[1].Value.ToString(), num); // hashdefines.Add(matchs[i].Groups[1].Value.ToString(), num);
} }
catch (Exception) { } catch (Exception) { }
} }
@ -95,10 +95,10 @@ namespace ArdupilotMega.GCSViews
sr.Close(); sr.Close();
if (!hashdefines.ContainsKey("WP_START_BYTE")) // if (!hashdefines.ContainsKey("WP_START_BYTE"))
{ {
MessageBox.Show("Your Ardupilot Mega project defines.h is Invalid"); MessageBox.Show("Your Ardupilot Mega project defines.h is Invalid");
return false; //return false;
} }
} }
catch (Exception) catch (Exception)
@ -514,12 +514,6 @@ namespace ArdupilotMega.GCSViews
Up.Image = global::ArdupilotMega.Properties.Resources.up; Up.Image = global::ArdupilotMega.Properties.Resources.up;
Down.Image = global::ArdupilotMega.Properties.Resources.down; Down.Image = global::ArdupilotMega.Properties.Resources.down;
hashdefines.Clear();
if (File.Exists(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "defines.h"))
{
readdefines(Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "defines.h");
}
} }
void updateCMDParams() void updateCMDParams()
@ -868,24 +862,6 @@ namespace ArdupilotMega.GCSViews
} }
} }
} }
DataGridViewTextBoxCell cell1;
cell1 = Commands.Rows[selectedrow].Cells[1] as DataGridViewTextBoxCell;
byte res;
if (byte.TryParse(cell1.Value.ToString(), out res))
{
}
else
{
try
{
cell1.Value = (byte)(int)hashdefines[cell1.Value.ToString().ToUpper().Trim()];
}
catch { }
}
} }
/// <summary> /// <summary>
@ -1499,21 +1475,21 @@ namespace ArdupilotMega.GCSViews
} }
} }
string hold_alt = ((float)param["ALT_HOLD_RTL"] * MainV2.cs.multiplierdist).ToString("0"); string hold_alt = ((int)((float)param["ALT_HOLD_RTL"] * MainV2.cs.multiplierdist)).ToString();
if (hold_alt != "-1") if (!hold_alt.Equals("-1"))
{ {
TXT_DefaultAlt.Text = hold_alt; TXT_DefaultAlt.Text = hold_alt;
} }
TXT_WPRad.Text = ((float)param["WP_RADIUS"] * MainV2.cs.multiplierdist).ToString("0"); TXT_WPRad.Text = ((int)((float)param["WP_RADIUS"] * MainV2.cs.multiplierdist)).ToString();
try try
{ {
TXT_loiterrad.Text = ((float)param["LOITER_RADIUS"] * MainV2.cs.multiplierdist).ToString("0"); TXT_loiterrad.Text = ((int)((float)param["LOITER_RADIUS"] * MainV2.cs.multiplierdist)).ToString();
} }
catch catch
{ {
TXT_loiterrad.Text = ((float)param["WP_LOITER_RAD"] * MainV2.cs.multiplierdist).ToString("0"); TXT_loiterrad.Text = ((int)((float)param["WP_LOITER_RAD"] * MainV2.cs.multiplierdist)).ToString();
} }
CHK_holdalt.Checked = Convert.ToBoolean((float)param["ALT_HOLD_RTL"] > 0); CHK_holdalt.Checked = Convert.ToBoolean((float)param["ALT_HOLD_RTL"] > 0);

View File

@ -190,8 +190,23 @@ namespace ArdupilotMega.GCSViews
// Fuel (gas & jet models) // Fuel (gas & jet models)
public float Model_fFuelConsumed; // l public float Model_fFuelConsumed; // l
public float Model_fFuelTankCapacity; // l public float Model_fFuelTankCapacity; // l
// Ver > 3.81
// Screen size
public short Win_nScreenSizeDX; public short Win_nScreenSizeDY; // Screen Size, used to resize and reposition simulator window
// Model Orientation Matrix
public float Model_fAxisRight_x; public float Model_fAxisRight_y; public float Model_fAxisRight_z;
public float Model_fAxisFront_x; public float Model_fAxisFront_y; public float Model_fAxisFront_z;
public float Model_fAxisUp_x; public float Model_fAxisUp_y; public float Model_fAxisUp_z;
// Model data in body frame coordinates (X=Right, Y=Front, Z=Up)
public float Model_fVel_Body_X; public float Model_fVel_Body_Y; public float Model_fVel_Body_Z; // m/s Model velocity in body coordinates
public float Model_fAngVel_Body_X; public float Model_fAngVel_Body_Y; public float Model_fAngVel_Body_Z; // rad/s Model angular velocity in body coordinates
public float Model_fAccel_Body_X; public float Model_fAccel_Body_Y; public float Model_fAccel_Body_Z; // m/s/s Model acceleration in body coordinates
}; };
~Simulation() ~Simulation()
{ {
if (threadrun == 1) if (threadrun == 1)
@ -558,7 +573,7 @@ namespace ArdupilotMega.GCSViews
RECVprocess(udpdata, recv, comPort); RECVprocess(udpdata, recv, comPort);
} }
} }
catch (Exception ex) { //OutputLog.AppendText("Xplanes Data Problem - You need DATA IN/OUT 3, 4, 17, 18, 19, 20\n" + ex.Message + "\n"); catch { //OutputLog.AppendText("Xplanes Data Problem - You need DATA IN/OUT 3, 4, 17, 18, 19, 20\n" + ex.Message + "\n");
} }
} }
if (MavLink != null && MavLink.Client != null && MavLink.Client.Connected && MavLink.Available > 0) if (MavLink != null && MavLink.Client != null && MavLink.Client.Connected && MavLink.Available > 0)
@ -885,7 +900,7 @@ namespace ArdupilotMega.GCSViews
//stream.Write(data, 0, receviedbytes); //stream.Write(data, 0, receviedbytes);
//stream.Close(); //stream.Close();
} }
else if (receviedbytes == 582) else if (receviedbytes == 658)
{ {
aeroin = new TDataFromAeroSimRC(); aeroin = new TDataFromAeroSimRC();
@ -903,18 +918,15 @@ namespace ArdupilotMega.GCSViews
//Console.WriteLine("mine2 {0} {1} {2} ", answer.Item1 , answer.Item2 , answer.Item3 ); //Console.WriteLine("mine2 {0} {1} {2} ", answer.Item1 , answer.Item2 , answer.Item3 );
//StreamWriter SW = new StreamWriter("aerosim.txt",true);
//SW.WriteLine(aeroin.Model_fRoll + "," + aeroin.Model_fPitch + "," + aeroin.Model_fHeading + "," + aeroin.Model_fAngVelX + "," + aeroin.Model_fAngVelY + "," + aeroin.Model_fAngVelZ);
var answer = HIL.Utils.EarthRatesToBodyRatesMine(att.roll * rad2deg, att.pitch * rad2deg, att.yaw * rad2deg, aeroin.Model_fAngVelX * rad2deg, aeroin.Model_fAngVelY * rad2deg, aeroin.Model_fAngVelZ * rad2deg); //SW.Close();
Console.WriteLine("\n{0:0.000} {1:0.000} {2:0.000} ", answer.Item1 * deg2rad, answer.Item2 * deg2rad, answer.Item3 * deg2rad);
// att.pitchspeed = (float)answer.Item1 * -deg2rad; att.pitchspeed = (float)aeroin.Model_fAngVel_Body_X;
// att.rollspeed = (float)answer.Item2 * -deg2rad; att.rollspeed = (float)aeroin.Model_fAngVel_Body_Y;
// att.yawspeed = (float)answer.Item3 * -deg2rad; att.yawspeed = (float)-aeroin.Model_fAngVel_Body_Z;
//att.pitchspeed = (float)(Math.Cos(att.yaw) * aeroin.Model_fAngVelX - Math.Sin(att.yaw) * aeroin.Model_fAngVelY);
//att.rollspeed = (float)(Math.Sin(att.yaw) * aeroin.Model_fAngVelX + Math.Cos(att.yaw) * aeroin.Model_fAngVelY);
// att.yawspeed = (float)-aeroin.Model_fAngVelZ * deg2rad;
#if MAVLINK10 #if MAVLINK10
@ -922,18 +934,18 @@ namespace ArdupilotMega.GCSViews
#else #else
imu.usec = ((ulong)DateTime.Now.ToBinary()); imu.usec = ((ulong)DateTime.Now.ToBinary());
#endif #endif
imu.xgyro = (short)(aeroin.Model_fAngVelX * 1000); // roll - yes imu.xgyro = (short)(aeroin.Model_fAngVel_Body_X * 1000); // roll - yes
//imu.xmag = (short)(Math.Sin(head * deg2rad) * 1000); //imu.xmag = (short)(Math.Sin(head * deg2rad) * 1000);
imu.ygyro = (short)(aeroin.Model_fAngVelY * 1000); // pitch - yes imu.ygyro = (short)(aeroin.Model_fAngVel_Body_Y * 1000); // pitch - yes
//imu.ymag = (short)(Math.Cos(head * deg2rad) * 1000); //imu.ymag = (short)(Math.Cos(head * deg2rad) * 1000);
imu.zgyro = (short)(aeroin.Model_fAngVelZ * 1000); imu.zgyro = (short)(aeroin.Model_fAngVel_Body_Z * 1000);
//imu.zmag = 0; //imu.zmag = 0;
YLScsDrawing.Drawing3d.Vector3d accel3D = HIL.QuadCopter.RPY_to_XYZ(att.roll, att.pitch, 0, -9.8); //DATA[18][2] YLScsDrawing.Drawing3d.Vector3d accel3D = HIL.QuadCopter.RPY_to_XYZ(att.roll, att.pitch, 0, -9.8); //DATA[18][2]
imu.xacc = (Int16)((accel3D.X + aeroin.Model_fAccelX) * 1000); // pitch imu.xacc = (Int16)((accel3D.X + aeroin.Model_fAccel_Body_X) * 1000); // pitch
imu.yacc = (Int16)((accel3D.Y + aeroin.Model_fAccelY) * 1000); // roll imu.yacc = (Int16)((accel3D.Y + aeroin.Model_fAccel_Body_Y) * 1000); // roll
imu.zacc = (Int16)((accel3D.Z + aeroin.Model_fAccelZ) * 1000); imu.zacc = (Int16)((accel3D.Z + aeroin.Model_fAccel_Body_Z) * 1000);
// Console.WriteLine("x {0} y {1} z {2}", imu.xacc, imu.yacc, imu.zacc); // Console.WriteLine("x {0} y {1} z {2}", imu.xacc, imu.yacc, imu.zacc);
@ -1443,7 +1455,7 @@ namespace ArdupilotMega.GCSViews
Array.Copy(BitConverter.GetBytes((double)(collective_out)), 0, AeroSimRC, 24, 8); Array.Copy(BitConverter.GetBytes((double)(collective_out)), 0, AeroSimRC, 24, 8);
} }
if (CHK_quad.Checked && false) if (CHK_quad.Checked)
{ {
//MainV2.cs.ch1out = 1100; //MainV2.cs.ch1out = 1100;
//MainV2.cs.ch2out = 1100; //MainV2.cs.ch2out = 1100;
@ -1461,6 +1473,10 @@ namespace ArdupilotMega.GCSViews
Array.Copy(BitConverter.GetBytes((double)((MainV2.cs.ch4out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 16, 8);// motor 3 = back Array.Copy(BitConverter.GetBytes((double)((MainV2.cs.ch4out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 16, 8);// motor 3 = back
Array.Copy(BitConverter.GetBytes((double)((MainV2.cs.ch2out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 24, 8);// motor 4 = left Array.Copy(BitConverter.GetBytes((double)((MainV2.cs.ch2out - 1100) / 800 * 2 - 1)), 0, AeroSimRC, 24, 8);// motor 4 = left
}
else
{
} }
try try
@ -1596,20 +1612,12 @@ namespace ArdupilotMega.GCSViews
private void RAD_softXplanes_CheckedChanged(object sender, EventArgs e) private void RAD_softXplanes_CheckedChanged(object sender, EventArgs e)
{ {
if (RAD_softXplanes.Checked && RAD_softFlightGear.Checked)
{
RAD_softFlightGear.Checked = false;
RAD_aerosimrc.Checked = false;
}
} }
private void RAD_softFlightGear_CheckedChanged(object sender, EventArgs e) private void RAD_softFlightGear_CheckedChanged(object sender, EventArgs e)
{ {
if (RAD_softFlightGear.Checked && RAD_softXplanes.Checked)
{
RAD_softXplanes.Checked = false;
RAD_aerosimrc.Checked = false;
}
} }
private void CHKREV_roll_CheckedChanged(object sender, EventArgs e) private void CHKREV_roll_CheckedChanged(object sender, EventArgs e)
@ -2067,11 +2075,7 @@ namespace ArdupilotMega.GCSViews
private void RAD_aerosimrc_CheckedChanged(object sender, EventArgs e) private void RAD_aerosimrc_CheckedChanged(object sender, EventArgs e)
{ {
if (RAD_aerosimrc.Checked && RAD_softXplanes.Checked)
{
RAD_softXplanes.Checked = false;
RAD_softFlightGear.Checked = false;
}
} }
private void RAD_JSBSim_CheckedChanged(object sender, EventArgs e) private void RAD_JSBSim_CheckedChanged(object sender, EventArgs e)

View File

@ -79,16 +79,16 @@ namespace ArdupilotMega.HIL
} }
public static Tuple<double, double, double> EarthRatesToBodyRatesRyan(double roll, double pitch, double yaw, public static Tuple<double, double, double> EarthRatesToBodyRatesRyan(double roll, double pitch, double yaw,
double rollRate, double pitchRate, double yawRate) double x, double y, double z)
{ {
// thanks to ryan beall // thanks to ryan beall
var phi = radians(roll); var phi = radians(roll);
var theta = radians(pitch); var theta = radians(pitch);
var psi = radians(yaw); var psi = radians((360 - yaw) * 1.0);
var Po = radians(pitchRate); var Po = radians(x);
var Ro = radians(yawRate); var Qo = radians(y);
var Qo = radians(rollRate); var Ro = radians(-z);
var P = Po * cos(psi) * cos(theta) - Ro * sin(theta) + Qo * cos(theta) * sin(psi); var P = Po * cos(psi) * cos(theta) - Ro * sin(theta) + Qo * cos(theta) * sin(psi);
@ -96,6 +96,12 @@ namespace ArdupilotMega.HIL
var R = Po * (sin(phi) * sin(psi) + cos(phi) * cos(psi) * sin(theta)) - Qo * (cos(psi) * sin(phi) - cos(phi) * sin(psi) * sin(theta)) + Ro * cos(phi) * cos(theta); var R = Po * (sin(phi) * sin(psi) + cos(phi) * cos(psi) * sin(theta)) - Qo * (cos(psi) * sin(phi) - cos(phi) * sin(psi) * sin(theta)) + Ro * cos(phi) * cos(theta);
// P = 0;
//Q = 0;
//R = 0;
return new Tuple<double, double, double>(degrees(P), degrees(Q), degrees(R)); return new Tuple<double, double, double>(degrees(P), degrees(Q), degrees(R));
} }

View File

@ -42,6 +42,8 @@ namespace hud
public bool opengl { get { return base.UseOpenGL; } set { base.UseOpenGL = value; } } public bool opengl { get { return base.UseOpenGL; } set { base.UseOpenGL = value; } }
bool started = false;
public HUD() public HUD()
{ {
if (this.DesignMode) if (this.DesignMode)
@ -50,12 +52,12 @@ namespace hud
//return; //return;
} }
InitializeComponent(); //InitializeComponent();
graphicsObject = this; graphicsObject = this;
graphicsObjectGDIP = Graphics.FromImage(objBitmap); graphicsObjectGDIP = Graphics.FromImage(objBitmap);
} }
/*
private void InitializeComponent() private void InitializeComponent()
{ {
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(HUD)); System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(HUD));
@ -68,32 +70,32 @@ namespace hud
resources.ApplyResources(this, "$this"); resources.ApplyResources(this, "$this");
this.ResumeLayout(false); this.ResumeLayout(false);
} }*/
float _roll; float _roll = 0;
float _navroll; float _navroll = 0;
float _pitch; float _pitch = 0;
float _navpitch; float _navpitch = 0;
float _heading; float _heading = 0;
float _targetheading; float _targetheading = 0;
float _alt; float _alt = 0;
float _targetalt; float _targetalt = 0;
float _groundspeed; float _groundspeed = 0;
float _airspeed; float _airspeed = 0;
float _targetspeed; float _targetspeed = 0;
float _batterylevel; float _batterylevel = 0;
float _batteryremaining; float _batteryremaining = 0;
float _gpsfix; float _gpsfix = 0;
float _gpshdop; float _gpshdop = 0;
float _disttowp; float _disttowp = 0;
float _groundcourse; float _groundcourse = 0;
float _xtrack_error; float _xtrack_error = 0;
float _turnrate; float _turnrate = 0;
float _verticalspeed; float _verticalspeed = 0;
float _linkqualitygcs; float _linkqualitygcs = 0;
DateTime _datetime; DateTime _datetime;
string _mode = "Manual"; string _mode = "Manual";
int _wpno; int _wpno = 0;
[System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
public float roll { get { return _roll; } set { if (_roll != value) { _roll = value; this.Invalidate(); } } } public float roll { get { return _roll; } set { if (_roll != value) { _roll = value; this.Invalidate(); } } }
@ -146,6 +148,7 @@ namespace hud
[System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")] [System.ComponentModel.Browsable(true), System.ComponentModel.Category("Values")]
public int status { get; set; } public int status { get; set; }
int statuslast = 0; int statuslast = 0;
DateTime armedtimer = DateTime.MinValue; DateTime armedtimer = DateTime.MinValue;
@ -180,9 +183,6 @@ namespace hud
protected override void OnLoad(EventArgs e) protected override void OnLoad(EventArgs e)
{ {
if (this.DesignMode)
return;
if (opengl) if (opengl)
{ {
try try
@ -236,12 +236,17 @@ namespace hud
} }
catch { } catch { }
} }
started = true;
} }
protected override void OnPaint(PaintEventArgs e) protected override void OnPaint(PaintEventArgs e)
{ {
//GL.Enable(EnableCap.AlphaTest) //GL.Enable(EnableCap.AlphaTest)
if (!started)
return;
if (this.DesignMode) if (this.DesignMode)
{ {
e.Graphics.Clear(this.BackColor); e.Graphics.Clear(this.BackColor);
@ -691,14 +696,14 @@ namespace hud
graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2); graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2);
graphicsObject.RotateTransform(-roll); graphicsObject.RotateTransform(-_roll);
int fontsize = this.Height / 30; // = 10 int fontsize = this.Height / 30; // = 10
int fontoffset = fontsize - 10; int fontoffset = fontsize - 10;
float every5deg = -this.Height / 60; float every5deg = -this.Height / 60;
float pitchoffset = -pitch * every5deg; float pitchoffset = -_pitch * every5deg;
int halfwidth = this.Width / 2; int halfwidth = this.Width / 2;
int halfheight = this.Height / 2; int halfheight = this.Height / 2;
@ -742,7 +747,7 @@ namespace hud
graphicsObject.SetClip(new Rectangle(0, this.Height / 14, this.Width, this.Height - this.Height / 14)); graphicsObject.SetClip(new Rectangle(0, this.Height / 14, this.Width, this.Height - this.Height / 14));
graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2); graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2);
graphicsObject.RotateTransform(-roll); graphicsObject.RotateTransform(-_roll);
// draw armed // draw armed
@ -776,7 +781,7 @@ namespace hud
for (int a = -90; a <= 90; a += 5) for (int a = -90; a <= 90; a += 5)
{ {
// limit to 40 degrees // limit to 40 degrees
if (a >= pitch - 34 && a <= pitch + 25) if (a >= _pitch - 34 && a <= _pitch + 25)
{ {
if (a % 10 == 0) if (a % 10 == 0)
{ {
@ -804,7 +809,7 @@ namespace hud
graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2 + this.Height / 14); graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2 + this.Height / 14);
graphicsObject.RotateTransform(-roll); graphicsObject.RotateTransform(-_roll);
Point[] pointlist = new Point[3]; Point[] pointlist = new Point[3];
@ -816,7 +821,7 @@ namespace hud
pointlist[1] = new Point(-lengthlong, -lengthlong - extra); pointlist[1] = new Point(-lengthlong, -lengthlong - extra);
pointlist[2] = new Point(lengthlong, -lengthlong - extra); pointlist[2] = new Point(lengthlong, -lengthlong - extra);
if (Math.Abs(roll) > 45) if (Math.Abs(_roll) > 45)
{ {
redPen.Width = 10; redPen.Width = 10;
} }
@ -870,30 +875,30 @@ namespace hud
graphicsObject.DrawLine(whitePen, headbg.Left + 5, headbg.Bottom - 5, headbg.Width - 5, headbg.Bottom - 5); graphicsObject.DrawLine(whitePen, headbg.Left + 5, headbg.Bottom - 5, headbg.Width - 5, headbg.Bottom - 5);
float space = (headbg.Width - 10) / 60.0f; float space = (headbg.Width - 10) / 60.0f;
int start = (int)Math.Round((heading - 30),1); int start = (int)Math.Round((_heading - 30),1);
// draw for outside the 60 deg // draw for outside the 60 deg
if (targetheading < start) if (_targetheading < start)
{ {
greenPen.Width = 6; greenPen.Width = 6;
graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * 0, headbg.Bottom, headbg.Left + 5 + space * (0), headbg.Top); graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * 0, headbg.Bottom, headbg.Left + 5 + space * (0), headbg.Top);
} }
if (targetheading > heading + 30) if (_targetheading > _heading + 30)
{ {
greenPen.Width = 6; greenPen.Width = 6;
graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * 60, headbg.Bottom, headbg.Left + 5 + space * (60), headbg.Top); graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * 60, headbg.Bottom, headbg.Left + 5 + space * (60), headbg.Top);
} }
for (int a = start; a <= heading + 30; a += 1) for (int a = start; a <= _heading + 30; a += 1)
{ {
// target heading // target heading
if (((int)(a + 360) % 360) == (int)targetheading) if (((int)(a + 360) % 360) == (int)_targetheading)
{ {
greenPen.Width = 6; greenPen.Width = 6;
graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * (a - start), headbg.Bottom, headbg.Left + 5 + space * (a - start), headbg.Top); graphicsObject.DrawLine(greenPen, headbg.Left + 5 + space * (a - start), headbg.Bottom, headbg.Left + 5 + space * (a - start), headbg.Top);
} }
if (((int)(a + 360) % 360) == (int)groundcourse) if (((int)(a + 360) % 360) == (int)_groundcourse)
{ {
blackPen.Width = 6; blackPen.Width = 6;
graphicsObject.DrawLine(blackPen, headbg.Left + 5 + space * (a - start), headbg.Bottom, headbg.Left + 5 + space * (a - start), headbg.Top); graphicsObject.DrawLine(blackPen, headbg.Left + 5 + space * (a - start), headbg.Bottom, headbg.Left + 5 + space * (a - start), headbg.Top);
@ -940,7 +945,7 @@ namespace hud
float xtspace = this.Width / 10.0f / 3.0f; float xtspace = this.Width / 10.0f / 3.0f;
int pad = 10; int pad = 10;
float myxtrack_error = xtrack_error; float myxtrack_error = _xtrack_error;
myxtrack_error = Math.Min(myxtrack_error, 40); myxtrack_error = Math.Min(myxtrack_error, 40);
myxtrack_error = Math.Max(myxtrack_error, -40); myxtrack_error = Math.Max(myxtrack_error, -40);
@ -977,7 +982,7 @@ namespace hud
graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace * 2 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 + xtspace * 2 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10); graphicsObject.DrawLine(whitePen, this.Width / 10 + xtspace * 2 - xtspace / 2, headbg.Bottom + this.Height / 10 + 10, this.Width / 10 + xtspace * 2 - xtspace / 2 + xtspace, headbg.Bottom + this.Height / 10 + 10);
float myturnrate = turnrate; float myturnrate = _turnrate;
float trwidth = (this.Width / 10 + xtspace * 2 - xtspace / 2) - (this.Width / 10 - xtspace * 2 - xtspace / 2); float trwidth = (this.Width / 10 + xtspace * 2 - xtspace / 2) - (this.Width / 10 - xtspace * 2 - xtspace / 2);
float range = 12; float range = 12;
@ -1023,21 +1028,21 @@ namespace hud
int viewrange = 26; int viewrange = 26;
float speed = airspeed; float speed = _airspeed;
if (speed == 0) if (speed == 0)
speed = groundspeed; speed = _groundspeed;
space = (scrollbg.Height) / (float)viewrange; space = (scrollbg.Height) / (float)viewrange;
start = ((int)speed - viewrange / 2); start = ((int)speed - viewrange / 2);
if (start > targetspeed) if (start > _targetspeed)
{ {
greenPen.Color = Color.FromArgb(128, greenPen.Color); greenPen.Color = Color.FromArgb(128, greenPen.Color);
greenPen.Width = 6; greenPen.Width = 6;
graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top, scrollbg.Left + scrollbg.Width, scrollbg.Top); graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top, scrollbg.Left + scrollbg.Width, scrollbg.Top);
greenPen.Color = Color.FromArgb(255, greenPen.Color); greenPen.Color = Color.FromArgb(255, greenPen.Color);
} }
if ((speed + viewrange / 2) < targetspeed) if ((speed + viewrange / 2) < _targetspeed)
{ {
greenPen.Color = Color.FromArgb(128, greenPen.Color); greenPen.Color = Color.FromArgb(128, greenPen.Color);
greenPen.Width = 6; greenPen.Width = 6;
@ -1047,7 +1052,7 @@ namespace hud
for (int a = (int)start; a <= (speed + viewrange / 2); a += 1) for (int a = (int)start; a <= (speed + viewrange / 2); a += 1)
{ {
if (a == (int)targetspeed && targetspeed != 0) if (a == (int)_targetspeed && _targetspeed != 0)
{ {
greenPen.Width = 6; greenPen.Width = 6;
graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + scrollbg.Width, scrollbg.Top - space * (a - start)); graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + scrollbg.Width, scrollbg.Top - space * (a - start));
@ -1068,8 +1073,8 @@ namespace hud
// extra text data // extra text data
drawstring(graphicsObject, "AS " + airspeed.ToString("0.0"), font, fontsize, whiteBrush, 1, scrollbg.Bottom + 5); drawstring(graphicsObject, "AS " + _airspeed.ToString("0.0"), font, fontsize, whiteBrush, 1, scrollbg.Bottom + 5);
drawstring(graphicsObject, "GS " + groundspeed.ToString("0.0"), font, fontsize, whiteBrush, 1, scrollbg.Bottom + fontsize + 2 + 10); drawstring(graphicsObject, "GS " + _groundspeed.ToString("0.0"), font, fontsize, whiteBrush, 1, scrollbg.Bottom + fontsize + 2 + 10);
//drawstring(e,, new Font("Arial", fontsize + 2), whiteBrush, 1, scrollbg.Bottom + fontsize + 2 + 10); //drawstring(e,, new Font("Arial", fontsize + 2), whiteBrush, 1, scrollbg.Bottom + fontsize + 2 + 10);
@ -1099,16 +1104,16 @@ namespace hud
viewrange = 26; viewrange = 26;
space = (scrollbg.Height) / (float)viewrange; space = (scrollbg.Height) / (float)viewrange;
start = ((int)alt - viewrange / 2); start = ((int)_alt - viewrange / 2);
if (start > targetalt) if (start > _targetalt)
{ {
greenPen.Color = Color.FromArgb(128, greenPen.Color); greenPen.Color = Color.FromArgb(128, greenPen.Color);
greenPen.Width = 6; greenPen.Width = 6;
graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top, scrollbg.Left + scrollbg.Width, scrollbg.Top); graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top, scrollbg.Left + scrollbg.Width, scrollbg.Top);
greenPen.Color = Color.FromArgb(255, greenPen.Color); greenPen.Color = Color.FromArgb(255, greenPen.Color);
} }
if ((alt + viewrange / 2) < targetalt) if ((_alt + viewrange / 2) < _targetalt)
{ {
greenPen.Color = Color.FromArgb(128, greenPen.Color); greenPen.Color = Color.FromArgb(128, greenPen.Color);
greenPen.Width = 6; greenPen.Width = 6;
@ -1116,9 +1121,9 @@ namespace hud
greenPen.Color = Color.FromArgb(255, greenPen.Color); greenPen.Color = Color.FromArgb(255, greenPen.Color);
} }
for (int a = (int)start; a <= (alt + viewrange / 2); a += 1) for (int a = (int)start; a <= (_alt + viewrange / 2); a += 1)
{ {
if (a == Math.Round(targetalt) && targetalt != 0) if (a == Math.Round(_targetalt) && _targetalt != 0)
{ {
greenPen.Width = 6; greenPen.Width = 6;
graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + scrollbg.Width, scrollbg.Top - space * (a - start)); graphicsObject.DrawLine(greenPen, scrollbg.Left, scrollbg.Top - space * (a - start), scrollbg.Left + scrollbg.Width, scrollbg.Top - space * (a - start));
@ -1148,10 +1153,10 @@ namespace hud
viewrange = 12; viewrange = 12;
verticalspeed = Math.Min(viewrange / 2, verticalspeed); _verticalspeed = Math.Min(viewrange / 2, _verticalspeed);
verticalspeed = Math.Max(viewrange / -2, verticalspeed); _verticalspeed = Math.Max(viewrange / -2, _verticalspeed);
float scaledvalue = verticalspeed / -viewrange * (scrollbg.Bottom - scrollbg.Top); float scaledvalue = _verticalspeed / -viewrange * (scrollbg.Bottom - scrollbg.Top);
float linespace = (float)1 / -viewrange * (scrollbg.Bottom - scrollbg.Top); float linespace = (float)1 / -viewrange * (scrollbg.Bottom - scrollbg.Top);
@ -1199,53 +1204,53 @@ namespace hud
graphicsObject.ResetTransform(); graphicsObject.ResetTransform();
graphicsObject.TranslateTransform(0, this.Height / 2); graphicsObject.TranslateTransform(0, this.Height / 2);
drawstring(graphicsObject, ((int)alt).ToString("0"), font, 10, Brushes.AliceBlue, scrollbg.Left + 10, -9); drawstring(graphicsObject, ((int)_alt).ToString("0"), font, 10, Brushes.AliceBlue, scrollbg.Left + 10, -9);
graphicsObject.ResetTransform(); graphicsObject.ResetTransform();
// mode and wp dist and wp // mode and wp dist and wp
drawstring(graphicsObject, mode, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + 5); drawstring(graphicsObject, _mode, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + 5);
drawstring(graphicsObject, (int)disttowp + ">" + wpno, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + fontsize + 2 + 10); drawstring(graphicsObject, (int)_disttowp + ">" + _wpno, font, fontsize, whiteBrush, scrollbg.Left - 30, scrollbg.Bottom + fontsize + 2 + 10);
graphicsObject.DrawLine(greenPen, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize) - 2 - 20); graphicsObject.DrawLine(greenPen, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left - 5, scrollbg.Top - (int)(fontsize) - 2 - 20);
graphicsObject.DrawLine(greenPen, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 15, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize) - 2 - 20); graphicsObject.DrawLine(greenPen, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 15, scrollbg.Left - 10, scrollbg.Top - (int)(fontsize) - 2 - 20);
graphicsObject.DrawLine(greenPen, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 10, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize ) - 2 - 20); graphicsObject.DrawLine(greenPen, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 10, scrollbg.Left - 15, scrollbg.Top - (int)(fontsize ) - 2 - 20);
drawstring(graphicsObject, linkqualitygcs.ToString("0") + "%", font, fontsize, whiteBrush, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20); drawstring(graphicsObject, _linkqualitygcs.ToString("0") + "%", font, fontsize, whiteBrush, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20);
if (linkqualitygcs == 0) if (_linkqualitygcs == 0)
{ {
graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2); graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2);
graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20); graphicsObject.DrawLine(redPen, scrollbg.Left, scrollbg.Top - (int)(fontsize * 2.2) - 2, scrollbg.Left + 50, scrollbg.Top - (int)(fontsize * 2.2) - 2 - 20);
} }
drawstring(graphicsObject, datetime.ToString("HH:mm:ss"), font, fontsize, whiteBrush, scrollbg.Left - 20, scrollbg.Top - fontsize - 2 - 20); drawstring(graphicsObject, _datetime.ToString("HH:mm:ss"), font, fontsize, whiteBrush, scrollbg.Left - 20, scrollbg.Top - fontsize - 2 - 20);
// battery // battery
graphicsObject.ResetTransform(); graphicsObject.ResetTransform();
drawstring(graphicsObject, resources.GetString("Bat"), font, fontsize + 2, whiteBrush, fontsize, this.Height - 30 - fontoffset); drawstring(graphicsObject, "Bat", font, fontsize + 2, whiteBrush, fontsize, this.Height - 30 - fontoffset);
drawstring(graphicsObject, batterylevel.ToString("0.00v"), font, fontsize + 2, whiteBrush, fontsize * 4, this.Height - 30 - fontoffset); drawstring(graphicsObject, _batterylevel.ToString("0.00v"), font, fontsize + 2, whiteBrush, fontsize * 4, this.Height - 30 - fontoffset);
drawstring(graphicsObject, batteryremaining.ToString("0%"), font, fontsize + 2, whiteBrush, fontsize * 9, this.Height - 30 - fontoffset); drawstring(graphicsObject, _batteryremaining.ToString("0%"), font, fontsize + 2, whiteBrush, fontsize * 9, this.Height - 30 - fontoffset);
// gps // gps
string gps = ""; string gps = "";
if (gpsfix == 0) if (_gpsfix == 0)
{ {
gps = ("GPS: No GPS"); gps = ("GPS: No GPS");
} }
else if (gpsfix == 1) else if (_gpsfix == 1)
{ {
gps = ("GPS: No Fix"); gps = ("GPS: No Fix");
} }
else if (gpsfix == 2) else if (_gpsfix == 2)
{ {
gps = ("GPS: 3D Fix"); gps = ("GPS: 3D Fix");
} }
else if (gpsfix == 3) else if (_gpsfix == 3)
{ {
gps = ("GPS: 3D Fix"); gps = ("GPS: 3D Fix");
} }
@ -1463,7 +1468,6 @@ namespace hud
pth.Reset(); pth.Reset();
if (text != null) if (text != null)
pth.AddString(text, font.FontFamily, 0, fontsize + 5, new Point((int)x, (int)y), StringFormat.GenericTypographic); pth.AddString(text, font.FontFamily, 0, fontsize + 5, new Point((int)x, (int)y), StringFormat.GenericTypographic);
@ -1472,6 +1476,10 @@ namespace hud
//e.SmoothingMode = SmoothingMode.HighSpeed; //e.SmoothingMode = SmoothingMode.HighSpeed;
if (e == null || P == null || pth == null || pth.PointCount == 0)
return;
if (!ArdupilotMega.MainV2.MONO)
e.DrawPath(P, pth); e.DrawPath(P, pth);
//Draw the face //Draw the face
@ -1507,7 +1515,7 @@ namespace hud
protected override void OnResize(EventArgs e) protected override void OnResize(EventArgs e)
{ {
if (DesignMode) if (DesignMode || !started)
return; return;
this.Height = (int)(this.Width / 1.333f); this.Height = (int)(this.Width / 1.333f);
base.OnResize(e); base.OnResize(e);

View File

@ -591,11 +591,11 @@ namespace ArdupilotMega
temp.Dock = DockStyle.Fill; temp.Dock = DockStyle.Fill;
MyView.Controls.Add(temp);
temp.ForeColor = Color.White; temp.ForeColor = Color.White;
temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28); temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
MyView.Controls.Add(temp);
} }
private void MenuTerminal_Click(object sender, EventArgs e) private void MenuTerminal_Click(object sender, EventArgs e)
@ -1109,6 +1109,8 @@ namespace ArdupilotMega
GCSViews.FlightData.myhud.Invalidate(); GCSViews.FlightData.myhud.Invalidate();
} }
GC.Collect();
} }
if (speechenable && talk != null && (MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen)) if (speechenable && talk != null && (MainV2.comPort.logreadmode || comPort.BaseStream.IsOpen))
@ -1127,7 +1129,10 @@ namespace ArdupilotMega
} }
if (!comPort.BaseStream.IsOpen || givecomport == true) if (!comPort.BaseStream.IsOpen || givecomport == true)
{
System.Threading.Thread.Sleep(100);
continue; continue;
}
if (heatbeatsend.Second != DateTime.Now.Second) if (heatbeatsend.Second != DateTime.Now.Second)
{ {

View File

@ -29,22 +29,6 @@ namespace ArdupilotMega
//Common.linearRegression(); //Common.linearRegression();
var answer = HIL.Utils.EarthRatesToBodyRatesMine(0, 0, 0, 0, 5, 0);
Console.WriteLine("roll {0:0.000} {1:0.000} {2:0.000} ", answer.Item1 , answer.Item2 , answer.Item3);
answer = HIL.Utils.EarthRatesToBodyRatesMine(0, 0, 45, 0, 5, 0);
Console.WriteLine("roll {0:0.000} {1:0.000} {2:0.000} ", answer.Item1, answer.Item2, answer.Item3);
answer = HIL.Utils.EarthRatesToBodyRatesMine(0, 0, 90, 0, 5, 0);
Console.WriteLine("roll {0:0.000} {1:0.000} {2:0.000} ", answer.Item1, answer.Item2, answer.Item3);
answer = HIL.Utils.EarthRatesToBodyRatesMine(0, 0, 135, 0, 5, 0);
Console.WriteLine("roll {0:0.000} {1:0.000} {2:0.000} ", answer.Item1, answer.Item2, answer.Item3);
//Console.ReadLine();
//return;
Application.EnableVisualStyles(); Application.EnableVisualStyles();
Application.SetCompatibleTextRenderingDefault(false); Application.SetCompatibleTextRenderingDefault(false);
try try

View File

@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below: // by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")] // [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.0.0.0")] [assembly: AssemblyVersion("1.0.0.0")]
[assembly: AssemblyFileVersion("1.1.28")] [assembly: AssemblyFileVersion("1.1.29")]
[assembly: NeutralResourcesLanguageAttribute("")] [assembly: NeutralResourcesLanguageAttribute("")]

View File

@ -284,6 +284,9 @@ namespace ArdupilotMega.Setup
private void tabControl1_SelectedIndexChanged(object sender, EventArgs e) private void tabControl1_SelectedIndexChanged(object sender, EventArgs e)
{ {
int monosux = 0;
monosux *= 5;
if (tabControl1.SelectedTab == tabRadioIn) if (tabControl1.SelectedTab == tabRadioIn)
{ {
startup = true; startup = true;

View File

@ -1,346 +0,0 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
// Internal defines, don't edit and expect things to work
// -------------------------------------------------------
#define DEBUG 0
#define LOITER_RANGE 30 // for calculating power outside of loiter radius
// GPS baud rates
// --------------
#define NO_GPS 38400
#define NMEA_GPS 38400
#define EM406_GPS 57600
#define UBLOX_GPS 38400
#define ARDU_IMU 38400
#define MTK_GPS 38400
#define SIM_GPS 38400
// GPS type codes - use the names, not the numbers
#define GPS_PROTOCOL_NONE -1
#define GPS_PROTOCOL_NMEA 0
#define GPS_PROTOCOL_SIRF 1
#define GPS_PROTOCOL_UBLOX 2
#define GPS_PROTOCOL_IMU 3
#define GPS_PROTOCOL_MTK 4
// Radio channels
// Note channels are from 0!
//
// XXX these should be CH_n defines from RC.h at some point.
#define CH_ROLL 0
#define CH_PITCH 1
#define CH_THROTTLE 2
#define CH_RUDDER 3
#define CH_1 0
#define CH_2 1
#define CH_3 2
#define CH_4 3
#define CH_5 4
#define CH_6 5
#define CH_7 6
#define CH_8 7
#define WP_START_BYTE 0x130 // where in memory home WP is stored + all other WP
#define WP_SIZE 14
// GCS enumeration
#define GCS_PROTOCOL_STANDARD 0 // standard APM protocol
#define GCS_PROTOCOL_SPECIAL 1 // special test protocol (?)
#define GCS_PROTOCOL_LEGACY 2 // legacy ArduPilot protocol
#define GCS_PROTOCOL_XPLANE 3 // X-Plane HIL simulation
#define GCS_PROTOCOL_IMU 4 // ArdiPilot IMU output
#define GCS_PROTOCOL_JASON 5 // Jason's special secret GCS protocol
#define GCS_PROTOCOL_DEBUGTERMINAL 6 // Text-based interactive GCS
#define GCS_PROTOCOL_NONE -1 // No GCS output
// PID enumeration
// ---------------
#define CASE_SERVO_ROLL 0
#define CASE_SERVO_PITCH 1
#define CASE_SERVO_RUDDER 2
#define CASE_NAV_ROLL 3
#define CASE_NAV_PITCH_ASP 4
#define CASE_NAV_PITCH_ALT 5
#define CASE_TE_THROTTLE 6
#define CASE_ALT_THROTTLE 7
// Feedforward cases
// ----------------
#define CASE_PITCH_COMP 0
#define CASE_RUDDER_MIX 1
#define CASE_P_TO_T 2
#define CASE_T_TO_P 3
// Auto Pilot modes
// ----------------
#define MANUAL 0
#define CIRCLE 1 // When flying sans GPS, and we loose the radio, just circle
#define STABILIZE 2
#define FLY_BY_WIRE_A 5 // Fly By Wire A has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical = manual throttle
#define FLY_BY_WIRE_B 6 // Fly By Wire B has left stick horizontal => desired roll angle, left stick vertical => desired pitch angle, right stick vertical => desired airspeed
// Fly By Wire B = Fly By Wire A if you have AIRSPEED_SENSOR 0
#define AUTO 10
#define RTL 11
#define LOITER 12
#define TAKEOFF 13
#define LAND 14
// Command IDs - Must
#define CMD_BLANK 0x00 // there is no command stored in the mem location requested
#define CMD_WAYPOINT 0x10
#define CMD_LOITER 0x11
#define CMD_LOITER_N_TURNS 0x12
#define CMD_LOITER_TIME 0x13
#define CMD_RTL 0x14
#define CMD_LAND 0x15
#define CMD_TAKEOFF 0x16
// Command IDs - May
#define CMD_DELAY 0x20
#define CMD_CLIMB 0x21 // NOT IMPLEMENTED
#define CMD_LAND_OPTIONS 0x22 // pitch in deg, airspeed m/s, throttle %, track WP 1 or 0
// Command IDs - Now
//#define CMD_AP_MODE 0x30
#define CMD_RESET_INDEX 0x31
#define CMD_GOTO_INDEX 0x32 // NOT IMPLEMENTED
#define CMD_GETVAR_INDEX 0x33
#define CMD_SENDVAR_INDEX 0x34
#define CMD_TELEMETRY 0x35
#define CMD_THROTTLE_CRUISE 0x40
#define CMD_AIRSPEED_CRUISE 0x41
#define CMD_RESET_HOME 0x44
#define CMD_KP_GAIN 0x60
#define CMD_KI_GAIN 0x61
#define CMD_KD_GAIN 0x62
#define CMD_KI_MAX 0x63
#define CMD_KFF_GAIN 0x64
#define CMD_RADIO_TRIM 0x70
#define CMD_RADIO_MAX 0x71
#define CMD_RADIO_MIN 0x72
#define CMD_RADIO_MIN 0x72
#define CMD_ELEVON_TRIM 0x73
#define CMD_INDEX 0x75 // sets the current Must index
#define CMD_REPEAT 0x80
#define CMD_RELAY 0x81
#define CMD_SERVO 0x82 // move servo N to PWM value
//repeating events
#define NO_REPEAT 0
#define CH_4_TOGGLE 1
#define CH_5_TOGGLE 2
#define CH_6_TOGGLE 3
#define CH_7_TOGGLE 4
#define RELAY_TOGGLE 5
#define STOP_REPEAT 10
// GCS Message ID's
#define MSG_ACKNOWLEDGE 0x00
#define MSG_HEARTBEAT 0x01
#define MSG_ATTITUDE 0x02
#define MSG_LOCATION 0x03
#define MSG_PRESSURE 0x04
#define MSG_STATUS_TEXT 0x05
#define MSG_PERF_REPORT 0x06
#define MSG_COMMAND 0x22
#define MSG_VALUE 0x32
#define MSG_PID 0x42
#define MSG_TRIMS 0x50
#define MSG_MINS 0x51
#define MSG_MAXS 0x52
#define MSG_IMU_OUT 0x53
#define SEVERITY_LOW 1
#define SEVERITY_MEDIUM 2
#define SEVERITY_HIGH 3
#define SEVERITY_CRITICAL 4
// Logging parameters
#define LOG_ATTITUDE_MSG 0x01
#define LOG_GPS_MSG 0x02
#define LOG_MODE_MSG 0X03
#define LOG_CONTROL_TUNING_MSG 0X04
#define LOG_NAV_TUNING_MSG 0X05
#define LOG_PERFORMANCE_MSG 0X06
#define LOG_RAW_MSG 0x07
#define LOG_CMD_MSG 0x08
#define LOG_STARTUP_MSG 0x09
#define TYPE_AIRSTART_MSG 0x00
#define TYPE_GROUNDSTART_MSG 0x01
#define MASK_LOG_ATTITUDE_FAST 0
#define MASK_LOG_ATTITUDE_MED 2
#define MASK_LOG_GPS 4
#define MASK_LOG_PM 8
#define MASK_LOG_CTUN 16
#define MASK_LOG_NTUN 32
#define MASK_LOG_MODE 64
#define MASK_LOG_RAW 128
#define MASK_LOG_CMD 256
// Yaw modes
#define YAW_MODE_COORDINATE_TURNS 0
#define YAW_MODE_HOLD_HEADING 1
#define YAW_MODE_SLIP 2
// Waypoint Modes
// ----------------
#define ABS_WP 0
#define REL_WP 1
// Command Queues
// ---------------
#define COMMAND_MUST 0
#define COMMAND_MAY 1
#define COMMAND_NOW 2
// Events
// ------
#define EVENT_WILL_REACH_WAYPOINT 1
#define EVENT_SET_NEW_WAYPOINT_INDEX 2
#define EVENT_LOADED_WAYPOINT 3
#define EVENT_LOOP 4
//GPS_fix
#define VALID_GPS 0x00
#define BAD_GPS 0x01
#define FAILED_GPS 0x03
#define BATTERY_VOLTAGE(x) (x*(INPUT_VOLTAGE/1024.0))*VOLT_DIV_RATIO
#define AIRSPEED_CH 7 // The external ADC channel for the airspeed sensor
#define BATTERY_PIN1 0 // These are the pins for the voltage dividers
#define BATTERY_PIN2 1
#define BATTERY_PIN3 2
#define BATTERY_PIN4 3
#define RELAY_PIN 47
// Hardware Parameters
#define SLIDE_SWITCH_PIN 40
#define PUSHBUTTON_PIN 41
#define A_LED_PIN 37 //36 = B, 37 = A, 35 = C
#define B_LED_PIN 36
#define C_LED_PIN 35
#define HOLD_ALT_ABOVE_HOME 8 // bitmask value
// IMU Parameters
#define ADC_CONSTRAINT 900
#define TRUE 1
#define FALSE 0
#define ADC_WARM_CYCLES 200
#define SPEEDFILT 400 // centimeters/second
#define GYRO_TEMP_CH 3 // The ADC channel reading the gyro temperature
// ADC : Voltage reference 3.3v / 12bits(4096 steps) => 0.8mV/ADC step
// ADXL335 Sensitivity(from datasheet) => 330mV/g, 0.8mV/ADC step => 330/0.8 = 412
// Tested value : 418
#define GRAVITY 418 //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
#define ToRad(x) (x*0.01745329252) // *pi/180
#define ToDeg(x) (x*57.2957795131) // *180/pi
// IDG500 Sensitivity (from datasheet) => 2.0mV/º/s, 0.8mV/ADC step => 0.8/3.33 = 0.4
// Tested values : 0.4026, ?, 0.4192
#define Gyro_Gain_X 0.4 //X axis Gyro gain
#define Gyro_Gain_Y 0.41 //Y axis Gyro gain
#define Gyro_Gain_Z 0.41 //Z axis Gyro gain
#define Gyro_Scaled_X(x) x*ToRad(Gyro_Gain_X) //Return the scaled ADC raw data of the gyro in radians for second
#define Gyro_Scaled_Y(x) x*ToRad(Gyro_Gain_Y) //Return the scaled ADC raw data of the gyro in radians for second
#define Gyro_Scaled_Z(x) x*ToRad(Gyro_Gain_Z) //Return the scaled ADC raw data of the gyro in radians for second
#define Kp_ROLLPITCH 0.0014 // Pitch&Roll Drift Correction Proportional Gain
#define Ki_ROLLPITCH 0.0000003 // Pitch&Roll Drift Correction Integrator Gain
#define Kp_YAW 0.8 // Yaw Drift Correction Porportional Gain
#define Ki_YAW 0.00004 // Yaw Drift CorrectionIntegrator Gain
/*For debugging purposes*/
#define OUTPUTMODE 1 //If value = 1 will print the corrected data, 0 will print uncorrected data of the gyros (with drift), 2 Accel only data
#define EEPROM_MAX_ADDR 4096
// Radio setup
#define EE_TRIM 0x00
#define EE_MIN 0x10
#define EE_MAX 0x20
#define EE_ELEVON1_TRIM 0x30
#define EE_ELEVON2_TRIM 0x32
// user gains
#define EE_XTRACK_GAIN 0x34
#define EE_XTRACK_ANGLE 0x36
#define EE_ALT_MIX 0x3B
#define EE_HEAD_MAX 0x38
#define EE_PITCH_MAX 0x39
#define EE_PITCH_MIN 0x3A
#define EE_KP 0x40
#define EE_KI 0x60
#define EE_KD 0x80
#define EE_IMAX 0xA0
#define EE_KFF 0xC0
#define EE_AN_OFFSET 0xE0
#define EE_PITCH_TARGET 0x127
//mission specific
#define EE_CONFIG 0X0F8
#define EE_WP_MODE 0x0F9
#define EE_YAW_MODE 0x0FA // not used
#define EE_WP_TOTAL 0x0FB
#define EE_WP_INDEX 0x0FC
#define EE_WP_RADIUS 0x0FD
#define EE_LOITER_RADIUS 0x0FE
#define EE_ALT_HOLD_HOME 0x0FF
// user configs
#define EE_AIRSPEED_CRUISE 0x103
#define EE_AIRSPEED_RATIO 0x104
#define EE_AIRSPEED_FBW_MIN 0x108
#define EE_AIRSPEED_FBW_MAX 0x109
#define EE_THROTTLE_MIN 0x10A
#define EE_THROTTLE_CRUISE 0x10B
#define EE_THROTTLE_MAX 0x10C
#define EE_THROTTLE_FAILSAFE 0x10D
#define EE_THROTTLE_FS_VALUE 0x10E
#define EE_THROTTLE_FAILSAFE_ACTION 0x110
#define EE_FLIGHT_MODE_CHANNEL 0x112
#define EE_AUTO_TRIM 0x113
#define EE_LOG_BITMASK 0x114
#define EE_REVERSE_SWITCH 0x120
#define EE_FLIGHT_MODES 0x121
// sensors
#define EE_ABS_PRESS_GND 0x116
#define EE_GND_TEMP 0x11A
#define EE_GND_ALT 0x11C
#define EE_AP_OFFSET 0x11E
// log
#define EE_LAST_LOG_PAGE 0xE00
#define EE_LAST_LOG_NUM 0xE02
#define EE_LOG_1_START 0xE04
// bits in log_bitmask
#define LOGBIT_ATTITUDE_FAST (1<<0)
#define LOGBIT_ATTITUDE_MED (1<<1)
#define LOGBIT_GPS (1<<2)
#define LOGBIT_PM (1<<3)
#define LOGBIT_CTUN (1<<4)
#define LOGBIT_NTUN (1<<5)
#define LOGBIT_MODE (1<<6)
#define LOGBIT_RAW (1<<7)
#define LOGBIT_CMD (1<<8)

View File

@ -21,7 +21,11 @@
#include "APM_RC_APM1.h" #include "APM_RC_APM1.h"
#include <avr/interrupt.h> #include <avr/interrupt.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) #if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__)
# error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target. # error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target.

View File

@ -20,7 +20,11 @@
*/ */
#include "APM_RC_APM2.h" #include "APM_RC_APM2.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) #if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__)
# error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target. # error Please check the Tools/Board menu to ensure you have selected Arduino Mega as your target.

View File

@ -16,6 +16,14 @@ void setup()
{ {
isr_registry.init(); isr_registry.init();
APM_RC.Init(&isr_registry); // APM Radio initialization APM_RC.Init(&isr_registry); // APM Radio initialization
APM_RC.enable_out(CH_1);
APM_RC.enable_out(CH_2);
APM_RC.enable_out(CH_3);
APM_RC.enable_out(CH_4);
APM_RC.enable_out(CH_5);
APM_RC.enable_out(CH_6);
APM_RC.enable_out(CH_7);
APM_RC.enable_out(CH_8);
Serial.begin(115200); Serial.begin(115200);
Serial.println("ArduPilot Mega RC library test"); Serial.println("ArduPilot Mega RC library test");

View File

@ -17,6 +17,15 @@ void setup()
isr_registry.init(); isr_registry.init();
APM_RC.Init(&isr_registry); // APM Radio initialization APM_RC.Init(&isr_registry); // APM Radio initialization
APM_RC.enable_out(CH_1);
APM_RC.enable_out(CH_2);
APM_RC.enable_out(CH_3);
APM_RC.enable_out(CH_4);
APM_RC.enable_out(CH_5);
APM_RC.enable_out(CH_6);
APM_RC.enable_out(CH_7);
APM_RC.enable_out(CH_8);
Serial.begin(115200); Serial.begin(115200);
Serial.println("ArduPilot Mega RC library test"); Serial.println("ArduPilot Mega RC library test");
delay(1000); delay(1000);

View File

@ -44,15 +44,19 @@
Channel 7 : Differential pressure sensor port Channel 7 : Differential pressure sensor port
*/ */
#include "AP_ADC_ADS7844.h"
extern "C" { extern "C" {
// AVR LibC Includes // AVR LibC Includes
#include <inttypes.h> #include <inttypes.h>
#include <stdint.h> #include <stdint.h>
#include <avr/interrupt.h> #include <avr/interrupt.h>
#include "WConstants.h"
} }
#if defined(ARDUINO) && ARDUINO >= 100
#include "AP_ADC_ADS7844.h" #include "Arduino.h"
#else
#include "WConstants.h"
#endif
// Commands for reading ADC channels on ADS7844 // Commands for reading ADC channels on ADS7844
static const unsigned char adc_cmd[9] = { 0x87, 0xC7, 0x97, 0xD7, 0xA7, 0xE7, 0xB7, 0xF7, 0x00 }; static const unsigned char adc_cmd[9] = { 0x87, 0xC7, 0x97, 0xD7, 0xA7, 0xE7, 0xB7, 0xF7, 0x00 };

View File

@ -1,5 +1,9 @@
#include "AP_ADC_HIL.h" #include "AP_ADC_HIL.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
/* /*
AP_ADC_HIL.cpp AP_ADC_HIL.cpp

View File

@ -1,6 +1,10 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "wiring.h" #include "wiring.h"
#endif
#include "AP_AnalogSource_Arduino.h" #include "AP_AnalogSource_Arduino.h"
float AP_AnalogSource_Arduino::read(void) float AP_AnalogSource_Arduino::read(void)

View File

@ -39,8 +39,12 @@ extern "C" {
// AVR LibC Includes // AVR LibC Includes
#include <inttypes.h> #include <inttypes.h>
#include <avr/interrupt.h> #include <avr/interrupt.h>
#include "WConstants.h"
} }
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WConstants.h"
#endif
#include <AP_Common.h> #include <AP_Common.h>
#include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library #include <AP_Math.h> // ArduPilot Mega Vector/Matrix math Library

View File

@ -4,8 +4,12 @@ extern "C" {
// AVR LibC Includes // AVR LibC Includes
#include <inttypes.h> #include <inttypes.h>
#include <avr/interrupt.h> #include <avr/interrupt.h>
#include "WConstants.h"
} }
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WConstants.h"
#endif
#include "AP_Baro_BMP085_hil.h" #include "AP_Baro_BMP085_hil.h"

View File

@ -16,7 +16,11 @@
#define _AP_COMMON_H #define _AP_COMMON_H
// Get the common arduino functions // Get the common arduino functions
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "wiring.h" #include "wiring.h"
#endif
// ... and remove some of their stupid macros // ... and remove some of their stupid macros
#undef round #undef round
#undef abs #undef abs

View File

@ -22,7 +22,11 @@
#include "../FastSerial/BetterStream.h" #include "../FastSerial/BetterStream.h"
#include <stdlib.h> #include <stdlib.h>
#include <inttypes.h> #include <inttypes.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include <WProgram.h> #include <WProgram.h>
#endif
#ifdef ASSERT #ifdef ASSERT
const static char vectorSource[] ="Vector.hpp"; const static char vectorSource[] ="Vector.hpp";

View File

@ -9,7 +9,11 @@
#include <stdlib.h> #include <stdlib.h>
#include "c++.h" #include "c++.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
void * operator new(size_t size) void * operator new(size_t size)
{ {

View File

@ -15,8 +15,12 @@
// AVR LibC Includes // AVR LibC Includes
#include <math.h> #include <math.h>
#include "WConstants.h"
#include <FastSerial.h> #include <FastSerial.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WConstants.h"
#endif
#include <I2C.h> #include <I2C.h>
#include "AP_Compass_HMC5843.h" #include "AP_Compass_HMC5843.h"

View File

@ -10,12 +10,15 @@
#include "../FastSerial/FastSerial.h" #include "../FastSerial/FastSerial.h"
#include "../AP_Math/AP_Math.h" #include "../AP_Math/AP_Math.h"
#include <inttypes.h> #include <inttypes.h>
#include "WProgram.h"
#include "../AP_Compass/AP_Compass.h" #include "../AP_Compass/AP_Compass.h"
#include "../AP_ADC/AP_ADC.h" #include "../AP_ADC/AP_ADC.h"
#include "../AP_GPS/AP_GPS.h" #include "../AP_GPS/AP_GPS.h"
#include "../AP_IMU/AP_IMU.h" #include "../AP_IMU/AP_IMU.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
class AP_DCM class AP_DCM
{ {

View File

@ -4,11 +4,15 @@
#include "../FastSerial/FastSerial.h" #include "../FastSerial/FastSerial.h"
#include "../AP_Math/AP_Math.h" #include "../AP_Math/AP_Math.h"
#include <inttypes.h> #include <inttypes.h>
#include "WProgram.h"
#include "../AP_Compass/AP_Compass.h" #include "../AP_Compass/AP_Compass.h"
#include "../AP_ADC/AP_ADC.h" #include "../AP_ADC/AP_ADC.h"
#include "../AP_GPS/AP_GPS.h" #include "../AP_GPS/AP_GPS.h"
#include "../AP_IMU/AP_IMU.h" #include "../AP_IMU/AP_IMU.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
class AP_DCM_HIL class AP_DCM_HIL

View File

@ -6,8 +6,11 @@
#ifndef AP_EEPROMB_h #ifndef AP_EEPROMB_h
#define AP_EEPROMB_h #define AP_EEPROMB_h
//#include <stdint.h> #if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
/// @class AP_EEPROMB /// @class AP_EEPROMB
/// @brief Object for reading and writing to the EEPROM /// @brief Object for reading and writing to the EEPROM

View File

@ -11,7 +11,11 @@
#include "../FastSerial/FastSerial.h" // because we need to change baud rates... ugh. #include "../FastSerial/FastSerial.h" // because we need to change baud rates... ugh.
#include "AP_GPS_406.h" #include "AP_GPS_406.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
static const char init_str[] = "$PSRF100,0,57600,8,1,0*37"; static const char init_str[] = "$PSRF100,0,57600,8,1,0*37";

View File

@ -12,7 +12,11 @@
// //
#include "AP_GPS_HIL.h" #include "AP_GPS_HIL.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
// Constructors //////////////////////////////////////////////////////////////// // Constructors ////////////////////////////////////////////////////////////////
AP_GPS_HIL::AP_GPS_HIL(Stream *s) : GPS(s) AP_GPS_HIL::AP_GPS_HIL(Stream *s) : GPS(s)

View File

@ -28,7 +28,11 @@
*/ */
#include "AP_GPS_IMU.h" #include "AP_GPS_IMU.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
// Constructors //////////////////////////////////////////////////////////////// // Constructors ////////////////////////////////////////////////////////////////

View File

@ -13,7 +13,11 @@
#include "AP_GPS_MTK16.h" #include "AP_GPS_MTK16.h"
#include <stdint.h> #include <stdint.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include <wiring.h> #include <wiring.h>
#endif
// Constructors //////////////////////////////////////////////////////////////// // Constructors ////////////////////////////////////////////////////////////////
AP_GPS_MTK16::AP_GPS_MTK16(Stream *s) : GPS(s) AP_GPS_MTK16::AP_GPS_MTK16(Stream *s) : GPS(s)

View File

@ -1,7 +1,11 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- // -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
#include "GPS.h" #include "GPS.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
void void
GPS::update(void) GPS::update(void)

View File

@ -3,8 +3,12 @@
#include "AP_InertialSensor_MPU6000.h" #include "AP_InertialSensor_MPU6000.h"
#include <wiring.h>
#include <SPI.h> #include <SPI.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include <wiring.h>
#endif
// MPU 6000 registers // MPU 6000 registers
#define MPUREG_WHOAMI 0x75 // #define MPUREG_WHOAMI 0x75 //

View File

@ -6,7 +6,11 @@
#define XTRACK_ENTRY_ANGLE 3000 // Max angle used to correct for track following degrees*100 #define XTRACK_ENTRY_ANGLE 3000 // Max angle used to correct for track following degrees*100
#include <GPS.h> // ArduPilot GPS Library #include <GPS.h> // ArduPilot GPS Library
#include "Waypoints.h" // ArduPilot Waypoints Library #include "Waypoints.h" // ArduPilot Waypoints Library
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
#define T7 10000000 #define T7 10000000

View File

@ -24,8 +24,12 @@
*/ */
#include "AP_OpticalFlow_ADNS3080.h" #include "AP_OpticalFlow_ADNS3080.h"
#include "WProgram.h"
#include "SPI.h" #include "SPI.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#define AP_SPI_TIMEOUT 1000 #define AP_SPI_TIMEOUT 1000
@ -190,11 +194,14 @@ AP_OpticalFlow_ADNS3080::reset()
bool bool
AP_OpticalFlow_ADNS3080::update() AP_OpticalFlow_ADNS3080::update()
{ {
byte motion_reg;
surface_quality = (unsigned int)read_register(ADNS3080_SQUAL); surface_quality = (unsigned int)read_register(ADNS3080_SQUAL);
delayMicroseconds(50); // small delay delayMicroseconds(50); // small delay
// check for movement, update x,y values // check for movement, update x,y values
if( (read_register(ADNS3080_MOTION) & 0x80) != 0 ) { motion_reg = read_register(ADNS3080_MOTION);
_overflow = ((motion_reg & 0x10) != 0); // check if we've had an overflow
if( (motion_reg & 0x80) != 0 ) {
raw_dx = ((char)read_register(ADNS3080_DELTA_X)); raw_dx = ((char)read_register(ADNS3080_DELTA_X));
delayMicroseconds(50); // small delay delayMicroseconds(50); // small delay
raw_dy = ((char)read_register(ADNS3080_DELTA_Y)); raw_dy = ((char)read_register(ADNS3080_DELTA_Y));

View File

@ -101,6 +101,7 @@ class AP_OpticalFlow_ADNS3080 : public AP_OpticalFlow
int _cs_pin; // pin used for chip select int _cs_pin; // pin used for chip select
int _reset_pin; // pin used for chip reset int _reset_pin; // pin used for chip reset
bool _motion; // true if there has been motion bool _motion; // true if there has been motion
bool _overflow; // true if the x or y data buffers overflowed
public: public:
AP_OpticalFlow_ADNS3080(int cs_pin = ADNS3080_CHIP_SELECT, int reset_pin = ADNS3080_RESET); AP_OpticalFlow_ADNS3080(int cs_pin = ADNS3080_CHIP_SELECT, int reset_pin = ADNS3080_RESET);

View File

@ -21,7 +21,7 @@
FastSerialPort0(Serial); // FTDI/console FastSerialPort0(Serial); // FTDI/console
AP_OpticalFlow_ADNS3080 flowSensor; AP_OpticalFlow_ADNS3080 flowSensor;
//AP_OpticalFlow_ADNS3080 flowSensor(A6); // override chip select pin to use A6 if using APM2 //AP_OpticalFlow_ADNS3080 flowSensor(A3); // override chip select pin to use A3 if using APM2
void setup() void setup()
{ {
@ -110,7 +110,6 @@ void display_config()
void set_frame_rate() void set_frame_rate()
{ {
int value; int value;
byte extConfig;
// frame rate // frame rate
Serial.print("frame rate: "); Serial.print("frame rate: ");
@ -196,7 +195,6 @@ void display_image_continuously()
void set_resolution() void set_resolution()
{ {
int value; int value;
byte reg;
int resolution = flowSensor.get_resolution(); int resolution = flowSensor.get_resolution();
Serial.print("resolution: "); Serial.print("resolution: ");
Serial.println(resolution); Serial.println(resolution);
@ -231,7 +229,6 @@ void set_resolution()
void set_shutter_speed() void set_shutter_speed()
{ {
int value; int value;
byte extConfig;
// shutter speed // shutter speed
Serial.print("shutter speed: "); Serial.print("shutter speed: ");
@ -300,7 +297,6 @@ void set_shutter_speed()
// //
void display_motion() void display_motion()
{ {
int value;
boolean first_time = true; boolean first_time = true;
Serial.flush(); Serial.flush();
@ -312,8 +308,11 @@ void display_motion()
flowSensor.update(); flowSensor.update();
flowSensor.update_position(0,0,0,1,100); flowSensor.update_position(0,0,0,1,100);
// check for errors
if( flowSensor._overflow )
Serial.println("overflow!!");
// x,y,squal // x,y,squal
//if( flowSensor.motion() || first_time ) {
Serial.print("x/dx: "); Serial.print("x/dx: ");
Serial.print(flowSensor.x,DEC); Serial.print(flowSensor.x,DEC);
Serial.print("/"); Serial.print("/");
@ -326,7 +325,6 @@ void display_motion()
Serial.print(flowSensor.surface_quality,DEC); Serial.print(flowSensor.surface_quality,DEC);
Serial.println(); Serial.println();
first_time = false; first_time = false;
//}
// short delay // short delay
delay(100); delay(100);

View File

@ -5,9 +5,13 @@
extern "C" { extern "C" {
#include <inttypes.h> #include <inttypes.h>
#include <stdint.h> #include <stdint.h>
#include "WConstants.h"
#include <avr/interrupt.h> #include <avr/interrupt.h>
} }
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WConstants.h"
#endif
uint8_t AP_TimerProcess::_period; uint8_t AP_TimerProcess::_period;
ap_procedure AP_TimerProcess::_proc[AP_TIMERPROCESS_MAX_PROCS]; ap_procedure AP_TimerProcess::_proc[AP_TIMERPROCESS_MAX_PROCS];

View File

@ -10,8 +10,12 @@
*/ */
#include "AP_RC.h" #include "AP_RC.h"
#include "WProgram.h"
#include <avr/interrupt.h> #include <avr/interrupt.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
// Variable definition for interrupt // Variable definition for interrupt
volatile uint16_t timer1count = 0; volatile uint16_t timer1count = 0;

View File

@ -11,7 +11,11 @@
#include <math.h> #include <math.h>
#include <avr/eeprom.h> #include <avr/eeprom.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
#include "AP_RC_Channel.h" #include "AP_RC_Channel.h"
#define ANGLE 0 #define ANGLE 0

View File

@ -26,7 +26,11 @@
*/ */
// AVR LibC Includes // AVR LibC Includes
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WConstants.h" #include "WConstants.h"
#endif
#include "AP_RangeFinder_MaxsonarXL.h" #include "AP_RangeFinder_MaxsonarXL.h"
// Constructor ////////////////////////////////////////////////////////////// // Constructor //////////////////////////////////////////////////////////////

View File

@ -26,7 +26,11 @@
*/ */
// AVR LibC Includes // AVR LibC Includes
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WConstants.h" #include "WConstants.h"
#endif
#include "AP_RangeFinder_SharpGP2Y.h" #include "AP_RangeFinder_SharpGP2Y.h"
// Constructor ////////////////////////////////////////////////////////////// // Constructor //////////////////////////////////////////////////////////////

View File

@ -13,7 +13,11 @@
*/ */
// AVR LibC Includes // AVR LibC Includes
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WConstants.h" #include "WConstants.h"
#endif
#include "RangeFinder.h" #include "RangeFinder.h"

View File

@ -30,7 +30,7 @@ ModeFilter mode_filter;
AP_ADC_ADS7844 adc; AP_ADC_ADS7844 adc;
AP_AnalogSource_ADC adc_source(&adc, AP_RANGEFINDER_PITOT_TYPE_ADC_CHANNEL, 0.25); // use Pitot tube AP_AnalogSource_ADC adc_source(&adc, AP_RANGEFINDER_PITOT_TYPE_ADC_CHANNEL, 0.25); // use Pitot tube
#else #else
AP_AnalogSource_Arduino adc_source(A1); // use AN1 analog pin (APM1: on oilpan at back right near the CLI switch. APM2: on left) AP_AnalogSource_Arduino adc_source(A0); // use AN0 analog pin for APM2 on left
#endif #endif
// create the range finder object // create the range finder object

View File

@ -8,7 +8,11 @@
*/ */
#include <avr/io.h> #include <avr/io.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "wiring.h" #include "wiring.h"
#endif
#include "AP_Relay.h" #include "AP_Relay.h"

View File

@ -36,8 +36,12 @@ extern "C" {
// AVR LibC Includes // AVR LibC Includes
#include <inttypes.h> #include <inttypes.h>
#include <avr/interrupt.h> #include <avr/interrupt.h>
#include "WConstants.h"
} }
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WConstants.h"
#endif
#include "DataFlash_APM2.h" #include "DataFlash_APM2.h"

View File

@ -31,7 +31,12 @@
//#include "../AP_Common/AP_Common.h" //#include "../AP_Common/AP_Common.h"
#include "FastSerial.h" #include "FastSerial.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
#if defined(UDR3) #if defined(UDR3)
# define FS_MAX_PORTS 4 # define FS_MAX_PORTS 4
@ -197,6 +202,30 @@ void FastSerial::flush(void)
_txBuffer->tail = _txBuffer->head; _txBuffer->tail = _txBuffer->head;
} }
#if defined(ARDUINO) && ARDUINO >= 100
size_t FastSerial::write(uint8_t c)
{
uint16_t i;
if (!_open) // drop bytes if not open
return 0;
// wait for room in the tx buffer
i = (_txBuffer->head + 1) & _txBuffer->mask;
while (i == _txBuffer->tail)
;
// add byte to the buffer
_txBuffer->bytes[_txBuffer->head] = c;
_txBuffer->head = i;
// enable the data-ready interrupt, as it may be off if the buffer is empty
*_ucsrb |= _portTxBits;
// return number of bytes written (always 1)
return 1;
}
#else
void FastSerial::write(uint8_t c) void FastSerial::write(uint8_t c)
{ {
uint16_t i; uint16_t i;
@ -216,6 +245,7 @@ void FastSerial::write(uint8_t c)
// enable the data-ready interrupt, as it may be off if the buffer is empty // enable the data-ready interrupt, as it may be off if the buffer is empty
*_ucsrb |= _portTxBits; *_ucsrb |= _portTxBits;
} }
#endif
// Buffer management /////////////////////////////////////////////////////////// // Buffer management ///////////////////////////////////////////////////////////

View File

@ -116,7 +116,11 @@ public:
virtual int read(void); virtual int read(void);
virtual int peek(void); virtual int peek(void);
virtual void flush(void); virtual void flush(void);
#if defined(ARDUINO) && ARDUINO >= 100
virtual size_t write(uint8_t c);
#else
virtual void write(uint8_t c); virtual void write(uint8_t c);
#endif
using BetterStream::write; using BetterStream::write;
//@} //@}

View File

@ -31,9 +31,13 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/ */
#include "WProgram.h"
#include <inttypes.h> #include <inttypes.h>
#include "I2C.h" #include "I2C.h"
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif

View File

@ -31,8 +31,12 @@
Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
*/ */
#include "WProgram.h"
#include <inttypes.h> #include <inttypes.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#ifndef I2C_h #ifndef I2C_h
#define I2C_h #define I2C_h

View File

@ -14,7 +14,11 @@
#include "ModeFilter.h" #include "ModeFilter.h"
#include <avr/interrupt.h> #include <avr/interrupt.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
// Constructors //////////////////////////////////////////////////////////////// // Constructors ////////////////////////////////////////////////////////////////

View File

@ -11,7 +11,11 @@
#include <math.h> #include <math.h>
#include <avr/eeprom.h> #include <avr/eeprom.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h" #include "WProgram.h"
#endif
#include "RC_Channel.h" #include "RC_Channel.h"
#define RC_CHANNEL_ANGLE 0 #define RC_CHANNEL_ANGLE 0

View File

@ -2,8 +2,12 @@
#define Waypoints_h #define Waypoints_h
#include <inttypes.h> #include <inttypes.h>
#include "WProgram.h"
#include <avr/eeprom.h> #include <avr/eeprom.h>
#if defined(ARDUINO) && ARDUINO >= 100
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
class Waypoints class Waypoints
{ {