diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde
index 687751530e..fc8136f937 100644
--- a/ArduCopter/ArduCopter.pde
+++ b/ArduCopter/ArduCopter.pde
@@ -7,7 +7,6 @@ Authors: Jason Short
Based on code and ideas from the Arducopter team: Jose Julio, Randy Mackay, Jani Hirvinen
Thanks to: Chris Anderson, Mike Smith, Jordi Munoz, Doug Weibel, James Goppert, Benjamin Pelletier
-
This firmware is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
@@ -393,7 +392,6 @@ static int16_t airspeed; // m/s * 100
// Location Errors
// ---------------
-static int32_t yaw_error; // how off are we pointed
static int32_t long_error, lat_error; // temp for debugging
// Battery Sensors
@@ -440,32 +438,32 @@ static byte throttle_mode;
static boolean takeoff_complete; // Flag for using take-off controls
static boolean land_complete;
static int32_t old_alt; // used for managing altitude rates
-static int16_t velocity_land;
+static int16_t velocity_land;
static byte yaw_tracking = MAV_ROI_WPNEXT; // no tracking, point at next wp, or at a target
-static int16_t manual_boost; // used in adjust altitude to make changing alt faster
-static int16_t angle_boost; // used in adjust altitude to make changing alt faster
+static int16_t manual_boost; // used in adjust altitude to make changing alt faster
+static int16_t angle_boost; // used in adjust altitude to make changing alt faster
// Loiter management
// -----------------
static int32_t original_target_bearing; // deg * 100, used to check we are not passing the WP
static int32_t old_target_bearing; // used to track difference in angle
-static int16_t loiter_total; // deg : how many times to loiter * 360
-static int16_t loiter_sum; // deg : how far we have turned around a waypoint
+static int16_t loiter_total; // deg : how many times to loiter * 360
+static int16_t loiter_sum; // deg : how far we have turned around a waypoint
static uint32_t loiter_time; // millis : when we started LOITER mode
static unsigned loiter_time_max; // millis : how long to stay in LOITER mode
// these are the values for navigation control functions
// ----------------------------------------------------
-static int32_t nav_roll; // deg * 100 : target roll angle
-static int32_t nav_pitch; // deg * 100 : target pitch angle
-static int32_t nav_yaw; // deg * 100 : target yaw angle
-static int32_t auto_yaw; // deg * 100 : target yaw angle
-static int32_t nav_lat; // for error calcs
-static int32_t nav_lon; // for error calcs
-static int16_t nav_throttle; // 0-1000 for throttle control
-static int16_t crosstrack_error;
+static int32_t nav_roll; // deg * 100 : target roll angle
+static int32_t nav_pitch; // deg * 100 : target pitch angle
+static int32_t nav_yaw; // deg * 100 : target yaw angle
+static int32_t auto_yaw; // deg * 100 : target yaw angle
+static int32_t nav_lat; // for error calcs
+static int32_t nav_lon; // for error calcs
+static int16_t nav_throttle; // 0-1000 for throttle control
+static int16_t crosstrack_error;
static uint32_t throttle_integrator; // used to integrate throttle output to predict battery life
static bool invalid_throttle; // used to control when we calculate nav_throttle
@@ -490,12 +488,12 @@ static int32_t wp_totalDistance; // meters - distance between old and next w
// repeating event control
// -----------------------
-static byte event_id; // what to do - see defines
-static uint32_t event_timer; // when the event was asked for in ms
-static uint16_t event_delay; // how long to delay the next firing of event in millis
-static int16_t event_repeat; // how many times to fire : 0 = forever, 1 = do once, 2 = do twice
-static int16_t event_value; // per command value, such as PWM for servos
-static int16_t event_undo_value; // the value used to undo commands
+static byte event_id; // what to do - see defines
+static uint32_t event_timer; // when the event was asked for in ms
+static uint16_t event_delay; // how long to delay the next firing of event in millis
+static int16_t event_repeat; // how many times to fire : 0 = forever, 1 = do once, 2 = do twice
+static int16_t event_value; // per command value, such as PWM for servos
+static int16_t event_undo_value; // the value used to undo commands
//static byte repeat_forever;
//static byte undo_event; // counter for timing the undo
@@ -1146,9 +1144,9 @@ void update_throttle_mode(void)
//remove alt_hold_velocity when implemented
#if FRAME_CONFIG == HELI_FRAME
- g.rc_3.servo_out = heli_get_angle_boost(g.throttle_cruise + manual_boost + get_z_damping());
+ g.rc_3.servo_out = heli_get_angle_boost(g.throttle_cruise + manual_boost);
#else
- g.rc_3.servo_out = g.throttle_cruise + angle_boost + manual_boost + get_z_damping();
+ g.rc_3.servo_out = g.throttle_cruise + angle_boost + manual_boost;
#endif
// reset next_WP.alt
@@ -1398,14 +1396,14 @@ adjust_altitude()
// we remove 0 to 100 PWM from hover
manual_boost = g.rc_3.control_in - 180;
manual_boost = max(-120, manual_boost);
- g.throttle_cruise += (g.pi_alt_hold.get_integrator() * g.pi_throttle.kP() + g.pi_throttle.get_integrator());
+ g.throttle_cruise += g.pi_alt_hold.get_integrator();
g.pi_alt_hold.reset_I();
g.pi_throttle.reset_I();
}else if (g.rc_3.control_in >= 650){
// we add 0 to 100 PWM to hover
manual_boost = g.rc_3.control_in - 650;
- g.throttle_cruise += (g.pi_alt_hold.get_integrator() * g.pi_throttle.kP() + g.pi_throttle.get_integrator());
+ g.throttle_cruise += g.pi_alt_hold.get_integrator();
g.pi_alt_hold.reset_I();
g.pi_throttle.reset_I();
@@ -1439,7 +1437,7 @@ static void tuning(){
break;
case CH6_RATE_KP:
- g.rc_6.set_range(0,300); // 0 to .3
+ g.rc_6.set_range(40,300); // 0 to .3
g.pi_rate_roll.kP(tuning_value);
g.pi_rate_pitch.kP(tuning_value);
break;
diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde
index 3aec0b6207..944786194f 100644
--- a/ArduCopter/Attitude.pde
+++ b/ArduCopter/Attitude.pde
@@ -13,18 +13,15 @@ get_stabilize_roll(int32_t target_angle)
error = constrain(error, -2500, 2500);
// conver to desired Rate:
- rate = g.pi_stabilize_roll.get_pi(error, G_Dt);
+ rate = g.pi_stabilize_roll.get_p(error);
// experiment to pipe iterm directly into the output
- int16_t iterm = g.pi_stabilize_roll.get_integrator();
+ int16_t iterm = g.pi_stabilize_roll.get_i(error, G_Dt);
- // remove iterm from PI output
- rate -= iterm;
-
-#if FRAME_CONFIG != HELI_FRAME // cannot use rate control for helicopters
+ #if FRAME_CONFIG != HELI_FRAME // cannot use rate control for helicopters
error = rate - (omega.x * DEGX100);
rate = g.pi_rate_roll.get_pi(error, G_Dt);
-#endif
+ #endif
// output control:
rate = constrain(rate, -2500, 2500);
@@ -43,19 +40,16 @@ get_stabilize_pitch(int32_t target_angle)
// limit the error we're feeding to the PID
error = constrain(error, -2500, 2500);
- // conver to desired Rate:
- rate = g.pi_stabilize_pitch.get_pi(error, G_Dt);
+ // convert to desired Rate:
+ rate = g.pi_stabilize_pitch.get_p(error);
// experiment to pipe iterm directly into the output
- int16_t iterm = g.pi_stabilize_roll.get_integrator();
+ int16_t iterm = g.pi_stabilize_roll.get_i(error, G_Dt);
- // remove iterm from PI output
- rate -= iterm;
-
-#if FRAME_CONFIG != HELI_FRAME // cannot use rate control for helicopters
+ #if FRAME_CONFIG != HELI_FRAME // cannot use rate control for helicopters
error = rate - (omega.y * DEGX100);
rate = g.pi_rate_pitch.get_pi(error, G_Dt);
-#endif
+ #endif
// output control:
rate = constrain(rate, -2500, 2500);
@@ -70,46 +64,61 @@ get_stabilize_yaw(int32_t target_angle)
int32_t error;
int32_t rate;
- yaw_error = wrap_180(target_angle - dcm.yaw_sensor);
+ // angle error
+ error = wrap_180(target_angle - dcm.yaw_sensor);
// limit the error we're feeding to the PID
- yaw_error = constrain(yaw_error, -YAW_ERROR_MAX, YAW_ERROR_MAX);
- rate = g.pi_stabilize_yaw.get_pi(yaw_error, G_Dt);
- //Serial.printf("%u\t%d\t%d\t", (int)target_angle, (int)error, (int)rate);
+ error = constrain(error, -YAW_ERROR_MAX, YAW_ERROR_MAX);
+
+ // convert to desired Rate:
+ rate = g.pi_stabilize_yaw.get_p(error);
+
+ // experiment to pipe iterm directly into the output
+ int16_t iterm = g.pi_stabilize_yaw.get_i(error, G_Dt);
#if FRAME_CONFIG == HELI_FRAME // cannot use rate control for helicopters
- if( ! g.heli_ext_gyro_enabled ) {
- // Rate P:
- error = rate - (degrees(omega.z) * 100.0);
- rate = g.pi_rate_yaw.get_pi(error, G_Dt);
+ if(!g.heli_ext_gyro_enabled ) {
+ error = rate - (degrees(omega.z) * 100.0);
+ rate = g.pi_rate_yaw.get_pi(error, G_Dt);
}
-
// output control:
- return (int)constrain(rate, -4500, 4500);
+ rate = constrain(rate, -4500, 4500);
+ return (int)rate + iterm;
#else
- // Rate P:
- error = rate - (degrees(omega.z) * 100.0);
- rate = g.pi_rate_yaw.get_pi(error, G_Dt);
- //Serial.printf("%d\t%d\n", (int)error, (int)rate);
+ error = rate - (omega.z * DEGX100);;
+ rate = g.pi_rate_yaw.get_pi(error, G_Dt);
// output control:
- return (int)constrain(rate, -2500, 2500);
+ rate = constrain(rate, -2500, 2500);
+ return (int)rate + iterm;
#endif
-
}
#define ALT_ERROR_MAX 300
-static int
+static int16_t
get_nav_throttle(int32_t z_error)
{
- bool calc_i = (abs(z_error) < ALT_ERROR_MAX);
+ int16_t rate_error;
+
+ float dt = (abs(z_error) < 200) ? .1 : 0.0;
+
// limit error to prevent I term run up
z_error = constrain(z_error, -ALT_ERROR_MAX, ALT_ERROR_MAX);
- int rate_error = g.pi_alt_hold.get_pi(z_error, .1, calc_i); //_p = .85
+
+ // convert to desired Rate:
+ rate_error = g.pi_alt_hold.get_p(z_error); //_p = .85
+
+ // experiment to pipe iterm directly into the output
+ int16_t iterm = g.pi_alt_hold.get_i(z_error, dt);
+
+ // calculate rate error
rate_error = rate_error - climb_rate;
// limit the rate
- return constrain((int)g.pi_throttle.get_pi(rate_error, .1), -120, 180);
+ rate_error = constrain((int)g.pi_throttle.get_pi(rate_error, .1), -120, 180);
+
+ // output control:
+ return rate_error + iterm;
}
static int
diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde
index 42d854afc0..09c607de22 100644
--- a/ArduCopter/Log.pde
+++ b/ArduCopter/Log.pde
@@ -108,7 +108,16 @@ dump_log(uint8_t argc, const Menu::arg *argv)
// check that the requested log number can be read
dump_log = argv[1].i;
last_log_num = g.log_last_filenumber;
- if (dump_log <= 0) {
+
+ if (dump_log == -2) {
+ for(int count=1; count<=DF_LAST_PAGE; count++) {
+ DataFlash.StartRead(count);
+ Serial.printf_P(PSTR("DF page, log file #, log page: %d,\t"), count);
+ Serial.printf_P(PSTR("%d,\t"), DataFlash.GetFileNumber());
+ Serial.printf_P(PSTR("%d\n"), DataFlash.GetFilePage());
+ }
+ return(-1);
+ } else if (dump_log <= 0) {
Serial.printf_P(PSTR("dumping all\n"));
Log_Read(1, DF_LAST_PAGE);
return(-1);
diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde
index de3fb66354..44d40dd3e9 100644
--- a/ArduCopter/commands_logic.pde
+++ b/ArduCopter/commands_logic.pde
@@ -470,8 +470,8 @@ static bool verify_RTL()
{
// loiter at the WP
wp_control = WP_MODE;
- // Did we pass the WP? // Distance checking
+ // Did we pass the WP? // Distance checking
if((wp_distance <= g.waypoint_radius) || check_missed_wp()){
wp_control = LOITER_MODE;
diff --git a/ArduCopter/config.h b/ArduCopter/config.h
index fe2d26598a..3fe6b47297 100644
--- a/ArduCopter/config.h
+++ b/ArduCopter/config.h
@@ -628,7 +628,7 @@
// RATE control
#ifndef THROTTLE_P
-# define THROTTLE_P 0.5 //
+# define THROTTLE_P 0.4 //
#endif
#ifndef THROTTLE_I
# define THROTTLE_I 0.0 //
diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde
index 01718439e2..243f25c8eb 100644
--- a/ArduCopter/navigation.pde
+++ b/ArduCopter/navigation.pde
@@ -61,8 +61,10 @@ static void calc_loiter(int x_error, int y_error)
x_error = constrain(x_error, -NAV_ERR_MAX, NAV_ERR_MAX);
y_error = constrain(y_error, -NAV_ERR_MAX, NAV_ERR_MAX);
- int x_target_speed = g.pi_loiter_lon.get_pi(x_error, dTnav);
- int y_target_speed = g.pi_loiter_lat.get_pi(y_error, dTnav);
+ int x_target_speed = g.pi_loiter_lon.get_p(x_error);
+ int y_target_speed = g.pi_loiter_lat.get_p(y_error);
+ int x_iterm = g.pi_loiter_lon.get_i(x_error, dTnav);
+ int y_iterm = g.pi_loiter_lon.get_i(y_error, dTnav);
// find the rates:
float temp = g_gps->ground_course * RADX100;
@@ -85,11 +87,13 @@ static void calc_loiter(int x_error, int y_error)
y_rate_error = constrain(y_rate_error, -250, 250); // added a rate error limit to keep pitching down to a minimum
nav_lat = g.pi_nav_lat.get_pi(y_rate_error, dTnav);
nav_lat = constrain(nav_lat, -3500, 3500);
+ nav_lat += y_iterm;
x_rate_error = x_target_speed - x_actual_speed;
x_rate_error = constrain(x_rate_error, -250, 250);
nav_lon = g.pi_nav_lon.get_pi(x_rate_error, dTnav);
nav_lon = constrain(nav_lon, -3500, 3500);
+ nav_lon += x_iterm;
}
static void calc_loiter2(int x_error, int y_error)
diff --git a/ArduCopter/planner.pde b/ArduCopter/planner.pde
index c9acf210fc..72c780eeaf 100644
--- a/ArduCopter/planner.pde
+++ b/ArduCopter/planner.pde
@@ -35,7 +35,7 @@ planner_gcs(uint8_t argc, const Menu::arg *argv)
fast_loopTimer = millis();
gcs_update();
-
+
read_radio();
gcs_data_stream_send(45, 1000);
diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde
index d0dc857c35..7555cb8d28 100644
--- a/ArduCopter/test.pde
+++ b/ArduCopter/test.pde
@@ -923,7 +923,7 @@ test_mag(uint8_t argc, const Menu::arg *argv)
}
/*
-static int8_t
+//static int8_t
//test_reverse(uint8_t argc, const Menu::arg *argv)
{
print_hit_enter();
diff --git a/ArduPlane/Log.pde b/ArduPlane/Log.pde
index db61ee5f3f..af08d3327d 100644
--- a/ArduPlane/Log.pde
+++ b/ArduPlane/Log.pde
@@ -112,7 +112,16 @@ dump_log(uint8_t argc, const Menu::arg *argv)
// check that the requested log number can be read
dump_log = argv[1].i;
last_log_num = g.log_last_filenumber;
- if (dump_log == -1) {
+
+ if (dump_log == -2) {
+ for(int count=1; count<=DF_LAST_PAGE; count++) {
+ DataFlash.StartRead(count);
+ Serial.printf_P(PSTR("DF page, log file #, log page: %d,\t"), count);
+ Serial.printf_P(PSTR("%d,\t"), DataFlash.GetFileNumber());
+ Serial.printf_P(PSTR("%d\n"), DataFlash.GetFilePage());
+ }
+ return(-1);
+ } else if (dump_log <= 0) {
Serial.printf_P(PSTR("dumping all\n"));
Log_Read(1, DF_LAST_PAGE);
return(-1);
diff --git a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Descriptors.c b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Descriptors.c
index ddab0c9ca8..c26f81d61d 100644
--- a/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Descriptors.c
+++ b/Tools/ArduPPM/ATMega32U2/Projects/arduino-usbserial/Descriptors.c
@@ -105,7 +105,7 @@ USB_Descriptor_Configuration_t PROGMEM ConfigurationDescriptor =
.ConfigAttributes = (USB_CONFIG_ATTR_BUSPOWERED | USB_CONFIG_ATTR_SELFPOWERED),
- .MaxPowerConsumption = USB_CONFIG_POWER_MA(100)
+ .MaxPowerConsumption = USB_CONFIG_POWER_MA(400)
},
.CDC_CCI_Interface =
diff --git a/Tools/ArduPPM/Binaries/Hash.txt b/Tools/ArduPPM/Binaries/Hash.txt
new file mode 100644
index 0000000000..ba247aee19
--- /dev/null
+++ b/Tools/ArduPPM/Binaries/Hash.txt
@@ -0,0 +1,4 @@
+Filename MD5 SHA1 CRC32 File Size
+ArduPPM_v2.2.65_ATMega32U2.hex 0835d7ec916201c5d6ee6041244cc9bf f4229cd1c377286fe06799b64cfe3522d552072a 06bb44ae 14 090
+ArduPPM_v0.9.87_Arduplane-APMv1.x.hex e56eba9edaaa4d704fdc0302c6518049 aecd8b213c94b178facc28995af05675abaa536d 84004ed9 5 033
+ArduPPM_v0.9.87_Arducopter-APMv1.x.hex dba6aa9ec37ab9084a80a14d11c5b3f8 742069427a26e9057d7536105a773dd572ae489f c0faa808 4 604
diff --git a/Tools/ArdupilotMegaPlanner/ArduinoDetect.cs b/Tools/ArdupilotMegaPlanner/ArduinoDetect.cs
index 675eb7d885..c4c7ea8e0c 100644
--- a/Tools/ArdupilotMegaPlanner/ArduinoDetect.cs
+++ b/Tools/ArdupilotMegaPlanner/ArduinoDetect.cs
@@ -3,6 +3,7 @@ using System.Collections.Generic;
using System.Linq;
using System.Text;
using System.Management;
+using System.Windows.Forms;
namespace ArdupilotMega
{
@@ -55,26 +56,6 @@ namespace ArdupilotMega
System.Threading.Thread.Sleep(500);
- //HKEY_LOCAL_MACHINE\SYSTEM\CurrentControlSet\Enum\USB\VID_2341&PID_0010\640333439373519060F0\Device Parameters
- if (!MainV2.MONO)
- {
- ObjectQuery query = new ObjectQuery("SELECT * FROM Win32_USBControllerDevice");
- ManagementObjectSearcher searcher = new ManagementObjectSearcher(query);
- foreach (ManagementObject obj2 in searcher.Get())
- {
- Console.WriteLine("Dependant : " + obj2["Dependent"]);
-
- if (obj2["Dependent"].ToString().Contains(@"USB\\VID_2341&PID_0010"))
- {
- //return "2560-2";
- }
- }
- }
- else
- {
- int fixme;
- }
-
serialPort.DtrEnable = true;
serialPort.BaudRate = 115200;
serialPort.Open();
@@ -94,7 +75,42 @@ namespace ArdupilotMega
if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
{
serialPort.Close();
- return "2560";
+ //HKEY_LOCAL_MACHINE\SYSTEM\CurrentControlSet\Enum\USB\VID_2341&PID_0010\640333439373519060F0\Device Parameters
+ if (!MainV2.MONO)
+ {
+ ObjectQuery query = new ObjectQuery("SELECT * FROM Win32_USBControllerDevice");
+ ManagementObjectSearcher searcher = new ManagementObjectSearcher(query);
+ foreach (ManagementObject obj2 in searcher.Get())
+ {
+ Console.WriteLine("Dependant : " + obj2["Dependent"]);
+
+ if (obj2["Dependent"].ToString().Contains(@"USB\\VID_2341&PID_0010"))
+ {
+ if (DialogResult.Yes == MessageBox.Show("Is this a APM 2?", "APM 2", MessageBoxButtons.YesNo))
+ {
+ return "2560-2";
+ }
+ else
+ {
+ return "2560";
+ }
+ }
+ }
+
+ return "2560";
+ }
+ else
+ {
+ if (DialogResult.Yes == MessageBox.Show("APM 2.0", "Is this a APM 2?", MessageBoxButtons.YesNo))
+ {
+ return "2560-2";
+ }
+ else
+ {
+ return "2560";
+ }
+ }
+
}
}
catch { }
@@ -103,7 +119,7 @@ namespace ArdupilotMega
serialPort.Close();
Console.WriteLine("Not a 2560");
return "";
- }
+ }
public static int decodeApVar(string comport, string version)
{
diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
index c1c1176ee0..bd933de328 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj
@@ -172,9 +172,18 @@
False
..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Scripting.ExtensionAttribute.dll
+
+ ..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\Source\Examples\Chapter13\ClipmapTerrainOnGlobe\bin\Debug\OpenGlobe.Core.dll
+
+
+ ..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\Source\Examples\Chapter13\ClipmapTerrainOnGlobe\bin\Debug\OpenGlobe.Renderer.dll
+
+
+ ..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\Source\Examples\Chapter13\ClipmapTerrainOnGlobe\bin\Debug\OpenGlobe.Scene.dll
+
False
- ..\..\..\..\..\Desktop\DIYDrones\opentk\trunk\Binaries\OpenTK\Release\OpenTK.dll
+ ..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\ThirdParty\OpenTKGL4\Binaries\OpenTK\Release\OpenTK.dll
False
@@ -571,13 +580,11 @@
Always
+
Always
-
- Always
-
Always
diff --git a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj.user b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj.user
index d776ccd39d..225c748121 100644
--- a/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj.user
+++ b/Tools/ArdupilotMegaPlanner/ArdupilotMega.csproj.user
@@ -11,6 +11,6 @@
- C:\Users\hog\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\;C:\Users\hog\Desktop\DIYDrones\myquad\sharpkml\SharpKml\bin\Release\;C:\Users\hog\Documents\Visual Studio 2010\Projects\ArdupilotMega\ArdupilotMega\bin\Release\
+ C:\Users\hog\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\;C:\Users\hog\Desktop\DIYDrones\myquad\sharpkml\SharpKml\bin\Release\
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml
index c12a8e30af..31a0608cb2 100644
--- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml
+++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml
@@ -55,7 +55,7 @@
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex
http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560-2.hex
- ArduCopter V2.0.54 Quad
+ ArduCopter V2.0.55 Quad
#define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION X_FRAME
@@ -67,7 +67,7 @@
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex
http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560-2.hex
- ArduCopter V2.0.54 Tri
+ ArduCopter V2.0.55 Tri
#define FRAME_CONFIG TRI_FRAME
#define FRAME_ORIENTATION X_FRAME
@@ -79,7 +79,7 @@
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex
http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560-2.hex
- ArduCopter V2.0.54 Hexa
+ ArduCopter V2.0.55 Hexa
#define FRAME_CONFIG HEXA_FRAME
#define FRAME_ORIENTATION X_FRAME
@@ -91,7 +91,7 @@
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex
http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560-2.hex
- ArduCopter V2.0.54 Y6
+ ArduCopter V2.0.55 Y6
#define FRAME_CONFIG Y6_FRAME
#define FRAME_ORIENTATION X_FRAME
@@ -151,7 +151,7 @@
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex
http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex
http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560-2.hex
- ArduCopter V2.0.54 Quad Hil
+ ArduCopter V2.0.55 Quad Hil
#define FRAME_CONFIG QUAD_FRAME
#define FRAME_ORIENTATION PLUS_FRAME
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs
index 45633480d0..7fb114ddfe 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.Designer.cs
@@ -30,8 +30,8 @@
{
this.components = new System.ComponentModel.Container();
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
- System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle3 = new System.Windows.Forms.DataGridViewCellStyle();
- System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle4 = new System.Windows.Forms.DataGridViewCellStyle();
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
this.Params = new System.Windows.Forms.DataGridView();
this.Command = new System.Windows.Forms.DataGridViewTextBoxColumn();
this.Value = new System.Windows.Forms.DataGridViewTextBoxColumn();
@@ -141,6 +141,8 @@
this.RLL2SRV_P = new System.Windows.Forms.NumericUpDown();
this.label52 = new System.Windows.Forms.Label();
this.TabAC2 = new System.Windows.Forms.TabPage();
+ this.myLabel1 = new ArdupilotMega.MyLabel();
+ this.CH7_OPT = new System.Windows.Forms.ComboBox();
this.groupBox17 = new System.Windows.Forms.GroupBox();
this.ACRO_PIT_IMAX = new System.Windows.Forms.NumericUpDown();
this.label27 = new System.Windows.Forms.Label();
@@ -403,14 +405,14 @@
this.Params.AllowUserToAddRows = false;
this.Params.AllowUserToDeleteRows = false;
resources.ApplyResources(this.Params, "Params");
- dataGridViewCellStyle3.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
- dataGridViewCellStyle3.BackColor = System.Drawing.Color.Maroon;
- dataGridViewCellStyle3.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
- dataGridViewCellStyle3.ForeColor = System.Drawing.Color.White;
- dataGridViewCellStyle3.SelectionBackColor = System.Drawing.SystemColors.Highlight;
- dataGridViewCellStyle3.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
- dataGridViewCellStyle3.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
- this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle3;
+ dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
+ dataGridViewCellStyle1.BackColor = System.Drawing.Color.Maroon;
+ dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
+ dataGridViewCellStyle1.ForeColor = System.Drawing.Color.White;
+ dataGridViewCellStyle1.SelectionBackColor = System.Drawing.SystemColors.Highlight;
+ dataGridViewCellStyle1.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
+ dataGridViewCellStyle1.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
+ this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle1;
this.Params.ColumnHeadersHeightSizeMode = System.Windows.Forms.DataGridViewColumnHeadersHeightSizeMode.AutoSize;
this.Params.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
this.Command,
@@ -419,14 +421,14 @@
this.mavScale,
this.RawValue});
this.Params.Name = "Params";
- dataGridViewCellStyle4.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
- dataGridViewCellStyle4.BackColor = System.Drawing.SystemColors.ActiveCaption;
- dataGridViewCellStyle4.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
- dataGridViewCellStyle4.ForeColor = System.Drawing.SystemColors.WindowText;
- dataGridViewCellStyle4.SelectionBackColor = System.Drawing.SystemColors.Highlight;
- dataGridViewCellStyle4.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
- dataGridViewCellStyle4.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
- this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle4;
+ dataGridViewCellStyle2.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
+ dataGridViewCellStyle2.BackColor = System.Drawing.SystemColors.ActiveCaption;
+ dataGridViewCellStyle2.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
+ dataGridViewCellStyle2.ForeColor = System.Drawing.SystemColors.WindowText;
+ dataGridViewCellStyle2.SelectionBackColor = System.Drawing.SystemColors.Highlight;
+ dataGridViewCellStyle2.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
+ dataGridViewCellStyle2.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
+ this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2;
this.Params.RowHeadersVisible = false;
this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged);
//
@@ -1087,6 +1089,8 @@
//
// TabAC2
//
+ this.TabAC2.Controls.Add(this.myLabel1);
+ this.TabAC2.Controls.Add(this.CH7_OPT);
this.TabAC2.Controls.Add(this.groupBox17);
this.TabAC2.Controls.Add(this.groupBox5);
this.TabAC2.Controls.Add(this.groupBox18);
@@ -1104,6 +1108,28 @@
resources.ApplyResources(this.TabAC2, "TabAC2");
this.TabAC2.Name = "TabAC2";
//
+ // myLabel1
+ //
+ resources.ApplyResources(this.myLabel1, "myLabel1");
+ this.myLabel1.Name = "myLabel1";
+ this.myLabel1.resize = false;
+ //
+ // CH7_OPT
+ //
+ this.CH7_OPT.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
+ this.CH7_OPT.FormattingEnabled = true;
+ this.CH7_OPT.Items.AddRange(new object[] {
+ resources.GetString("CH7_OPT.Items"),
+ resources.GetString("CH7_OPT.Items1"),
+ resources.GetString("CH7_OPT.Items2"),
+ resources.GetString("CH7_OPT.Items3"),
+ resources.GetString("CH7_OPT.Items4"),
+ resources.GetString("CH7_OPT.Items5"),
+ resources.GetString("CH7_OPT.Items6"),
+ resources.GetString("CH7_OPT.Items7")});
+ resources.ApplyResources(this.CH7_OPT, "CH7_OPT");
+ this.CH7_OPT.Name = "CH7_OPT";
+ //
// groupBox17
//
this.groupBox17.Controls.Add(this.ACRO_PIT_IMAX);
@@ -2451,5 +2477,7 @@
private System.Windows.Forms.Label label44;
private System.Windows.Forms.NumericUpDown ACRO_RLL_P;
private System.Windows.Forms.Label label48;
+ private MyLabel myLabel1;
+ private System.Windows.Forms.ComboBox CH7_OPT;
}
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
index ef790e211a..d50d12f4e8 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.cs
@@ -380,6 +380,15 @@ namespace ArdupilotMega.GCSViews
}
catch { }
+ try
+ {
+ ComboBox thisctl = ((ComboBox)ctl);
+
+ thisctl.SelectedIndex = (int)(float)param[value];
+
+ thisctl.Validated += new EventHandler(ComboBox_Validated);
+ } catch {}
+
}
if (text.Length == 0)
{
@@ -390,6 +399,11 @@ namespace ArdupilotMega.GCSViews
Params.Sort(Params.Columns[0], ListSortDirection.Ascending);
}
+ void ComboBox_Validated(object sender, EventArgs e)
+ {
+ EEPROM_View_float_TextChanged(sender, e);
+ }
+
void Configuration_Validating(object sender, CancelEventArgs e)
{
EEPROM_View_float_TextChanged(sender, e);
@@ -403,8 +417,16 @@ namespace ArdupilotMega.GCSViews
// do domainupdown state check
try
{
- value = float.Parse(((Control)sender).Text);
- changes[name] = value;
+ if (sender.GetType() == typeof(NumericUpDown))
+ {
+ value = float.Parse(((Control)sender).Text);
+ changes[name] = value;
+ }
+ else if (sender.GetType() == typeof(ComboBox))
+ {
+ value = ((ComboBox)sender).SelectedIndex;
+ changes[name] = value;
+ }
((Control)sender).BackColor = Color.Green;
}
catch (Exception)
@@ -481,7 +503,14 @@ namespace ArdupilotMega.GCSViews
{
if (row.Cells[0].Value.ToString() == name)
{
- row.Cells[1].Value = float.Parse(((Control)sender).Text);
+ if (sender.GetType() == typeof(NumericUpDown))
+ {
+ row.Cells[1].Value = float.Parse(((Control)sender).Text);
+ }
+ else if (sender.GetType() == typeof(ComboBox))
+ {
+ row.Cells[1].Value = ((ComboBox)sender).SelectedIndex;
+ }
break;
}
}
@@ -516,12 +545,21 @@ namespace ArdupilotMega.GCSViews
{
if (text.Length > 0)
{
- decimal option = (decimal)(float.Parse(Params[e.ColumnIndex, e.RowIndex].Value.ToString()));
- ((NumericUpDown)text[0]).Value = option;
- ((NumericUpDown)text[0]).BackColor = Color.Green;
+ if (sender.GetType() == typeof(NumericUpDown))
+ {
+ decimal option = (decimal)(float.Parse(Params[e.ColumnIndex, e.RowIndex].Value.ToString()));
+ ((NumericUpDown)text[0]).Value = option;
+ ((NumericUpDown)text[0]).BackColor = Color.Green;
+ }
+ else if (sender.GetType() == typeof(ComboBox))
+ {
+ int option = (int)(float.Parse(Params[e.ColumnIndex, e.RowIndex].Value.ToString()));
+ ((ComboBox)text[0]).SelectedIndex = option;
+ ((ComboBox)text[0]).BackColor = Color.Green;
+ }
}
}
- catch { ((NumericUpDown)text[0]).BackColor = Color.Red; }
+ catch { ((Control)text[0]).BackColor = Color.Red; }
Params.Focus();
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx
index 4c7ed22dcd..e9b9c455f0 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Configuration.resx
@@ -121,28 +121,28 @@
Top, Bottom, Left
-
+
+
True
-
+
Command
-
150
-
+
True
-
+
Value
80
-
+
True
-
+
Default
@@ -155,9 +155,9 @@
False
-
+
True
-
+
RawValue
@@ -192,2196 +192,6 @@
Top, Bottom, Left, Right
-
- groupBox3
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 0
-
-
- groupBox1
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 1
-
-
- groupBox2
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 2
-
-
- groupBox15
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 3
-
-
- groupBox16
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 4
-
-
- groupBox14
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 5
-
-
- groupBox13
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 6
-
-
- groupBox12
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 7
-
-
- groupBox11
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 8
-
-
- groupBox10
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 9
-
-
- groupBox9
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 10
-
-
- groupBox8
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 11
-
-
- 4, 22
-
-
- 0, 0, 0, 0
-
-
- 722, 434
-
-
- 0
-
-
- APM 2.x
-
-
- TabAPM2
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- ConfigTabs
-
-
- 0
-
-
- ACRO_PIT_IMAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox17
-
-
- 0
-
-
- label27
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox17
-
-
- 1
-
-
- ACRO_PIT_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox17
-
-
- 2
-
-
- label29
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox17
-
-
- 3
-
-
- ACRO_PIT_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox17
-
-
- 4
-
-
- label33
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox17
-
-
- 5
-
-
- 182, 337
-
-
- 170, 91
-
-
- 13
-
-
- Acro Pitch
-
-
- groupBox17
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 0
-
-
- label14
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox5
-
-
- 0
-
-
- THR_RATE_IMAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox5
-
-
- 1
-
-
- THR_RATE_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox5
-
-
- 2
-
-
- label20
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox5
-
-
- 3
-
-
- THR_RATE_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox5
-
-
- 4
-
-
- label25
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox5
-
-
- 5
-
-
- 6, 221
-
-
- 170, 110
-
-
- 16
-
-
- Throttle Rate
-
-
- groupBox5
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 1
-
-
- ACRO_RLL_IMAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox18
-
-
- 0
-
-
- label40
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox18
-
-
- 1
-
-
- ACRO_RLL_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox18
-
-
- 2
-
-
- label44
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox18
-
-
- 3
-
-
- ACRO_RLL_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox18
-
-
- 4
-
-
- label48
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox18
-
-
- 5
-
-
- 6, 337
-
-
- 170, 91
-
-
- 14
-
-
- Acro Roll
-
-
- groupBox18
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 2
-
-
- True
-
-
- 3, 198
-
-
- 154, 17
-
-
- 13
-
-
- Lock Pitch and Roll Values
-
-
- CHK_lockrollpitch
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 3
-
-
- WP_SPEED_MAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 0
-
-
- label9
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 1
-
-
- NAV_LAT_IMAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 2
-
-
- label13
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 3
-
-
- NAV_LAT_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 4
-
-
- label15
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 5
-
-
- NAV_LAT_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 6
-
-
- label16
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox4
-
-
- 7
-
-
- 534, 107
-
-
- 170, 108
-
-
- 0
-
-
- Nav WP
-
-
- groupBox4
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 4
-
-
- 80, 13
-
-
- 78, 20
-
-
- 5
-
-
- XTRK_GAIN_SC1
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox6
-
-
- 0
-
-
- NoControl
-
-
- 6, 16
-
-
- 38, 13
-
-
- 15
-
-
- Gain
-
-
- label18
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox6
-
-
- 1
-
-
- 358, 221
-
-
- 170, 43
-
-
- 2
-
-
- Crosstrack Correction
-
-
- groupBox6
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 5
-
-
- THR_ALT_IMAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox7
-
-
- 0
-
-
- label19
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox7
-
-
- 1
-
-
- THR_ALT_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox7
-
-
- 2
-
-
- label21
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox7
-
-
- 3
-
-
- THR_ALT_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox7
-
-
- 4
-
-
- label22
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox7
-
-
- 5
-
-
- 182, 221
-
-
- 170, 110
-
-
- 3
-
-
- Altitude Hold
-
-
- groupBox7
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 6
-
-
- HLD_LAT_IMAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox19
-
-
- 0
-
-
- label28
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox19
-
-
- 1
-
-
- HLD_LAT_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox19
-
-
- 2
-
-
- label30
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox19
-
-
- 3
-
-
- HLD_LAT_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox19
-
-
- 4
-
-
- label31
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox19
-
-
- 5
-
-
- 531, 6
-
-
- 170, 95
-
-
- 6
-
-
- Loiter
-
-
- groupBox19
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 7
-
-
- STB_YAW_IMAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox20
-
-
- 0
-
-
- label32
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox20
-
-
- 1
-
-
- STB_YAW_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox20
-
-
- 2
-
-
- label34
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox20
-
-
- 3
-
-
- STB_YAW_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox20
-
-
- 4
-
-
- label35
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox20
-
-
- 5
-
-
- 358, 6
-
-
- 170, 95
-
-
- 7
-
-
- Stabilize Yaw
-
-
- groupBox20
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 8
-
-
- STB_PIT_IMAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox21
-
-
- 0
-
-
- label36
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox21
-
-
- 1
-
-
- STB_PIT_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox21
-
-
- 2
-
-
- label41
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox21
-
-
- 3
-
-
- STB_PIT_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox21
-
-
- 4
-
-
- label42
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox21
-
-
- 5
-
-
- 182, 6
-
-
- 170, 95
-
-
- 8
-
-
- Stabilize Pitch
-
-
- groupBox21
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 9
-
-
- STB_RLL_IMAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox22
-
-
- 0
-
-
- label43
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox22
-
-
- 1
-
-
- STB_RLL_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox22
-
-
- 2
-
-
- label45
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox22
-
-
- 3
-
-
- STB_RLL_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox22
-
-
- 4
-
-
- label46
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox22
-
-
- 5
-
-
- 6, 6
-
-
- 170, 95
-
-
- 9
-
-
- Stabilize Roll
-
-
- groupBox22
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 10
-
-
- RATE_YAW_IMAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox23
-
-
- 0
-
-
- label47
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox23
-
-
- 1
-
-
- RATE_YAW_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox23
-
-
- 2
-
-
- label77
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox23
-
-
- 3
-
-
- RATE_YAW_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox23
-
-
- 4
-
-
- label82
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox23
-
-
- 5
-
-
- 358, 107
-
-
- 170, 91
-
-
- 10
-
-
- Rate Yaw
-
-
- groupBox23
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 11
-
-
- RATE_PIT_IMAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox24
-
-
- 0
-
-
- label84
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox24
-
-
- 1
-
-
- RATE_PIT_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox24
-
-
- 2
-
-
- label86
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox24
-
-
- 3
-
-
- RATE_PIT_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox24
-
-
- 4
-
-
- label87
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox24
-
-
- 5
-
-
- 182, 107
-
-
- 170, 91
-
-
- 11
-
-
- Rate Pitch
-
-
- groupBox24
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 12
-
-
- RATE_RLL_IMAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox25
-
-
- 0
-
-
- label88
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox25
-
-
- 1
-
-
- RATE_RLL_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox25
-
-
- 2
-
-
- label90
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox25
-
-
- 3
-
-
- RATE_RLL_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox25
-
-
- 4
-
-
- label91
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox25
-
-
- 5
-
-
- 6, 107
-
-
- 170, 91
-
-
- 12
-
-
- Rate Roll
-
-
- groupBox25
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAC2
-
-
- 13
-
-
- 4, 22
-
-
- 3, 3, 3, 3
-
-
- 722, 434
-
-
- 1
-
-
- AC2
-
-
- TabAC2
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- ConfigTabs
-
-
- 1
-
-
- label26
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 0
-
-
- CMB_videoresolutions
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 1
-
-
- label12
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 2
-
-
- CHK_GDIPlus
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 3
-
-
- label24
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 4
-
-
- CHK_loadwponconnect
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 5
-
-
- label23
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 6
-
-
- NUM_tracklength
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 7
-
-
- CHK_speechaltwarning
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 8
-
-
- label108
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 9
-
-
- CHK_resetapmonconnect
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 10
-
-
- CHK_mavdebug
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 11
-
-
- label107
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 12
-
-
- CMB_raterc
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 13
-
-
- label104
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 14
-
-
- label103
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 15
-
-
- label102
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 16
-
-
- label101
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 17
-
-
- CMB_ratestatus
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 18
-
-
- CMB_rateposition
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 19
-
-
- CMB_rateattitude
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 20
-
-
- label99
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 21
-
-
- label98
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 22
-
-
- label97
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 23
-
-
- CMB_speedunits
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 24
-
-
- CMB_distunits
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 25
-
-
- label96
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 26
-
-
- label95
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 27
-
-
- CHK_speechbattery
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 28
-
-
- CHK_speechcustom
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 29
-
-
- CHK_speechmode
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 30
-
-
- CHK_speechwaypoint
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 31
-
-
- label94
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 32
-
-
- CMB_osdcolor
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 33
-
-
- CMB_language
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 34
-
-
- label93
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 35
-
-
- CHK_enablespeech
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 36
-
-
- CHK_hudshow
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 37
-
-
- label92
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 38
-
-
- CMB_videosources
-
-
- System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabPlanner
-
-
- 39
-
-
- BUT_Joystick
-
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
-
-
- TabPlanner
-
-
- 40
-
-
- BUT_videostop
-
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
-
-
- TabPlanner
-
-
- 41
-
-
- BUT_videostart
-
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
-
-
- TabPlanner
-
-
- 42
-
-
- 4, 22
-
-
- 3, 3, 3, 3
-
-
- 722, 434
-
-
- 2
-
-
- Planner
-
-
- TabPlanner
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- ConfigTabs
-
-
- 2
-
-
- 4, 22
-
-
- 722, 434
-
-
- 3
-
-
- Setup
-
-
- TabSetup
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- ConfigTabs
-
-
- 3
-
-
- 52, 18
-
-
- 278, 0
-
-
- 0, 0, 0, 0
-
-
- 0, 0
-
-
- 730, 460
-
-
- 62
-
-
- ConfigTabs
-
-
- System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- $this
-
-
- 2
-
-
- THR_FS_VALUE
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox3
-
-
- 0
-
-
- label5
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox3
-
-
- 1
-
-
- THR_MAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox3
-
-
- 2
-
-
- label6
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox3
-
-
- 3
-
-
- THR_MIN
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox3
-
-
- 4
-
-
- label7
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox3
-
-
- 5
-
-
- TRIM_THROTTLE
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox3
-
-
- 6
-
-
- label8
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox3
-
-
- 7
-
-
- 405, 217
-
-
- 195, 108
-
-
- 0
-
-
- Throttle 0-100%
-
-
- groupBox3
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- TabAPM2
-
-
- 0
-
111, 82
@@ -2574,125 +384,29 @@
7
-
- ARSPD_RATIO
+
+ 405, 217
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox1
-
-
- 0
-
-
- label1
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox1
-
-
- 1
-
-
- ARSPD_FBW_MAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox1
-
-
- 2
-
-
- label2
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox1
-
-
- 3
-
-
- ARSPD_FBW_MIN
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox1
-
-
- 4
-
-
- label3
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox1
-
-
- 5
-
-
- TRIM_ARSPD_CM
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox1
-
-
- 6
-
-
- label4
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox1
-
-
- 7
-
-
- 406, 325
-
-
+
195, 108
-
- 1
+
+ 0
-
- Airspeed m/s
+
+ Throttle 0-100%
-
- groupBox1
+
+ groupBox3
-
+
System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
TabAPM2
-
- 1
+
+ 0
111, 82
@@ -2886,101 +600,29 @@
7
-
- LIM_PITCH_MIN
+
+ 406, 325
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox2
-
-
- 0
-
-
- label39
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox2
-
-
- 1
-
-
- LIM_PITCH_MAX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox2
-
-
- 2
-
-
- label38
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox2
-
-
- 3
-
-
- LIM_ROLL_CD
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox2
-
-
- 4
-
-
- label37
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox2
-
-
- 5
-
-
- 205, 325
-
-
+
195, 108
-
- 2
+
+ 1
-
- Navigation Angles
+
+ Airspeed m/s
-
- groupBox2
+
+ groupBox1
-
+
System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
TabAPM2
-
- 2
+
+ 1
111, 59
@@ -3126,77 +768,29 @@
5
-
- XTRK_ANGLE_CD
+
+ 205, 325
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox15
-
-
- 0
-
-
- label79
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox15
-
-
- 1
-
-
- XTRK_GAIN_SC
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox15
-
-
- 2
-
-
- label80
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox15
-
-
- 3
-
-
- 4, 325
-
-
+
195, 108
-
- 3
+
+ 2
-
- Xtrack Pids
+
+ Navigation Angles
-
- groupBox15
+
+ groupBox2
-
+
System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
TabAPM2
-
- 3
+
+ 2
111, 36
@@ -3294,101 +888,29 @@
3
-
- KFF_PTCH2THR
+
+ 4, 325
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox16
-
-
- 0
-
-
- label83
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox16
-
-
- 1
-
-
- KFF_RDDRMIX
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox16
-
-
- 2
-
-
- label78
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox16
-
-
- 3
-
-
- KFF_PTCHCOMP
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox16
-
-
- 4
-
-
- label81
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox16
-
-
- 5
-
-
- 205, 217
-
-
+
195, 108
-
- 4
+
+ 3
-
- Other Mix's
+
+ Xtrack Pids
-
- groupBox16
+
+ groupBox15
-
+
System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
TabAPM2
-
- 4
+
+ 3
111, 13
@@ -3534,125 +1056,29 @@
5
-
- ENRGY2THR_IMAX
+
+ 205, 217
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox14
-
-
- 0
-
-
- label73
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox14
-
-
- 1
-
-
- ENRGY2THR_D
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox14
-
-
- 2
-
-
- label74
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox14
-
-
- 3
-
-
- ENRGY2THR_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox14
-
-
- 4
-
-
- label75
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox14
-
-
- 5
-
-
- ENRGY2THR_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox14
-
-
- 6
-
-
- label76
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox14
-
-
- 7
-
-
- 4, 217
-
-
+
195, 108
-
- 5
+
+ 4
-
- Energy/Alt Pid
+
+ Other Mix's
-
- groupBox14
+
+ groupBox16
-
+
System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
TabAPM2
-
- 5
+
+ 4
111, 82
@@ -3846,125 +1272,29 @@
7
-
- ALT2PTCH_IMAX
+
+ 4, 217
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox13
-
-
- 0
-
-
- label69
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox13
-
-
- 1
-
-
- ALT2PTCH_D
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox13
-
-
- 2
-
-
- label70
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox13
-
-
- 3
-
-
- ALT2PTCH_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox13
-
-
- 4
-
-
- label71
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox13
-
-
- 5
-
-
- ALT2PTCH_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox13
-
-
- 6
-
-
- label72
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox13
-
-
- 7
-
-
- 406, 109
-
-
+
195, 108
-
- 6
+
+ 5
-
- Nav Pitch Alt Pid
+
+ Energy/Alt Pid
-
- groupBox13
+
+ groupBox14
-
+
System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
TabAPM2
-
- 6
+
+ 5
111, 82
@@ -4158,125 +1488,29 @@
7
-
- ARSP2PTCH_IMAX
+
+ 406, 109
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox12
-
-
- 0
-
-
- label65
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox12
-
-
- 1
-
-
- ARSP2PTCH_D
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox12
-
-
- 2
-
-
- label66
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox12
-
-
- 3
-
-
- ARSP2PTCH_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox12
-
-
- 4
-
-
- label67
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox12
-
-
- 5
-
-
- ARSP2PTCH_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox12
-
-
- 6
-
-
- label68
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox12
-
-
- 7
-
-
- 205, 109
-
-
+
195, 108
-
- 7
+
+ 6
-
- Nav Pitch AS Pid
+
+ Nav Pitch Alt Pid
-
- groupBox12
+
+ groupBox13
-
+
System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
TabAPM2
-
- 7
+
+ 6
111, 82
@@ -4470,125 +1704,29 @@
7
-
- HDNG2RLL_IMAX
+
+ 205, 109
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox11
-
-
- 0
-
-
- label61
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox11
-
-
- 1
-
-
- HDNG2RLL_D
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox11
-
-
- 2
-
-
- label62
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox11
-
-
- 3
-
-
- HDNG2RLL_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox11
-
-
- 4
-
-
- label63
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox11
-
-
- 5
-
-
- HDNG2RLL_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox11
-
-
- 6
-
-
- label64
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox11
-
-
- 7
-
-
- 4, 109
-
-
+
195, 108
-
- 8
+
+ 7
-
- Nav Roll Pid
+
+ Nav Pitch AS Pid
-
- groupBox11
+
+ groupBox12
-
+
System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
TabAPM2
-
- 8
+
+ 7
111, 82
@@ -4782,125 +1920,29 @@
7
-
- YW2SRV_IMAX
+
+ 4, 109
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox10
-
-
- 0
-
-
- label57
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox10
-
-
- 1
-
-
- YW2SRV_D
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox10
-
-
- 2
-
-
- label58
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox10
-
-
- 3
-
-
- YW2SRV_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox10
-
-
- 4
-
-
- label59
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox10
-
-
- 5
-
-
- YW2SRV_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox10
-
-
- 6
-
-
- label60
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox10
-
-
- 7
-
-
- 406, 1
-
-
+
195, 108
-
- 9
+
+ 8
-
- Servo Yaw Pid
+
+ Nav Roll Pid
-
- groupBox10
+
+ groupBox11
-
+
System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
TabAPM2
-
- 9
+
+ 8
111, 82
@@ -5094,125 +2136,29 @@
7
-
- PTCH2SRV_IMAX
+
+ 406, 1
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox9
-
-
- 0
-
-
- label53
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox9
-
-
- 1
-
-
- PTCH2SRV_D
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox9
-
-
- 2
-
-
- label54
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox9
-
-
- 3
-
-
- PTCH2SRV_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox9
-
-
- 4
-
-
- label55
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox9
-
-
- 5
-
-
- PTCH2SRV_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox9
-
-
- 6
-
-
- label56
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox9
-
-
- 7
-
-
- 205, 1
-
-
+
195, 108
-
- 10
+
+ 9
-
- Servo Pitch Pid
+
+ Servo Yaw Pid
-
- groupBox9
+
+ groupBox10
-
+
System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
TabAPM2
-
- 10
+
+ 9
111, 82
@@ -5406,125 +2352,29 @@
7
-
- RLL2SRV_IMAX
+
+ 205, 1
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox8
-
-
- 0
-
-
- label49
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox8
-
-
- 1
-
-
- RLL2SRV_D
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox8
-
-
- 2
-
-
- label50
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox8
-
-
- 3
-
-
- RLL2SRV_I
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox8
-
-
- 4
-
-
- label51
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox8
-
-
- 5
-
-
- RLL2SRV_P
-
-
- System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox8
-
-
- 6
-
-
- label52
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- groupBox8
-
-
- 7
-
-
- 4, 1
-
-
+
195, 108
-
- 11
+
+ 10
-
- Servo Roll Pid
+
+ Servo Pitch Pid
-
- groupBox8
+
+ groupBox9
-
+
System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
TabAPM2
-
- 11
+
+ 10
111, 82
@@ -5718,6 +2568,126 @@
7
+
+ 4, 1
+
+
+ 195, 108
+
+
+ 11
+
+
+ Servo Roll Pid
+
+
+ groupBox8
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAPM2
+
+
+ 11
+
+
+ 4, 22
+
+
+ 0, 0, 0, 0
+
+
+ 722, 434
+
+
+ 0
+
+
+ APM 2.x
+
+
+ TabAPM2
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ ConfigTabs
+
+
+ 0
+
+
+ 358, 270
+
+
+ 53, 23
+
+
+ 18
+
+
+ Ch7 Opt
+
+
+ myLabel1
+
+
+ ArdupilotMega.MyLabel, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ TabAC2
+
+
+ 0
+
+
+ Do Nothing
+
+
+
+
+
+
+
+
+ Simple Mode
+
+
+ RTL
+
+
+
+
+
+
+
+
+ Save WP
+
+
+ 417, 270
+
+
+ 112, 21
+
+
+ 17
+
+
+ CH7_OPT
+
+
+ System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 1
+
80, 63
@@ -5862,6 +2832,30 @@
5
+
+ 182, 337
+
+
+ 170, 91
+
+
+ 13
+
+
+ Acro Pitch
+
+
+ groupBox17
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 2
+
NoControl
@@ -6006,6 +3000,30 @@
5
+
+ 6, 221
+
+
+ 170, 110
+
+
+ 16
+
+
+ Throttle Rate
+
+
+ groupBox5
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 3
+
80, 63
@@ -6150,6 +3168,57 @@
5
+
+ 6, 337
+
+
+ 170, 91
+
+
+ 14
+
+
+ Acro Roll
+
+
+ groupBox18
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 4
+
+
+ True
+
+
+ 3, 198
+
+
+ 154, 17
+
+
+ 13
+
+
+ Lock Pitch and Roll Values
+
+
+ CHK_lockrollpitch
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 5
+
80, 86
@@ -6342,6 +3411,102 @@
7
+
+ 534, 107
+
+
+ 170, 108
+
+
+ 0
+
+
+ Nav WP
+
+
+ groupBox4
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 6
+
+
+ 80, 13
+
+
+ 78, 20
+
+
+ 5
+
+
+ XTRK_GAIN_SC1
+
+
+ System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox6
+
+
+ 0
+
+
+ NoControl
+
+
+ 6, 16
+
+
+ 38, 13
+
+
+ 15
+
+
+ Gain
+
+
+ label18
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox6
+
+
+ 1
+
+
+ 358, 221
+
+
+ 170, 43
+
+
+ 2
+
+
+ Crosstrack Correction
+
+
+ groupBox6
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 7
+
80, 63
@@ -6486,6 +3651,30 @@
5
+
+ 182, 221
+
+
+ 170, 110
+
+
+ 3
+
+
+ Altitude Hold
+
+
+ groupBox7
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 8
+
80, 61
@@ -6630,6 +3819,30 @@
5
+
+ 531, 6
+
+
+ 170, 95
+
+
+ 6
+
+
+ Loiter
+
+
+ groupBox19
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 9
+
80, 63
@@ -6774,6 +3987,30 @@
5
+
+ 358, 6
+
+
+ 170, 95
+
+
+ 7
+
+
+ Stabilize Yaw
+
+
+ groupBox20
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 10
+
80, 63
@@ -6918,6 +4155,30 @@
5
+
+ 182, 6
+
+
+ 170, 95
+
+
+ 8
+
+
+ Stabilize Pitch
+
+
+ groupBox21
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 11
+
80, 63
@@ -7062,6 +4323,30 @@
5
+
+ 6, 6
+
+
+ 170, 95
+
+
+ 9
+
+
+ Stabilize Roll
+
+
+ groupBox22
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 12
+
80, 63
@@ -7206,6 +4491,30 @@
5
+
+ 358, 107
+
+
+ 170, 91
+
+
+ 10
+
+
+ Rate Yaw
+
+
+ groupBox23
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 13
+
80, 63
@@ -7350,6 +4659,30 @@
5
+
+ 182, 107
+
+
+ 170, 91
+
+
+ 11
+
+
+ Rate Pitch
+
+
+ groupBox24
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 14
+
80, 63
@@ -7494,6 +4827,57 @@
5
+
+ 6, 107
+
+
+ 170, 91
+
+
+ 12
+
+
+ Rate Roll
+
+
+ groupBox25
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ TabAC2
+
+
+ 15
+
+
+ 4, 22
+
+
+ 3, 3, 3, 3
+
+
+ 722, 434
+
+
+ 1
+
+
+ AC2
+
+
+ TabAC2
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ ConfigTabs
+
+
+ 1
+
NoControl
@@ -7569,9 +4953,6 @@
2
-
- 17, 17
-
NoControl
@@ -7587,6 +4968,9 @@
GDI+ (old type)
+
+ 17, 17
+
OpenGL = Disabled
GDI+ = Enabled
@@ -8651,6 +6035,87 @@ GDI+ = Enabled
42
+
+ 4, 22
+
+
+ 3, 3, 3, 3
+
+
+ 722, 434
+
+
+ 2
+
+
+ Planner
+
+
+ TabPlanner
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ ConfigTabs
+
+
+ 2
+
+
+ 4, 22
+
+
+ 722, 434
+
+
+ 3
+
+
+ Setup
+
+
+ TabSetup
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ ConfigTabs
+
+
+ 3
+
+
+ 52, 18
+
+
+ 278, 0
+
+
+ 0, 0, 0, 0
+
+
+ 0, 0
+
+
+ 730, 460
+
+
+ 62
+
+
+ ConfigTabs
+
+
+ System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 2
+
0, 0
@@ -8804,9 +6269,6 @@ GDI+ = Enabled
5
-
- 17, 17
-
Bottom, Left
@@ -8837,9 +6299,9 @@ GDI+ = Enabled
0
-
+
True
-
+
6, 13
@@ -8888,4 +6350,7 @@ GDI+ = Enabled
System.Windows.Forms.MyUserControl, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+ ..\Resources\MAVParam.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252
+
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
index bde3cb13a8..06e13f9c70 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/Firmware.cs
@@ -258,6 +258,18 @@ namespace ArdupilotMega.GCSViews
findfirmware("AC2-QUADHIL");
return true;
}
+
+ if (keyData == (Keys.Control | Keys.C))
+ {
+ OpenFileDialog fd = new OpenFileDialog();
+ fd.Filter = "Firmware (*.hex)|*.hex";
+ fd.ShowDialog();
+ if (File.Exists(fd.FileName))
+ {
+ UploadFlash(fd.FileName, ArduinoDetect.DetectVersion(MainV2.comportname));
+ }
+ return true;
+ }
return base.ProcessCmdKey(ref msg, keyData);
}
@@ -534,6 +546,8 @@ namespace ArdupilotMega.GCSViews
return;
}
+ Console.WriteLine("Using "+baseurl);
+
// Create a request using a URL that can receive a post.
WebRequest request = WebRequest.Create(baseurl);
request.Timeout = 10000;
@@ -615,7 +629,7 @@ namespace ArdupilotMega.GCSViews
//port = new ArduinoSTK();
port.BaudRate = 57600;
}
- else if (board == "2560")
+ else if (board == "2560" || board == "2560-2")
{
port = new ArduinoSTKv2();
port.BaudRate = 115200;
@@ -691,7 +705,7 @@ namespace ArdupilotMega.GCSViews
}
}
- lbl_status.Text = "Write Done... Waiting";
+ lbl_status.Text = "Write Done... Waiting (60 sec)";
}
else
{
@@ -704,7 +718,7 @@ namespace ArdupilotMega.GCSViews
Application.DoEvents();
- System.Threading.Thread.Sleep(10000); // 10 seconds - new apvar erases eeprom on new format version, this should buy us some time.
+ System.Threading.Thread.Sleep(60000); // 10 seconds - new apvar erases eeprom on new format version, this should buy us some time.
lbl_status.Text = "Done";
}
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs
index 851f72bc0c..84db00fb4e 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.Designer.cs
@@ -31,14 +31,14 @@
{
this.components = new System.ComponentModel.Container();
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(FlightPlanner));
- System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
- System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle5 = new System.Windows.Forms.DataGridViewCellStyle();
- System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle6 = new System.Windows.Forms.DataGridViewCellStyle();
- System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
- System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle3 = new System.Windows.Forms.DataGridViewCellStyle();
- System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle4 = new System.Windows.Forms.DataGridViewCellStyle();
- System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle7 = new System.Windows.Forms.DataGridViewCellStyle();
- System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle8 = new System.Windows.Forms.DataGridViewCellStyle();
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle9 = new System.Windows.Forms.DataGridViewCellStyle();
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle13 = new System.Windows.Forms.DataGridViewCellStyle();
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle14 = new System.Windows.Forms.DataGridViewCellStyle();
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle10 = new System.Windows.Forms.DataGridViewCellStyle();
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle11 = new System.Windows.Forms.DataGridViewCellStyle();
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle12 = new System.Windows.Forms.DataGridViewCellStyle();
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle15 = new System.Windows.Forms.DataGridViewCellStyle();
+ System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle16 = new System.Windows.Forms.DataGridViewCellStyle();
this.CHK_altmode = new System.Windows.Forms.CheckBox();
this.CHK_holdalt = new System.Windows.Forms.CheckBox();
this.Commands = new System.Windows.Forms.DataGridView();
@@ -89,6 +89,7 @@
this.textBox1 = new System.Windows.Forms.TextBox();
this.panelWaypoints = new BSE.Windows.Forms.Panel();
this.splitter1 = new BSE.Windows.Forms.Splitter();
+ this.BUT_zoomto = new ArdupilotMega.MyButton();
this.BUT_Camera = new ArdupilotMega.MyButton();
this.BUT_grid = new ArdupilotMega.MyButton();
this.BUT_Prefetch = new ArdupilotMega.MyButton();
@@ -120,7 +121,7 @@
this.label11 = new System.Windows.Forms.Label();
this.panelBASE = new System.Windows.Forms.Panel();
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
- this.BUT_zoomto = new ArdupilotMega.MyButton();
+ this.BUT_loadkml = new ArdupilotMega.MyButton();
((System.ComponentModel.ISupportInitialize)(this.Commands)).BeginInit();
this.panel5.SuspendLayout();
this.panel1.SuspendLayout();
@@ -152,14 +153,14 @@
//
this.Commands.AllowUserToAddRows = false;
resources.ApplyResources(this.Commands, "Commands");
- dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
- dataGridViewCellStyle1.BackColor = System.Drawing.SystemColors.Control;
- dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
- dataGridViewCellStyle1.ForeColor = System.Drawing.SystemColors.WindowText;
- dataGridViewCellStyle1.SelectionBackColor = System.Drawing.SystemColors.Highlight;
- dataGridViewCellStyle1.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
- dataGridViewCellStyle1.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
- this.Commands.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle1;
+ dataGridViewCellStyle9.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
+ dataGridViewCellStyle9.BackColor = System.Drawing.SystemColors.Control;
+ dataGridViewCellStyle9.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
+ dataGridViewCellStyle9.ForeColor = System.Drawing.SystemColors.WindowText;
+ dataGridViewCellStyle9.SelectionBackColor = System.Drawing.SystemColors.Highlight;
+ dataGridViewCellStyle9.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
+ dataGridViewCellStyle9.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
+ this.Commands.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle9;
this.Commands.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
this.Command,
this.Param1,
@@ -173,17 +174,17 @@
this.Up,
this.Down});
this.Commands.Name = "Commands";
- dataGridViewCellStyle5.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
- dataGridViewCellStyle5.BackColor = System.Drawing.SystemColors.Control;
- dataGridViewCellStyle5.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
- dataGridViewCellStyle5.ForeColor = System.Drawing.SystemColors.WindowText;
- dataGridViewCellStyle5.Format = "N0";
- dataGridViewCellStyle5.NullValue = "0";
- dataGridViewCellStyle5.SelectionBackColor = System.Drawing.SystemColors.Highlight;
- dataGridViewCellStyle5.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
- this.Commands.RowHeadersDefaultCellStyle = dataGridViewCellStyle5;
- dataGridViewCellStyle6.ForeColor = System.Drawing.Color.Black;
- this.Commands.RowsDefaultCellStyle = dataGridViewCellStyle6;
+ dataGridViewCellStyle13.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
+ dataGridViewCellStyle13.BackColor = System.Drawing.SystemColors.Control;
+ dataGridViewCellStyle13.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
+ dataGridViewCellStyle13.ForeColor = System.Drawing.SystemColors.WindowText;
+ dataGridViewCellStyle13.Format = "N0";
+ dataGridViewCellStyle13.NullValue = "0";
+ dataGridViewCellStyle13.SelectionBackColor = System.Drawing.SystemColors.Highlight;
+ dataGridViewCellStyle13.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
+ this.Commands.RowHeadersDefaultCellStyle = dataGridViewCellStyle13;
+ dataGridViewCellStyle14.ForeColor = System.Drawing.Color.Black;
+ this.Commands.RowsDefaultCellStyle = dataGridViewCellStyle14;
this.Commands.CellContentClick += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellContentClick);
this.Commands.CellEndEdit += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellEndEdit);
this.Commands.DataError += new System.Windows.Forms.DataGridViewDataErrorEventHandler(this.Commands_DataError);
@@ -195,9 +196,9 @@
//
// Command
//
- dataGridViewCellStyle2.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
- dataGridViewCellStyle2.ForeColor = System.Drawing.Color.White;
- this.Command.DefaultCellStyle = dataGridViewCellStyle2;
+ dataGridViewCellStyle10.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
+ dataGridViewCellStyle10.ForeColor = System.Drawing.Color.White;
+ this.Command.DefaultCellStyle = dataGridViewCellStyle10;
this.Command.DisplayStyle = System.Windows.Forms.DataGridViewComboBoxDisplayStyle.ComboBox;
resources.ApplyResources(this.Command, "Command");
this.Command.Name = "Command";
@@ -263,7 +264,7 @@
//
// Up
//
- this.Up.DefaultCellStyle = dataGridViewCellStyle3;
+ this.Up.DefaultCellStyle = dataGridViewCellStyle11;
resources.ApplyResources(this.Up, "Up");
this.Up.Image = global::ArdupilotMega.Properties.Resources.up;
this.Up.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
@@ -271,8 +272,8 @@
//
// Down
//
- dataGridViewCellStyle4.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
- this.Down.DefaultCellStyle = dataGridViewCellStyle4;
+ dataGridViewCellStyle12.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
+ this.Down.DefaultCellStyle = dataGridViewCellStyle12;
resources.ApplyResources(this.Down, "Down");
this.Down.Image = global::ArdupilotMega.Properties.Resources.down;
this.Down.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
@@ -416,8 +417,8 @@
//
// dataGridViewImageColumn1
//
- dataGridViewCellStyle7.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
- this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle7;
+ dataGridViewCellStyle15.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
+ this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle15;
resources.ApplyResources(this.dataGridViewImageColumn1, "dataGridViewImageColumn1");
this.dataGridViewImageColumn1.Image = global::ArdupilotMega.Properties.Resources.up;
this.dataGridViewImageColumn1.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
@@ -425,8 +426,8 @@
//
// dataGridViewImageColumn2
//
- dataGridViewCellStyle8.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
- this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle8;
+ dataGridViewCellStyle16.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
+ this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle16;
resources.ApplyResources(this.dataGridViewImageColumn2, "dataGridViewImageColumn2");
this.dataGridViewImageColumn2.Image = global::ArdupilotMega.Properties.Resources.down;
this.dataGridViewImageColumn2.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
@@ -509,6 +510,7 @@
this.panelWaypoints.CaptionFont = new System.Drawing.Font("Segoe UI", 11.75F, System.Drawing.FontStyle.Bold);
this.panelWaypoints.CaptionHeight = 21;
this.panelWaypoints.ColorScheme = BSE.Windows.Forms.ColorScheme.Custom;
+ this.panelWaypoints.Controls.Add(this.BUT_loadkml);
this.panelWaypoints.Controls.Add(this.BUT_zoomto);
this.panelWaypoints.Controls.Add(this.BUT_Camera);
this.panelWaypoints.Controls.Add(this.BUT_grid);
@@ -557,6 +559,14 @@
this.splitter1.Name = "splitter1";
this.splitter1.TabStop = false;
//
+ // BUT_zoomto
+ //
+ resources.ApplyResources(this.BUT_zoomto, "BUT_zoomto");
+ this.BUT_zoomto.Name = "BUT_zoomto";
+ this.toolTip1.SetToolTip(this.BUT_zoomto, resources.GetString("BUT_zoomto.ToolTip"));
+ this.BUT_zoomto.UseVisualStyleBackColor = true;
+ this.BUT_zoomto.Click += new System.EventHandler(this.BUT_zoomto_Click);
+ //
// BUT_Camera
//
resources.ApplyResources(this.BUT_Camera, "BUT_Camera");
@@ -834,13 +844,13 @@
resources.ApplyResources(this.panelBASE, "panelBASE");
this.panelBASE.Name = "panelBASE";
//
- // BUT_zoomto
+ // BUT_loadkml
//
- resources.ApplyResources(this.BUT_zoomto, "BUT_zoomto");
- this.BUT_zoomto.Name = "BUT_zoomto";
- this.toolTip1.SetToolTip(this.BUT_zoomto, resources.GetString("BUT_zoomto.ToolTip"));
- this.BUT_zoomto.UseVisualStyleBackColor = true;
- this.BUT_zoomto.Click += new System.EventHandler(this.BUT_zoomto_Click);
+ resources.ApplyResources(this.BUT_loadkml, "BUT_loadkml");
+ this.BUT_loadkml.Name = "BUT_loadkml";
+ this.toolTip1.SetToolTip(this.BUT_loadkml, resources.GetString("BUT_loadkml.ToolTip"));
+ this.BUT_loadkml.UseVisualStyleBackColor = true;
+ this.BUT_loadkml.Click += new System.EventHandler(this.BUT_loadkml_Click);
//
// FlightPlanner
//
@@ -954,5 +964,6 @@
private System.Windows.Forms.DataGridViewImageColumn Up;
private System.Windows.Forms.DataGridViewImageColumn Down;
private MyButton BUT_zoomto;
+ private MyButton BUT_loadkml;
}
}
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
index 55f50b788b..bb08d54539 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.cs
@@ -18,6 +18,8 @@ using System.Resources;
using System.Reflection;
using System.ComponentModel;
using System.Threading;
+using SharpKml.Base;
+
namespace ArdupilotMega.GCSViews
@@ -440,6 +442,10 @@ namespace ArdupilotMega.GCSViews
trackBar1.Minimum = MainMap.MinZoom;
trackBar1.Maximum = MainMap.MaxZoom + 0.99;
+ // draw this layer first
+ kmlpolygons = new GMapOverlay(MainMap, "kmlpolygons");
+ MainMap.Overlays.Add(kmlpolygons);
+
routes = new GMapOverlay(MainMap, "routes");
MainMap.Overlays.Add(routes);
@@ -452,6 +458,8 @@ namespace ArdupilotMega.GCSViews
drawnpolygons = new GMapOverlay(MainMap, "drawnpolygons");
MainMap.Overlays.Add(drawnpolygons);
+
+
top = new GMapOverlay(MainMap, "top");
//MainMap.Overlays.Add(top);
@@ -648,6 +656,23 @@ namespace ArdupilotMega.GCSViews
writeKML();
}
+ void parser_ElementAdded(object sender, SharpKml.Base.ElementEventArgs e)
+ {
+
+ SharpKml.Dom.Polygon polygon = e.Element as SharpKml.Dom.Polygon;
+ if (polygon != null)
+ {
+ GMapPolygon kmlpolygon = new GMapPolygon(new List(), "kmlpolygon");
+
+ foreach (var loc in polygon.OuterBoundary.LinearRing.Coordinates)
+ {
+ kmlpolygon.Points.Add(new PointLatLng(loc.Latitude,loc.Longitude));
+ }
+
+ kmlpolygons.Polygons.Add(kmlpolygon);
+ }
+ }
+
private void ChangeColumnHeader(string command)
{
try
@@ -1721,7 +1746,9 @@ namespace ArdupilotMega.GCSViews
// polygons
GMapPolygon polygon;
GMapPolygon drawnpolygon;
+
//static GMapRoute route;
+ GMapOverlay kmlpolygons;
// layers
GMapOverlay top;
@@ -2070,7 +2097,7 @@ namespace ArdupilotMega.GCSViews
}
private void comboBoxMapType_SelectedValueChanged(object sender, EventArgs e)
- {
+ {
MainMap.MapType = (MapType)comboBoxMapType.SelectedItem;
FlightData.mymap.MapType = (MapType)comboBoxMapType.SelectedItem;
MainV2.config["MapType"] = comboBoxMapType.Text;
@@ -2101,7 +2128,8 @@ namespace ArdupilotMega.GCSViews
DataGridViewCell tcell = Commands.Rows[selectedrow].Cells[i];
if (tcell.GetType() == typeof(DataGridViewTextBoxCell))
{
- tcell.Value = "0";
+ if (tcell.Value.ToString() == "?")
+ tcell.Value = "0";
}
}
}
@@ -2625,6 +2653,8 @@ namespace ArdupilotMega.GCSViews
drawnpolygon.Points.Clear();
drawnpolygons.Markers.Clear();
MainMap.Invalidate();
+
+ writeKML();
}
private void clearMissionToolStripMenuItem_Click(object sender, EventArgs e)
@@ -2640,7 +2670,11 @@ namespace ArdupilotMega.GCSViews
Commands.Rows[selectedrow].Cells[Command.Index].Value = MAVLink.MAV_CMD.LOITER_UNLIM.ToString();
+ ChangeColumnHeader(MAVLink.MAV_CMD.LOITER_UNLIM.ToString());
+
setfromGE(end.Lat, end.Lng, (int)float.Parse(TXT_DefaultAlt.Text));
+
+ writeKML();
}
private void jumpstartToolStripMenuItem_Click(object sender, EventArgs e)
@@ -2655,6 +2689,8 @@ namespace ArdupilotMega.GCSViews
Commands.Rows[row].Cells[Param1.Index].Value = 1;
Commands.Rows[row].Cells[Param2.Index].Value = repeat;
+
+ writeKML();
}
private void jumpwPToolStripMenuItem_Click(object sender, EventArgs e)
@@ -2671,6 +2707,8 @@ namespace ArdupilotMega.GCSViews
Commands.Rows[row].Cells[Param1.Index].Value = wp;
Commands.Rows[row].Cells[Param2.Index].Value = repeat;
+
+ writeKML();
}
private void deleteWPToolStripMenuItem_Click(object sender, EventArgs e)
@@ -2717,7 +2755,11 @@ namespace ArdupilotMega.GCSViews
Commands.Rows[selectedrow].Cells[Param1.Index].Value = time;
+ ChangeColumnHeader(MAVLink.MAV_CMD.LOITER_TIME.ToString());
+
setfromGE(end.Lat, end.Lng, (int)float.Parse(TXT_DefaultAlt.Text));
+
+ writeKML();
}
private void loitercirclesToolStripMenuItem_Click(object sender, EventArgs e)
@@ -2731,7 +2773,11 @@ namespace ArdupilotMega.GCSViews
Commands.Rows[selectedrow].Cells[Param1.Index].Value = turns;
+ ChangeColumnHeader(MAVLink.MAV_CMD.LOITER_TURNS.ToString());
+
setfromGE(end.Lat, end.Lng, (int)float.Parse(TXT_DefaultAlt.Text));
+
+ writeKML();
}
private void BUT_Camera_Click(object sender, EventArgs e)
@@ -2768,5 +2814,29 @@ namespace ArdupilotMega.GCSViews
}
}
}
+
+ private void BUT_loadkml_Click(object sender, EventArgs e)
+ {
+
+ OpenFileDialog fd = new OpenFileDialog();
+ fd.Filter = "Google Earth KML (*.kml)|*.kml";
+ fd.DefaultExt = ".kml";
+ DialogResult result = fd.ShowDialog();
+ string file = fd.FileName;
+ if (file != "")
+ {
+ try
+ {
+ kmlpolygons.Polygons.Clear();
+
+ var parser = new SharpKml.Base.Parser();
+
+ parser.ElementAdded += new EventHandler(parser_ElementAdded);
+ parser.Parse(File.OpenRead(file));
+ }
+ catch (Exception ex) { MessageBox.Show("Bad KML File :" + ex.ToString()); }
+ }
+
+ }
}
}
\ No newline at end of file
diff --git a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx
index 4495da6c9f..4526c0fe26 100644
--- a/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx
+++ b/Tools/ArdupilotMegaPlanner/GCSViews/FlightPlanner.resx
@@ -148,7 +148,7 @@
panelWaypoints
- 4
+ 5
True
@@ -178,7 +178,7 @@
panelWaypoints
- 9
+ 10
Top, Bottom, Left, Right
@@ -340,7 +340,7 @@
panelWaypoints
- 11
+ 12
True
@@ -370,7 +370,7 @@
panelWaypoints
- 13
+ 14
23, 36
@@ -394,7 +394,7 @@
panelWaypoints
- 14
+ 15
154, 36
@@ -418,7 +418,7 @@
panelWaypoints
- 12
+ 13
True
@@ -448,7 +448,7 @@
panelWaypoints
- 5
+ 6
True
@@ -478,7 +478,7 @@
panelWaypoints
- 10
+ 11
89, 36
@@ -502,7 +502,7 @@
panelWaypoints
- 8
+ 9
True
@@ -532,11 +532,80 @@
panelWaypoints
- 7
+ 8
Bottom, Right
+
+ BUT_write
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ panel5
+
+
+ 0
+
+
+ BUT_read
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ panel5
+
+
+ 1
+
+
+ SaveFile
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ panel5
+
+
+ 2
+
+
+ BUT_loadwpfile
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ panel5
+
+
+ 3
+
+
+ 8, 250
+
+
+ 117, 114
+
+
+ 29
+
+
+ panel5
+
+
+ System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panelAction
+
+
+ 1
+
NoControl
@@ -645,30 +714,114 @@
3
-
- 8, 250
-
-
- 117, 114
-
-
- 29
-
-
- panel5
-
-
- System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- panelAction
-
-
- 1
-
Bottom, Right
+
+ label4
+
+
+ System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel1
+
+
+ 0
+
+
+ label3
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel1
+
+
+ 1
+
+
+ label2
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel1
+
+
+ 2
+
+
+ Label1
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel1
+
+
+ 3
+
+
+ TXT_homealt
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel1
+
+
+ 4
+
+
+ TXT_homelng
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel1
+
+
+ 5
+
+
+ TXT_homelat
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel1
+
+
+ 6
+
+
+ 8, 365
+
+
+ 117, 89
+
+
+ 31
+
+
+ panel1
+
+
+ System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panelAction
+
+
+ 2
+
True
@@ -852,27 +1005,6 @@
6
-
- 8, 365
-
-
- 117, 89
-
-
- 31
-
-
- panel1
-
-
- System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- panelAction
-
-
- 2
-
Up
@@ -912,6 +1044,111 @@
Bottom, Right
+
+ label7
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel2
+
+
+ 0
+
+
+ label8
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel2
+
+
+ 1
+
+
+ label9
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel2
+
+
+ 2
+
+
+ label10
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel2
+
+
+ 3
+
+
+ TXT_mousealt
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel2
+
+
+ 4
+
+
+ TXT_mouselong
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel2
+
+
+ 5
+
+
+ TXT_mouselat
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panel2
+
+
+ 6
+
+
+ 8, 130
+
+
+ 114, 79
+
+
+ 38
+
+
+ panel2
+
+
+ System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panelAction
+
+
+ 3
+
True
@@ -1095,27 +1332,9 @@
6
-
- 8, 130
-
-
- 114, 79
-
-
- 38
-
-
- panel2
-
-
- System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- panelAction
-
-
- 3
-
+
+ 172, 17
+
Bottom, Right
@@ -1128,9 +1347,6 @@
42
-
- 172, 17
-
Change the current map type
@@ -1239,11 +1455,44 @@
0
+
+ NoControl
+
+
+ 800, 25
+
+
+ 58, 23
+
+
+ 54
+
+
+ KML overlay
+
+
+ 172, 17
+
+
+ Get Camera settings for overlap
+
+
+ BUT_loadkml
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ panelWaypoints
+
+
+ 0
+
NoControl
- 746, 26
+ 732, 26
62, 23
@@ -1267,13 +1516,13 @@
panelWaypoints
- 0
+ 1
NoControl
- 692, 26
+ 678, 26
48, 23
@@ -1297,13 +1546,13 @@
panelWaypoints
- 1
+ 2
NoControl
- 638, 26
+ 624, 26
48, 23
@@ -1327,13 +1576,13 @@
panelWaypoints
- 2
+ 3
NoControl
- 576, 26
+ 562, 26
56, 23
@@ -1357,7 +1606,7 @@
panelWaypoints
- 3
+ 4
NoControl
@@ -1366,7 +1615,7 @@
479, 26
- 91, 23
+ 77, 23
48
@@ -1387,7 +1636,7 @@
panelWaypoints
- 6
+ 7
NoControl
@@ -1417,7 +1666,7 @@
panelWaypoints
- 15
+ 16
Bottom
@@ -1473,6 +1722,105 @@
3
+
+ lbl_distance
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panelMap
+
+
+ 0
+
+
+ lbl_homedist
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panelMap
+
+
+ 1
+
+
+ lbl_prevdist
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panelMap
+
+
+ 2
+
+
+ MainMap
+
+
+ GMap.NET.WindowsForms.GMapControl, GMap.NET.WindowsForms, Version=1.5.5.5, Culture=neutral, PublicKeyToken=b85b9027b614afef
+
+
+ panelMap
+
+
+ 3
+
+
+ trackBar1
+
+
+ ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ panelMap
+
+
+ 4
+
+
+ label11
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panelMap
+
+
+ 5
+
+
+ Fill
+
+
+ 0, 0
+
+
+ 878, 313
+
+
+ 51
+
+
+ panel6
+
+
+ panelMap
+
+
+ System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ panelBASE
+
+
+ 1
+
True
@@ -1569,93 +1917,6 @@
17, 17
-
- 167, 22
-
-
- Delete WP
-
-
- 113, 22
-
-
- Forever
-
-
- 113, 22
-
-
- Time
-
-
- 113, 22
-
-
- Circles
-
-
- 167, 22
-
-
- Loiter
-
-
- 102, 22
-
-
- Start
-
-
- 102, 22
-
-
- WP #
-
-
- 167, 22
-
-
- Jump
-
-
- 164, 6
-
-
- 167, 22
-
-
- Measure Distance
-
-
- 167, 22
-
-
- Rotate Map
-
-
- 174, 22
-
-
- Add Polygon Point
-
-
- 174, 22
-
-
- Clear Polygon
-
-
- 167, 22
-
-
- Grid Polygon
-
-
- 167, 22
-
-
- Clear Mission
-
168, 164
@@ -1831,6 +2092,93 @@
3
+
+ 167, 22
+
+
+ Delete WP
+
+
+ 167, 22
+
+
+ Loiter
+
+
+ 113, 22
+
+
+ Forever
+
+
+ 113, 22
+
+
+ Time
+
+
+ 113, 22
+
+
+ Circles
+
+
+ 167, 22
+
+
+ Jump
+
+
+ 102, 22
+
+
+ Start
+
+
+ 102, 22
+
+
+ WP #
+
+
+ 164, 6
+
+
+ 167, 22
+
+
+ Measure Distance
+
+
+ 167, 22
+
+
+ Rotate Map
+
+
+ 167, 22
+
+
+ Grid Polygon
+
+
+ 174, 22
+
+
+ Add Polygon Point
+
+
+ 174, 22
+
+
+ Clear Polygon
+
+
+ 167, 22
+
+
+ Clear Mission
+
Top, Bottom, Right
@@ -1894,33 +2242,6 @@
5
-
- Fill
-
-
- 0, 0
-
-
- 878, 313
-
-
- 51
-
-
- panel6
-
-
- panelMap
-
-
- System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- panelBASE
-
-
- 1
-
Fill
diff --git a/Tools/ArdupilotMegaPlanner/MAVLink.cs b/Tools/ArdupilotMegaPlanner/MAVLink.cs
index 1327dce0a5..685136fb38 100644
--- a/Tools/ArdupilotMegaPlanner/MAVLink.cs
+++ b/Tools/ArdupilotMegaPlanner/MAVLink.cs
@@ -34,6 +34,7 @@ namespace ArdupilotMega
bool oldlogformat = false;
byte mavlinkversion = 0;
+ public byte aptype = 0;
byte[] readingpacket = new byte[256];
public PointLatLngAlt[] wps = new PointLatLngAlt[200];
@@ -190,6 +191,7 @@ namespace ArdupilotMega
hb = (MAVLink.__mavlink_heartbeat_t)(temp);
mavlinkversion = hb.mavlink_version;
+ aptype = hb.type;
sysid = buffer[3];
compid = buffer[4];
diff --git a/Tools/ArdupilotMegaPlanner/MainV2.cs b/Tools/ArdupilotMegaPlanner/MainV2.cs
index c14c2567fe..d7b09349a4 100644
--- a/Tools/ArdupilotMegaPlanner/MainV2.cs
+++ b/Tools/ArdupilotMegaPlanner/MainV2.cs
@@ -79,13 +79,12 @@ namespace ArdupilotMega
GCSViews.Firmware Firmware;
GCSViews.Terminal Terminal;
- public void testpython()
- {
- Console.WriteLine("hello world from c# via python");
- }
-
public MainV2()
{
+ //new temp().ShowDialog();
+ //return;
+
+
Form splash = new Splash();
splash.Show();
@@ -108,10 +107,6 @@ namespace ArdupilotMega
//return;
-
- // preload
- Python.CreateEngine();
-
var t = Type.GetType("Mono.Runtime");
MONO = (t != null);
@@ -176,6 +171,9 @@ namespace ArdupilotMega
Simulation = new GCSViews.Simulation();
Firmware = new GCSViews.Firmware();
//Terminal = new GCSViews.Terminal();
+
+ // preload
+ Python.CreateEngine();
}
catch (Exception e) { MessageBox.Show("A Major error has occured : " + e.ToString()); this.Close(); }
diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
index 4c387fa873..60d13013cd 100644
--- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
+++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs
@@ -34,5 +34,5 @@ using System.Resources;
// by using the '*' as shown below:
// [assembly: AssemblyVersion("1.0.*")]
[assembly: AssemblyVersion("1.0.0.0")]
-[assembly: AssemblyFileVersion("1.0.99")]
+[assembly: AssemblyFileVersion("1.1.1")]
[assembly: NeutralResourcesLanguageAttribute("")]
diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs
index 1f30541e5a..31aa448918 100644
--- a/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs
@@ -121,13 +121,11 @@
this.label44 = new System.Windows.Forms.Label();
this.label43 = new System.Windows.Forms.Label();
this.label42 = new System.Windows.Forms.Label();
- this.BUT_HS4save = new ArdupilotMega.MyButton();
this.groupBox2 = new System.Windows.Forms.GroupBox();
this.label24 = new System.Windows.Forms.Label();
this.HS4_MIN = new System.Windows.Forms.TextBox();
this.HS4_MAX = new System.Windows.Forms.TextBox();
this.label40 = new System.Windows.Forms.Label();
- this.BUT_swash_manual = new ArdupilotMega.MyButton();
this.groupBox1 = new System.Windows.Forms.GroupBox();
this.label41 = new System.Windows.Forms.Label();
this.label21 = new System.Windows.Forms.Label();
@@ -160,6 +158,8 @@
this.HS2_REV = new System.Windows.Forms.CheckBox();
this.HS1_REV = new System.Windows.Forms.CheckBox();
this.label17 = new System.Windows.Forms.Label();
+ this.BUT_HS4save = new ArdupilotMega.MyButton();
+ this.BUT_swash_manual = new ArdupilotMega.MyButton();
this.HS4 = new ArdupilotMega.HorizontalProgressBar2();
this.HS3 = new ArdupilotMega.VerticalProgressBar2();
this.Gservoloc = new AGaugeApp.AGauge();
@@ -874,9 +874,7 @@
this.tabHeli.Controls.Add(this.label44);
this.tabHeli.Controls.Add(this.label43);
this.tabHeli.Controls.Add(this.label42);
- this.tabHeli.Controls.Add(this.BUT_HS4save);
this.tabHeli.Controls.Add(this.groupBox2);
- this.tabHeli.Controls.Add(this.BUT_swash_manual);
this.tabHeli.Controls.Add(this.groupBox1);
this.tabHeli.Controls.Add(this.HS4_TRIM);
this.tabHeli.Controls.Add(this.HS3_TRIM);
@@ -903,6 +901,8 @@
this.tabHeli.Controls.Add(this.HS2_REV);
this.tabHeli.Controls.Add(this.HS1_REV);
this.tabHeli.Controls.Add(this.label17);
+ this.tabHeli.Controls.Add(this.BUT_HS4save);
+ this.tabHeli.Controls.Add(this.BUT_swash_manual);
this.tabHeli.Controls.Add(this.HS4);
this.tabHeli.Controls.Add(this.HS3);
this.tabHeli.Controls.Add(this.Gservoloc);
@@ -959,13 +959,6 @@
resources.ApplyResources(this.label42, "label42");
this.label42.Name = "label42";
//
- // BUT_HS4save
- //
- resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save");
- this.BUT_HS4save.Name = "BUT_HS4save";
- this.BUT_HS4save.UseVisualStyleBackColor = true;
- this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click);
- //
// groupBox2
//
this.groupBox2.Controls.Add(this.label24);
@@ -1002,13 +995,6 @@
resources.ApplyResources(this.label40, "label40");
this.label40.Name = "label40";
//
- // BUT_swash_manual
- //
- resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual");
- this.BUT_swash_manual.Name = "BUT_swash_manual";
- this.BUT_swash_manual.UseVisualStyleBackColor = true;
- this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click);
- //
// groupBox1
//
this.groupBox1.Controls.Add(this.label41);
@@ -1262,6 +1248,20 @@
resources.ApplyResources(this.label17, "label17");
this.label17.Name = "label17";
//
+ // BUT_HS4save
+ //
+ resources.ApplyResources(this.BUT_HS4save, "BUT_HS4save");
+ this.BUT_HS4save.Name = "BUT_HS4save";
+ this.BUT_HS4save.UseVisualStyleBackColor = true;
+ this.BUT_HS4save.Click += new System.EventHandler(this.BUT_HS4save_Click);
+ //
+ // BUT_swash_manual
+ //
+ resources.ApplyResources(this.BUT_swash_manual, "BUT_swash_manual");
+ this.BUT_swash_manual.Name = "BUT_swash_manual";
+ this.BUT_swash_manual.UseVisualStyleBackColor = true;
+ this.BUT_swash_manual.Click += new System.EventHandler(this.BUT_swash_manual_Click);
+ //
// HS4
//
this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs
index c40d138e23..fbe470c9be 100644
--- a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs
+++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs
@@ -544,6 +544,8 @@ namespace ArdupilotMega.Setup
}
catch { MessageBox.Show("Invalid input!"); return; }
+ TXT_declination.Text = dec.ToString();
+
MainV2.comPort.setParam("COMPASS_DEC", dec * deg2rad);
}
}
@@ -786,11 +788,11 @@ namespace ArdupilotMega.Setup
}
catch (Exception ex) { MainV2.givecomport = false; MessageBox.Show("Invalid Comport Settings : " + ex.Message); return; }
- BUT_reset.Text = "Rebooting (20 sec)";
+ BUT_reset.Text = "Rebooting (60 sec)";
BUT_reset.Refresh();
Application.DoEvents();
- Sleep(20000, comPortT); // wait for boot/reset
+ Sleep(60000, comPortT); // wait for boot/reset
comPortT.DtrEnable = false;
diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx
index d1d8d1e2a1..4ae6d03fdf 100644
--- a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx
+++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx
@@ -117,29 +117,11 @@
System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- NoControl
-
-
-
- 214, 161
-
-
- 195, 23
-
-
-
- 0
-
-
- Reset APM Hardware to Default
-
BUT_reset
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabReset
@@ -147,12 +129,14 @@
0
+
4, 22
666, 393
+
4
@@ -171,6 +155,1663 @@
0
+
+ CHK_revch3
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabRadioIn
+
+
+ 0
+
+
+ CHK_revch4
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabRadioIn
+
+
+ 1
+
+
+ CHK_revch2
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabRadioIn
+
+
+ 2
+
+
+ CHK_revch1
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabRadioIn
+
+
+ 3
+
+
+ BUT_Calibrateradio
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabRadioIn
+
+
+ 4
+
+
+ BAR8
+
+
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabRadioIn
+
+
+ 5
+
+
+ BAR7
+
+
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabRadioIn
+
+
+ 6
+
+
+ BAR6
+
+
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabRadioIn
+
+
+ 7
+
+
+ BAR5
+
+
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabRadioIn
+
+
+ 8
+
+
+ BARpitch
+
+
+ ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabRadioIn
+
+
+ 9
+
+
+ BARthrottle
+
+
+ ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabRadioIn
+
+
+ 10
+
+
+ BARyaw
+
+
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabRadioIn
+
+
+ 11
+
+
+ BARroll
+
+
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabRadioIn
+
+
+ 12
+
+
+ 4, 22
+
+
+
+ 3, 3, 3, 3
+
+
+ 666, 393
+
+
+ 0
+
+
+ Radio Input
+
+
+ tabRadioIn
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabControl1
+
+
+ 1
+
+
+ CB_simple6
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 0
+
+
+ CB_simple5
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 1
+
+
+ CB_simple4
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 2
+
+
+ CB_simple3
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 3
+
+
+ CB_simple2
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 4
+
+
+ CB_simple1
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 5
+
+
+ label14
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 6
+
+
+ LBL_flightmodepwm
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 7
+
+
+ label13
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 8
+
+
+ lbl_currentmode
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 9
+
+
+ label12
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 10
+
+
+ label11
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 11
+
+
+ label10
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 12
+
+
+ label9
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 13
+
+
+ label8
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 14
+
+
+ label7
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 15
+
+
+ label6
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 16
+
+
+ CMB_fmode6
+
+
+ System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 17
+
+
+ label5
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 18
+
+
+ CMB_fmode5
+
+
+ System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 19
+
+
+ label4
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 20
+
+
+ CMB_fmode4
+
+
+ System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 21
+
+
+ label3
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 22
+
+
+ CMB_fmode3
+
+
+ System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 23
+
+
+ label2
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 24
+
+
+ CMB_fmode2
+
+
+ System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 25
+
+
+ label1
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 26
+
+
+ CMB_fmode1
+
+
+ System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabModes
+
+
+ 27
+
+
+ BUT_SaveModes
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabModes
+
+
+ 28
+
+
+ 4, 22
+
+
+ 666, 393
+
+
+ 3
+
+
+ Modes
+
+
+ tabModes
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabControl1
+
+
+ 2
+
+
+ True
+
+
+ NoControl
+
+
+ 390, 80
+
+
+ 104, 13
+
+
+ 28
+
+
+ Declination WebSite
+
+
+ linkLabelmagdec
+
+
+ System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHardware
+
+
+ 0
+
+
+ NoControl
+
+
+ 305, 57
+
+
+ 72, 16
+
+
+ 23
+
+
+ Declination
+
+
+ label100
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHardware
+
+
+ 1
+
+
+ 214, 17
+
+
+ 383, 57
+
+
+ 121, 20
+
+
+ 20
+
+
+ Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3
+
+
+ TXT_declination
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHardware
+
+
+ 2
+
+
+ NoControl
+
+
+ 162, 214
+
+
+ 103, 17
+
+
+ 24
+
+
+ Enable Airspeed
+
+
+ CHK_enableairspeed
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHardware
+
+
+ 3
+
+
+ NoControl
+
+
+ 159, 136
+
+
+ 90, 17
+
+
+ 25
+
+
+ Enable Sonar
+
+
+ CHK_enablesonar
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHardware
+
+
+ 4
+
+
+ NoControl
+
+
+ 162, 56
+
+
+ 105, 17
+
+
+ 27
+
+
+ Enable Compass
+
+
+ CHK_enablecompass
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHardware
+
+
+ 5
+
+
+ Zoom
+
+
+ NoControl
+
+
+ 78, 188
+
+
+ 75, 75
+
+
+ 3
+
+
+ pictureBox4
+
+
+ System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHardware
+
+
+ 6
+
+
+ Zoom
+
+
+ NoControl
+
+
+ 78, 106
+
+
+ 75, 75
+
+
+ 2
+
+
+ pictureBox3
+
+
+ System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHardware
+
+
+ 7
+
+
+ Zoom
+
+
+
+
+
+ NoControl
+
+
+
+
+
+ 78, 25
+
+
+ 75, 75
+
+
+ 0
+
+
+ pictureBox1
+
+
+ System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHardware
+
+
+ 8
+
+
+ 4, 22
+
+
+ 3, 3, 3, 3
+
+
+ 666, 393
+
+
+ 1
+
+
+ Hardware
+
+
+ tabHardware
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabControl1
+
+
+ 3
+
+
+ TXT_ampspervolt
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 0
+
+
+ TXT_divider
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 1
+
+
+ TXT_voltage
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 2
+
+
+ TXT_measuredvoltage
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 3
+
+
+ TXT_inputvoltage
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 4
+
+
+ label35
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 5
+
+
+ label34
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 6
+
+
+ label33
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 7
+
+
+ label32
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 8
+
+
+ label31
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 9
+
+
+ textBox3
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 10
+
+
+ label29
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 11
+
+
+ label30
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 12
+
+
+ TXT_battcapacity
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 13
+
+
+ CMB_batmontype
+
+
+ System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 14
+
+
+ pictureBox5
+
+
+ System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabBattery
+
+
+ 15
+
+
+ 4, 22
+
+
+ 2, 2, 2, 2
+
+
+ 666, 393
+
+
+ 6
+
+
+ Battery
+
+
+ tabBattery
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabControl1
+
+
+ 4
+
+
+ label28
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabArducopter
+
+
+ 0
+
+
+ label16
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabArducopter
+
+
+ 1
+
+
+ label15
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabArducopter
+
+
+ 2
+
+
+ pictureBoxQuadX
+
+
+ System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabArducopter
+
+
+ 3
+
+
+ pictureBoxQuad
+
+
+ System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabArducopter
+
+
+ 4
+
+
+ BUT_levelac2
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabArducopter
+
+
+ 5
+
+
+ 4, 22
+
+
+ 666, 393
+
+
+ 2
+
+
+ ArduCopter2
+
+
+ tabArducopter
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabControl1
+
+
+ 5
+
+
+ groupBox3
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 0
+
+
+ label44
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 1
+
+
+ label43
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 2
+
+
+ label42
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 3
+
+
+ groupBox2
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 4
+
+
+ groupBox1
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 5
+
+
+ HS4_TRIM
+
+
+ System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 6
+
+
+ HS3_TRIM
+
+
+ System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 7
+
+
+ HS2_TRIM
+
+
+ System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 8
+
+
+ HS1_TRIM
+
+
+ System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 9
+
+
+ label39
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 10
+
+
+ label38
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 11
+
+
+ label37
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 12
+
+
+ label36
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 13
+
+
+ label26
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 14
+
+
+ PIT_MAX_
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 15
+
+
+ label25
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 16
+
+
+ ROL_MAX_
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 17
+
+
+ label23
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 18
+
+
+ label22
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 19
+
+
+ HS4_REV
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 20
+
+
+ label20
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 21
+
+
+ label19
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 22
+
+
+ label18
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 23
+
+
+ SV3_POS_
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 24
+
+
+ SV2_POS_
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 25
+
+
+ SV1_POS_
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 26
+
+
+ HS3_REV
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 27
+
+
+ HS2_REV
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 28
+
+
+ HS1_REV
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 29
+
+
+ label17
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 30
+
+
+ BUT_HS4save
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabHeli
+
+
+ 31
+
+
+ BUT_swash_manual
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabHeli
+
+
+ 32
+
+
+ HS4
+
+
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabHeli
+
+
+ 33
+
+
+ HS3
+
+
+ ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabHeli
+
+
+ 34
+
+
+ Gservoloc
+
+
+ AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabHeli
+
+
+ 35
+
+
+ 4, 22
+
+
+ 666, 393
+
+
+ 5
+
+
+ AC2 Heli
+
+
+ tabHeli
+
+
+ System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabControl1
+
+
+ 6
+
+
+ Fill
+
+
+ 0, 0
+
+
+ 674, 419
+
+
+ 93
+
+
+ tabControl1
+
+
+ System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ $this
+
+
+ 0
+
+
+ NoControl
+
+
+ 214, 161
+
+
+ 195, 23
+
+
+ 0
+
+
+ Reset APM Hardware to Default
+
+
+ BUT_reset
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabReset
+
+
+ 0
+
True
@@ -310,7 +1951,7 @@
BUT_Calibrateradio
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabRadioIn
@@ -334,7 +1975,7 @@
BAR8
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabRadioIn
@@ -342,6 +1983,9 @@
5
+
+ 17, 17
+
446, 185
@@ -355,7 +1999,7 @@
BAR7
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabRadioIn
@@ -376,7 +2020,7 @@
BAR6
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabRadioIn
@@ -397,7 +2041,7 @@
BAR5
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabRadioIn
@@ -418,7 +2062,7 @@
BARpitch
- ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabRadioIn
@@ -439,7 +2083,7 @@
BARthrottle
- ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabRadioIn
@@ -460,7 +2104,7 @@
BARyaw
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabRadioIn
@@ -481,7 +2125,7 @@
BARroll
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabRadioIn
@@ -489,33 +2133,6 @@
12
-
- 4, 22
-
-
- 3, 3, 3, 3
-
-
- 666, 393
-
-
- 0
-
-
- Radio Input
-
-
- tabRadioIn
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabControl1
-
-
- 1
-
True
@@ -684,6 +2301,9 @@
True
+
+ NoControl
+
380, 100
@@ -1354,7 +2974,7 @@
BUT_SaveModes
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabModes
@@ -1362,309 +2982,6 @@
28
-
- 4, 22
-
-
- 666, 393
-
-
- 3
-
-
- Modes
-
-
- tabModes
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabControl1
-
-
- 2
-
-
- True
-
-
- NoControl
-
-
- 390, 80
-
-
- 104, 13
-
-
- 28
-
-
- Declination WebSite
-
-
- linkLabelmagdec
-
-
- System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 0
-
-
- NoControl
-
-
- 310, 57
-
-
- 60, 13
-
-
- 23
-
-
- Declination
-
-
- label100
-
-
- System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 1
-
-
- 383, 57
-
-
- 121, 20
-
-
- 20
-
-
- 214, 17
-
-
- Magnetic Declination (-20.0 to 20.0) eg 2° 3' W is -2.3
-
-
- TXT_declination
-
-
- System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 2
-
-
- NoControl
-
-
- 162, 214
-
-
- 103, 17
-
-
- 24
-
-
- Enable Airspeed
-
-
- CHK_enableairspeed
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 3
-
-
- NoControl
-
-
- 159, 136
-
-
- 90, 17
-
-
- 25
-
-
- Enable Sonar
-
-
- CHK_enablesonar
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 4
-
-
- NoControl
-
-
- 162, 56
-
-
- 105, 17
-
-
- 27
-
-
- Enable Compass
-
-
- CHK_enablecompass
-
-
- System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 5
-
-
- Zoom
-
-
- NoControl
-
-
- 78, 188
-
-
- 75, 75
-
-
- 3
-
-
- pictureBox4
-
-
- System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 6
-
-
- Zoom
-
-
- NoControl
-
-
- 78, 106
-
-
- 75, 75
-
-
- 2
-
-
- pictureBox3
-
-
- System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 7
-
-
- Zoom
-
-
-
-
-
- NoControl
-
-
-
-
-
- 78, 25
-
-
- 75, 75
-
-
- 0
-
-
- pictureBox1
-
-
- System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHardware
-
-
- 8
-
-
- 4, 22
-
-
- 3, 3, 3, 3
-
-
- 666, 393
-
-
- 1
-
-
- Hardware
-
-
- tabHardware
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabControl1
-
-
- 3
-
162, 267
@@ -2124,33 +3441,6 @@
15
-
- 4, 22
-
-
- 2, 2, 2, 2
-
-
- 666, 393
-
-
- 6
-
-
- Battery
-
-
- tabBattery
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabControl1
-
-
- 4
-
True
@@ -2315,7 +3605,7 @@ will work with hexa's etc
BUT_levelac2
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabArducopter
@@ -2323,29 +3613,77 @@ will work with hexa's etc
5
-
- 4, 22
+
+ label46
-
- 666, 393
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
+
+ groupBox3
+
+
+ 0
+
+
+ label45
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox3
+
+
+ 1
+
+
+ GYR_ENABLE_
+
+
+ System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox3
+
+
2
-
- ArduCopter2
+
+ GYR_GAIN_
-
- tabArducopter
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+ groupBox3
-
- tabControl1
+
+ 3
-
- 5
+
+ 433, 271
+
+
+ 101, 63
+
+
+ 135
+
+
+ Gyro
+
+
+ groupBox3
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ tabHeli
+
+
+ 0
True
@@ -2458,30 +3796,6 @@ will work with hexa's etc
3
-
- 433, 271
-
-
- 101, 63
-
-
- 135
-
-
- Gyro
-
-
- groupBox3
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 0
-
True
@@ -2545,6 +3859,9 @@ will work with hexa's etc
True
+
+ NoControl
+
451, 245
@@ -2569,31 +3886,73 @@ will work with hexa's etc
3
-
- NoControl
+
+ label24
-
- 479, 138
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
- 69, 23
+
+ groupBox2
-
- 131
+
+ 0
-
- Manual
+
+ HS4_MIN
-
- BUT_HS4save
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+
+ groupBox2
-
+
+ 1
+
+
+ HS4_MAX
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox2
+
+
+ 2
+
+
+ label40
+
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox2
+
+
+ 3
+
+
+ 433, 143
+
+
+ 169, 78
+
+
+ 130
+
+
+ groupBox2
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
tabHeli
-
+
4
@@ -2704,50 +4063,98 @@ will work with hexa's etc
3
-
- 433, 143
+
+ label41
-
- 169, 78
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
- 130
+
+ groupBox1
-
- groupBox2
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 5
-
-
- 298, 47
-
-
- 69, 23
-
-
+
0
-
- Manual
+
+ label21
-
- BUT_swash_manual
+
+ System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+
+ groupBox1
-
+
+ 1
+
+
+ COL_MIN_
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox1
+
+
+ 2
+
+
+ COL_MID_
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox1
+
+
+ 3
+
+
+ COL_MAX_
+
+
+ System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
+ groupBox1
+
+
+ 4
+
+
+ BUT_0collective
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ groupBox1
+
+
+ 5
+
+
+ 293, 52
+
+
+ 80, 209
+
+
+ 129
+
+
+ groupBox1
+
+
+ System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
+
+
tabHeli
-
- 6
+
+ 5
True
@@ -2782,6 +4189,9 @@ will work with hexa's etc
True
+
+ NoControl
+
24, 28
@@ -2897,7 +4307,7 @@ will work with hexa's etc
BUT_0collective
- ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
groupBox1
@@ -2905,27 +4315,6 @@ will work with hexa's etc
5
-
- 293, 52
-
-
- 80, 209
-
-
- 129
-
-
- groupBox1
-
-
- System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabHeli
-
-
- 7
-
535, 241
@@ -2945,7 +4334,7 @@ will work with hexa's etc
tabHeli
- 8
+ 6
122, 271
@@ -2966,7 +4355,7 @@ will work with hexa's etc
tabHeli
- 9
+ 7
122, 245
@@ -2987,7 +4376,7 @@ will work with hexa's etc
tabHeli
- 10
+ 8
122, 219
@@ -3008,7 +4397,7 @@ will work with hexa's etc
tabHeli
- 11
+ 9
True
@@ -3038,7 +4427,7 @@ will work with hexa's etc
tabHeli
- 12
+ 10
True
@@ -3068,7 +4457,7 @@ will work with hexa's etc
tabHeli
- 13
+ 11
True
@@ -3098,7 +4487,7 @@ will work with hexa's etc
tabHeli
- 14
+ 12
True
@@ -3128,7 +4517,7 @@ will work with hexa's etc
tabHeli
- 15
+ 13
True
@@ -3158,7 +4547,7 @@ will work with hexa's etc
tabHeli
- 16
+ 14
310, 342
@@ -3182,7 +4571,7 @@ will work with hexa's etc
tabHeli
- 17
+ 15
True
@@ -3212,7 +4601,7 @@ will work with hexa's etc
tabHeli
- 18
+ 16
310, 316
@@ -3236,7 +4625,7 @@ will work with hexa's etc
tabHeli
- 19
+ 17
True
@@ -3266,7 +4655,7 @@ will work with hexa's etc
tabHeli
- 20
+ 18
True
@@ -3296,7 +4685,7 @@ will work with hexa's etc
tabHeli
- 21
+ 19
True
@@ -3323,7 +4712,7 @@ will work with hexa's etc
tabHeli
- 22
+ 20
True
@@ -3353,7 +4742,7 @@ will work with hexa's etc
tabHeli
- 23
+ 21
True
@@ -3383,7 +4772,7 @@ will work with hexa's etc
tabHeli
- 24
+ 22
True
@@ -3413,7 +4802,7 @@ will work with hexa's etc
tabHeli
- 25
+ 23
53, 271
@@ -3437,7 +4826,7 @@ will work with hexa's etc
tabHeli
- 26
+ 24
53, 245
@@ -3461,7 +4850,7 @@ will work with hexa's etc
tabHeli
- 27
+ 25
53, 219
@@ -3485,7 +4874,7 @@ will work with hexa's etc
tabHeli
- 28
+ 26
True
@@ -3512,7 +4901,7 @@ will work with hexa's etc
tabHeli
- 29
+ 27
True
@@ -3539,7 +4928,7 @@ will work with hexa's etc
tabHeli
- 30
+ 28
True
@@ -3566,7 +4955,7 @@ will work with hexa's etc
tabHeli
- 31
+ 29
True
@@ -3596,6 +4985,60 @@ will work with hexa's etc
tabHeli
+ 30
+
+
+ NoControl
+
+
+ 479, 138
+
+
+ 69, 23
+
+
+ 131
+
+
+ Manual
+
+
+ BUT_HS4save
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabHeli
+
+
+ 31
+
+
+ NoControl
+
+
+ 298, 47
+
+
+ 69, 23
+
+
+ 0
+
+
+ Manual
+
+
+ BUT_swash_manual
+
+
+ ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
+
+
+ tabHeli
+
+
32
@@ -3611,7 +5054,7 @@ will work with hexa's etc
HS4
- ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabHeli
@@ -3632,7 +5075,7 @@ will work with hexa's etc
HS3
- ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabHeli
@@ -3662,7 +5105,7 @@ will work with hexa's etc
Gservoloc
- AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=ff91852278f5092c
+ AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc
tabHeli
@@ -3670,54 +5113,9 @@ will work with hexa's etc
35
-
- 4, 22
-
-
- 666, 393
-
-
- 5
-
-
- AC2 Heli
-
-
- tabHeli
-
-
- System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- tabControl1
-
-
- 6
-
-
- Fill
-
-
- 0, 0
-
-
- 674, 419
-
-
- 93
-
-
- tabControl1
-
-
- System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089
-
-
- $this
-
-
- 0
-
+
+ 214, 17
+
True
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application
index ab815306fe..38c1663988 100644
--- a/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application
+++ b/Tools/ArdupilotMegaPlanner/bin/Release/ArdupilotMegaPlanner.application
@@ -4,14 +4,14 @@
-
+
- QOAVY4eRCMREZxVv8+wq0bmXS7U=
+ mN7pjMOs48ZdF2S8vaEAJbtq8b4=
diff --git a/Tools/ArdupilotMegaPlanner/bin/Release/srtm/placeholder.txt b/Tools/ArdupilotMegaPlanner/bin/Release/srtm/placeholder.txt
new file mode 100644
index 0000000000..e69de29bb2
diff --git a/Tools/ArdupilotMegaPlanner/temp.Designer.cs b/Tools/ArdupilotMegaPlanner/temp.Designer.cs
index 2b3ee6077d..369fb59438 100644
--- a/Tools/ArdupilotMegaPlanner/temp.Designer.cs
+++ b/Tools/ArdupilotMegaPlanner/temp.Designer.cs
@@ -44,6 +44,7 @@
this.BUT_geinjection = new ArdupilotMega.MyButton();
this.BUT_clearcustommaps = new ArdupilotMega.MyButton();
this.BUT_lang_edit = new ArdupilotMega.MyButton();
+ this.myButton1 = new ArdupilotMega.MyButton();
this.SuspendLayout();
//
// button1
@@ -202,11 +203,22 @@
this.BUT_lang_edit.UseVisualStyleBackColor = true;
this.BUT_lang_edit.Click += new System.EventHandler(this.BUT_lang_edit_Click);
//
+ // myButton1
+ //
+ this.myButton1.Location = new System.Drawing.Point(30, 174);
+ this.myButton1.Name = "myButton1";
+ this.myButton1.Size = new System.Drawing.Size(75, 23);
+ this.myButton1.TabIndex = 17;
+ this.myButton1.Text = "myButton1";
+ this.myButton1.UseVisualStyleBackColor = true;
+ this.myButton1.Click += new System.EventHandler(this.myButton1_Click);
+ //
// temp
//
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
this.ClientSize = new System.Drawing.Size(731, 281);
+ this.Controls.Add(this.myButton1);
this.Controls.Add(this.BUT_lang_edit);
this.Controls.Add(this.BUT_clearcustommaps);
this.Controls.Add(this.BUT_geinjection);
@@ -249,6 +261,7 @@
private MyButton BUT_geinjection;
private MyButton BUT_clearcustommaps;
private MyButton BUT_lang_edit;
+ private MyButton myButton1;
//private SharpVectors.Renderers.Forms.SvgPictureBox svgPictureBox1;
}
diff --git a/Tools/ArdupilotMegaPlanner/temp.cs b/Tools/ArdupilotMegaPlanner/temp.cs
index 4e7a1a35f9..53d44660f2 100644
--- a/Tools/ArdupilotMegaPlanner/temp.cs
+++ b/Tools/ArdupilotMegaPlanner/temp.cs
@@ -9,12 +9,14 @@ using System.Text.RegularExpressions;
using System.IO.Ports;
using System.IO;
using System.Runtime.InteropServices;
+using System.Net;
using GMap.NET.WindowsForms;
using GMap.NET.CacheProviders;
-//using SharpVectors.Renderers.Forms;
-//using SharpVectors.Converters;
+using OpenGlobe.Core;
+using OpenGlobe.Renderer;
+using OpenGlobe.Scene;
namespace ArdupilotMega
@@ -870,6 +872,217 @@ namespace ArdupilotMega
{
new resedit.Form1().Show();
}
+
+ GraphicsWindow _window;
+ SceneState _sceneState;
+ CameraLookAtPoint _lookCamera;
+ CameraFly _flyCamera;
+ ClearState _clearState;
+ GlobeClipmapTerrain _clipmap;
+ HeadsUpDisplay _hud;
+ Font _hudFont;
+ RayCastedGlobe _globe;
+ ClearState _clearDepth;
+ Ellipsoid _ellipsoid;
+
+ private void myButton1_Click(object sender, EventArgs e)
+ {
+
+
+ _window = Device.CreateWindow(800, 600, "Chapter 13: Clipmap Terrain on a Globe");
+
+ _ellipsoid = Ellipsoid.Wgs84;
+
+ WorldWindTerrainSource terrainSource = new WorldWindTerrainSource();
+ GMapRestImagery imagery = new GMapRestImagery();
+ _clipmap = new GlobeClipmapTerrain(_window.Context, terrainSource, imagery, _ellipsoid, 511);
+ _clipmap.HeightExaggeration = 1.0f;
+
+
+
+ IList gridResolutions = new List();
+ gridResolutions.Add(new GridResolution(
+ new Interval(0, 1000000, IntervalEndpoint.Closed, IntervalEndpoint.Open),
+ new Vector2D(0.005, 0.005)));
+ gridResolutions.Add(new GridResolution(
+ new Interval(1000000, 2000000, IntervalEndpoint.Closed, IntervalEndpoint.Open),
+ new Vector2D(0.01, 0.01)));
+ gridResolutions.Add(new GridResolution(
+ new Interval(2000000, 20000000, IntervalEndpoint.Closed, IntervalEndpoint.Open),
+ new Vector2D(0.05, 0.05)));
+ gridResolutions.Add(new GridResolution(
+ new Interval(20000000, double.MaxValue, IntervalEndpoint.Closed, IntervalEndpoint.Open),
+ new Vector2D(0.1, 0.1)));
+
+
+
+ _sceneState = new SceneState();
+ _sceneState.DiffuseIntensity = 0.90f;
+ _sceneState.SpecularIntensity = 0.05f;
+ _sceneState.AmbientIntensity = 0.05f;
+ _sceneState.Camera.FieldOfViewY = Math.PI / 3.0;
+
+ _clearState = new ClearState();
+ _clearState.Color = Color.White;
+
+ _sceneState.Camera.PerspectiveNearPlaneDistance = 0.000001 * _ellipsoid.MaximumRadius;
+ _sceneState.Camera.PerspectiveFarPlaneDistance = 10.0 * _ellipsoid.MaximumRadius;
+ _sceneState.SunPosition = new Vector3D(200000, 300000, 200000) * _ellipsoid.MaximumRadius;
+
+ _lookCamera = new CameraLookAtPoint(_sceneState.Camera, _window, _ellipsoid);
+ _lookCamera.Range = 1.5 * _ellipsoid.MaximumRadius;
+
+ _globe = new RayCastedGlobe(_window.Context);
+ _globe.Shape = _ellipsoid;
+ Bitmap bitmap = new Bitmap("NE2_50M_SR_W_4096.jpg");
+ _globe.Texture = Device.CreateTexture2D(bitmap, TextureFormat.RedGreenBlue8, false);
+ //_globe.GridResolutions = new GridResolutionCollection(gridResolutions);
+
+ _clearDepth = new ClearState();
+ _clearDepth.Buffers = ClearBuffers.DepthBuffer | ClearBuffers.StencilBuffer;
+
+ //_window.Keyboard.KeyDown += OnKeyDown;
+
+ _window.Resize += OnResize;
+ _window.RenderFrame += OnRenderFrame;
+ _window.PreRenderFrame += OnPreRenderFrame;
+
+ _hudFont = new Font("Arial", 16);
+ _hud = new HeadsUpDisplay();
+ _hud.Color = Color.Blue;
+
+ //_flyCamera = new CameraFly(_sceneState.Camera, _window);
+ //_flyCamera.MovementRate = 1200.0;
+ //_flyCamera.InputEnabled = true;
+
+ _sceneState.Camera.Target = new Vector3D(115, -35, 100.0);
+
+ _window.Run(30);
+
+
+ }
+
+ private void OnResize()
+ {
+ _window.Context.Viewport = new Rectangle(0, 0, _window.Width, _window.Height);
+ _sceneState.Camera.AspectRatio = _window.Width / (double)_window.Height;
+ }
+
+ private void OnRenderFrame()
+ {
+ Context context = _window.Context;
+ context.Clear(_clearState);
+
+ _globe.Render(context, _sceneState);
+
+ context.Clear(_clearDepth);
+
+ _clipmap.Render(context, _sceneState);
+
+ //_sceneState.Camera.Target = new Vector3D(115000, -350000, 100000.0);
+
+ if (_hud != null)
+ {
+ //_hud.Render(context, _sceneState);
+ }
+ }
+
+ private void OnPreRenderFrame()
+ {
+ Context context = _window.Context;
+ _clipmap.PreRender(context, _sceneState);
+ }
}
+
+ public class GMapRestImagery : RasterSource
+ {
+ GMapControl MainMap;
+ public GMapRestImagery()
+ {
+ //_baseUri = baseUri;
+
+ _levels = new RasterLevel[NumberOfLevels];
+ _levelsCollection = new RasterLevelCollection(_levels);
+
+ double deltaLongitude = LevelZeroDeltaLongitudeDegrees;
+ double deltaLatitude = LevelZeroDeltaLatitudeDegrees;
+ for (int i = 0; i < _levels.Length; ++i)
+ {
+ int longitudePosts = (int)Math.Round(360.0 / deltaLongitude) * TileLongitudePosts + 1;
+ int latitudePosts = (int)Math.Round(180 / deltaLatitude) * TileLatitudePosts + 1;
+ _levels[i] = new RasterLevel(this, i, _extent, longitudePosts, latitudePosts, TileLongitudePosts, TileLatitudePosts);
+ deltaLongitude /= 2.0;
+ deltaLatitude /= 2.0;
+ }
+
+ MainMap = new GMapControl();
+ MainMap.MapType = GMap.NET.MapType.GoogleSatellite;
+
+ MainMap.CacheLocation = Path.GetDirectoryName(Application.ExecutablePath) + "/gmapcache/";
+ }
+
+ public override GeodeticExtent Extent
+ {
+ get { return _extent; }
+ }
+
+ public int TileLongitudePosts
+ {
+ get { return 256; }
+ }
+
+ public int TileLatitudePosts
+ {
+ get { return 256; }
+ }
+
+ public override RasterLevelCollection Levels
+ {
+ get { return _levelsCollection; }
+ }
+
+ public override Texture2D LoadTileTexture(RasterTileIdentifier identifier)
+ {
+ //if (identifier.Level > 4)
+ //return null;
+ int level = identifier.Level; // 0 is -180 long
+ int longitudeIndex = ((_levels[level].LongitudePosts / _levels[level].LongitudePostsPerTile) / 2 / 2) + identifier.X; // (_levels[level].LongitudePosts / _levels[level].LongitudePostsPerTile) -
+ int latitudeIndex = identifier.Y; // (_levels[level].LatitudePosts / _levels[level].LatitudePostsPerTile) -
+
+ int damn = (1 << level) - latitudeIndex - 1;
+
+ Console.WriteLine(" z {0} lat {1} lon {2} ", level, damn, longitudeIndex);
+
+ GMap.NET.PureImage img = MainMap.Manager.ImageCacheLocal.GetImageFromCache(GMap.NET.MapType.GoogleSatellite, new GMap.NET.GPoint(longitudeIndex, damn), level);
+
+ Application.DoEvents();
+
+ try
+ {
+ Bitmap bitmap = new Bitmap(new Bitmap(img.Data), 256, 256);
+ Graphics e = Graphics.FromImage(bitmap);
+ e.DrawString(level + " " +longitudeIndex + "," + damn, new Font("Arial", 20), Brushes.White, new PointF(0, 0));
+
+ return Device.CreateTexture2DRectangle(bitmap, TextureFormat.RedGreenBlue8);
+ }
+ catch {
+ try
+ {
+ return null;
+ }
+ catch { return null; }
+ }
+ }
+
+ private Uri _baseUri;
+ private GeodeticExtent _extent = new GeodeticExtent(-0, -90, 360, 90);
+ private int _tilesLoaded;
+ private RasterLevel[] _levels;
+ private RasterLevelCollection _levelsCollection;
+
+ private const int NumberOfLevels = 20;
+ private const double LevelZeroDeltaLongitudeDegrees = 180;
+ private const double LevelZeroDeltaLatitudeDegrees = 180;
+ }
}
diff --git a/Tools/autotest/pysim/aircraft.py b/Tools/autotest/pysim/aircraft.py
index e7a7d09aa1..9087ec97ed 100644
--- a/Tools/autotest/pysim/aircraft.py
+++ b/Tools/autotest/pysim/aircraft.py
@@ -17,9 +17,17 @@ class Aircraft(object):
self.pitch = 0.0 # degrees
self.roll = 0.0 # degrees
self.yaw = 0.0 # degrees
+
+ # rates in earth frame
self.pitch_rate = 0.0 # degrees/s
self.roll_rate = 0.0 # degrees/s
self.yaw_rate = 0.0 # degrees/s
+
+ # rates in body frame
+ self.pDeg = 0.0 # degrees/s
+ self.qDeg = 0.0 # degrees/s
+ self.rDeg = 0.0 # degrees/s
+
self.velocity = euclid.Vector3(0, 0, 0) # m/s, North, East, Up
self.position = euclid.Vector3(0, 0, 0) # m North, East, Up
self.accel = euclid.Vector3(0, 0, 0) # m/s/s North, East, Up
diff --git a/Tools/autotest/pysim/quadcopter.py b/Tools/autotest/pysim/quadcopter.py
index 43c734e3cc..60fb398395 100755
--- a/Tools/autotest/pysim/quadcopter.py
+++ b/Tools/autotest/pysim/quadcopter.py
@@ -34,15 +34,21 @@ class QuadCopter(Aircraft):
delta_time = t - self.last_time
self.last_time = t
- # rotational acceleration, in degrees/s/s
+ # rotational acceleration, in degrees/s/s, in body frame
roll_accel = (m[1] - m[0]) * 5000.0
pitch_accel = (m[2] - m[3]) * 5000.0
yaw_accel = -((m[2]+m[3]) - (m[0]+m[1])) * 400.0
- # update rotational rates
- self.roll_rate += roll_accel * delta_time
- self.pitch_rate += pitch_accel * delta_time
- self.yaw_rate += yaw_accel * delta_time
+ # update rotational rates in body frame
+ self.pDeg += roll_accel * delta_time
+ self.qDeg += pitch_accel * delta_time
+ self.rDeg += yaw_accel * delta_time
+
+ # calculate rates in earth frame
+ (self.roll_rate,
+ self.pitch_rate,
+ self.yaw_rate) = util.BodyRatesToEarthRates(self.roll, self.pitch, self.yaw,
+ self.pDeg, self.qDeg, self.rDeg)
# update rotation
self.roll += self.roll_rate * delta_time
diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py
index 1b9bf83537..5d458243c2 100644
--- a/Tools/autotest/pysim/util.py
+++ b/Tools/autotest/pysim/util.py
@@ -290,6 +290,55 @@ def check_parent(parent_pid=os.getppid()):
sys.exit(1)
+def EarthRatesToBodyRates(roll, pitch, yaw,
+ rollRate, pitchRate, yawRate):
+ '''convert the angular velocities from earth frame to
+ body frame. Thanks to James Goppert for the formula
+
+ all inputs and outputs are in degrees
+
+ returns a tuple, (p,q,r)
+ '''
+ from math import radians, degrees, sin, cos, tan
+
+ phi = radians(roll)
+ theta = radians(pitch)
+ phiDot = radians(rollRate)
+ thetaDot = radians(pitchRate)
+ psiDot = radians(yawRate)
+
+ p = phiDot - psiDot*sin(theta)
+ q = cos(phi)*thetaDot + sin(phi)*psiDot*cos(theta)
+ r = cos(phi)*psiDot*cos(theta) - sin(phi)*thetaDot
+
+ return (degrees(p), degrees(q), degrees(r))
+
+def BodyRatesToEarthRates(roll, pitch, yaw, pDeg, qDeg, rDeg):
+ '''convert the angular velocities from body frame to
+ earth frame.
+
+ all inputs and outputs are in degrees
+
+ returns a tuple, (rollRate,pitchRate,yawRate)
+ '''
+ from math import radians, degrees, sin, cos, tan, fabs
+
+ p = radians(pDeg)
+ q = radians(qDeg)
+ r = radians(rDeg)
+
+ phi = radians(roll)
+ theta = radians(pitch)
+
+ phiDot = p + tan(theta)*(q*sin(phi) + r*cos(phi))
+ thetaDot = q*cos(phi) - r*sin(phi)
+ if fabs(cos(theta)) < 1.0e-20:
+ theta += 1.0e-10
+ psiDot = (q*sin(phi) + r*cos(phi))/cos(theta)
+
+ return (degrees(phiDot), degrees(thetaDot), degrees(psiDot))
+
+
if __name__ == "__main__":
import doctest
doctest.testmod()
diff --git a/libraries/APM_PI/APM_PI.cpp b/libraries/APM_PI/APM_PI.cpp
index d6efc6fb29..14328022fd 100644
--- a/libraries/APM_PI/APM_PI.cpp
+++ b/libraries/APM_PI/APM_PI.cpp
@@ -7,10 +7,14 @@
#include "APM_PI.h"
-long
-APM_PI::get_pi(int32_t error, float dt, bool calc_i)
+int32_t APM_PI::get_p(int32_t error)
{
- if(calc_i){
+ return (float)error * _kp;
+}
+
+int32_t APM_PI::get_i(int32_t error, float dt)
+{
+ if(dt != 0){
_integrator += ((float)error * _ki) * dt;
if (_integrator < -_imax) {
@@ -19,7 +23,12 @@ APM_PI::get_pi(int32_t error, float dt, bool calc_i)
_integrator = _imax;
}
}
- return (float)error * _kp + _integrator;
+ return _integrator;
+}
+
+int32_t APM_PI::get_pi(int32_t error, float dt)
+{
+ return get_p(error) + get_i(error, dt);
}
void
diff --git a/libraries/APM_PI/APM_PI.h b/libraries/APM_PI/APM_PI.h
index c94e1cb951..accfab992c 100644
--- a/libraries/APM_PI/APM_PI.h
+++ b/libraries/APM_PI/APM_PI.h
@@ -78,7 +78,10 @@ public:
/// @returns The updated control output.
///
//long get_pi(int32_t error, float dt);
- long get_pi(int32_t error, float dt, bool calc_i=true);
+ int32_t get_pi(int32_t error, float dt);
+ int32_t get_p(int32_t error);
+ int32_t get_i(int32_t error, float dt);
+
/// Reset the PI integrator
///
diff --git a/libraries/APM_RC/APM_RC.h b/libraries/APM_RC/APM_RC.h
index d36b0f11eb..65e5b278d5 100644
--- a/libraries/APM_RC/APM_RC.h
+++ b/libraries/APM_RC/APM_RC.h
@@ -39,7 +39,7 @@ class Arduino_Mega_ISR_Registry;
class APM_RC_Class
{
public:
- virtual void Init( Arduino_Mega_ISR_Registry * isr_reg );
+ virtual void Init( Arduino_Mega_ISR_Registry * isr_reg ) = 0;
virtual void OutputCh(uint8_t ch, uint16_t pwm) = 0;
virtual uint16_t InputCh(uint8_t ch) = 0;
virtual uint8_t GetState() = 0;