mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 06:28:32 -04:00
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
8ef704face
@ -7,7 +7,6 @@ Authors: Jason Short
|
|||||||
Based on code and ideas from the Arducopter team: Jose Julio, Randy Mackay, Jani Hirvinen
|
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
|
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
|
This firmware is free software; you can redistribute it and/or
|
||||||
modify it under the terms of the GNU Lesser General Public
|
modify it under the terms of the GNU Lesser General Public
|
||||||
License as published by the Free Software Foundation; either
|
License as published by the Free Software Foundation; either
|
||||||
@ -393,7 +392,6 @@ static int16_t airspeed; // m/s * 100
|
|||||||
|
|
||||||
// Location Errors
|
// Location Errors
|
||||||
// ---------------
|
// ---------------
|
||||||
static int32_t yaw_error; // how off are we pointed
|
|
||||||
static int32_t long_error, lat_error; // temp for debugging
|
static int32_t long_error, lat_error; // temp for debugging
|
||||||
|
|
||||||
// Battery Sensors
|
// Battery Sensors
|
||||||
@ -440,32 +438,32 @@ static byte throttle_mode;
|
|||||||
static boolean takeoff_complete; // Flag for using take-off controls
|
static boolean takeoff_complete; // Flag for using take-off controls
|
||||||
static boolean land_complete;
|
static boolean land_complete;
|
||||||
static int32_t old_alt; // used for managing altitude rates
|
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 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 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 angle_boost; // used in adjust altitude to make changing alt faster
|
||||||
|
|
||||||
// Loiter management
|
// Loiter management
|
||||||
// -----------------
|
// -----------------
|
||||||
static int32_t original_target_bearing; // deg * 100, used to check we are not passing the WP
|
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 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_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_sum; // deg : how far we have turned around a waypoint
|
||||||
static uint32_t loiter_time; // millis : when we started LOITER mode
|
static uint32_t loiter_time; // millis : when we started LOITER mode
|
||||||
static unsigned loiter_time_max; // millis : how long to stay in LOITER mode
|
static unsigned loiter_time_max; // millis : how long to stay in LOITER mode
|
||||||
|
|
||||||
|
|
||||||
// these are the values for navigation control functions
|
// these are the values for navigation control functions
|
||||||
// ----------------------------------------------------
|
// ----------------------------------------------------
|
||||||
static int32_t nav_roll; // deg * 100 : target roll angle
|
static int32_t nav_roll; // deg * 100 : target roll angle
|
||||||
static int32_t nav_pitch; // deg * 100 : target pitch angle
|
static int32_t nav_pitch; // deg * 100 : target pitch angle
|
||||||
static int32_t nav_yaw; // deg * 100 : target yaw angle
|
static int32_t nav_yaw; // deg * 100 : target yaw angle
|
||||||
static int32_t auto_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_lat; // for error calcs
|
||||||
static int32_t nav_lon; // for error calcs
|
static int32_t nav_lon; // for error calcs
|
||||||
static int16_t nav_throttle; // 0-1000 for throttle control
|
static int16_t nav_throttle; // 0-1000 for throttle control
|
||||||
static int16_t crosstrack_error;
|
static int16_t crosstrack_error;
|
||||||
|
|
||||||
static uint32_t throttle_integrator; // used to integrate throttle output to predict battery life
|
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
|
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
|
// repeating event control
|
||||||
// -----------------------
|
// -----------------------
|
||||||
static byte event_id; // what to do - see defines
|
static byte event_id; // what to do - see defines
|
||||||
static uint32_t event_timer; // when the event was asked for in ms
|
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 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_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_value; // per command value, such as PWM for servos
|
||||||
static int16_t event_undo_value; // the value used to undo commands
|
static int16_t event_undo_value; // the value used to undo commands
|
||||||
//static byte repeat_forever;
|
//static byte repeat_forever;
|
||||||
//static byte undo_event; // counter for timing the undo
|
//static byte undo_event; // counter for timing the undo
|
||||||
|
|
||||||
@ -1146,9 +1144,9 @@ void update_throttle_mode(void)
|
|||||||
|
|
||||||
//remove alt_hold_velocity when implemented
|
//remove alt_hold_velocity when implemented
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#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
|
#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
|
#endif
|
||||||
|
|
||||||
// reset next_WP.alt
|
// reset next_WP.alt
|
||||||
@ -1398,14 +1396,14 @@ adjust_altitude()
|
|||||||
// we remove 0 to 100 PWM from hover
|
// we remove 0 to 100 PWM from hover
|
||||||
manual_boost = g.rc_3.control_in - 180;
|
manual_boost = g.rc_3.control_in - 180;
|
||||||
manual_boost = max(-120, manual_boost);
|
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_alt_hold.reset_I();
|
||||||
g.pi_throttle.reset_I();
|
g.pi_throttle.reset_I();
|
||||||
|
|
||||||
}else if (g.rc_3.control_in >= 650){
|
}else if (g.rc_3.control_in >= 650){
|
||||||
// we add 0 to 100 PWM to hover
|
// we add 0 to 100 PWM to hover
|
||||||
manual_boost = g.rc_3.control_in - 650;
|
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_alt_hold.reset_I();
|
||||||
g.pi_throttle.reset_I();
|
g.pi_throttle.reset_I();
|
||||||
|
|
||||||
@ -1439,7 +1437,7 @@ static void tuning(){
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case CH6_RATE_KP:
|
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_roll.kP(tuning_value);
|
||||||
g.pi_rate_pitch.kP(tuning_value);
|
g.pi_rate_pitch.kP(tuning_value);
|
||||||
break;
|
break;
|
||||||
|
@ -13,18 +13,15 @@ get_stabilize_roll(int32_t target_angle)
|
|||||||
error = constrain(error, -2500, 2500);
|
error = constrain(error, -2500, 2500);
|
||||||
|
|
||||||
// conver to desired Rate:
|
// 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
|
// 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
|
#if FRAME_CONFIG != HELI_FRAME // cannot use rate control for helicopters
|
||||||
rate -= iterm;
|
|
||||||
|
|
||||||
#if FRAME_CONFIG != HELI_FRAME // cannot use rate control for helicopters
|
|
||||||
error = rate - (omega.x * DEGX100);
|
error = rate - (omega.x * DEGX100);
|
||||||
rate = g.pi_rate_roll.get_pi(error, G_Dt);
|
rate = g.pi_rate_roll.get_pi(error, G_Dt);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// output control:
|
// output control:
|
||||||
rate = constrain(rate, -2500, 2500);
|
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
|
// limit the error we're feeding to the PID
|
||||||
error = constrain(error, -2500, 2500);
|
error = constrain(error, -2500, 2500);
|
||||||
|
|
||||||
// conver to desired Rate:
|
// convert to desired Rate:
|
||||||
rate = g.pi_stabilize_pitch.get_pi(error, G_Dt);
|
rate = g.pi_stabilize_pitch.get_p(error);
|
||||||
|
|
||||||
// experiment to pipe iterm directly into the output
|
// 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
|
#if FRAME_CONFIG != HELI_FRAME // cannot use rate control for helicopters
|
||||||
rate -= iterm;
|
|
||||||
|
|
||||||
#if FRAME_CONFIG != HELI_FRAME // cannot use rate control for helicopters
|
|
||||||
error = rate - (omega.y * DEGX100);
|
error = rate - (omega.y * DEGX100);
|
||||||
rate = g.pi_rate_pitch.get_pi(error, G_Dt);
|
rate = g.pi_rate_pitch.get_pi(error, G_Dt);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// output control:
|
// output control:
|
||||||
rate = constrain(rate, -2500, 2500);
|
rate = constrain(rate, -2500, 2500);
|
||||||
@ -70,46 +64,61 @@ get_stabilize_yaw(int32_t target_angle)
|
|||||||
int32_t error;
|
int32_t error;
|
||||||
int32_t rate;
|
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
|
// limit the error we're feeding to the PID
|
||||||
yaw_error = constrain(yaw_error, -YAW_ERROR_MAX, YAW_ERROR_MAX);
|
error = constrain(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);
|
// 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 FRAME_CONFIG == HELI_FRAME // cannot use rate control for helicopters
|
||||||
if( ! g.heli_ext_gyro_enabled ) {
|
if(!g.heli_ext_gyro_enabled ) {
|
||||||
// Rate P:
|
error = rate - (degrees(omega.z) * 100.0);
|
||||||
error = rate - (degrees(omega.z) * 100.0);
|
rate = g.pi_rate_yaw.get_pi(error, G_Dt);
|
||||||
rate = g.pi_rate_yaw.get_pi(error, G_Dt);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// output control:
|
// output control:
|
||||||
return (int)constrain(rate, -4500, 4500);
|
rate = constrain(rate, -4500, 4500);
|
||||||
|
return (int)rate + iterm;
|
||||||
#else
|
#else
|
||||||
// Rate P:
|
error = rate - (omega.z * DEGX100);;
|
||||||
error = rate - (degrees(omega.z) * 100.0);
|
rate = g.pi_rate_yaw.get_pi(error, G_Dt);
|
||||||
rate = g.pi_rate_yaw.get_pi(error, G_Dt);
|
|
||||||
//Serial.printf("%d\t%d\n", (int)error, (int)rate);
|
|
||||||
|
|
||||||
// output control:
|
// output control:
|
||||||
return (int)constrain(rate, -2500, 2500);
|
rate = constrain(rate, -2500, 2500);
|
||||||
|
return (int)rate + iterm;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#define ALT_ERROR_MAX 300
|
#define ALT_ERROR_MAX 300
|
||||||
static int
|
static int16_t
|
||||||
get_nav_throttle(int32_t z_error)
|
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
|
// limit error to prevent I term run up
|
||||||
z_error = constrain(z_error, -ALT_ERROR_MAX, ALT_ERROR_MAX);
|
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;
|
rate_error = rate_error - climb_rate;
|
||||||
|
|
||||||
// limit the 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
|
static int
|
||||||
|
@ -108,7 +108,16 @@ dump_log(uint8_t argc, const Menu::arg *argv)
|
|||||||
// check that the requested log number can be read
|
// check that the requested log number can be read
|
||||||
dump_log = argv[1].i;
|
dump_log = argv[1].i;
|
||||||
last_log_num = g.log_last_filenumber;
|
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"));
|
Serial.printf_P(PSTR("dumping all\n"));
|
||||||
Log_Read(1, DF_LAST_PAGE);
|
Log_Read(1, DF_LAST_PAGE);
|
||||||
return(-1);
|
return(-1);
|
||||||
|
@ -470,8 +470,8 @@ static bool verify_RTL()
|
|||||||
{
|
{
|
||||||
// loiter at the WP
|
// loiter at the WP
|
||||||
wp_control = WP_MODE;
|
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()){
|
if((wp_distance <= g.waypoint_radius) || check_missed_wp()){
|
||||||
wp_control = LOITER_MODE;
|
wp_control = LOITER_MODE;
|
||||||
|
|
||||||
|
@ -628,7 +628,7 @@
|
|||||||
|
|
||||||
// RATE control
|
// RATE control
|
||||||
#ifndef THROTTLE_P
|
#ifndef THROTTLE_P
|
||||||
# define THROTTLE_P 0.5 //
|
# define THROTTLE_P 0.4 //
|
||||||
#endif
|
#endif
|
||||||
#ifndef THROTTLE_I
|
#ifndef THROTTLE_I
|
||||||
# define THROTTLE_I 0.0 //
|
# define THROTTLE_I 0.0 //
|
||||||
|
@ -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);
|
x_error = constrain(x_error, -NAV_ERR_MAX, NAV_ERR_MAX);
|
||||||
y_error = constrain(y_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 x_target_speed = g.pi_loiter_lon.get_p(x_error);
|
||||||
int y_target_speed = g.pi_loiter_lat.get_pi(y_error, dTnav);
|
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:
|
// find the rates:
|
||||||
float temp = g_gps->ground_course * RADX100;
|
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
|
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 = g.pi_nav_lat.get_pi(y_rate_error, dTnav);
|
||||||
nav_lat = constrain(nav_lat, -3500, 3500);
|
nav_lat = constrain(nav_lat, -3500, 3500);
|
||||||
|
nav_lat += y_iterm;
|
||||||
|
|
||||||
x_rate_error = x_target_speed - x_actual_speed;
|
x_rate_error = x_target_speed - x_actual_speed;
|
||||||
x_rate_error = constrain(x_rate_error, -250, 250);
|
x_rate_error = constrain(x_rate_error, -250, 250);
|
||||||
nav_lon = g.pi_nav_lon.get_pi(x_rate_error, dTnav);
|
nav_lon = g.pi_nav_lon.get_pi(x_rate_error, dTnav);
|
||||||
nav_lon = constrain(nav_lon, -3500, 3500);
|
nav_lon = constrain(nav_lon, -3500, 3500);
|
||||||
|
nav_lon += x_iterm;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void calc_loiter2(int x_error, int y_error)
|
static void calc_loiter2(int x_error, int y_error)
|
||||||
|
@ -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)
|
//test_reverse(uint8_t argc, const Menu::arg *argv)
|
||||||
{
|
{
|
||||||
print_hit_enter();
|
print_hit_enter();
|
||||||
|
@ -112,7 +112,16 @@ dump_log(uint8_t argc, const Menu::arg *argv)
|
|||||||
// check that the requested log number can be read
|
// check that the requested log number can be read
|
||||||
dump_log = argv[1].i;
|
dump_log = argv[1].i;
|
||||||
last_log_num = g.log_last_filenumber;
|
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"));
|
Serial.printf_P(PSTR("dumping all\n"));
|
||||||
Log_Read(1, DF_LAST_PAGE);
|
Log_Read(1, DF_LAST_PAGE);
|
||||||
return(-1);
|
return(-1);
|
||||||
|
@ -105,7 +105,7 @@ USB_Descriptor_Configuration_t PROGMEM ConfigurationDescriptor =
|
|||||||
|
|
||||||
.ConfigAttributes = (USB_CONFIG_ATTR_BUSPOWERED | USB_CONFIG_ATTR_SELFPOWERED),
|
.ConfigAttributes = (USB_CONFIG_ATTR_BUSPOWERED | USB_CONFIG_ATTR_SELFPOWERED),
|
||||||
|
|
||||||
.MaxPowerConsumption = USB_CONFIG_POWER_MA(100)
|
.MaxPowerConsumption = USB_CONFIG_POWER_MA(400)
|
||||||
},
|
},
|
||||||
|
|
||||||
.CDC_CCI_Interface =
|
.CDC_CCI_Interface =
|
||||||
|
4
Tools/ArduPPM/Binaries/Hash.txt
Normal file
4
Tools/ArduPPM/Binaries/Hash.txt
Normal file
@ -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
|
@ -3,6 +3,7 @@ using System.Collections.Generic;
|
|||||||
using System.Linq;
|
using System.Linq;
|
||||||
using System.Text;
|
using System.Text;
|
||||||
using System.Management;
|
using System.Management;
|
||||||
|
using System.Windows.Forms;
|
||||||
|
|
||||||
namespace ArdupilotMega
|
namespace ArdupilotMega
|
||||||
{
|
{
|
||||||
@ -55,26 +56,6 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
System.Threading.Thread.Sleep(500);
|
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.DtrEnable = true;
|
||||||
serialPort.BaudRate = 115200;
|
serialPort.BaudRate = 115200;
|
||||||
serialPort.Open();
|
serialPort.Open();
|
||||||
@ -94,7 +75,42 @@ namespace ArdupilotMega
|
|||||||
if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
|
if (temp[0] == 6 && temp[1] == 0 && temp.Length == 2)
|
||||||
{
|
{
|
||||||
serialPort.Close();
|
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 { }
|
catch { }
|
||||||
|
@ -172,9 +172,18 @@
|
|||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Scripting.ExtensionAttribute.dll</HintPath>
|
<HintPath>..\..\..\..\..\..\..\Program Files (x86)\IronPython 2.7.1\IronPython-2.6.1\Microsoft.Scripting.ExtensionAttribute.dll</HintPath>
|
||||||
</Reference>
|
</Reference>
|
||||||
|
<Reference Include="OpenGlobe.Core">
|
||||||
|
<HintPath>..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\Source\Examples\Chapter13\ClipmapTerrainOnGlobe\bin\Debug\OpenGlobe.Core.dll</HintPath>
|
||||||
|
</Reference>
|
||||||
|
<Reference Include="OpenGlobe.Renderer">
|
||||||
|
<HintPath>..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\Source\Examples\Chapter13\ClipmapTerrainOnGlobe\bin\Debug\OpenGlobe.Renderer.dll</HintPath>
|
||||||
|
</Reference>
|
||||||
|
<Reference Include="OpenGlobe.Scene">
|
||||||
|
<HintPath>..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\Source\Examples\Chapter13\ClipmapTerrainOnGlobe\bin\Debug\OpenGlobe.Scene.dll</HintPath>
|
||||||
|
</Reference>
|
||||||
<Reference Include="OpenTK, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
|
<Reference Include="OpenTK, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\opentk\trunk\Binaries\OpenTK\Release\OpenTK.dll</HintPath>
|
<HintPath>..\..\..\..\..\Desktop\DIYDrones\virtualglobebook-OpenGlobe-ddf1d7e\ThirdParty\OpenTKGL4\Binaries\OpenTK\Release\OpenTK.dll</HintPath>
|
||||||
</Reference>
|
</Reference>
|
||||||
<Reference Include="OpenTK.GLControl, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
|
<Reference Include="OpenTK.GLControl, Version=1.0.0.0, Culture=neutral, PublicKeyToken=bad199fe84eb3df4, processorArchitecture=MSIL">
|
||||||
<SpecificVersion>False</SpecificVersion>
|
<SpecificVersion>False</SpecificVersion>
|
||||||
@ -571,13 +580,11 @@
|
|||||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||||
</Content>
|
</Content>
|
||||||
<Content Include="Resources\MAVCmd.zh-Hans.txt" />
|
<Content Include="Resources\MAVCmd.zh-Hans.txt" />
|
||||||
|
<None Include="Resources\MAVParam.txt" />
|
||||||
<Content Include="Resources\MAVParam.zh-Hans.txt" />
|
<Content Include="Resources\MAVParam.zh-Hans.txt" />
|
||||||
<None Include="Resources\MAVCmd.txt">
|
<None Include="Resources\MAVCmd.txt">
|
||||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||||
</None>
|
</None>
|
||||||
<None Include="Resources\MAVParam.txt">
|
|
||||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
|
||||||
</None>
|
|
||||||
<None Include="Resources\new frames-09.png" />
|
<None Include="Resources\new frames-09.png" />
|
||||||
<Content Include="dataflashlog.xml">
|
<Content Include="dataflashlog.xml">
|
||||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||||
|
@ -11,6 +11,6 @@
|
|||||||
<UpdateUrlHistory />
|
<UpdateUrlHistory />
|
||||||
</PropertyGroup>
|
</PropertyGroup>
|
||||||
<PropertyGroup>
|
<PropertyGroup>
|
||||||
<ReferencePath>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\</ReferencePath>
|
<ReferencePath>C:\Users\hog\Desktop\DIYDrones\myquad\greatmaps_e1bb830a18a3\Demo.WindowsForms\bin\Debug\;C:\Users\hog\Desktop\DIYDrones\myquad\sharpkml\SharpKml\bin\Release\</ReferencePath>
|
||||||
</PropertyGroup>
|
</PropertyGroup>
|
||||||
</Project>
|
</Project>
|
@ -55,7 +55,7 @@
|
|||||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
|
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex</url>
|
||||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560>
|
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex</url2560>
|
||||||
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560-2.hex</url2560-2>
|
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560-2.hex</url2560-2>
|
||||||
<name>ArduCopter V2.0.54 Quad</name>
|
<name>ArduCopter V2.0.55 Quad</name>
|
||||||
<desc>
|
<desc>
|
||||||
#define FRAME_CONFIG QUAD_FRAME
|
#define FRAME_CONFIG QUAD_FRAME
|
||||||
#define FRAME_ORIENTATION X_FRAME
|
#define FRAME_ORIENTATION X_FRAME
|
||||||
@ -67,7 +67,7 @@
|
|||||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url>
|
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex</url>
|
||||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560>
|
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex</url2560>
|
||||||
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560-2.hex</url2560-2>
|
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560-2.hex</url2560-2>
|
||||||
<name>ArduCopter V2.0.54 Tri</name>
|
<name>ArduCopter V2.0.55 Tri</name>
|
||||||
<desc>
|
<desc>
|
||||||
#define FRAME_CONFIG TRI_FRAME
|
#define FRAME_CONFIG TRI_FRAME
|
||||||
#define FRAME_ORIENTATION X_FRAME
|
#define FRAME_ORIENTATION X_FRAME
|
||||||
@ -79,7 +79,7 @@
|
|||||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url>
|
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex</url>
|
||||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560>
|
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex</url2560>
|
||||||
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560-2.hex</url2560-2>
|
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560-2.hex</url2560-2>
|
||||||
<name>ArduCopter V2.0.54 Hexa</name>
|
<name>ArduCopter V2.0.55 Hexa</name>
|
||||||
<desc>
|
<desc>
|
||||||
#define FRAME_CONFIG HEXA_FRAME
|
#define FRAME_CONFIG HEXA_FRAME
|
||||||
#define FRAME_ORIENTATION X_FRAME
|
#define FRAME_ORIENTATION X_FRAME
|
||||||
@ -91,7 +91,7 @@
|
|||||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url>
|
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex</url>
|
||||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex</url2560>
|
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex</url2560>
|
||||||
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560-2.hex</url2560-2>
|
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560-2.hex</url2560-2>
|
||||||
<name>ArduCopter V2.0.54 Y6</name>
|
<name>ArduCopter V2.0.55 Y6</name>
|
||||||
<desc>
|
<desc>
|
||||||
#define FRAME_CONFIG Y6_FRAME
|
#define FRAME_CONFIG Y6_FRAME
|
||||||
#define FRAME_ORIENTATION X_FRAME
|
#define FRAME_ORIENTATION X_FRAME
|
||||||
@ -151,7 +151,7 @@
|
|||||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url>
|
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex</url>
|
||||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex</url2560>
|
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex</url2560>
|
||||||
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560-2.hex</url2560-2>
|
<url2560-2>http://meee146.planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560-2.hex</url2560-2>
|
||||||
<name>ArduCopter V2.0.54 Quad Hil</name>
|
<name>ArduCopter V2.0.55 Quad Hil</name>
|
||||||
<desc>
|
<desc>
|
||||||
#define FRAME_CONFIG QUAD_FRAME
|
#define FRAME_CONFIG QUAD_FRAME
|
||||||
#define FRAME_ORIENTATION PLUS_FRAME
|
#define FRAME_ORIENTATION PLUS_FRAME
|
||||||
|
@ -30,8 +30,8 @@
|
|||||||
{
|
{
|
||||||
this.components = new System.ComponentModel.Container();
|
this.components = new System.ComponentModel.Container();
|
||||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
|
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
|
||||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle3 = new System.Windows.Forms.DataGridViewCellStyle();
|
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle4 = new System.Windows.Forms.DataGridViewCellStyle();
|
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||||
this.Params = new System.Windows.Forms.DataGridView();
|
this.Params = new System.Windows.Forms.DataGridView();
|
||||||
this.Command = new System.Windows.Forms.DataGridViewTextBoxColumn();
|
this.Command = new System.Windows.Forms.DataGridViewTextBoxColumn();
|
||||||
this.Value = 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.RLL2SRV_P = new System.Windows.Forms.NumericUpDown();
|
||||||
this.label52 = new System.Windows.Forms.Label();
|
this.label52 = new System.Windows.Forms.Label();
|
||||||
this.TabAC2 = new System.Windows.Forms.TabPage();
|
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.groupBox17 = new System.Windows.Forms.GroupBox();
|
||||||
this.ACRO_PIT_IMAX = new System.Windows.Forms.NumericUpDown();
|
this.ACRO_PIT_IMAX = new System.Windows.Forms.NumericUpDown();
|
||||||
this.label27 = new System.Windows.Forms.Label();
|
this.label27 = new System.Windows.Forms.Label();
|
||||||
@ -403,14 +405,14 @@
|
|||||||
this.Params.AllowUserToAddRows = false;
|
this.Params.AllowUserToAddRows = false;
|
||||||
this.Params.AllowUserToDeleteRows = false;
|
this.Params.AllowUserToDeleteRows = false;
|
||||||
resources.ApplyResources(this.Params, "Params");
|
resources.ApplyResources(this.Params, "Params");
|
||||||
dataGridViewCellStyle3.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
||||||
dataGridViewCellStyle3.BackColor = System.Drawing.Color.Maroon;
|
dataGridViewCellStyle1.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)));
|
dataGridViewCellStyle1.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;
|
dataGridViewCellStyle1.ForeColor = System.Drawing.Color.White;
|
||||||
dataGridViewCellStyle3.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
dataGridViewCellStyle1.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
||||||
dataGridViewCellStyle3.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
dataGridViewCellStyle1.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
||||||
dataGridViewCellStyle3.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
|
dataGridViewCellStyle1.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
|
||||||
this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle3;
|
this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle1;
|
||||||
this.Params.ColumnHeadersHeightSizeMode = System.Windows.Forms.DataGridViewColumnHeadersHeightSizeMode.AutoSize;
|
this.Params.ColumnHeadersHeightSizeMode = System.Windows.Forms.DataGridViewColumnHeadersHeightSizeMode.AutoSize;
|
||||||
this.Params.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
|
this.Params.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
|
||||||
this.Command,
|
this.Command,
|
||||||
@ -419,14 +421,14 @@
|
|||||||
this.mavScale,
|
this.mavScale,
|
||||||
this.RawValue});
|
this.RawValue});
|
||||||
this.Params.Name = "Params";
|
this.Params.Name = "Params";
|
||||||
dataGridViewCellStyle4.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
dataGridViewCellStyle2.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
||||||
dataGridViewCellStyle4.BackColor = System.Drawing.SystemColors.ActiveCaption;
|
dataGridViewCellStyle2.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)));
|
dataGridViewCellStyle2.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;
|
dataGridViewCellStyle2.ForeColor = System.Drawing.SystemColors.WindowText;
|
||||||
dataGridViewCellStyle4.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
dataGridViewCellStyle2.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
||||||
dataGridViewCellStyle4.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
dataGridViewCellStyle2.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
||||||
dataGridViewCellStyle4.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
|
dataGridViewCellStyle2.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
|
||||||
this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle4;
|
this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2;
|
||||||
this.Params.RowHeadersVisible = false;
|
this.Params.RowHeadersVisible = false;
|
||||||
this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged);
|
this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged);
|
||||||
//
|
//
|
||||||
@ -1087,6 +1089,8 @@
|
|||||||
//
|
//
|
||||||
// TabAC2
|
// 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.groupBox17);
|
||||||
this.TabAC2.Controls.Add(this.groupBox5);
|
this.TabAC2.Controls.Add(this.groupBox5);
|
||||||
this.TabAC2.Controls.Add(this.groupBox18);
|
this.TabAC2.Controls.Add(this.groupBox18);
|
||||||
@ -1104,6 +1108,28 @@
|
|||||||
resources.ApplyResources(this.TabAC2, "TabAC2");
|
resources.ApplyResources(this.TabAC2, "TabAC2");
|
||||||
this.TabAC2.Name = "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
|
// groupBox17
|
||||||
//
|
//
|
||||||
this.groupBox17.Controls.Add(this.ACRO_PIT_IMAX);
|
this.groupBox17.Controls.Add(this.ACRO_PIT_IMAX);
|
||||||
@ -2451,5 +2477,7 @@
|
|||||||
private System.Windows.Forms.Label label44;
|
private System.Windows.Forms.Label label44;
|
||||||
private System.Windows.Forms.NumericUpDown ACRO_RLL_P;
|
private System.Windows.Forms.NumericUpDown ACRO_RLL_P;
|
||||||
private System.Windows.Forms.Label label48;
|
private System.Windows.Forms.Label label48;
|
||||||
|
private MyLabel myLabel1;
|
||||||
|
private System.Windows.Forms.ComboBox CH7_OPT;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -380,6 +380,15 @@ namespace ArdupilotMega.GCSViews
|
|||||||
}
|
}
|
||||||
catch { }
|
catch { }
|
||||||
|
|
||||||
|
try
|
||||||
|
{
|
||||||
|
ComboBox thisctl = ((ComboBox)ctl);
|
||||||
|
|
||||||
|
thisctl.SelectedIndex = (int)(float)param[value];
|
||||||
|
|
||||||
|
thisctl.Validated += new EventHandler(ComboBox_Validated);
|
||||||
|
} catch {}
|
||||||
|
|
||||||
}
|
}
|
||||||
if (text.Length == 0)
|
if (text.Length == 0)
|
||||||
{
|
{
|
||||||
@ -390,6 +399,11 @@ namespace ArdupilotMega.GCSViews
|
|||||||
Params.Sort(Params.Columns[0], ListSortDirection.Ascending);
|
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)
|
void Configuration_Validating(object sender, CancelEventArgs e)
|
||||||
{
|
{
|
||||||
EEPROM_View_float_TextChanged(sender, e);
|
EEPROM_View_float_TextChanged(sender, e);
|
||||||
@ -403,8 +417,16 @@ namespace ArdupilotMega.GCSViews
|
|||||||
// do domainupdown state check
|
// do domainupdown state check
|
||||||
try
|
try
|
||||||
{
|
{
|
||||||
value = float.Parse(((Control)sender).Text);
|
if (sender.GetType() == typeof(NumericUpDown))
|
||||||
changes[name] = value;
|
{
|
||||||
|
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;
|
((Control)sender).BackColor = Color.Green;
|
||||||
}
|
}
|
||||||
catch (Exception)
|
catch (Exception)
|
||||||
@ -481,7 +503,14 @@ namespace ArdupilotMega.GCSViews
|
|||||||
{
|
{
|
||||||
if (row.Cells[0].Value.ToString() == name)
|
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;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -516,12 +545,21 @@ namespace ArdupilotMega.GCSViews
|
|||||||
{
|
{
|
||||||
if (text.Length > 0)
|
if (text.Length > 0)
|
||||||
{
|
{
|
||||||
decimal option = (decimal)(float.Parse(Params[e.ColumnIndex, e.RowIndex].Value.ToString()));
|
if (sender.GetType() == typeof(NumericUpDown))
|
||||||
((NumericUpDown)text[0]).Value = option;
|
{
|
||||||
((NumericUpDown)text[0]).BackColor = Color.Green;
|
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();
|
Params.Focus();
|
||||||
}
|
}
|
||||||
|
File diff suppressed because it is too large
Load Diff
@ -258,6 +258,18 @@ namespace ArdupilotMega.GCSViews
|
|||||||
findfirmware("AC2-QUADHIL");
|
findfirmware("AC2-QUADHIL");
|
||||||
return true;
|
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);
|
return base.ProcessCmdKey(ref msg, keyData);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -534,6 +546,8 @@ namespace ArdupilotMega.GCSViews
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Console.WriteLine("Using "+baseurl);
|
||||||
|
|
||||||
// Create a request using a URL that can receive a post.
|
// Create a request using a URL that can receive a post.
|
||||||
WebRequest request = WebRequest.Create(baseurl);
|
WebRequest request = WebRequest.Create(baseurl);
|
||||||
request.Timeout = 10000;
|
request.Timeout = 10000;
|
||||||
@ -615,7 +629,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
//port = new ArduinoSTK();
|
//port = new ArduinoSTK();
|
||||||
port.BaudRate = 57600;
|
port.BaudRate = 57600;
|
||||||
}
|
}
|
||||||
else if (board == "2560")
|
else if (board == "2560" || board == "2560-2")
|
||||||
{
|
{
|
||||||
port = new ArduinoSTKv2();
|
port = new ArduinoSTKv2();
|
||||||
port.BaudRate = 115200;
|
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
|
else
|
||||||
{
|
{
|
||||||
@ -704,7 +718,7 @@ namespace ArdupilotMega.GCSViews
|
|||||||
|
|
||||||
Application.DoEvents();
|
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";
|
lbl_status.Text = "Done";
|
||||||
}
|
}
|
||||||
|
@ -31,14 +31,14 @@
|
|||||||
{
|
{
|
||||||
this.components = new System.ComponentModel.Container();
|
this.components = new System.ComponentModel.Container();
|
||||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(FlightPlanner));
|
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(FlightPlanner));
|
||||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
|
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle9 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle5 = new System.Windows.Forms.DataGridViewCellStyle();
|
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle13 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle6 = new System.Windows.Forms.DataGridViewCellStyle();
|
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle14 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
|
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle10 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle3 = new System.Windows.Forms.DataGridViewCellStyle();
|
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle11 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle4 = new System.Windows.Forms.DataGridViewCellStyle();
|
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle12 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle7 = new System.Windows.Forms.DataGridViewCellStyle();
|
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle15 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle8 = 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_altmode = new System.Windows.Forms.CheckBox();
|
||||||
this.CHK_holdalt = new System.Windows.Forms.CheckBox();
|
this.CHK_holdalt = new System.Windows.Forms.CheckBox();
|
||||||
this.Commands = new System.Windows.Forms.DataGridView();
|
this.Commands = new System.Windows.Forms.DataGridView();
|
||||||
@ -89,6 +89,7 @@
|
|||||||
this.textBox1 = new System.Windows.Forms.TextBox();
|
this.textBox1 = new System.Windows.Forms.TextBox();
|
||||||
this.panelWaypoints = new BSE.Windows.Forms.Panel();
|
this.panelWaypoints = new BSE.Windows.Forms.Panel();
|
||||||
this.splitter1 = new BSE.Windows.Forms.Splitter();
|
this.splitter1 = new BSE.Windows.Forms.Splitter();
|
||||||
|
this.BUT_zoomto = new ArdupilotMega.MyButton();
|
||||||
this.BUT_Camera = new ArdupilotMega.MyButton();
|
this.BUT_Camera = new ArdupilotMega.MyButton();
|
||||||
this.BUT_grid = new ArdupilotMega.MyButton();
|
this.BUT_grid = new ArdupilotMega.MyButton();
|
||||||
this.BUT_Prefetch = new ArdupilotMega.MyButton();
|
this.BUT_Prefetch = new ArdupilotMega.MyButton();
|
||||||
@ -120,7 +121,7 @@
|
|||||||
this.label11 = new System.Windows.Forms.Label();
|
this.label11 = new System.Windows.Forms.Label();
|
||||||
this.panelBASE = new System.Windows.Forms.Panel();
|
this.panelBASE = new System.Windows.Forms.Panel();
|
||||||
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
|
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();
|
((System.ComponentModel.ISupportInitialize)(this.Commands)).BeginInit();
|
||||||
this.panel5.SuspendLayout();
|
this.panel5.SuspendLayout();
|
||||||
this.panel1.SuspendLayout();
|
this.panel1.SuspendLayout();
|
||||||
@ -152,14 +153,14 @@
|
|||||||
//
|
//
|
||||||
this.Commands.AllowUserToAddRows = false;
|
this.Commands.AllowUserToAddRows = false;
|
||||||
resources.ApplyResources(this.Commands, "Commands");
|
resources.ApplyResources(this.Commands, "Commands");
|
||||||
dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
dataGridViewCellStyle9.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
||||||
dataGridViewCellStyle1.BackColor = System.Drawing.SystemColors.Control;
|
dataGridViewCellStyle9.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)));
|
dataGridViewCellStyle9.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;
|
dataGridViewCellStyle9.ForeColor = System.Drawing.SystemColors.WindowText;
|
||||||
dataGridViewCellStyle1.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
dataGridViewCellStyle9.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
||||||
dataGridViewCellStyle1.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
dataGridViewCellStyle9.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
||||||
dataGridViewCellStyle1.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
|
dataGridViewCellStyle9.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
|
||||||
this.Commands.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle1;
|
this.Commands.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle9;
|
||||||
this.Commands.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
|
this.Commands.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
|
||||||
this.Command,
|
this.Command,
|
||||||
this.Param1,
|
this.Param1,
|
||||||
@ -173,17 +174,17 @@
|
|||||||
this.Up,
|
this.Up,
|
||||||
this.Down});
|
this.Down});
|
||||||
this.Commands.Name = "Commands";
|
this.Commands.Name = "Commands";
|
||||||
dataGridViewCellStyle5.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
dataGridViewCellStyle13.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
||||||
dataGridViewCellStyle5.BackColor = System.Drawing.SystemColors.Control;
|
dataGridViewCellStyle13.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)));
|
dataGridViewCellStyle13.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;
|
dataGridViewCellStyle13.ForeColor = System.Drawing.SystemColors.WindowText;
|
||||||
dataGridViewCellStyle5.Format = "N0";
|
dataGridViewCellStyle13.Format = "N0";
|
||||||
dataGridViewCellStyle5.NullValue = "0";
|
dataGridViewCellStyle13.NullValue = "0";
|
||||||
dataGridViewCellStyle5.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
dataGridViewCellStyle13.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
||||||
dataGridViewCellStyle5.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
dataGridViewCellStyle13.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
||||||
this.Commands.RowHeadersDefaultCellStyle = dataGridViewCellStyle5;
|
this.Commands.RowHeadersDefaultCellStyle = dataGridViewCellStyle13;
|
||||||
dataGridViewCellStyle6.ForeColor = System.Drawing.Color.Black;
|
dataGridViewCellStyle14.ForeColor = System.Drawing.Color.Black;
|
||||||
this.Commands.RowsDefaultCellStyle = dataGridViewCellStyle6;
|
this.Commands.RowsDefaultCellStyle = dataGridViewCellStyle14;
|
||||||
this.Commands.CellContentClick += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellContentClick);
|
this.Commands.CellContentClick += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellContentClick);
|
||||||
this.Commands.CellEndEdit += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellEndEdit);
|
this.Commands.CellEndEdit += new System.Windows.Forms.DataGridViewCellEventHandler(this.Commands_CellEndEdit);
|
||||||
this.Commands.DataError += new System.Windows.Forms.DataGridViewDataErrorEventHandler(this.Commands_DataError);
|
this.Commands.DataError += new System.Windows.Forms.DataGridViewDataErrorEventHandler(this.Commands_DataError);
|
||||||
@ -195,9 +196,9 @@
|
|||||||
//
|
//
|
||||||
// Command
|
// Command
|
||||||
//
|
//
|
||||||
dataGridViewCellStyle2.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
|
dataGridViewCellStyle10.BackColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
|
||||||
dataGridViewCellStyle2.ForeColor = System.Drawing.Color.White;
|
dataGridViewCellStyle10.ForeColor = System.Drawing.Color.White;
|
||||||
this.Command.DefaultCellStyle = dataGridViewCellStyle2;
|
this.Command.DefaultCellStyle = dataGridViewCellStyle10;
|
||||||
this.Command.DisplayStyle = System.Windows.Forms.DataGridViewComboBoxDisplayStyle.ComboBox;
|
this.Command.DisplayStyle = System.Windows.Forms.DataGridViewComboBoxDisplayStyle.ComboBox;
|
||||||
resources.ApplyResources(this.Command, "Command");
|
resources.ApplyResources(this.Command, "Command");
|
||||||
this.Command.Name = "Command";
|
this.Command.Name = "Command";
|
||||||
@ -263,7 +264,7 @@
|
|||||||
//
|
//
|
||||||
// Up
|
// Up
|
||||||
//
|
//
|
||||||
this.Up.DefaultCellStyle = dataGridViewCellStyle3;
|
this.Up.DefaultCellStyle = dataGridViewCellStyle11;
|
||||||
resources.ApplyResources(this.Up, "Up");
|
resources.ApplyResources(this.Up, "Up");
|
||||||
this.Up.Image = global::ArdupilotMega.Properties.Resources.up;
|
this.Up.Image = global::ArdupilotMega.Properties.Resources.up;
|
||||||
this.Up.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
|
this.Up.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
|
||||||
@ -271,8 +272,8 @@
|
|||||||
//
|
//
|
||||||
// Down
|
// Down
|
||||||
//
|
//
|
||||||
dataGridViewCellStyle4.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
|
dataGridViewCellStyle12.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
|
||||||
this.Down.DefaultCellStyle = dataGridViewCellStyle4;
|
this.Down.DefaultCellStyle = dataGridViewCellStyle12;
|
||||||
resources.ApplyResources(this.Down, "Down");
|
resources.ApplyResources(this.Down, "Down");
|
||||||
this.Down.Image = global::ArdupilotMega.Properties.Resources.down;
|
this.Down.Image = global::ArdupilotMega.Properties.Resources.down;
|
||||||
this.Down.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
|
this.Down.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
|
||||||
@ -416,8 +417,8 @@
|
|||||||
//
|
//
|
||||||
// dataGridViewImageColumn1
|
// dataGridViewImageColumn1
|
||||||
//
|
//
|
||||||
dataGridViewCellStyle7.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
|
dataGridViewCellStyle15.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
|
||||||
this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle7;
|
this.dataGridViewImageColumn1.DefaultCellStyle = dataGridViewCellStyle15;
|
||||||
resources.ApplyResources(this.dataGridViewImageColumn1, "dataGridViewImageColumn1");
|
resources.ApplyResources(this.dataGridViewImageColumn1, "dataGridViewImageColumn1");
|
||||||
this.dataGridViewImageColumn1.Image = global::ArdupilotMega.Properties.Resources.up;
|
this.dataGridViewImageColumn1.Image = global::ArdupilotMega.Properties.Resources.up;
|
||||||
this.dataGridViewImageColumn1.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
|
this.dataGridViewImageColumn1.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
|
||||||
@ -425,8 +426,8 @@
|
|||||||
//
|
//
|
||||||
// dataGridViewImageColumn2
|
// dataGridViewImageColumn2
|
||||||
//
|
//
|
||||||
dataGridViewCellStyle8.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
|
dataGridViewCellStyle16.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleCenter;
|
||||||
this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle8;
|
this.dataGridViewImageColumn2.DefaultCellStyle = dataGridViewCellStyle16;
|
||||||
resources.ApplyResources(this.dataGridViewImageColumn2, "dataGridViewImageColumn2");
|
resources.ApplyResources(this.dataGridViewImageColumn2, "dataGridViewImageColumn2");
|
||||||
this.dataGridViewImageColumn2.Image = global::ArdupilotMega.Properties.Resources.down;
|
this.dataGridViewImageColumn2.Image = global::ArdupilotMega.Properties.Resources.down;
|
||||||
this.dataGridViewImageColumn2.ImageLayout = System.Windows.Forms.DataGridViewImageCellLayout.Stretch;
|
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.CaptionFont = new System.Drawing.Font("Segoe UI", 11.75F, System.Drawing.FontStyle.Bold);
|
||||||
this.panelWaypoints.CaptionHeight = 21;
|
this.panelWaypoints.CaptionHeight = 21;
|
||||||
this.panelWaypoints.ColorScheme = BSE.Windows.Forms.ColorScheme.Custom;
|
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_zoomto);
|
||||||
this.panelWaypoints.Controls.Add(this.BUT_Camera);
|
this.panelWaypoints.Controls.Add(this.BUT_Camera);
|
||||||
this.panelWaypoints.Controls.Add(this.BUT_grid);
|
this.panelWaypoints.Controls.Add(this.BUT_grid);
|
||||||
@ -557,6 +559,14 @@
|
|||||||
this.splitter1.Name = "splitter1";
|
this.splitter1.Name = "splitter1";
|
||||||
this.splitter1.TabStop = false;
|
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
|
// BUT_Camera
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.BUT_Camera, "BUT_Camera");
|
resources.ApplyResources(this.BUT_Camera, "BUT_Camera");
|
||||||
@ -834,13 +844,13 @@
|
|||||||
resources.ApplyResources(this.panelBASE, "panelBASE");
|
resources.ApplyResources(this.panelBASE, "panelBASE");
|
||||||
this.panelBASE.Name = "panelBASE";
|
this.panelBASE.Name = "panelBASE";
|
||||||
//
|
//
|
||||||
// BUT_zoomto
|
// BUT_loadkml
|
||||||
//
|
//
|
||||||
resources.ApplyResources(this.BUT_zoomto, "BUT_zoomto");
|
resources.ApplyResources(this.BUT_loadkml, "BUT_loadkml");
|
||||||
this.BUT_zoomto.Name = "BUT_zoomto";
|
this.BUT_loadkml.Name = "BUT_loadkml";
|
||||||
this.toolTip1.SetToolTip(this.BUT_zoomto, resources.GetString("BUT_zoomto.ToolTip"));
|
this.toolTip1.SetToolTip(this.BUT_loadkml, resources.GetString("BUT_loadkml.ToolTip"));
|
||||||
this.BUT_zoomto.UseVisualStyleBackColor = true;
|
this.BUT_loadkml.UseVisualStyleBackColor = true;
|
||||||
this.BUT_zoomto.Click += new System.EventHandler(this.BUT_zoomto_Click);
|
this.BUT_loadkml.Click += new System.EventHandler(this.BUT_loadkml_Click);
|
||||||
//
|
//
|
||||||
// FlightPlanner
|
// FlightPlanner
|
||||||
//
|
//
|
||||||
@ -954,5 +964,6 @@
|
|||||||
private System.Windows.Forms.DataGridViewImageColumn Up;
|
private System.Windows.Forms.DataGridViewImageColumn Up;
|
||||||
private System.Windows.Forms.DataGridViewImageColumn Down;
|
private System.Windows.Forms.DataGridViewImageColumn Down;
|
||||||
private MyButton BUT_zoomto;
|
private MyButton BUT_zoomto;
|
||||||
|
private MyButton BUT_loadkml;
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -18,6 +18,8 @@ using System.Resources;
|
|||||||
using System.Reflection;
|
using System.Reflection;
|
||||||
using System.ComponentModel;
|
using System.ComponentModel;
|
||||||
using System.Threading;
|
using System.Threading;
|
||||||
|
using SharpKml.Base;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
namespace ArdupilotMega.GCSViews
|
namespace ArdupilotMega.GCSViews
|
||||||
@ -440,6 +442,10 @@ namespace ArdupilotMega.GCSViews
|
|||||||
trackBar1.Minimum = MainMap.MinZoom;
|
trackBar1.Minimum = MainMap.MinZoom;
|
||||||
trackBar1.Maximum = MainMap.MaxZoom + 0.99;
|
trackBar1.Maximum = MainMap.MaxZoom + 0.99;
|
||||||
|
|
||||||
|
// draw this layer first
|
||||||
|
kmlpolygons = new GMapOverlay(MainMap, "kmlpolygons");
|
||||||
|
MainMap.Overlays.Add(kmlpolygons);
|
||||||
|
|
||||||
routes = new GMapOverlay(MainMap, "routes");
|
routes = new GMapOverlay(MainMap, "routes");
|
||||||
MainMap.Overlays.Add(routes);
|
MainMap.Overlays.Add(routes);
|
||||||
|
|
||||||
@ -452,6 +458,8 @@ namespace ArdupilotMega.GCSViews
|
|||||||
drawnpolygons = new GMapOverlay(MainMap, "drawnpolygons");
|
drawnpolygons = new GMapOverlay(MainMap, "drawnpolygons");
|
||||||
MainMap.Overlays.Add(drawnpolygons);
|
MainMap.Overlays.Add(drawnpolygons);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
top = new GMapOverlay(MainMap, "top");
|
top = new GMapOverlay(MainMap, "top");
|
||||||
//MainMap.Overlays.Add(top);
|
//MainMap.Overlays.Add(top);
|
||||||
|
|
||||||
@ -648,6 +656,23 @@ namespace ArdupilotMega.GCSViews
|
|||||||
writeKML();
|
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<PointLatLng>(), "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)
|
private void ChangeColumnHeader(string command)
|
||||||
{
|
{
|
||||||
try
|
try
|
||||||
@ -1721,7 +1746,9 @@ namespace ArdupilotMega.GCSViews
|
|||||||
// polygons
|
// polygons
|
||||||
GMapPolygon polygon;
|
GMapPolygon polygon;
|
||||||
GMapPolygon drawnpolygon;
|
GMapPolygon drawnpolygon;
|
||||||
|
|
||||||
//static GMapRoute route;
|
//static GMapRoute route;
|
||||||
|
GMapOverlay kmlpolygons;
|
||||||
|
|
||||||
// layers
|
// layers
|
||||||
GMapOverlay top;
|
GMapOverlay top;
|
||||||
@ -2101,7 +2128,8 @@ namespace ArdupilotMega.GCSViews
|
|||||||
DataGridViewCell tcell = Commands.Rows[selectedrow].Cells[i];
|
DataGridViewCell tcell = Commands.Rows[selectedrow].Cells[i];
|
||||||
if (tcell.GetType() == typeof(DataGridViewTextBoxCell))
|
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();
|
drawnpolygon.Points.Clear();
|
||||||
drawnpolygons.Markers.Clear();
|
drawnpolygons.Markers.Clear();
|
||||||
MainMap.Invalidate();
|
MainMap.Invalidate();
|
||||||
|
|
||||||
|
writeKML();
|
||||||
}
|
}
|
||||||
|
|
||||||
private void clearMissionToolStripMenuItem_Click(object sender, EventArgs e)
|
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();
|
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));
|
setfromGE(end.Lat, end.Lng, (int)float.Parse(TXT_DefaultAlt.Text));
|
||||||
|
|
||||||
|
writeKML();
|
||||||
}
|
}
|
||||||
|
|
||||||
private void jumpstartToolStripMenuItem_Click(object sender, EventArgs e)
|
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[Param1.Index].Value = 1;
|
||||||
|
|
||||||
Commands.Rows[row].Cells[Param2.Index].Value = repeat;
|
Commands.Rows[row].Cells[Param2.Index].Value = repeat;
|
||||||
|
|
||||||
|
writeKML();
|
||||||
}
|
}
|
||||||
|
|
||||||
private void jumpwPToolStripMenuItem_Click(object sender, EventArgs e)
|
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[Param1.Index].Value = wp;
|
||||||
|
|
||||||
Commands.Rows[row].Cells[Param2.Index].Value = repeat;
|
Commands.Rows[row].Cells[Param2.Index].Value = repeat;
|
||||||
|
|
||||||
|
writeKML();
|
||||||
}
|
}
|
||||||
|
|
||||||
private void deleteWPToolStripMenuItem_Click(object sender, EventArgs e)
|
private void deleteWPToolStripMenuItem_Click(object sender, EventArgs e)
|
||||||
@ -2717,7 +2755,11 @@ namespace ArdupilotMega.GCSViews
|
|||||||
|
|
||||||
Commands.Rows[selectedrow].Cells[Param1.Index].Value = time;
|
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));
|
setfromGE(end.Lat, end.Lng, (int)float.Parse(TXT_DefaultAlt.Text));
|
||||||
|
|
||||||
|
writeKML();
|
||||||
}
|
}
|
||||||
|
|
||||||
private void loitercirclesToolStripMenuItem_Click(object sender, EventArgs e)
|
private void loitercirclesToolStripMenuItem_Click(object sender, EventArgs e)
|
||||||
@ -2731,7 +2773,11 @@ namespace ArdupilotMega.GCSViews
|
|||||||
|
|
||||||
Commands.Rows[selectedrow].Cells[Param1.Index].Value = turns;
|
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));
|
setfromGE(end.Lat, end.Lng, (int)float.Parse(TXT_DefaultAlt.Text));
|
||||||
|
|
||||||
|
writeKML();
|
||||||
}
|
}
|
||||||
|
|
||||||
private void BUT_Camera_Click(object sender, EventArgs e)
|
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<SharpKml.Base.ElementEventArgs>(parser_ElementAdded);
|
||||||
|
parser.Parse(File.OpenRead(file));
|
||||||
|
}
|
||||||
|
catch (Exception ex) { MessageBox.Show("Bad KML File :" + ex.ToString()); }
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
@ -148,7 +148,7 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHK_altmode.ZOrder" xml:space="preserve">
|
<data name=">>CHK_altmode.ZOrder" xml:space="preserve">
|
||||||
<value>4</value>
|
<value>5</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_holdalt.AutoSize" type="System.Boolean, mscorlib">
|
<data name="CHK_holdalt.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -178,7 +178,7 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHK_holdalt.ZOrder" xml:space="preserve">
|
<data name=">>CHK_holdalt.ZOrder" xml:space="preserve">
|
||||||
<value>9</value>
|
<value>10</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="Commands.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="Commands.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Top, Bottom, Left, Right</value>
|
<value>Top, Bottom, Left, Right</value>
|
||||||
@ -340,7 +340,7 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>Commands.ZOrder" xml:space="preserve">
|
<data name=">>Commands.ZOrder" xml:space="preserve">
|
||||||
<value>11</value>
|
<value>12</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="CHK_geheight.AutoSize" type="System.Boolean, mscorlib">
|
<data name="CHK_geheight.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -370,7 +370,7 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>CHK_geheight.ZOrder" xml:space="preserve">
|
<data name=">>CHK_geheight.ZOrder" xml:space="preserve">
|
||||||
<value>13</value>
|
<value>14</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="TXT_WPRad.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="TXT_WPRad.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>23, 36</value>
|
<value>23, 36</value>
|
||||||
@ -394,7 +394,7 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>TXT_WPRad.ZOrder" xml:space="preserve">
|
<data name=">>TXT_WPRad.ZOrder" xml:space="preserve">
|
||||||
<value>14</value>
|
<value>15</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="TXT_DefaultAlt.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="TXT_DefaultAlt.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>154, 36</value>
|
<value>154, 36</value>
|
||||||
@ -418,7 +418,7 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>TXT_DefaultAlt.ZOrder" xml:space="preserve">
|
<data name=">>TXT_DefaultAlt.ZOrder" xml:space="preserve">
|
||||||
<value>12</value>
|
<value>13</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="LBL_WPRad.AutoSize" type="System.Boolean, mscorlib">
|
<data name="LBL_WPRad.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -448,7 +448,7 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>LBL_WPRad.ZOrder" xml:space="preserve">
|
<data name=">>LBL_WPRad.ZOrder" xml:space="preserve">
|
||||||
<value>5</value>
|
<value>6</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="LBL_defalutalt.AutoSize" type="System.Boolean, mscorlib">
|
<data name="LBL_defalutalt.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -478,7 +478,7 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>LBL_defalutalt.ZOrder" xml:space="preserve">
|
<data name=">>LBL_defalutalt.ZOrder" xml:space="preserve">
|
||||||
<value>10</value>
|
<value>11</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="TXT_loiterrad.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="TXT_loiterrad.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>89, 36</value>
|
<value>89, 36</value>
|
||||||
@ -502,7 +502,7 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>TXT_loiterrad.ZOrder" xml:space="preserve">
|
<data name=">>TXT_loiterrad.ZOrder" xml:space="preserve">
|
||||||
<value>8</value>
|
<value>9</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="label5.AutoSize" type="System.Boolean, mscorlib">
|
<data name="label5.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
@ -532,11 +532,80 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>label5.ZOrder" xml:space="preserve">
|
<data name=">>label5.ZOrder" xml:space="preserve">
|
||||||
<value>7</value>
|
<value>8</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="panel5.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="panel5.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Bottom, Right</value>
|
<value>Bottom, Right</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name=">>BUT_write.Name" xml:space="preserve">
|
||||||
|
<value>BUT_write</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_write.Type" xml:space="preserve">
|
||||||
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_write.Parent" xml:space="preserve">
|
||||||
|
<value>panel5</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_write.ZOrder" xml:space="preserve">
|
||||||
|
<value>0</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_read.Name" xml:space="preserve">
|
||||||
|
<value>BUT_read</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_read.Type" xml:space="preserve">
|
||||||
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_read.Parent" xml:space="preserve">
|
||||||
|
<value>panel5</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_read.ZOrder" xml:space="preserve">
|
||||||
|
<value>1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>SaveFile.Name" xml:space="preserve">
|
||||||
|
<value>SaveFile</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>SaveFile.Type" xml:space="preserve">
|
||||||
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>SaveFile.Parent" xml:space="preserve">
|
||||||
|
<value>panel5</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>SaveFile.ZOrder" xml:space="preserve">
|
||||||
|
<value>2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_loadwpfile.Name" xml:space="preserve">
|
||||||
|
<value>BUT_loadwpfile</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_loadwpfile.Type" xml:space="preserve">
|
||||||
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_loadwpfile.Parent" xml:space="preserve">
|
||||||
|
<value>panel5</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_loadwpfile.ZOrder" xml:space="preserve">
|
||||||
|
<value>3</value>
|
||||||
|
</data>
|
||||||
|
<data name="panel5.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
|
<value>8, 250</value>
|
||||||
|
</data>
|
||||||
|
<data name="panel5.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>117, 114</value>
|
||||||
|
</data>
|
||||||
|
<data name="panel5.TabIndex" type="System.Int32, mscorlib">
|
||||||
|
<value>29</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panel5.Name" xml:space="preserve">
|
||||||
|
<value>panel5</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panel5.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panel5.Parent" xml:space="preserve">
|
||||||
|
<value>panelAction</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panel5.ZOrder" xml:space="preserve">
|
||||||
|
<value>1</value>
|
||||||
|
</data>
|
||||||
<data name="BUT_write.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_write.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
</data>
|
</data>
|
||||||
@ -645,30 +714,114 @@
|
|||||||
<data name=">>BUT_loadwpfile.ZOrder" xml:space="preserve">
|
<data name=">>BUT_loadwpfile.ZOrder" xml:space="preserve">
|
||||||
<value>3</value>
|
<value>3</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="panel5.Location" type="System.Drawing.Point, System.Drawing">
|
|
||||||
<value>8, 250</value>
|
|
||||||
</data>
|
|
||||||
<data name="panel5.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>117, 114</value>
|
|
||||||
</data>
|
|
||||||
<data name="panel5.TabIndex" type="System.Int32, mscorlib">
|
|
||||||
<value>29</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panel5.Name" xml:space="preserve">
|
|
||||||
<value>panel5</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panel5.Type" xml:space="preserve">
|
|
||||||
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panel5.Parent" xml:space="preserve">
|
|
||||||
<value>panelAction</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panel5.ZOrder" xml:space="preserve">
|
|
||||||
<value>1</value>
|
|
||||||
</data>
|
|
||||||
<data name="panel1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="panel1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Bottom, Right</value>
|
<value>Bottom, Right</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name=">>label4.Name" xml:space="preserve">
|
||||||
|
<value>label4</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label4.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label4.Parent" xml:space="preserve">
|
||||||
|
<value>panel1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label4.ZOrder" xml:space="preserve">
|
||||||
|
<value>0</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label3.Name" xml:space="preserve">
|
||||||
|
<value>label3</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label3.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label3.Parent" xml:space="preserve">
|
||||||
|
<value>panel1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label3.ZOrder" xml:space="preserve">
|
||||||
|
<value>1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label2.Name" xml:space="preserve">
|
||||||
|
<value>label2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label2.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label2.Parent" xml:space="preserve">
|
||||||
|
<value>panel1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label2.ZOrder" xml:space="preserve">
|
||||||
|
<value>2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>Label1.Name" xml:space="preserve">
|
||||||
|
<value>Label1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>Label1.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>Label1.Parent" xml:space="preserve">
|
||||||
|
<value>panel1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>Label1.ZOrder" xml:space="preserve">
|
||||||
|
<value>3</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_homealt.Name" xml:space="preserve">
|
||||||
|
<value>TXT_homealt</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_homealt.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_homealt.Parent" xml:space="preserve">
|
||||||
|
<value>panel1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_homealt.ZOrder" xml:space="preserve">
|
||||||
|
<value>4</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_homelng.Name" xml:space="preserve">
|
||||||
|
<value>TXT_homelng</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_homelng.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_homelng.Parent" xml:space="preserve">
|
||||||
|
<value>panel1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_homelng.ZOrder" xml:space="preserve">
|
||||||
|
<value>5</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_homelat.Name" xml:space="preserve">
|
||||||
|
<value>TXT_homelat</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_homelat.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_homelat.Parent" xml:space="preserve">
|
||||||
|
<value>panel1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_homelat.ZOrder" xml:space="preserve">
|
||||||
|
<value>6</value>
|
||||||
|
</data>
|
||||||
|
<data name="panel1.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
|
<value>8, 365</value>
|
||||||
|
</data>
|
||||||
|
<data name="panel1.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>117, 89</value>
|
||||||
|
</data>
|
||||||
|
<data name="panel1.TabIndex" type="System.Int32, mscorlib">
|
||||||
|
<value>31</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panel1.Name" xml:space="preserve">
|
||||||
|
<value>panel1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panel1.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panel1.Parent" xml:space="preserve">
|
||||||
|
<value>panelAction</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panel1.ZOrder" xml:space="preserve">
|
||||||
|
<value>2</value>
|
||||||
|
</data>
|
||||||
<data name="label4.AutoSize" type="System.Boolean, mscorlib">
|
<data name="label4.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</data>
|
</data>
|
||||||
@ -852,27 +1005,6 @@
|
|||||||
<data name=">>TXT_homelat.ZOrder" xml:space="preserve">
|
<data name=">>TXT_homelat.ZOrder" xml:space="preserve">
|
||||||
<value>6</value>
|
<value>6</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="panel1.Location" type="System.Drawing.Point, System.Drawing">
|
|
||||||
<value>8, 365</value>
|
|
||||||
</data>
|
|
||||||
<data name="panel1.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>117, 89</value>
|
|
||||||
</data>
|
|
||||||
<data name="panel1.TabIndex" type="System.Int32, mscorlib">
|
|
||||||
<value>31</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panel1.Name" xml:space="preserve">
|
|
||||||
<value>panel1</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panel1.Type" xml:space="preserve">
|
|
||||||
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panel1.Parent" xml:space="preserve">
|
|
||||||
<value>panelAction</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panel1.ZOrder" xml:space="preserve">
|
|
||||||
<value>2</value>
|
|
||||||
</data>
|
|
||||||
<data name="dataGridViewImageColumn1.HeaderText" xml:space="preserve">
|
<data name="dataGridViewImageColumn1.HeaderText" xml:space="preserve">
|
||||||
<value>Up</value>
|
<value>Up</value>
|
||||||
</data>
|
</data>
|
||||||
@ -912,6 +1044,111 @@
|
|||||||
<data name="panel2.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="panel2.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Bottom, Right</value>
|
<value>Bottom, Right</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name=">>label7.Name" xml:space="preserve">
|
||||||
|
<value>label7</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label7.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label7.Parent" xml:space="preserve">
|
||||||
|
<value>panel2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label7.ZOrder" xml:space="preserve">
|
||||||
|
<value>0</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label8.Name" xml:space="preserve">
|
||||||
|
<value>label8</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label8.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label8.Parent" xml:space="preserve">
|
||||||
|
<value>panel2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label8.ZOrder" xml:space="preserve">
|
||||||
|
<value>1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label9.Name" xml:space="preserve">
|
||||||
|
<value>label9</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label9.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label9.Parent" xml:space="preserve">
|
||||||
|
<value>panel2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label9.ZOrder" xml:space="preserve">
|
||||||
|
<value>2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label10.Name" xml:space="preserve">
|
||||||
|
<value>label10</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label10.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label10.Parent" xml:space="preserve">
|
||||||
|
<value>panel2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label10.ZOrder" xml:space="preserve">
|
||||||
|
<value>3</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_mousealt.Name" xml:space="preserve">
|
||||||
|
<value>TXT_mousealt</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_mousealt.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_mousealt.Parent" xml:space="preserve">
|
||||||
|
<value>panel2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_mousealt.ZOrder" xml:space="preserve">
|
||||||
|
<value>4</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_mouselong.Name" xml:space="preserve">
|
||||||
|
<value>TXT_mouselong</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_mouselong.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_mouselong.Parent" xml:space="preserve">
|
||||||
|
<value>panel2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_mouselong.ZOrder" xml:space="preserve">
|
||||||
|
<value>5</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_mouselat.Name" xml:space="preserve">
|
||||||
|
<value>TXT_mouselat</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_mouselat.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_mouselat.Parent" xml:space="preserve">
|
||||||
|
<value>panel2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>TXT_mouselat.ZOrder" xml:space="preserve">
|
||||||
|
<value>6</value>
|
||||||
|
</data>
|
||||||
|
<data name="panel2.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
|
<value>8, 130</value>
|
||||||
|
</data>
|
||||||
|
<data name="panel2.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>114, 79</value>
|
||||||
|
</data>
|
||||||
|
<data name="panel2.TabIndex" type="System.Int32, mscorlib">
|
||||||
|
<value>38</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panel2.Name" xml:space="preserve">
|
||||||
|
<value>panel2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panel2.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panel2.Parent" xml:space="preserve">
|
||||||
|
<value>panelAction</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panel2.ZOrder" xml:space="preserve">
|
||||||
|
<value>3</value>
|
||||||
|
</data>
|
||||||
<data name="label7.AutoSize" type="System.Boolean, mscorlib">
|
<data name="label7.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</data>
|
</data>
|
||||||
@ -1095,27 +1332,9 @@
|
|||||||
<data name=">>TXT_mouselat.ZOrder" xml:space="preserve">
|
<data name=">>TXT_mouselat.ZOrder" xml:space="preserve">
|
||||||
<value>6</value>
|
<value>6</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="panel2.Location" type="System.Drawing.Point, System.Drawing">
|
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||||
<value>8, 130</value>
|
<value>172, 17</value>
|
||||||
</data>
|
</metadata>
|
||||||
<data name="panel2.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>114, 79</value>
|
|
||||||
</data>
|
|
||||||
<data name="panel2.TabIndex" type="System.Int32, mscorlib">
|
|
||||||
<value>38</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panel2.Name" xml:space="preserve">
|
|
||||||
<value>panel2</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panel2.Type" xml:space="preserve">
|
|
||||||
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panel2.Parent" xml:space="preserve">
|
|
||||||
<value>panelAction</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panel2.ZOrder" xml:space="preserve">
|
|
||||||
<value>3</value>
|
|
||||||
</data>
|
|
||||||
<data name="comboBoxMapType.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="comboBoxMapType.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Bottom, Right</value>
|
<value>Bottom, Right</value>
|
||||||
</data>
|
</data>
|
||||||
@ -1128,9 +1347,6 @@
|
|||||||
<data name="comboBoxMapType.TabIndex" type="System.Int32, mscorlib">
|
<data name="comboBoxMapType.TabIndex" type="System.Int32, mscorlib">
|
||||||
<value>42</value>
|
<value>42</value>
|
||||||
</data>
|
</data>
|
||||||
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
|
||||||
<value>172, 17</value>
|
|
||||||
</metadata>
|
|
||||||
<data name="comboBoxMapType.ToolTip" xml:space="preserve">
|
<data name="comboBoxMapType.ToolTip" xml:space="preserve">
|
||||||
<value>Change the current map type</value>
|
<value>Change the current map type</value>
|
||||||
</data>
|
</data>
|
||||||
@ -1239,11 +1455,44 @@
|
|||||||
<data name=">>splitter1.ZOrder" xml:space="preserve">
|
<data name=">>splitter1.ZOrder" xml:space="preserve">
|
||||||
<value>0</value>
|
<value>0</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="BUT_loadkml.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
|
<value>NoControl</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_loadkml.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
|
<value>800, 25</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_loadkml.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>58, 23</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_loadkml.TabIndex" type="System.Int32, mscorlib">
|
||||||
|
<value>54</value>
|
||||||
|
</data>
|
||||||
|
<data name="BUT_loadkml.Text" xml:space="preserve">
|
||||||
|
<value>KML overlay</value>
|
||||||
|
</data>
|
||||||
|
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||||
|
<value>172, 17</value>
|
||||||
|
</metadata>
|
||||||
|
<data name="BUT_loadkml.ToolTip" xml:space="preserve">
|
||||||
|
<value>Get Camera settings for overlap</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_loadkml.Name" xml:space="preserve">
|
||||||
|
<value>BUT_loadkml</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_loadkml.Type" xml:space="preserve">
|
||||||
|
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_loadkml.Parent" xml:space="preserve">
|
||||||
|
<value>panelWaypoints</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>BUT_loadkml.ZOrder" xml:space="preserve">
|
||||||
|
<value>0</value>
|
||||||
|
</data>
|
||||||
<data name="BUT_zoomto.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_zoomto.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_zoomto.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="BUT_zoomto.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>746, 26</value>
|
<value>732, 26</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_zoomto.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="BUT_zoomto.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>62, 23</value>
|
<value>62, 23</value>
|
||||||
@ -1267,13 +1516,13 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_zoomto.ZOrder" xml:space="preserve">
|
<data name=">>BUT_zoomto.ZOrder" xml:space="preserve">
|
||||||
<value>0</value>
|
<value>1</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_Camera.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_Camera.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_Camera.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="BUT_Camera.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>692, 26</value>
|
<value>678, 26</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_Camera.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="BUT_Camera.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>48, 23</value>
|
<value>48, 23</value>
|
||||||
@ -1297,13 +1546,13 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_Camera.ZOrder" xml:space="preserve">
|
<data name=">>BUT_Camera.ZOrder" xml:space="preserve">
|
||||||
<value>1</value>
|
<value>2</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_grid.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_grid.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_grid.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="BUT_grid.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>638, 26</value>
|
<value>624, 26</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_grid.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="BUT_grid.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>48, 23</value>
|
<value>48, 23</value>
|
||||||
@ -1327,13 +1576,13 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_grid.ZOrder" xml:space="preserve">
|
<data name=">>BUT_grid.ZOrder" xml:space="preserve">
|
||||||
<value>2</value>
|
<value>3</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_Prefetch.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_Prefetch.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_Prefetch.Location" type="System.Drawing.Point, System.Drawing">
|
<data name="BUT_Prefetch.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
<value>576, 26</value>
|
<value>562, 26</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_Prefetch.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="BUT_Prefetch.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>56, 23</value>
|
<value>56, 23</value>
|
||||||
@ -1357,7 +1606,7 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_Prefetch.ZOrder" xml:space="preserve">
|
<data name=">>BUT_Prefetch.ZOrder" xml:space="preserve">
|
||||||
<value>3</value>
|
<value>4</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="button1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="button1.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -1366,7 +1615,7 @@
|
|||||||
<value>479, 26</value>
|
<value>479, 26</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="button1.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="button1.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>91, 23</value>
|
<value>77, 23</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="button1.TabIndex" type="System.Int32, mscorlib">
|
<data name="button1.TabIndex" type="System.Int32, mscorlib">
|
||||||
<value>48</value>
|
<value>48</value>
|
||||||
@ -1387,7 +1636,7 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>button1.ZOrder" xml:space="preserve">
|
<data name=">>button1.ZOrder" xml:space="preserve">
|
||||||
<value>6</value>
|
<value>7</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="BUT_Add.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
<data name="BUT_Add.ImeMode" type="System.Windows.Forms.ImeMode, System.Windows.Forms">
|
||||||
<value>NoControl</value>
|
<value>NoControl</value>
|
||||||
@ -1417,7 +1666,7 @@
|
|||||||
<value>panelWaypoints</value>
|
<value>panelWaypoints</value>
|
||||||
</data>
|
</data>
|
||||||
<data name=">>BUT_Add.ZOrder" xml:space="preserve">
|
<data name=">>BUT_Add.ZOrder" xml:space="preserve">
|
||||||
<value>15</value>
|
<value>16</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="panelWaypoints.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
|
<data name="panelWaypoints.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
|
||||||
<value>Bottom</value>
|
<value>Bottom</value>
|
||||||
@ -1473,6 +1722,105 @@
|
|||||||
<data name=">>panelAction.ZOrder" xml:space="preserve">
|
<data name=">>panelAction.ZOrder" xml:space="preserve">
|
||||||
<value>3</value>
|
<value>3</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name=">>lbl_distance.Name" xml:space="preserve">
|
||||||
|
<value>lbl_distance</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>lbl_distance.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>lbl_distance.Parent" xml:space="preserve">
|
||||||
|
<value>panelMap</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>lbl_distance.ZOrder" xml:space="preserve">
|
||||||
|
<value>0</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>lbl_homedist.Name" xml:space="preserve">
|
||||||
|
<value>lbl_homedist</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>lbl_homedist.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>lbl_homedist.Parent" xml:space="preserve">
|
||||||
|
<value>panelMap</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>lbl_homedist.ZOrder" xml:space="preserve">
|
||||||
|
<value>1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>lbl_prevdist.Name" xml:space="preserve">
|
||||||
|
<value>lbl_prevdist</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>lbl_prevdist.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>lbl_prevdist.Parent" xml:space="preserve">
|
||||||
|
<value>panelMap</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>lbl_prevdist.ZOrder" xml:space="preserve">
|
||||||
|
<value>2</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>MainMap.Name" xml:space="preserve">
|
||||||
|
<value>MainMap</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>MainMap.Type" xml:space="preserve">
|
||||||
|
<value>GMap.NET.WindowsForms.GMapControl, GMap.NET.WindowsForms, Version=1.5.5.5, Culture=neutral, PublicKeyToken=b85b9027b614afef</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>MainMap.Parent" xml:space="preserve">
|
||||||
|
<value>panelMap</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>MainMap.ZOrder" xml:space="preserve">
|
||||||
|
<value>3</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>trackBar1.Name" xml:space="preserve">
|
||||||
|
<value>trackBar1</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>trackBar1.Type" xml:space="preserve">
|
||||||
|
<value>ArdupilotMega.MyTrackBar, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>trackBar1.Parent" xml:space="preserve">
|
||||||
|
<value>panelMap</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>trackBar1.ZOrder" xml:space="preserve">
|
||||||
|
<value>4</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label11.Name" xml:space="preserve">
|
||||||
|
<value>label11</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label11.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label11.Parent" xml:space="preserve">
|
||||||
|
<value>panelMap</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>label11.ZOrder" xml:space="preserve">
|
||||||
|
<value>5</value>
|
||||||
|
</data>
|
||||||
|
<data name="panelMap.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
|
||||||
|
<value>Fill</value>
|
||||||
|
</data>
|
||||||
|
<data name="panelMap.Location" type="System.Drawing.Point, System.Drawing">
|
||||||
|
<value>0, 0</value>
|
||||||
|
</data>
|
||||||
|
<data name="panelMap.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>878, 313</value>
|
||||||
|
</data>
|
||||||
|
<data name="panelMap.TabIndex" type="System.Int32, mscorlib">
|
||||||
|
<value>51</value>
|
||||||
|
</data>
|
||||||
|
<data name="panelMap.Text" xml:space="preserve">
|
||||||
|
<value>panel6</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panelMap.Name" xml:space="preserve">
|
||||||
|
<value>panelMap</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panelMap.Type" xml:space="preserve">
|
||||||
|
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panelMap.Parent" xml:space="preserve">
|
||||||
|
<value>panelBASE</value>
|
||||||
|
</data>
|
||||||
|
<data name=">>panelMap.ZOrder" xml:space="preserve">
|
||||||
|
<value>1</value>
|
||||||
|
</data>
|
||||||
<data name="lbl_distance.AutoSize" type="System.Boolean, mscorlib">
|
<data name="lbl_distance.AutoSize" type="System.Boolean, mscorlib">
|
||||||
<value>True</value>
|
<value>True</value>
|
||||||
</data>
|
</data>
|
||||||
@ -1569,93 +1917,6 @@
|
|||||||
<metadata name="contextMenuStrip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
<metadata name="contextMenuStrip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||||
<value>17, 17</value>
|
<value>17, 17</value>
|
||||||
</metadata>
|
</metadata>
|
||||||
<data name="deleteWPToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>167, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="deleteWPToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>Delete WP</value>
|
|
||||||
</data>
|
|
||||||
<data name="loiterForeverToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>113, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="loiterForeverToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>Forever</value>
|
|
||||||
</data>
|
|
||||||
<data name="loitertimeToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>113, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="loitertimeToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>Time</value>
|
|
||||||
</data>
|
|
||||||
<data name="loitercirclesToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>113, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="loitercirclesToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>Circles</value>
|
|
||||||
</data>
|
|
||||||
<data name="loiterToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>167, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="loiterToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>Loiter</value>
|
|
||||||
</data>
|
|
||||||
<data name="jumpstartToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>102, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="jumpstartToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>Start</value>
|
|
||||||
</data>
|
|
||||||
<data name="jumpwPToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>102, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="jumpwPToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>WP #</value>
|
|
||||||
</data>
|
|
||||||
<data name="jumpToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>167, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="jumpToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>Jump</value>
|
|
||||||
</data>
|
|
||||||
<data name="toolStripSeparator1.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>164, 6</value>
|
|
||||||
</data>
|
|
||||||
<data name="ContextMeasure.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>167, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="ContextMeasure.Text" xml:space="preserve">
|
|
||||||
<value>Measure Distance</value>
|
|
||||||
</data>
|
|
||||||
<data name="rotateMapToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>167, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="rotateMapToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>Rotate Map</value>
|
|
||||||
</data>
|
|
||||||
<data name="addPolygonPointToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>174, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="addPolygonPointToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>Add Polygon Point</value>
|
|
||||||
</data>
|
|
||||||
<data name="clearPolygonToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>174, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="clearPolygonToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>Clear Polygon</value>
|
|
||||||
</data>
|
|
||||||
<data name="gridToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>167, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="gridToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>Grid Polygon</value>
|
|
||||||
</data>
|
|
||||||
<data name="clearMissionToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>167, 22</value>
|
|
||||||
</data>
|
|
||||||
<data name="clearMissionToolStripMenuItem.Text" xml:space="preserve">
|
|
||||||
<value>Clear Mission</value>
|
|
||||||
</data>
|
|
||||||
<data name="contextMenuStrip1.Size" type="System.Drawing.Size, System.Drawing">
|
<data name="contextMenuStrip1.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
<value>168, 164</value>
|
<value>168, 164</value>
|
||||||
</data>
|
</data>
|
||||||
@ -1831,6 +2092,93 @@
|
|||||||
<data name=">>MainMap.ZOrder" xml:space="preserve">
|
<data name=">>MainMap.ZOrder" xml:space="preserve">
|
||||||
<value>3</value>
|
<value>3</value>
|
||||||
</data>
|
</data>
|
||||||
|
<data name="deleteWPToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>167, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="deleteWPToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>Delete WP</value>
|
||||||
|
</data>
|
||||||
|
<data name="loiterToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>167, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="loiterToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>Loiter</value>
|
||||||
|
</data>
|
||||||
|
<data name="loiterForeverToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>113, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="loiterForeverToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>Forever</value>
|
||||||
|
</data>
|
||||||
|
<data name="loitertimeToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>113, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="loitertimeToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>Time</value>
|
||||||
|
</data>
|
||||||
|
<data name="loitercirclesToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>113, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="loitercirclesToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>Circles</value>
|
||||||
|
</data>
|
||||||
|
<data name="jumpToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>167, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="jumpToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>Jump</value>
|
||||||
|
</data>
|
||||||
|
<data name="jumpstartToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>102, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="jumpstartToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>Start</value>
|
||||||
|
</data>
|
||||||
|
<data name="jumpwPToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>102, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="jumpwPToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>WP #</value>
|
||||||
|
</data>
|
||||||
|
<data name="toolStripSeparator1.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>164, 6</value>
|
||||||
|
</data>
|
||||||
|
<data name="ContextMeasure.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>167, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="ContextMeasure.Text" xml:space="preserve">
|
||||||
|
<value>Measure Distance</value>
|
||||||
|
</data>
|
||||||
|
<data name="rotateMapToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>167, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="rotateMapToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>Rotate Map</value>
|
||||||
|
</data>
|
||||||
|
<data name="gridToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>167, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="gridToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>Grid Polygon</value>
|
||||||
|
</data>
|
||||||
|
<data name="addPolygonPointToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>174, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="addPolygonPointToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>Add Polygon Point</value>
|
||||||
|
</data>
|
||||||
|
<data name="clearPolygonToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>174, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="clearPolygonToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>Clear Polygon</value>
|
||||||
|
</data>
|
||||||
|
<data name="clearMissionToolStripMenuItem.Size" type="System.Drawing.Size, System.Drawing">
|
||||||
|
<value>167, 22</value>
|
||||||
|
</data>
|
||||||
|
<data name="clearMissionToolStripMenuItem.Text" xml:space="preserve">
|
||||||
|
<value>Clear Mission</value>
|
||||||
|
</data>
|
||||||
<data name="trackBar1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
<data name="trackBar1.Anchor" type="System.Windows.Forms.AnchorStyles, System.Windows.Forms">
|
||||||
<value>Top, Bottom, Right</value>
|
<value>Top, Bottom, Right</value>
|
||||||
</data>
|
</data>
|
||||||
@ -1894,33 +2242,6 @@
|
|||||||
<data name=">>label11.ZOrder" xml:space="preserve">
|
<data name=">>label11.ZOrder" xml:space="preserve">
|
||||||
<value>5</value>
|
<value>5</value>
|
||||||
</data>
|
</data>
|
||||||
<data name="panelMap.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
|
|
||||||
<value>Fill</value>
|
|
||||||
</data>
|
|
||||||
<data name="panelMap.Location" type="System.Drawing.Point, System.Drawing">
|
|
||||||
<value>0, 0</value>
|
|
||||||
</data>
|
|
||||||
<data name="panelMap.Size" type="System.Drawing.Size, System.Drawing">
|
|
||||||
<value>878, 313</value>
|
|
||||||
</data>
|
|
||||||
<data name="panelMap.TabIndex" type="System.Int32, mscorlib">
|
|
||||||
<value>51</value>
|
|
||||||
</data>
|
|
||||||
<data name="panelMap.Text" xml:space="preserve">
|
|
||||||
<value>panel6</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panelMap.Name" xml:space="preserve">
|
|
||||||
<value>panelMap</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panelMap.Type" xml:space="preserve">
|
|
||||||
<value>System.Windows.Forms.Panel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panelMap.Parent" xml:space="preserve">
|
|
||||||
<value>panelBASE</value>
|
|
||||||
</data>
|
|
||||||
<data name=">>panelMap.ZOrder" xml:space="preserve">
|
|
||||||
<value>1</value>
|
|
||||||
</data>
|
|
||||||
<data name="panelBASE.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
|
<data name="panelBASE.Dock" type="System.Windows.Forms.DockStyle, System.Windows.Forms">
|
||||||
<value>Fill</value>
|
<value>Fill</value>
|
||||||
</data>
|
</data>
|
||||||
|
@ -34,6 +34,7 @@ namespace ArdupilotMega
|
|||||||
bool oldlogformat = false;
|
bool oldlogformat = false;
|
||||||
|
|
||||||
byte mavlinkversion = 0;
|
byte mavlinkversion = 0;
|
||||||
|
public byte aptype = 0;
|
||||||
byte[] readingpacket = new byte[256];
|
byte[] readingpacket = new byte[256];
|
||||||
|
|
||||||
public PointLatLngAlt[] wps = new PointLatLngAlt[200];
|
public PointLatLngAlt[] wps = new PointLatLngAlt[200];
|
||||||
@ -190,6 +191,7 @@ namespace ArdupilotMega
|
|||||||
hb = (MAVLink.__mavlink_heartbeat_t)(temp);
|
hb = (MAVLink.__mavlink_heartbeat_t)(temp);
|
||||||
|
|
||||||
mavlinkversion = hb.mavlink_version;
|
mavlinkversion = hb.mavlink_version;
|
||||||
|
aptype = hb.type;
|
||||||
|
|
||||||
sysid = buffer[3];
|
sysid = buffer[3];
|
||||||
compid = buffer[4];
|
compid = buffer[4];
|
||||||
|
@ -79,13 +79,12 @@ namespace ArdupilotMega
|
|||||||
GCSViews.Firmware Firmware;
|
GCSViews.Firmware Firmware;
|
||||||
GCSViews.Terminal Terminal;
|
GCSViews.Terminal Terminal;
|
||||||
|
|
||||||
public void testpython()
|
|
||||||
{
|
|
||||||
Console.WriteLine("hello world from c# via python");
|
|
||||||
}
|
|
||||||
|
|
||||||
public MainV2()
|
public MainV2()
|
||||||
{
|
{
|
||||||
|
//new temp().ShowDialog();
|
||||||
|
//return;
|
||||||
|
|
||||||
|
|
||||||
Form splash = new Splash();
|
Form splash = new Splash();
|
||||||
splash.Show();
|
splash.Show();
|
||||||
|
|
||||||
@ -108,10 +107,6 @@ namespace ArdupilotMega
|
|||||||
|
|
||||||
//return;
|
//return;
|
||||||
|
|
||||||
|
|
||||||
// preload
|
|
||||||
Python.CreateEngine();
|
|
||||||
|
|
||||||
var t = Type.GetType("Mono.Runtime");
|
var t = Type.GetType("Mono.Runtime");
|
||||||
MONO = (t != null);
|
MONO = (t != null);
|
||||||
|
|
||||||
@ -176,6 +171,9 @@ namespace ArdupilotMega
|
|||||||
Simulation = new GCSViews.Simulation();
|
Simulation = new GCSViews.Simulation();
|
||||||
Firmware = new GCSViews.Firmware();
|
Firmware = new GCSViews.Firmware();
|
||||||
//Terminal = new GCSViews.Terminal();
|
//Terminal = new GCSViews.Terminal();
|
||||||
|
|
||||||
|
// preload
|
||||||
|
Python.CreateEngine();
|
||||||
}
|
}
|
||||||
catch (Exception e) { MessageBox.Show("A Major error has occured : " + e.ToString()); this.Close(); }
|
catch (Exception e) { MessageBox.Show("A Major error has occured : " + e.ToString()); this.Close(); }
|
||||||
|
|
||||||
|
@ -34,5 +34,5 @@ using System.Resources;
|
|||||||
// by using the '*' as shown below:
|
// by using the '*' as shown below:
|
||||||
// [assembly: AssemblyVersion("1.0.*")]
|
// [assembly: AssemblyVersion("1.0.*")]
|
||||||
[assembly: AssemblyVersion("1.0.0.0")]
|
[assembly: AssemblyVersion("1.0.0.0")]
|
||||||
[assembly: AssemblyFileVersion("1.0.99")]
|
[assembly: AssemblyFileVersion("1.1.1")]
|
||||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||||
|
36
Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs
generated
36
Tools/ArdupilotMegaPlanner/Setup/Setup.Designer.cs
generated
@ -121,13 +121,11 @@
|
|||||||
this.label44 = new System.Windows.Forms.Label();
|
this.label44 = new System.Windows.Forms.Label();
|
||||||
this.label43 = new System.Windows.Forms.Label();
|
this.label43 = new System.Windows.Forms.Label();
|
||||||
this.label42 = 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.groupBox2 = new System.Windows.Forms.GroupBox();
|
||||||
this.label24 = new System.Windows.Forms.Label();
|
this.label24 = new System.Windows.Forms.Label();
|
||||||
this.HS4_MIN = new System.Windows.Forms.TextBox();
|
this.HS4_MIN = new System.Windows.Forms.TextBox();
|
||||||
this.HS4_MAX = new System.Windows.Forms.TextBox();
|
this.HS4_MAX = new System.Windows.Forms.TextBox();
|
||||||
this.label40 = new System.Windows.Forms.Label();
|
this.label40 = new System.Windows.Forms.Label();
|
||||||
this.BUT_swash_manual = new ArdupilotMega.MyButton();
|
|
||||||
this.groupBox1 = new System.Windows.Forms.GroupBox();
|
this.groupBox1 = new System.Windows.Forms.GroupBox();
|
||||||
this.label41 = new System.Windows.Forms.Label();
|
this.label41 = new System.Windows.Forms.Label();
|
||||||
this.label21 = 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.HS2_REV = new System.Windows.Forms.CheckBox();
|
||||||
this.HS1_REV = new System.Windows.Forms.CheckBox();
|
this.HS1_REV = new System.Windows.Forms.CheckBox();
|
||||||
this.label17 = new System.Windows.Forms.Label();
|
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.HS4 = new ArdupilotMega.HorizontalProgressBar2();
|
||||||
this.HS3 = new ArdupilotMega.VerticalProgressBar2();
|
this.HS3 = new ArdupilotMega.VerticalProgressBar2();
|
||||||
this.Gservoloc = new AGaugeApp.AGauge();
|
this.Gservoloc = new AGaugeApp.AGauge();
|
||||||
@ -874,9 +874,7 @@
|
|||||||
this.tabHeli.Controls.Add(this.label44);
|
this.tabHeli.Controls.Add(this.label44);
|
||||||
this.tabHeli.Controls.Add(this.label43);
|
this.tabHeli.Controls.Add(this.label43);
|
||||||
this.tabHeli.Controls.Add(this.label42);
|
this.tabHeli.Controls.Add(this.label42);
|
||||||
this.tabHeli.Controls.Add(this.BUT_HS4save);
|
|
||||||
this.tabHeli.Controls.Add(this.groupBox2);
|
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.groupBox1);
|
||||||
this.tabHeli.Controls.Add(this.HS4_TRIM);
|
this.tabHeli.Controls.Add(this.HS4_TRIM);
|
||||||
this.tabHeli.Controls.Add(this.HS3_TRIM);
|
this.tabHeli.Controls.Add(this.HS3_TRIM);
|
||||||
@ -903,6 +901,8 @@
|
|||||||
this.tabHeli.Controls.Add(this.HS2_REV);
|
this.tabHeli.Controls.Add(this.HS2_REV);
|
||||||
this.tabHeli.Controls.Add(this.HS1_REV);
|
this.tabHeli.Controls.Add(this.HS1_REV);
|
||||||
this.tabHeli.Controls.Add(this.label17);
|
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.HS4);
|
||||||
this.tabHeli.Controls.Add(this.HS3);
|
this.tabHeli.Controls.Add(this.HS3);
|
||||||
this.tabHeli.Controls.Add(this.Gservoloc);
|
this.tabHeli.Controls.Add(this.Gservoloc);
|
||||||
@ -959,13 +959,6 @@
|
|||||||
resources.ApplyResources(this.label42, "label42");
|
resources.ApplyResources(this.label42, "label42");
|
||||||
this.label42.Name = "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
|
// groupBox2
|
||||||
//
|
//
|
||||||
this.groupBox2.Controls.Add(this.label24);
|
this.groupBox2.Controls.Add(this.label24);
|
||||||
@ -1002,13 +995,6 @@
|
|||||||
resources.ApplyResources(this.label40, "label40");
|
resources.ApplyResources(this.label40, "label40");
|
||||||
this.label40.Name = "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
|
// groupBox1
|
||||||
//
|
//
|
||||||
this.groupBox1.Controls.Add(this.label41);
|
this.groupBox1.Controls.Add(this.label41);
|
||||||
@ -1262,6 +1248,20 @@
|
|||||||
resources.ApplyResources(this.label17, "label17");
|
resources.ApplyResources(this.label17, "label17");
|
||||||
this.label17.Name = "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
|
// HS4
|
||||||
//
|
//
|
||||||
this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
|
this.HS4.BackgroundColor = System.Drawing.Color.FromArgb(((int)(((byte)(67)))), ((int)(((byte)(68)))), ((int)(((byte)(69)))));
|
||||||
|
@ -544,6 +544,8 @@ namespace ArdupilotMega.Setup
|
|||||||
}
|
}
|
||||||
catch { MessageBox.Show("Invalid input!"); return; }
|
catch { MessageBox.Show("Invalid input!"); return; }
|
||||||
|
|
||||||
|
TXT_declination.Text = dec.ToString();
|
||||||
|
|
||||||
MainV2.comPort.setParam("COMPASS_DEC", dec * deg2rad);
|
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; }
|
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();
|
BUT_reset.Refresh();
|
||||||
Application.DoEvents();
|
Application.DoEvents();
|
||||||
|
|
||||||
Sleep(20000, comPortT); // wait for boot/reset
|
Sleep(60000, comPortT); // wait for boot/reset
|
||||||
|
|
||||||
comPortT.DtrEnable = false;
|
comPortT.DtrEnable = false;
|
||||||
|
|
||||||
|
File diff suppressed because it is too large
Load Diff
@ -4,14 +4,14 @@
|
|||||||
<description asmv2:publisher="Michael Oborne" asmv2:product="ArdupilotMegaPlanner" xmlns="urn:schemas-microsoft-com:asm.v1" />
|
<description asmv2:publisher="Michael Oborne" asmv2:product="ArdupilotMegaPlanner" xmlns="urn:schemas-microsoft-com:asm.v1" />
|
||||||
<deployment install="true" />
|
<deployment install="true" />
|
||||||
<dependency>
|
<dependency>
|
||||||
<dependentAssembly dependencyType="install" codebase="ArdupilotMegaPlanner.exe.manifest" size="23309">
|
<dependentAssembly dependencyType="install" codebase="ArdupilotMegaPlanner.exe.manifest" size="25308">
|
||||||
<assemblyIdentity name="ArdupilotMegaPlanner.exe" version="0.0.0.1" publicKeyToken="0000000000000000" language="en-US" processorArchitecture="x86" type="win32" />
|
<assemblyIdentity name="ArdupilotMegaPlanner.exe" version="0.0.0.1" publicKeyToken="0000000000000000" language="en-US" processorArchitecture="x86" type="win32" />
|
||||||
<hash>
|
<hash>
|
||||||
<dsig:Transforms>
|
<dsig:Transforms>
|
||||||
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
|
<dsig:Transform Algorithm="urn:schemas-microsoft-com:HashTransforms.Identity" />
|
||||||
</dsig:Transforms>
|
</dsig:Transforms>
|
||||||
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
|
<dsig:DigestMethod Algorithm="http://www.w3.org/2000/09/xmldsig#sha1" />
|
||||||
<dsig:DigestValue>QOAVY4eRCMREZxVv8+wq0bmXS7U=</dsig:DigestValue>
|
<dsig:DigestValue>mN7pjMOs48ZdF2S8vaEAJbtq8b4=</dsig:DigestValue>
|
||||||
</hash>
|
</hash>
|
||||||
</dependentAssembly>
|
</dependentAssembly>
|
||||||
</dependency>
|
</dependency>
|
||||||
|
13
Tools/ArdupilotMegaPlanner/temp.Designer.cs
generated
13
Tools/ArdupilotMegaPlanner/temp.Designer.cs
generated
@ -44,6 +44,7 @@
|
|||||||
this.BUT_geinjection = new ArdupilotMega.MyButton();
|
this.BUT_geinjection = new ArdupilotMega.MyButton();
|
||||||
this.BUT_clearcustommaps = new ArdupilotMega.MyButton();
|
this.BUT_clearcustommaps = new ArdupilotMega.MyButton();
|
||||||
this.BUT_lang_edit = new ArdupilotMega.MyButton();
|
this.BUT_lang_edit = new ArdupilotMega.MyButton();
|
||||||
|
this.myButton1 = new ArdupilotMega.MyButton();
|
||||||
this.SuspendLayout();
|
this.SuspendLayout();
|
||||||
//
|
//
|
||||||
// button1
|
// button1
|
||||||
@ -202,11 +203,22 @@
|
|||||||
this.BUT_lang_edit.UseVisualStyleBackColor = true;
|
this.BUT_lang_edit.UseVisualStyleBackColor = true;
|
||||||
this.BUT_lang_edit.Click += new System.EventHandler(this.BUT_lang_edit_Click);
|
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
|
// temp
|
||||||
//
|
//
|
||||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||||
this.ClientSize = new System.Drawing.Size(731, 281);
|
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_lang_edit);
|
||||||
this.Controls.Add(this.BUT_clearcustommaps);
|
this.Controls.Add(this.BUT_clearcustommaps);
|
||||||
this.Controls.Add(this.BUT_geinjection);
|
this.Controls.Add(this.BUT_geinjection);
|
||||||
@ -249,6 +261,7 @@
|
|||||||
private MyButton BUT_geinjection;
|
private MyButton BUT_geinjection;
|
||||||
private MyButton BUT_clearcustommaps;
|
private MyButton BUT_clearcustommaps;
|
||||||
private MyButton BUT_lang_edit;
|
private MyButton BUT_lang_edit;
|
||||||
|
private MyButton myButton1;
|
||||||
//private SharpVectors.Renderers.Forms.SvgPictureBox svgPictureBox1;
|
//private SharpVectors.Renderers.Forms.SvgPictureBox svgPictureBox1;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -9,12 +9,14 @@ using System.Text.RegularExpressions;
|
|||||||
using System.IO.Ports;
|
using System.IO.Ports;
|
||||||
using System.IO;
|
using System.IO;
|
||||||
using System.Runtime.InteropServices;
|
using System.Runtime.InteropServices;
|
||||||
|
using System.Net;
|
||||||
|
|
||||||
using GMap.NET.WindowsForms;
|
using GMap.NET.WindowsForms;
|
||||||
using GMap.NET.CacheProviders;
|
using GMap.NET.CacheProviders;
|
||||||
|
|
||||||
//using SharpVectors.Renderers.Forms;
|
using OpenGlobe.Core;
|
||||||
//using SharpVectors.Converters;
|
using OpenGlobe.Renderer;
|
||||||
|
using OpenGlobe.Scene;
|
||||||
|
|
||||||
|
|
||||||
namespace ArdupilotMega
|
namespace ArdupilotMega
|
||||||
@ -870,6 +872,217 @@ namespace ArdupilotMega
|
|||||||
{
|
{
|
||||||
new resedit.Form1().Show();
|
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<GridResolution> gridResolutions = new List<GridResolution>();
|
||||||
|
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;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
@ -17,9 +17,17 @@ class Aircraft(object):
|
|||||||
self.pitch = 0.0 # degrees
|
self.pitch = 0.0 # degrees
|
||||||
self.roll = 0.0 # degrees
|
self.roll = 0.0 # degrees
|
||||||
self.yaw = 0.0 # degrees
|
self.yaw = 0.0 # degrees
|
||||||
|
|
||||||
|
# rates in earth frame
|
||||||
self.pitch_rate = 0.0 # degrees/s
|
self.pitch_rate = 0.0 # degrees/s
|
||||||
self.roll_rate = 0.0 # degrees/s
|
self.roll_rate = 0.0 # degrees/s
|
||||||
self.yaw_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.velocity = euclid.Vector3(0, 0, 0) # m/s, North, East, Up
|
||||||
self.position = euclid.Vector3(0, 0, 0) # m 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
|
self.accel = euclid.Vector3(0, 0, 0) # m/s/s North, East, Up
|
||||||
|
@ -34,15 +34,21 @@ class QuadCopter(Aircraft):
|
|||||||
delta_time = t - self.last_time
|
delta_time = t - self.last_time
|
||||||
self.last_time = t
|
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
|
roll_accel = (m[1] - m[0]) * 5000.0
|
||||||
pitch_accel = (m[2] - m[3]) * 5000.0
|
pitch_accel = (m[2] - m[3]) * 5000.0
|
||||||
yaw_accel = -((m[2]+m[3]) - (m[0]+m[1])) * 400.0
|
yaw_accel = -((m[2]+m[3]) - (m[0]+m[1])) * 400.0
|
||||||
|
|
||||||
# update rotational rates
|
# update rotational rates in body frame
|
||||||
self.roll_rate += roll_accel * delta_time
|
self.pDeg += roll_accel * delta_time
|
||||||
self.pitch_rate += pitch_accel * delta_time
|
self.qDeg += pitch_accel * delta_time
|
||||||
self.yaw_rate += yaw_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
|
# update rotation
|
||||||
self.roll += self.roll_rate * delta_time
|
self.roll += self.roll_rate * delta_time
|
||||||
|
@ -290,6 +290,55 @@ def check_parent(parent_pid=os.getppid()):
|
|||||||
sys.exit(1)
|
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__":
|
if __name__ == "__main__":
|
||||||
import doctest
|
import doctest
|
||||||
doctest.testmod()
|
doctest.testmod()
|
||||||
|
@ -7,10 +7,14 @@
|
|||||||
|
|
||||||
#include "APM_PI.h"
|
#include "APM_PI.h"
|
||||||
|
|
||||||
long
|
int32_t APM_PI::get_p(int32_t error)
|
||||||
APM_PI::get_pi(int32_t error, float dt, bool calc_i)
|
|
||||||
{
|
{
|
||||||
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;
|
_integrator += ((float)error * _ki) * dt;
|
||||||
|
|
||||||
if (_integrator < -_imax) {
|
if (_integrator < -_imax) {
|
||||||
@ -19,7 +23,12 @@ APM_PI::get_pi(int32_t error, float dt, bool calc_i)
|
|||||||
_integrator = _imax;
|
_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
|
void
|
||||||
|
@ -78,7 +78,10 @@ public:
|
|||||||
/// @returns The updated control output.
|
/// @returns The updated control output.
|
||||||
///
|
///
|
||||||
//long get_pi(int32_t error, float dt);
|
//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
|
/// Reset the PI integrator
|
||||||
///
|
///
|
||||||
|
@ -39,7 +39,7 @@ class Arduino_Mega_ISR_Registry;
|
|||||||
class APM_RC_Class
|
class APM_RC_Class
|
||||||
{
|
{
|
||||||
public:
|
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 void OutputCh(uint8_t ch, uint16_t pwm) = 0;
|
||||||
virtual uint16_t InputCh(uint8_t ch) = 0;
|
virtual uint16_t InputCh(uint8_t ch) = 0;
|
||||||
virtual uint8_t GetState() = 0;
|
virtual uint8_t GetState() = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user