mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Merge branch 'master' of https://code.google.com/p/ardupilot-mega
This commit is contained in:
commit
2b48a557ec
@ -1,6 +1,6 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#define THISFIRMWARE "ArduCopter V2.4"
|
||||
#define THISFIRMWARE "ArduCopter V2.4.1"
|
||||
/*
|
||||
ArduCopter Version 2.4
|
||||
Authors: Jason Short
|
||||
@ -78,7 +78,9 @@ http://code.google.com/p/ardupilot-mega/downloads/list
|
||||
#include <RC_Channel.h> // RC Channel Library
|
||||
#include <AP_RangeFinder.h> // Range finder library
|
||||
#include <AP_OpticalFlow.h> // Optical Flow library
|
||||
#include <ModeFilter.h>
|
||||
#include <Filter.h> // Filter library
|
||||
#include <ModeFilter.h> // Mode Filter from Filter library
|
||||
#include <AverageFilter.h> // Mode Filter from Filter library
|
||||
#include <AP_Relay.h> // APM relay
|
||||
#include <GCS_MAVLink.h> // MAVLink GCS definitions
|
||||
#include <memcheck.h>
|
||||
@ -220,7 +222,10 @@ AP_InertialSensor_MPU6000 ins( CONFIG_MPU6000_CHIP_SELECT_PIN );
|
||||
AP_InertialSensor_Oilpan ins(&adc);
|
||||
#endif
|
||||
AP_IMU_INS imu(&ins);
|
||||
AP_DCM dcm(&imu, g_gps);
|
||||
// we don't want to use gps for yaw correction on ArduCopter, so pass
|
||||
// a NULL GPS object pointer
|
||||
static GPS *g_gps_null;
|
||||
AP_DCM dcm(&imu, g_gps_null);
|
||||
AP_TimerProcess timer_scheduler;
|
||||
|
||||
#elif HIL_MODE == HIL_MODE_SENSORS
|
||||
@ -265,7 +270,7 @@ GCS_MAVLINK gcs3;
|
||||
// SONAR selection
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
ModeFilter sonar_mode_filter;
|
||||
ModeFilterInt16_Size5 sonar_mode_filter(2);
|
||||
#if CONFIG_SONAR == ENABLED
|
||||
#if CONFIG_SONAR_SOURCE == SONAR_SOURCE_ADC
|
||||
AP_AnalogSource_ADC sonar_analog_source( &adc, CONFIG_SONAR_SOURCE_ADC_CHANNEL, 0.25);
|
||||
@ -366,10 +371,10 @@ static uint32_t rc_override_fs_timer = 0;
|
||||
// Heli
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
static float heli_rollFactor[3], heli_pitchFactor[3]; // only required for 3 swashplate servos
|
||||
static int16_t heli_servo_min[3], heli_servo_max[3]; // same here. for yaw servo we use heli_servo4_min/max parameter directly
|
||||
static int32_t heli_servo_out[4]; // used for servo averaging for analog servos
|
||||
static int16_t heli_servo_out_count; // use for servo averaging
|
||||
static float heli_rollFactor[3], heli_pitchFactor[3], heli_collectiveFactor[3]; // only required for 3 swashplate servos
|
||||
static int16_t heli_servo_min[3], heli_servo_max[3]; // same here. for yaw servo we use heli_servo4_min/max parameter directly
|
||||
static int32_t heli_servo_out[4]; // used for servo averaging for analog servos
|
||||
static int16_t heli_servo_out_count; // use for servo averaging
|
||||
#endif
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
@ -395,6 +400,8 @@ static boolean motor_auto_armed;
|
||||
static Vector3f omega;
|
||||
// This is used to hold radio tuning values for in-flight CH6 tuning
|
||||
float tuning_value;
|
||||
// This will keep track of the percent of roll or pitch the user is applying
|
||||
float roll_scale_d, pitch_scale_d;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// LED output
|
||||
@ -480,7 +487,7 @@ static boolean loiter_override;
|
||||
static float cos_roll_x = 1;
|
||||
static float cos_pitch_x = 1;
|
||||
static float cos_yaw_x = 1;
|
||||
static float sin_pitch_y, sin_yaw_y, sin_roll_y;
|
||||
static float sin_yaw_y;
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// SIMPLE Mode
|
||||
@ -495,6 +502,9 @@ static int32_t initial_simple_bearing;
|
||||
// Used to control Axis lock
|
||||
int32_t roll_axis;
|
||||
int32_t pitch_axis;
|
||||
// Filters
|
||||
AverageFilterInt32_Size3 roll_rate_d_filter; // filtered acceleration
|
||||
AverageFilterInt32_Size3 pitch_rate_d_filter; // filtered pitch acceleration
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
// Circle Mode / Loiter control
|
||||
@ -594,7 +604,7 @@ static byte throttle_mode;
|
||||
// This flag is reset when we are in a manual throttle mode with 0 throttle or disarmed
|
||||
static boolean takeoff_complete;
|
||||
// Used to record the most recent time since we enaged the throttle to take off
|
||||
static int32_t takeoff_timer;
|
||||
static uint32_t takeoff_timer;
|
||||
// Used to see if we have landed and if we should shut our engines - not fully implemented
|
||||
static boolean land_complete = true;
|
||||
// used to manually override throttle in interactive Alt hold modes
|
||||
@ -1479,8 +1489,20 @@ void update_roll_pitch_mode(void)
|
||||
//reset_stability_I();
|
||||
}
|
||||
|
||||
// clear new radio frame info
|
||||
new_radio_frame = false;
|
||||
if(new_radio_frame){
|
||||
// clear new radio frame info
|
||||
new_radio_frame = false;
|
||||
|
||||
// These values can be used to scale the PID gains
|
||||
// This allows for a simple gain scheduling implementation
|
||||
roll_scale_d = g.stabilize_d_schedule * (float)abs(g.rc_1.control_in);
|
||||
roll_scale_d = (1 - (roll_scale_d / 4500.0));
|
||||
roll_scale_d = constrain(roll_scale_d, 0, 1) * g.stabilize_d;
|
||||
|
||||
pitch_scale_d = g.stabilize_d_schedule * (float)abs(g.rc_2.control_in);
|
||||
pitch_scale_d = (1 - (pitch_scale_d / 4500.0));
|
||||
pitch_scale_d = constrain(pitch_scale_d, 0, 1) * g.stabilize_d;
|
||||
}
|
||||
}
|
||||
|
||||
// new radio frame is used to make sure we only call this at 50hz
|
||||
@ -1512,7 +1534,7 @@ void update_simple_mode(void)
|
||||
g.rc_2.control_in = control_pitch;
|
||||
}
|
||||
|
||||
#define THROTTLE_FILTER_SIZE 4
|
||||
#define THROTTLE_FILTER_SIZE 2
|
||||
|
||||
// 50 hz update rate, not 250
|
||||
// controls all throttle behavior
|
||||
@ -1649,7 +1671,10 @@ void update_throttle_mode(void)
|
||||
}
|
||||
|
||||
// light filter of output
|
||||
g.rc_3.servo_out = (g.rc_3.servo_out * (THROTTLE_FILTER_SIZE - 1) + throttle_out) / THROTTLE_FILTER_SIZE;
|
||||
//g.rc_3.servo_out = (g.rc_3.servo_out * (THROTTLE_FILTER_SIZE - 1) + throttle_out) / THROTTLE_FILTER_SIZE;
|
||||
|
||||
// no filter
|
||||
g.rc_3.servo_out = throttle_out;
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -1816,12 +1841,13 @@ static void update_trig(void){
|
||||
yawvector.y = temp.b.x; // cos
|
||||
yawvector.normalize();
|
||||
|
||||
cos_pitch_x = safe_sqrt(1 - (temp.c.x * temp.c.x)); // level = 1
|
||||
cos_roll_x = temp.c.z / cos_pitch_x; // level = 1
|
||||
|
||||
sin_pitch_y = -temp.c.x; // level = 0
|
||||
cos_pitch_x = sqrt(1 - (temp.c.x * temp.c.x)); // level = 1
|
||||
|
||||
sin_roll_y = temp.c.y / cos_pitch_x; // level = 0
|
||||
cos_roll_x = temp.c.z / cos_pitch_x; // level = 1
|
||||
cos_pitch_x = constrain(cos_pitch_x, 0, 1.0);
|
||||
// this relies on constrain() of infinity doing the right thing,
|
||||
// which it does do in avr-libc
|
||||
cos_roll_x = constrain(cos_roll_x, -1.0, 1.0);
|
||||
|
||||
sin_yaw_y = yawvector.x; // 1y = north
|
||||
cos_yaw_x = yawvector.y; // 0x = north
|
||||
@ -1914,7 +1940,7 @@ static void update_altitude()
|
||||
climb_rate = (climb_rate + old_climb_rate)>>1;
|
||||
|
||||
// manage bad data
|
||||
climb_rate = constrain(climb_rate, -300, 300);
|
||||
climb_rate = constrain(climb_rate, -800, 800);
|
||||
|
||||
// save for filtering
|
||||
old_climb_rate = climb_rate;
|
||||
@ -2013,6 +2039,11 @@ static void tuning(){
|
||||
g.pid_nav_lon.kP(tuning_value);
|
||||
break;
|
||||
|
||||
case CH6_LOITER_RATE_P:
|
||||
g.pid_loiter_rate_lon.kP(tuning_value);
|
||||
g.pid_loiter_rate_lat.kP(tuning_value);
|
||||
break;
|
||||
|
||||
case CH6_NAV_I:
|
||||
g.pid_nav_lat.kI(tuning_value);
|
||||
g.pid_nav_lon.kI(tuning_value);
|
||||
|
@ -1,6 +1,6 @@
|
||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
static int
|
||||
static int16_t
|
||||
get_stabilize_roll(int32_t target_angle)
|
||||
{
|
||||
// angle error
|
||||
@ -29,7 +29,7 @@ get_stabilize_roll(int32_t target_angle)
|
||||
#endif
|
||||
}
|
||||
|
||||
static int
|
||||
static int16_t
|
||||
get_stabilize_pitch(int32_t target_angle)
|
||||
{
|
||||
// angle error
|
||||
@ -56,14 +56,19 @@ get_stabilize_pitch(int32_t target_angle)
|
||||
#endif
|
||||
}
|
||||
|
||||
static int
|
||||
static int16_t
|
||||
get_stabilize_yaw(int32_t target_angle)
|
||||
{
|
||||
// angle error
|
||||
target_angle = wrap_180(target_angle - dcm.yaw_sensor);
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME // cannot use rate control for helicopters
|
||||
// limit the error we're feeding to the PID
|
||||
target_angle = constrain(target_angle, -4500, 4500);
|
||||
#else
|
||||
// limit the error we're feeding to the PID
|
||||
target_angle = constrain(target_angle, -2000, 2000);
|
||||
#endif
|
||||
|
||||
// conver to desired Rate:
|
||||
int32_t target_rate = g.pi_stabilize_yaw.get_p(target_angle);
|
||||
@ -80,7 +85,7 @@ get_stabilize_yaw(int32_t target_angle)
|
||||
#endif
|
||||
}
|
||||
|
||||
static int
|
||||
static int16_t
|
||||
get_acro_roll(int32_t target_rate)
|
||||
{
|
||||
target_rate = target_rate * g.acro_p;
|
||||
@ -88,7 +93,7 @@ get_acro_roll(int32_t target_rate)
|
||||
return get_rate_roll(target_rate);
|
||||
}
|
||||
|
||||
static int
|
||||
static int16_t
|
||||
get_acro_pitch(int32_t target_rate)
|
||||
{
|
||||
target_rate = target_rate * g.acro_p;
|
||||
@ -96,7 +101,7 @@ get_acro_pitch(int32_t target_rate)
|
||||
return get_rate_pitch(target_rate);
|
||||
}
|
||||
|
||||
static int
|
||||
static int16_t
|
||||
get_acro_yaw(int32_t target_rate)
|
||||
{
|
||||
target_rate = g.pi_stabilize_yaw.get_p(target_rate);
|
||||
@ -104,76 +109,67 @@ get_acro_yaw(int32_t target_rate)
|
||||
return get_rate_yaw(target_rate);
|
||||
}
|
||||
|
||||
static int
|
||||
static int16_t
|
||||
get_rate_roll(int32_t target_rate)
|
||||
{
|
||||
int16_t rate_d1 = 0;
|
||||
static int16_t rate_d2 = 0;
|
||||
static int16_t rate_d3 = 0;
|
||||
static int32_t last_rate = 0;
|
||||
static int32_t last_rate = 0; // previous iterations rate
|
||||
int32_t current_rate; // this iteration's rate
|
||||
int32_t rate_d; // roll's acceleration
|
||||
int32_t output; // output from pid controller
|
||||
int32_t rate_d_dampener; // value to dampen output based on acceleration
|
||||
|
||||
int32_t current_rate = (omega.x * DEGX100);
|
||||
// get current rate
|
||||
current_rate = (omega.x * DEGX100);
|
||||
|
||||
// History of last 3 dir
|
||||
rate_d3 = rate_d2;
|
||||
rate_d2 = rate_d1;
|
||||
rate_d1 = current_rate - last_rate;
|
||||
// calculate and filter the acceleration
|
||||
rate_d = roll_rate_d_filter.apply(current_rate - last_rate);
|
||||
|
||||
// store rate for next iteration
|
||||
last_rate = current_rate;
|
||||
|
||||
// rate control
|
||||
target_rate = target_rate - current_rate;
|
||||
target_rate = g.pid_rate_roll.get_pid(target_rate, G_Dt);
|
||||
// call pid controller
|
||||
output = g.pid_rate_roll.get_pid(target_rate - current_rate, G_Dt);
|
||||
|
||||
// Dampening
|
||||
//int16_t d_temp = (float)(current_rate - last_rate) * g.stabilize_d;
|
||||
//target_rate -= constrain(d_temp, -500, 500);
|
||||
//last_rate = current_rate;
|
||||
// Dampening output with D term
|
||||
rate_d_dampener = rate_d * roll_scale_d;
|
||||
rate_d_dampener = constrain(rate_d_dampener, -400, 400);
|
||||
output -= rate_d_dampener;
|
||||
|
||||
// D term
|
||||
// I had tried this before with little result. Recently, someone mentioned to me that
|
||||
// MultiWii uses a filter of the last three to get around noise and get a stronger signal.
|
||||
// Works well! Thanks!
|
||||
int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stabilize_d;
|
||||
target_rate -= d_temp;
|
||||
|
||||
// output control:
|
||||
return constrain(target_rate, -2500, 2500);
|
||||
// output control
|
||||
return constrain(output, -2500, 2500);
|
||||
}
|
||||
|
||||
static int
|
||||
static int16_t
|
||||
get_rate_pitch(int32_t target_rate)
|
||||
{
|
||||
int16_t rate_d1 = 0;
|
||||
static int16_t rate_d2 = 0;
|
||||
static int16_t rate_d3 = 0;
|
||||
static int32_t last_rate = 0;
|
||||
static int32_t last_rate = 0; // previous iterations rate
|
||||
int32_t current_rate; // this iteration's rate
|
||||
int32_t rate_d; // roll's acceleration
|
||||
int32_t output; // output from pid controller
|
||||
int32_t rate_d_dampener; // value to dampen output based on acceleration
|
||||
|
||||
int32_t current_rate = (omega.y * DEGX100);
|
||||
// get current rate
|
||||
current_rate = (omega.y * DEGX100);
|
||||
|
||||
// History of last 3 dir
|
||||
rate_d3 = rate_d2;
|
||||
rate_d2 = rate_d1;
|
||||
rate_d1 = current_rate - last_rate;
|
||||
// calculate and filter the acceleration
|
||||
rate_d = pitch_rate_d_filter.apply(current_rate - last_rate);
|
||||
|
||||
// store rate for next iteration
|
||||
last_rate = current_rate;
|
||||
|
||||
// rate control
|
||||
target_rate = target_rate - current_rate;
|
||||
target_rate = g.pid_rate_pitch.get_pid(target_rate, G_Dt);
|
||||
// call pid controller
|
||||
output = g.pid_rate_pitch.get_pid(target_rate - current_rate, G_Dt);
|
||||
|
||||
// Dampening
|
||||
//int16_t d_temp = (float)(current_rate - last_rate) * g.stabilize_d;
|
||||
//target_rate -= constrain(d_temp, -500, 500);
|
||||
//last_rate = current_rate;
|
||||
// Dampening output with D term
|
||||
rate_d_dampener = rate_d * pitch_scale_d;
|
||||
rate_d_dampener = constrain(rate_d_dampener, -400, 400);
|
||||
output -= rate_d_dampener;
|
||||
|
||||
// D term
|
||||
int16_t d_temp = (rate_d1 + rate_d2 + rate_d3) * g.stabilize_d;
|
||||
target_rate -= d_temp;
|
||||
|
||||
// output control:
|
||||
return constrain(target_rate, -2500, 2500);
|
||||
// output control
|
||||
return constrain(output, -2500, 2500);
|
||||
}
|
||||
|
||||
static int
|
||||
static int16_t
|
||||
get_rate_yaw(int32_t target_rate)
|
||||
{
|
||||
// rate control
|
||||
@ -196,7 +192,7 @@ get_nav_throttle(int32_t z_error)
|
||||
|
||||
// convert to desired Rate:
|
||||
rate_error = g.pi_alt_hold.get_p(z_error);
|
||||
rate_error = constrain(rate_error, -100, 100);
|
||||
rate_error = constrain(rate_error, -150, 150);
|
||||
|
||||
// limit error to prevent I term wind up
|
||||
z_error = constrain(z_error, -400, 400);
|
||||
@ -339,7 +335,7 @@ get_nav_yaw_offset(int yaw_input, int reset)
|
||||
}
|
||||
}
|
||||
|
||||
static int get_angle_boost(int value)
|
||||
static int16_t get_angle_boost(int16_t value)
|
||||
{
|
||||
float temp = cos_pitch_x * cos_roll_x;
|
||||
temp = 1.0 - constrain(temp, .5, 1.0);
|
||||
@ -489,7 +485,7 @@ get_of_roll(int32_t control_roll)
|
||||
{
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
static float tot_x_cm = 0; // total distance from target
|
||||
static unsigned long last_of_roll_update = 0;
|
||||
static uint32_t last_of_roll_update = 0;
|
||||
int32_t new_roll = 0;
|
||||
|
||||
// check if new optflow data available
|
||||
@ -523,7 +519,7 @@ get_of_pitch(int32_t control_pitch)
|
||||
{
|
||||
#ifdef OPTFLOW_ENABLED
|
||||
static float tot_y_cm = 0; // total distance from target
|
||||
static unsigned long last_of_pitch_update = 0;
|
||||
static uint32_t last_of_pitch_update = 0;
|
||||
int32_t new_pitch = 0;
|
||||
|
||||
// check if new optflow data available
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -1647,18 +1647,18 @@ GCS_MAVLINK::queued_param_send()
|
||||
value = vp->cast_to_float(_queued_parameter_type);
|
||||
|
||||
char param_name[ONBOARD_PARAM_NAME_LENGTH];
|
||||
vp->copy_name(param_name, sizeof(param_name));
|
||||
vp->copy_name(param_name, sizeof(param_name), true);
|
||||
|
||||
mavlink_msg_param_value_send(
|
||||
chan,
|
||||
(int8_t*)param_name,
|
||||
value,
|
||||
_queued_parameter_count,
|
||||
_queued_parameter_index);
|
||||
mavlink_msg_param_value_send(
|
||||
chan,
|
||||
(int8_t*)param_name,
|
||||
value,
|
||||
_queued_parameter_count,
|
||||
_queued_parameter_index);
|
||||
|
||||
_queued_parameter = AP_Param::next_scalar(&_queued_parameter_token, &_queued_parameter_type);
|
||||
_queued_parameter_index++;
|
||||
}
|
||||
_queued_parameter_index++;
|
||||
}
|
||||
|
||||
/**
|
||||
* @brief Send the next pending waypoint, called from deferred message
|
||||
|
@ -619,7 +619,7 @@ static void Log_Write_Performance()
|
||||
DataFlash.WriteByte(LOG_PERFORMANCE_MSG);
|
||||
DataFlash.WriteByte( dcm.gyro_sat_count); //1
|
||||
DataFlash.WriteByte( imu.adc_constraints); //2
|
||||
DataFlash.WriteByte( dcm.renorm_sqrt_count); //3
|
||||
DataFlash.WriteByte( dcm.renorm_range_count); //3
|
||||
DataFlash.WriteByte( dcm.renorm_blowup_count); //4
|
||||
DataFlash.WriteByte( gps_fix_count); //5
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
@ -701,6 +701,7 @@ static void Log_Write_Attitude()
|
||||
DataFlash.WriteInt((int)dcm.pitch_sensor); // 4
|
||||
DataFlash.WriteInt(g.rc_4.control_in); // 5
|
||||
DataFlash.WriteInt((uint16_t)dcm.yaw_sensor); // 6
|
||||
DataFlash.WriteInt((uint16_t)compass.heading); // 6
|
||||
|
||||
DataFlash.WriteByte(END_BYTE);
|
||||
}
|
||||
@ -714,15 +715,18 @@ static void Log_Read_Attitude()
|
||||
int16_t temp4 = DataFlash.ReadInt();
|
||||
int16_t temp5 = DataFlash.ReadInt();
|
||||
uint16_t temp6 = DataFlash.ReadInt();
|
||||
uint16_t temp7 = DataFlash.ReadInt();
|
||||
temp7 = wrap_360(temp7);
|
||||
|
||||
// 1 2 3 4 5 6
|
||||
Serial.printf_P(PSTR("ATT, %d, %d, %d, %d, %d, %u\n"),
|
||||
// 1 2 3 4 5 6 7
|
||||
Serial.printf_P(PSTR("ATT, %d, %d, %d, %d, %d, %u, %u\n"),
|
||||
temp1,
|
||||
temp2,
|
||||
temp3,
|
||||
temp4,
|
||||
temp5,
|
||||
temp6);
|
||||
temp6,
|
||||
temp7);
|
||||
}
|
||||
|
||||
// Write a mode packet. Total length : 7 bytes
|
||||
|
@ -17,7 +17,7 @@ public:
|
||||
// The increment will prevent old parameters from being used incorrectly
|
||||
// by newer code.
|
||||
//
|
||||
static const uint16_t k_format_version = 116;
|
||||
static const uint16_t k_format_version = 117;
|
||||
|
||||
// The parameter software_type is set up solely for ground station use
|
||||
// and identifies the software type (eg ArduPilotMega versus ArduCopterMega)
|
||||
@ -121,9 +121,9 @@ public:
|
||||
|
||||
|
||||
//
|
||||
// 180: Radio settings
|
||||
// 170: Radio settings
|
||||
//
|
||||
k_param_rc_1 = 180,
|
||||
k_param_rc_1 = 170,
|
||||
k_param_rc_2,
|
||||
k_param_rc_3,
|
||||
k_param_rc_4,
|
||||
@ -145,6 +145,7 @@ public:
|
||||
k_param_radio_tuning_low,
|
||||
k_param_camera_pitch_gain,
|
||||
k_param_camera_roll_gain,
|
||||
k_param_rc_speed,
|
||||
|
||||
//
|
||||
// 200: flight modes
|
||||
@ -171,6 +172,7 @@ public:
|
||||
//
|
||||
// 220: PI/D Controllers
|
||||
//
|
||||
k_param_stabilize_d_schedule = 219,
|
||||
k_param_stabilize_d = 220,
|
||||
k_param_acro_p,
|
||||
k_param_axis_lock_p,
|
||||
@ -292,10 +294,12 @@ public:
|
||||
RC_Channel rc_8;
|
||||
RC_Channel rc_camera_pitch;
|
||||
RC_Channel rc_camera_roll;
|
||||
AP_Int16 rc_speed; // speed of fast RC Channels in Hz
|
||||
|
||||
AP_Float camera_pitch_gain;
|
||||
AP_Float camera_roll_gain;
|
||||
AP_Float stabilize_d;
|
||||
AP_Float stabilize_d_schedule;
|
||||
|
||||
// PI/D controllers
|
||||
AP_Float acro_p;
|
||||
@ -399,9 +403,12 @@ public:
|
||||
heli_collective_yaw_effect (0),
|
||||
#endif
|
||||
|
||||
rc_speed(RC_FAST_SPEED),
|
||||
|
||||
camera_pitch_gain (CAM_PITCH_GAIN),
|
||||
camera_roll_gain (CAM_ROLL_GAIN),
|
||||
stabilize_d (STABILIZE_D),
|
||||
stabilize_d_schedule (STABILIZE_D_SCHEDULE),
|
||||
acro_p (ACRO_P),
|
||||
axis_lock_p (AXIS_LOCK_P),
|
||||
|
||||
|
@ -105,11 +105,15 @@ static const AP_Param::Info var_info[] PROGMEM = {
|
||||
GGROUP(rc_camera_pitch, "CAM_P_", RC_Channel),
|
||||
GGROUP(rc_camera_roll, "CAM_R_", RC_Channel),
|
||||
|
||||
// speed of fast RC channels in Hz
|
||||
GSCALAR(rc_speed, "RC_SPEED"),
|
||||
|
||||
// variable
|
||||
//---------
|
||||
GSCALAR(camera_pitch_gain, "CAM_P_G"),
|
||||
GSCALAR(camera_roll_gain, "CAM_R_G"),
|
||||
GSCALAR(stabilize_d, "STAB_D"),
|
||||
GSCALAR(stabilize_d_schedule, "STAB_D_S"),
|
||||
GSCALAR(acro_p, "ACRO_P"),
|
||||
GSCALAR(axis_lock_p, "AXIS_P"),
|
||||
GSCALAR(axis_enabled, "AXIS_ENABLE"),
|
||||
|
@ -105,6 +105,11 @@
|
||||
# define INSTANT_PWM DISABLED
|
||||
#endif
|
||||
|
||||
// default RC speed in Hz if INSTANT_PWM is not used
|
||||
#ifndef RC_FAST_SPEED
|
||||
# define RC_FAST_SPEED 400
|
||||
#endif
|
||||
|
||||
// LED and IO Pins
|
||||
//
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
||||
@ -644,14 +649,18 @@
|
||||
|
||||
|
||||
#ifndef STABILIZE_D
|
||||
# define STABILIZE_D 0.05
|
||||
# define STABILIZE_D 0.1
|
||||
#endif
|
||||
|
||||
#ifndef STABILIZE_D_SCHEDULE
|
||||
# define STABILIZE_D_SCHEDULE 0.0
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Loiter control gains
|
||||
//
|
||||
#ifndef LOITER_P
|
||||
# define LOITER_P .2 // was .25 in previous
|
||||
# define LOITER_P .8
|
||||
#endif
|
||||
#ifndef LOITER_I
|
||||
# define LOITER_I 0.0
|
||||
@ -663,27 +672,31 @@
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// Loiter Navigation control gains
|
||||
//
|
||||
#ifndef LOITER_RATE
|
||||
# define LOITER_RATE 1
|
||||
#endif
|
||||
|
||||
#ifndef LOITER_RATE_P
|
||||
# define LOITER_RATE_P 3.0 //
|
||||
# define LOITER_RATE_P 3.5 //
|
||||
#endif
|
||||
#ifndef LOITER_RATE_I
|
||||
# define LOITER_RATE_I 0.1 // Wind control
|
||||
# define LOITER_RATE_I 0.2 // Wind control
|
||||
#endif
|
||||
#ifndef LOITER_RATE_D
|
||||
# define LOITER_RATE_D 0.00 //
|
||||
# define LOITER_RATE_D 0.0 // try 2 or 3 for LOITER_RATE 1
|
||||
#endif
|
||||
#ifndef LOITER_RATE_IMAX
|
||||
# define LOITER_RATE_IMAX 30 // degrees
|
||||
# define LOITER_RATE_IMAX 30 // degrees
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// WP Navigation control gains
|
||||
//
|
||||
#ifndef NAV_P
|
||||
# define NAV_P 3.0 //
|
||||
# define NAV_P 3.5 //
|
||||
#endif
|
||||
#ifndef NAV_I
|
||||
# define NAV_I 0.1 // Wind control
|
||||
# define NAV_I 0.2 // Wind control
|
||||
#endif
|
||||
#ifndef NAV_D
|
||||
# define NAV_D 0.00 //
|
||||
@ -717,7 +730,7 @@
|
||||
# define ALT_HOLD_P 0.4 //
|
||||
#endif
|
||||
#ifndef ALT_HOLD_I
|
||||
# define ALT_HOLD_I 0.02
|
||||
# define ALT_HOLD_I 0.04
|
||||
#endif
|
||||
#ifndef ALT_HOLD_IMAX
|
||||
# define ALT_HOLD_IMAX 300
|
||||
|
@ -168,6 +168,7 @@
|
||||
#define CH6_OPTFLOW_KD 19
|
||||
|
||||
#define CH6_NAV_I 20
|
||||
#define CH6_LOITER_RATE_P 22
|
||||
|
||||
|
||||
// nav byte mask
|
||||
|
@ -141,6 +141,15 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
|
||||
pitch_out = constrain(pitch_out, (int)-g.heli_pitch_max, (int)g.heli_pitch_max);
|
||||
coll_out = constrain(coll_out, 0, 1000);
|
||||
coll_out_scaled = coll_out * heli_collective_scalar + g.heli_collective_min - 1000;
|
||||
|
||||
// rescale roll_out and pitch-out into the min and max ranges to provide linear motion
|
||||
// across the input range instead of stopping when the input hits the constrain value
|
||||
// these calculations are based on an assumption of the user specified roll_max and pitch_max
|
||||
// coming into this equation at 4500 or less, and based on the original assumption of the
|
||||
// total g.heli_servo_x.servo_out range being -4500 to 4500.
|
||||
roll_out = (-g.heli_roll_max + (float)( 2 * g.heli_roll_max * (roll_out + 4500.0)/9000.0));
|
||||
pitch_out = (-g.heli_pitch_max + (float)(2 * g.heli_pitch_max * (pitch_out + 4500.0)/9000.0));
|
||||
|
||||
|
||||
// rudder feed forward based on collective
|
||||
#if HIL_MODE == HIL_MODE_DISABLED // don't do rudder feed forward in simulator
|
||||
@ -209,7 +218,7 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels( _BV(CH_1) | _BV(CH_2) | _BV(CH_3) | _BV(CH_4) );
|
||||
APM_RC.SetFastOutputChannels( _BV(CH_1) | _BV(CH_2) | _BV(CH_3) | _BV(CH_4), g.rc_speed );
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -5,19 +5,19 @@
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels( _BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
|
||||
| _BV(MOT_5) | _BV(MOT_6) );
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
|
||||
| _BV(MOT_5) | _BV(MOT_6), g.rc_speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
static void motors_output_enable()
|
||||
{
|
||||
APM_RC.enable_out(MOT_1);
|
||||
APM_RC.enable_out(MOT_2);
|
||||
APM_RC.enable_out(MOT_3);
|
||||
APM_RC.enable_out(MOT_4);
|
||||
APM_RC.enable_out(MOT_5);
|
||||
APM_RC.enable_out(MOT_6);
|
||||
APM_RC.enable_out(MOT_1);
|
||||
APM_RC.enable_out(MOT_2);
|
||||
APM_RC.enable_out(MOT_3);
|
||||
APM_RC.enable_out(MOT_4);
|
||||
APM_RC.enable_out(MOT_5);
|
||||
APM_RC.enable_out(MOT_6);
|
||||
}
|
||||
|
||||
static void output_motors_armed()
|
||||
@ -44,7 +44,7 @@ static void output_motors_armed()
|
||||
//left side
|
||||
motor_out[MOT_2] = g.rc_3.radio_out + g.rc_1.pwm_out; // CCW Middle
|
||||
motor_out[MOT_3] = g.rc_3.radio_out + roll_out + pitch_out; // CW Front
|
||||
motor_out[MOT_6] = g.rc_3.radio_out + roll_out - pitch_out; // CW Back
|
||||
motor_out[MOT_6] = g.rc_3.radio_out + roll_out - pitch_out; // CW Back
|
||||
|
||||
//right side
|
||||
motor_out[MOT_1] = g.rc_3.radio_out - g.rc_1.pwm_out; // CW Middle
|
||||
@ -73,26 +73,26 @@ static void output_motors_armed()
|
||||
|
||||
motor_out[MOT_3] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_1] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_6] -= g.rc_4.pwm_out; // CW
|
||||
motor_out[MOT_6] -= g.rc_4.pwm_out; // CW
|
||||
|
||||
|
||||
// Tridge's stability patch
|
||||
for (int m = 0; m <= 6; m++) {
|
||||
int c = ch_of_mot(m);
|
||||
int c_opp = ch_of_mot(m^1); // m^1 is the opposite motor. c_opp is channel of opposite motor.
|
||||
if (motor_out[c] > out_max) {
|
||||
motor_out[c_opp] -= motor_out[c] - out_max;
|
||||
motor_out[c] = out_max;
|
||||
}
|
||||
}
|
||||
for (int m = 0; m <= 6; m++){
|
||||
int c = ch_of_mot(m);
|
||||
int c_opp = ch_of_mot(m ^ 1); // m ^ 1 is the opposite motor. c_opp is channel of opposite motor.
|
||||
if(motor_out[c] > out_max){
|
||||
motor_out[c_opp] -= motor_out[c] - out_max;
|
||||
motor_out[c] = out_max;
|
||||
}
|
||||
}
|
||||
|
||||
// limit output so motors don't stop
|
||||
motor_out[MOT_1] = max(motor_out[MOT_1], out_min);
|
||||
motor_out[MOT_2] = max(motor_out[MOT_2], out_min);
|
||||
motor_out[MOT_3] = max(motor_out[MOT_3], out_min);
|
||||
motor_out[MOT_4] = max(motor_out[MOT_4], out_min);
|
||||
motor_out[MOT_5] = max(motor_out[MOT_5], out_min);
|
||||
motor_out[MOT_6] = max(motor_out[MOT_6], out_min);
|
||||
motor_out[MOT_1] = max(motor_out[MOT_1], out_min);
|
||||
motor_out[MOT_2] = max(motor_out[MOT_2], out_min);
|
||||
motor_out[MOT_3] = max(motor_out[MOT_3], out_min);
|
||||
motor_out[MOT_4] = max(motor_out[MOT_4], out_min);
|
||||
motor_out[MOT_5] = max(motor_out[MOT_5], out_min);
|
||||
motor_out[MOT_6] = max(motor_out[MOT_6], out_min);
|
||||
|
||||
#if CUT_MOTORS == ENABLED
|
||||
// if we are not sending a throttle output, we cut the motors
|
||||
@ -108,8 +108,8 @@ static void output_motors_armed()
|
||||
|
||||
// this filter slows the acceleration of motors vs the deceleration
|
||||
// Idea by Denny Rowland to help with his Yaw issue
|
||||
for(int8_t m = 0; m <= 6; m++ ) {
|
||||
int c = ch_of_mot(m);
|
||||
for(int8_t m = 0; m <= 6; m++){
|
||||
int c = ch_of_mot(m);
|
||||
if(motor_filtered[c] < motor_out[c]){
|
||||
motor_filtered[c] = (motor_out[c] + motor_filtered[c]) / 2;
|
||||
}else{
|
||||
@ -143,7 +143,7 @@ static void output_motors_disarmed()
|
||||
}
|
||||
|
||||
// fill the motor_out[] array for HIL use
|
||||
for (unsigned char i = 0; i < 8; i++) {
|
||||
for (unsigned char i = 0; i < 8; i++){
|
||||
motor_out[i] = g.rc_3.radio_min;
|
||||
}
|
||||
|
||||
@ -158,7 +158,7 @@ static void output_motors_disarmed()
|
||||
|
||||
static void output_motor_test()
|
||||
{
|
||||
motors_output_enable();
|
||||
motors_output_enable();
|
||||
|
||||
motor_out[MOT_1] = g.rc_3.radio_min;
|
||||
motor_out[MOT_2] = g.rc_3.radio_min;
|
||||
@ -167,57 +167,69 @@ static void output_motor_test()
|
||||
motor_out[MOT_5] = g.rc_3.radio_min;
|
||||
motor_out[MOT_6] = g.rc_3.radio_min;
|
||||
|
||||
bool right = (g.rc_1.control_in > 3000);
|
||||
bool left = (g.rc_1.control_in < -3000);
|
||||
bool front = (g.rc_2.control_in < -3000);
|
||||
bool back = (g.rc_2.control_in > 3000);
|
||||
|
||||
if(g.frame_orientation == X_FRAME){
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
delay(4000);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
if(right && !(front || back))
|
||||
motor_out[MOT_1] += 150; // Right
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
if(left && !(front || back))
|
||||
motor_out[MOT_2] += 150; // Left
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
if(back){
|
||||
if(left)
|
||||
motor_out[MOT_6] += 150;
|
||||
if(right)
|
||||
motor_out[MOT_4] += 150;
|
||||
}
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
if(front){
|
||||
if(left)
|
||||
motor_out[MOT_3] += 150;
|
||||
if(right)
|
||||
motor_out[MOT_5] += 150;
|
||||
}
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
} else { /* PLUS_FRAME */
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min);
|
||||
delay(4000);
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
if(front && !(left || right))
|
||||
motor_out[MOT_1] += 150;
|
||||
APM_RC.OutputCh(MOT_1, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
if(back && !(left || right))
|
||||
motor_out[MOT_2] += 150;
|
||||
APM_RC.OutputCh(MOT_4, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
if(left){
|
||||
if(front)
|
||||
motor_out[MOT_5] += 150;
|
||||
if(back)
|
||||
motor_out[MOT_3] += 150;
|
||||
APM_RC.OutputCh(MOT_6, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_2, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
|
||||
APM_RC.OutputCh(MOT_3, g.rc_3.radio_min);
|
||||
delay(2000);
|
||||
APM_RC.OutputCh(MOT_5, g.rc_3.radio_min + 100);
|
||||
delay(300);
|
||||
}
|
||||
|
||||
if(right){
|
||||
if(front)
|
||||
motor_out[MOT_4] += 150;
|
||||
if(back)
|
||||
motor_out[MOT_6] += 150;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(MOT_1, motor_out[MOT_1]);
|
||||
APM_RC.OutputCh(MOT_2, motor_out[MOT_2]);
|
||||
APM_RC.OutputCh(MOT_3, motor_out[MOT_3]);
|
||||
|
@ -6,7 +6,8 @@ static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
|
||||
| _BV(MOT_5) | _BV(MOT_6) | _BV(MOT_7) | _BV(MOT_8));
|
||||
| _BV(MOT_5) | _BV(MOT_6) | _BV(MOT_7) | _BV(MOT_8),
|
||||
g.rc_speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -6,7 +6,8 @@ static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
|
||||
| _BV(MOT_5) | _BV(MOT_6) | _BV(MOT_7) | _BV(MOT_8));
|
||||
| _BV(MOT_5) | _BV(MOT_6) | _BV(MOT_7) | _BV(MOT_8),
|
||||
g.rc_speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -5,7 +5,8 @@
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4));
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4),
|
||||
g.rc_speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -4,7 +4,8 @@
|
||||
static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_4));
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_4),
|
||||
g.rc_speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -8,7 +8,8 @@ static void init_motors_out()
|
||||
{
|
||||
#if INSTANT_PWM == 0
|
||||
APM_RC.SetFastOutputChannels(_BV(MOT_1) | _BV(MOT_2) | _BV(MOT_3) | _BV(MOT_4)
|
||||
| _BV(MOT_5) | _BV(MOT_6));
|
||||
| _BV(MOT_5) | _BV(MOT_6),
|
||||
g.rc_speed);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -66,7 +66,7 @@ static void calc_XY_velocity(){
|
||||
|
||||
/*
|
||||
// Ryan Beall's forward estimator:
|
||||
int16_t x_speed_new = (float)(g_gps->longitude - last_longitude) * tmp;
|
||||
int16_t x_speed_new = (float)(g_gps->longitude - last_longitude) * scaleLongDown* tmp;
|
||||
int16_t y_speed_new = (float)(g_gps->latitude - last_latitude) * tmp;
|
||||
|
||||
x_actual_speed = x_speed_new + (x_speed_new - x_speed_old);
|
||||
@ -101,33 +101,50 @@ static void calc_location_error(struct Location *next_loc)
|
||||
#define NAV_ERR_MAX 600
|
||||
static void calc_loiter(int x_error, int y_error)
|
||||
{
|
||||
// East/West
|
||||
int16_t x_target_speed = g.pi_loiter_lon.get_p(x_error);
|
||||
x_target_speed = constrain(x_error, -250, 250);
|
||||
#if LOITER_RATE == 1
|
||||
int16_t x_target_speed, y_target_speed;
|
||||
int16_t x_iterm, y_iterm;
|
||||
|
||||
// East / West
|
||||
x_target_speed = g.pi_loiter_lon.get_p(x_error); // not contstrained yet
|
||||
//x_target_speed = constrain(x_target_speed, -250, 250); // limit to 2.5m/s travel speed
|
||||
x_rate_error = x_target_speed - x_actual_speed; // calc the speed error
|
||||
nav_lon = g.pid_loiter_rate_lon.get_pid(x_rate_error, dTnav);
|
||||
nav_lon = constrain(nav_lon, -3000, 3000); // 30°
|
||||
|
||||
// North / South
|
||||
y_target_speed = g.pi_loiter_lat.get_p(y_error);
|
||||
//y_target_speed = constrain(y_target_speed, -250, 250);
|
||||
y_rate_error = y_target_speed - y_actual_speed;
|
||||
nav_lat = g.pid_loiter_rate_lat.get_pid(y_rate_error, dTnav);
|
||||
nav_lat = constrain(nav_lat, -3000, 3000); // 30°
|
||||
|
||||
// copy over I term to Nav_Rate
|
||||
g.pid_nav_lon.set_integrator(g.pid_loiter_rate_lon.get_integrator());
|
||||
g.pid_nav_lat.set_integrator(g.pid_loiter_rate_lat.get_integrator());
|
||||
|
||||
#else
|
||||
|
||||
// no rate control on Loiter
|
||||
nav_lon = g.pid_loiter_rate_lon.get_pid(x_error, dTnav);
|
||||
nav_lat = g.pid_loiter_rate_lat.get_pid(y_error, dTnav);
|
||||
|
||||
nav_lon = constrain(nav_lon, -3000, 3000); // 30°
|
||||
nav_lat = constrain(nav_lat, -3000, 3000); // 30°
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
// Wind I term based on location error,
|
||||
// limit windup
|
||||
x_error = constrain(x_error, -NAV_ERR_MAX, NAV_ERR_MAX);
|
||||
int16_t x_iterm = g.pi_loiter_lon.get_i(x_error, dTnav);
|
||||
x_rate_error = x_target_speed - x_actual_speed;
|
||||
|
||||
// North/South
|
||||
int16_t y_target_speed = g.pi_loiter_lat.get_p(y_error);
|
||||
y_target_speed = constrain(y_error, -250, 250);
|
||||
// limit windup
|
||||
y_error = constrain(y_error, -NAV_ERR_MAX, NAV_ERR_MAX);
|
||||
int16_t y_iterm = g.pi_loiter_lat.get_i(y_error, dTnav);
|
||||
y_rate_error = y_target_speed - y_actual_speed;
|
||||
|
||||
//nav_lon = g.pid_loiter_rate_lon.get_pid(x_rate_error, dTnav);
|
||||
//nav_lat = g.pid_loiter_rate_lat.get_pid(y_rate_error, dTnav);
|
||||
nav_lon = g.pid_nav_lon.get_pid(x_rate_error, dTnav);
|
||||
nav_lat = g.pid_nav_lat.get_pid(y_rate_error, dTnav);
|
||||
nav_lon = constrain(nav_lon, -3000, 3000);
|
||||
nav_lat = constrain(nav_lat, -3000, 3000);
|
||||
|
||||
nav_lat = nav_lat + y_iterm;
|
||||
nav_lon = nav_lon + x_iterm;
|
||||
|
||||
|
||||
/*
|
||||
x_error = constrain(x_error, -NAV_ERR_MAX, NAV_ERR_MAX);
|
||||
y_error = constrain(y_error, -NAV_ERR_MAX, NAV_ERR_MAX);
|
||||
x_iterm = g.pi_loiter_lon.get_i(x_error, dTnav);
|
||||
y_iterm = g.pi_loiter_lat.get_i(y_error, dTnav);
|
||||
nav_lat = nav_lat + y_iterm;
|
||||
nav_lon = nav_lon + x_iterm;
|
||||
*/
|
||||
|
||||
/*
|
||||
int8_t ttt = 1.0/dTnav;
|
||||
@ -170,24 +187,31 @@ static void calc_nav_rate(int max_speed)
|
||||
update_crosstrack();
|
||||
|
||||
// nav_bearing includes crosstrack
|
||||
float temp = (9000l - nav_bearing) * RADX100;
|
||||
float temp = (9000l - nav_bearing) * RADX100;
|
||||
|
||||
x_rate_error = (cos(temp) * max_speed) - x_actual_speed; // 413
|
||||
x_rate_error = constrain(x_rate_error, -1000, 1000);
|
||||
int16_t x_iterm = g.pi_loiter_lon.get_i(x_rate_error, dTnav);
|
||||
// East / West
|
||||
x_rate_error = (cos(temp) * max_speed) - x_actual_speed; // 413
|
||||
x_rate_error = constrain(x_rate_error, -1000, 1000);
|
||||
nav_lon = g.pid_nav_lon.get_pid(x_rate_error, dTnav);
|
||||
nav_lon = constrain(nav_lon, -3000, 3000);
|
||||
|
||||
y_rate_error = (sin(temp) * max_speed) - y_actual_speed; // 413
|
||||
y_rate_error = constrain(y_rate_error, -1000, 1000); // added a rate error limit to keep pitching down to a minimum
|
||||
int16_t y_iterm = g.pi_loiter_lat.get_i(y_rate_error, dTnav);
|
||||
// North / South
|
||||
y_rate_error = (sin(temp) * max_speed) - y_actual_speed; // 413
|
||||
y_rate_error = constrain(y_rate_error, -1000, 1000); // added a rate error limit to keep pitching down to a minimum
|
||||
nav_lat = g.pid_nav_lat.get_pid(y_rate_error, dTnav);
|
||||
nav_lat = constrain(nav_lat, -3000, 3000);
|
||||
|
||||
nav_lon = g.pid_nav_lon.get_pid(x_rate_error, dTnav);
|
||||
nav_lat = g.pid_nav_lat.get_pid(y_rate_error, dTnav);
|
||||
// copy over I term to Loiter_Rate
|
||||
g.pid_loiter_rate_lon.set_integrator(g.pid_nav_lon.get_integrator());
|
||||
g.pid_loiter_rate_lat.set_integrator(g.pid_nav_lat.get_integrator());
|
||||
|
||||
//int16_t x_iterm = g.pi_loiter_lon.get_i(x_rate_error, dTnav);
|
||||
//int16_t y_iterm = g.pi_loiter_lat.get_i(y_rate_error, dTnav);
|
||||
|
||||
//nav_lon = nav_lon + x_iterm;
|
||||
//nav_lat = nav_lat + y_iterm;
|
||||
|
||||
nav_lon = constrain(nav_lon, -3000, 3000);
|
||||
nav_lat = constrain(nav_lat, -3000, 3000);
|
||||
|
||||
nav_lon = nav_lon + x_iterm;
|
||||
nav_lat = nav_lat + y_iterm;
|
||||
|
||||
/*
|
||||
Serial.printf("max_sp %d,\t x_sp %d, y_sp %d,\t x_re: %d, y_re: %d, \tnav_lon: %d, nav_lat: %d, Xi:%d, Yi:%d, \t XE %d \n",
|
||||
|
@ -78,10 +78,14 @@ static int32_t read_barometer(void)
|
||||
static void init_compass()
|
||||
{
|
||||
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
|
||||
dcm.set_compass(&compass);
|
||||
compass.init();
|
||||
compass.get_offsets(); // load offsets to account for airframe magnetic interference
|
||||
compass.null_offsets_enable();
|
||||
if (!compass.init() || !compass.read()) {
|
||||
// make sure we don't pass a broken compass to DCM
|
||||
Serial.println_P(PSTR("COMPASS INIT ERROR"));
|
||||
return;
|
||||
}
|
||||
dcm.set_compass(&compass);
|
||||
compass.get_offsets(); // load offsets to account for airframe magnetic interference
|
||||
compass.null_offsets_enable();
|
||||
}
|
||||
|
||||
static void init_optflow()
|
||||
|
@ -343,6 +343,10 @@ static void init_ardupilot()
|
||||
Log_Write_Data(20, (float)g.pid_nav_lon.kD());
|
||||
|
||||
Log_Write_Data(21, (int32_t)g.auto_slew_rate.get());
|
||||
|
||||
Log_Write_Data(22, (float)g.pid_loiter_rate_lon.kP());
|
||||
Log_Write_Data(23, (float)g.pid_loiter_rate_lon.kI());
|
||||
Log_Write_Data(24, (float)g.pid_loiter_rate_lon.kD());
|
||||
#endif
|
||||
|
||||
SendDebug("\nReady to FLY ");
|
||||
@ -405,10 +409,9 @@ static void set_mode(byte mode)
|
||||
mode = STABILIZE;
|
||||
}
|
||||
|
||||
old_control_mode = control_mode;
|
||||
|
||||
control_mode = mode;
|
||||
control_mode = constrain(control_mode, 0, NUM_MODES - 1);
|
||||
old_control_mode = control_mode;
|
||||
control_mode = mode;
|
||||
control_mode = constrain(control_mode, 0, NUM_MODES - 1);
|
||||
|
||||
// used to stop fly_aways
|
||||
motor_auto_armed = (g.rc_3.control_in > 0);
|
||||
@ -429,7 +432,7 @@ static void set_mode(byte mode)
|
||||
land_complete = false;
|
||||
|
||||
// debug to Serial terminal
|
||||
Serial.println(flight_mode_strings[control_mode]);
|
||||
//Serial.println(flight_mode_strings[control_mode]);
|
||||
|
||||
// report the GPS and Motor arming status
|
||||
led_mode = NORMAL_LEDS;
|
||||
@ -532,6 +535,9 @@ static void set_mode(byte mode)
|
||||
if(throttle_mode == THROTTLE_MANUAL){
|
||||
// reset all of the throttle iterms
|
||||
update_throttle_cruise();
|
||||
|
||||
// reset auto_throttle
|
||||
nav_throttle = 0;
|
||||
}else {
|
||||
// an automatic throttle
|
||||
init_throttle_cruise();
|
||||
@ -657,3 +663,36 @@ void flash_leds(bool on)
|
||||
digitalWrite(A_LED_PIN, on?LED_OFF:LED_ON);
|
||||
digitalWrite(C_LED_PIN, on?LED_ON:LED_OFF);
|
||||
}
|
||||
|
||||
#ifndef DESKTOP_BUILD
|
||||
/*
|
||||
* Read Vcc vs 1.1v internal reference
|
||||
*
|
||||
* This call takes about 150us total. ADC conversion is 13 cycles of
|
||||
* 125khz default changes the mux if it isn't set, and return last
|
||||
* reading (allows necessary settle time) otherwise trigger the
|
||||
* conversion
|
||||
*/
|
||||
uint16_t board_voltage(void)
|
||||
{
|
||||
static uint16_t vcc = 5000;
|
||||
const uint8_t mux = (_BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1));
|
||||
|
||||
if (ADMUX == mux) {
|
||||
ADCSRA |= _BV(ADSC); // Convert
|
||||
uint16_t counter=4000; // normally takes about 1700 loops
|
||||
while (bit_is_set(ADCSRA, ADSC) && counter) // Wait
|
||||
counter--;
|
||||
if (counter == 0) {
|
||||
// we don't actually expect this timeout to happen,
|
||||
// but we don't want any more code that could hang
|
||||
return vcc;
|
||||
}
|
||||
uint32_t result = ADCL | ADCH<<8;
|
||||
vcc = 1126400L / result; // Read and back-calculate Vcc in mV
|
||||
} else {
|
||||
ADMUX = mux; // switch mux, settle time is needed
|
||||
}
|
||||
return vcc; // in mV
|
||||
}
|
||||
#endif
|
||||
|
@ -16,6 +16,7 @@ static int8_t test_imu(uint8_t argc, const Menu::arg *argv);
|
||||
//static int8_t test_dcm_eulers(uint8_t argc, const Menu::arg *argv);
|
||||
//static int8_t test_dcm(uint8_t argc, const Menu::arg *argv);
|
||||
//static int8_t test_omega(uint8_t argc, const Menu::arg *argv);
|
||||
//static int8_t test_stab_d(uint8_t argc, const Menu::arg *argv);
|
||||
static int8_t test_battery(uint8_t argc, const Menu::arg *argv);
|
||||
//static int8_t test_boost(uint8_t argc, const Menu::arg *argv);
|
||||
//static int8_t test_wp_nav(uint8_t argc, const Menu::arg *argv);
|
||||
@ -65,6 +66,7 @@ const struct Menu::command test_menu_commands[] PROGMEM = {
|
||||
{"imu", test_imu},
|
||||
// {"dcm", test_dcm_eulers},
|
||||
//{"omega", test_omega},
|
||||
// {"stab_d", test_stab_d},
|
||||
{"battery", test_battery},
|
||||
{"tune", test_tuning},
|
||||
//{"tri", test_tri},
|
||||
@ -592,6 +594,42 @@ test_gps(uint8_t argc, const Menu::arg *argv)
|
||||
return 0;
|
||||
}
|
||||
|
||||
// used to test the gain scheduler for Stab_D
|
||||
/*
|
||||
static int8_t
|
||||
test_stab_d(uint8_t argc, const Menu::arg *argv)
|
||||
{
|
||||
int16_t i = 0;
|
||||
g.stabilize_d = 1;
|
||||
|
||||
g.stabilize_d_schedule = 1
|
||||
for (i = -4600; i < 4600; i+=10) {
|
||||
new_radio_frame = true;
|
||||
g.rc_1.control_in = i;
|
||||
g.rc_2.control_in = i;
|
||||
update_roll_pitch_mode();
|
||||
Serial.printf("rin:%d, d:%1.6f \tpin:%d, d:%1.6f\n",g.rc_1.control_in, roll_scale_d, g.rc_2.control_in, pitch_scale_d);
|
||||
}
|
||||
g.stabilize_d_schedule = .5
|
||||
for (i = -4600; i < 4600; i+=10) {
|
||||
new_radio_frame = true;
|
||||
g.rc_1.control_in = i;
|
||||
g.rc_2.control_in = i;
|
||||
update_roll_pitch_mode();
|
||||
Serial.printf("rin:%d, d:%1.6f \tpin:%d, d:%1.6f\n",g.rc_1.control_in, roll_scale_d, g.rc_2.control_in, pitch_scale_d);
|
||||
}
|
||||
|
||||
g.stabilize_d_schedule = 0
|
||||
for (i = -4600; i < 4600; i+=10) {
|
||||
new_radio_frame = true;
|
||||
g.rc_1.control_in = i;
|
||||
g.rc_2.control_in = i;
|
||||
update_roll_pitch_mode();
|
||||
Serial.printf("rin:%d, d:%1.6f \tpin:%d, d:%1.6f\n",g.rc_1.control_in, roll_scale_d, g.rc_2.control_in, pitch_scale_d);
|
||||
}
|
||||
|
||||
}*/
|
||||
|
||||
/*
|
||||
//static int8_t
|
||||
//test_dcm(uint8_t argc, const Menu::arg *argv)
|
||||
|
@ -44,7 +44,8 @@ version 2.1 of the License, or (at your option) any later version.
|
||||
#include <PID.h> // PID library
|
||||
#include <RC_Channel.h> // RC Channel Library
|
||||
#include <AP_RangeFinder.h> // Range finder library
|
||||
#include <ModeFilter.h>
|
||||
#include <Filter.h> // Filter library
|
||||
#include <ModeFilter.h> // Mode Filter from Filter library
|
||||
#include <AP_Relay.h> // APM relay
|
||||
#include <AP_Mount.h> // Camera/Antenna mount
|
||||
#include <GCS_MAVLink.h> // MAVLink GCS definitions
|
||||
@ -224,7 +225,7 @@ GCS_MAVLINK gcs3;
|
||||
// PITOT selection
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
//
|
||||
ModeFilter sonar_mode_filter;
|
||||
ModeFilterInt16_Size5 sonar_mode_filter(2);
|
||||
|
||||
#if CONFIG_PITOT_SOURCE == PITOT_SOURCE_ADC
|
||||
AP_AnalogSource_ADC pitot_analog_source( &adc,
|
||||
@ -769,8 +770,11 @@ static void medium_loop()
|
||||
|
||||
#if HIL_MODE != HIL_MODE_ATTITUDE
|
||||
if (g.compass_enabled && compass.read()) {
|
||||
dcm.set_compass(&compass);
|
||||
compass.calculate(dcm.get_dcm_matrix()); // Calculate heading
|
||||
compass.null_offsets(dcm.get_dcm_matrix());
|
||||
} else {
|
||||
dcm.set_compass(NULL);
|
||||
}
|
||||
#endif
|
||||
/*{
|
||||
|
@ -2000,7 +2000,7 @@ GCS_MAVLINK::queued_param_send()
|
||||
value = vp->cast_to_float(_queued_parameter_type);
|
||||
|
||||
char param_name[ONBOARD_PARAM_NAME_LENGTH];
|
||||
vp->copy_name(param_name, sizeof(param_name));
|
||||
vp->copy_name(param_name, sizeof(param_name), true);
|
||||
|
||||
mavlink_msg_param_value_send(
|
||||
chan,
|
||||
|
@ -241,7 +241,7 @@ static void Log_Write_Performance()
|
||||
DataFlash.WriteInt(G_Dt_max);
|
||||
DataFlash.WriteByte(dcm.gyro_sat_count);
|
||||
DataFlash.WriteByte(imu.adc_constraints);
|
||||
DataFlash.WriteByte(dcm.renorm_sqrt_count);
|
||||
DataFlash.WriteByte(dcm.renorm_range_count);
|
||||
DataFlash.WriteByte(dcm.renorm_blowup_count);
|
||||
DataFlash.WriteByte(gps_fix_count);
|
||||
DataFlash.WriteInt((int)(dcm.get_health() * 1000));
|
||||
|
@ -175,12 +175,11 @@ static void init_ardupilot()
|
||||
|
||||
if (g.compass_enabled==true) {
|
||||
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
|
||||
if (!compass.init()) {
|
||||
if (!compass.init() || !compass.read()) {
|
||||
Serial.println_P(PSTR("Compass initialisation failed!"));
|
||||
g.compass_enabled = false;
|
||||
} else {
|
||||
dcm.set_compass(&compass);
|
||||
compass.get_offsets(); // load offsets to account for airframe magnetic interference
|
||||
compass.null_offsets_enable();
|
||||
}
|
||||
}
|
||||
@ -509,7 +508,7 @@ static void resetPerfData(void) {
|
||||
G_Dt_max = 0;
|
||||
dcm.gyro_sat_count = 0;
|
||||
imu.adc_constraints = 0;
|
||||
dcm.renorm_sqrt_count = 0;
|
||||
dcm.renorm_range_count = 0;
|
||||
dcm.renorm_blowup_count = 0;
|
||||
gps_fix_count = 0;
|
||||
pmTest1 = 0;
|
||||
@ -566,3 +565,36 @@ void flash_leds(bool on)
|
||||
digitalWrite(A_LED_PIN, on?LED_OFF:LED_ON);
|
||||
digitalWrite(C_LED_PIN, on?LED_ON:LED_OFF);
|
||||
}
|
||||
|
||||
#ifndef DESKTOP_BUILD
|
||||
/*
|
||||
* Read Vcc vs 1.1v internal reference
|
||||
*
|
||||
* This call takes about 150us total. ADC conversion is 13 cycles of
|
||||
* 125khz default changes the mux if it isn't set, and return last
|
||||
* reading (allows necessary settle time) otherwise trigger the
|
||||
* conversion
|
||||
*/
|
||||
uint16_t board_voltage(void)
|
||||
{
|
||||
static uint16_t vcc = 5000;
|
||||
const uint8_t mux = (_BV(REFS0)|_BV(MUX4)|_BV(MUX3)|_BV(MUX2)|_BV(MUX1));
|
||||
|
||||
if (ADMUX == mux) {
|
||||
ADCSRA |= _BV(ADSC); // Convert
|
||||
uint16_t counter=4000; // normally takes about 1700 loops
|
||||
while (bit_is_set(ADCSRA, ADSC) && counter) // Wait
|
||||
counter--;
|
||||
if (counter == 0) {
|
||||
// we don't actually expect this timeout to happen,
|
||||
// but we don't want any more code that could hang
|
||||
return vcc;
|
||||
}
|
||||
uint32_t result = ADCL | ADCH<<8;
|
||||
vcc = 1126400L / result; // Read and back-calculate Vcc in mV
|
||||
} else {
|
||||
ADMUX = mux; // switch mux, settle time is needed
|
||||
}
|
||||
return vcc; // in mV
|
||||
}
|
||||
#endif
|
||||
|
30
Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs
Normal file
30
Tools/ArdupilotMegaPlanner/Antenna/ITrackerOutput.cs
Normal file
@ -0,0 +1,30 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
|
||||
namespace ArdupilotMega.Antenna
|
||||
{
|
||||
interface ITrackerOutput
|
||||
{
|
||||
SerialPort ComPort { get; set; }
|
||||
|
||||
double TrimPan { get; set; }
|
||||
double TrimTilt { get; set; }
|
||||
|
||||
int PanStartRange { get; set; }
|
||||
int TiltStartRange { get; set; }
|
||||
int PanEndRange { get; set; }
|
||||
int TiltEndRange { get; set; }
|
||||
|
||||
bool PanReverse { get; set; }
|
||||
bool TiltReverse { get; set; }
|
||||
|
||||
bool Init();
|
||||
bool Setup();
|
||||
bool Pan(double Angle);
|
||||
bool Tilt(double Angle);
|
||||
bool PanAndTilt(double Pan,double Tilt);
|
||||
bool Close();
|
||||
}
|
||||
}
|
162
Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs
Normal file
162
Tools/ArdupilotMegaPlanner/Antenna/Maestro.cs
Normal file
@ -0,0 +1,162 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
|
||||
namespace ArdupilotMega.Antenna
|
||||
{
|
||||
class Maestro : ITrackerOutput
|
||||
{
|
||||
public SerialPort ComPort { get; set; }
|
||||
/// <summary>
|
||||
/// 0-360
|
||||
/// </summary>
|
||||
public double TrimPan { get; set; }
|
||||
/// <summary>
|
||||
/// -90 - 90
|
||||
/// </summary>
|
||||
public double TrimTilt { get; set; }
|
||||
|
||||
public int PanStartRange { get; set; }
|
||||
public int TiltStartRange { get; set; }
|
||||
public int PanEndRange { get; set; }
|
||||
public int TiltEndRange { get; set; }
|
||||
|
||||
public bool PanReverse { get { return _panreverse == -1; } set { _panreverse = value == true ? -1 : 1 ; } }
|
||||
public bool TiltReverse { get { return _tiltreverse == -1; } set { _tiltreverse = value == true ? -1 : 1; } }
|
||||
|
||||
int _panreverse = 1;
|
||||
int _tiltreverse = 1;
|
||||
|
||||
byte PanAddress = 0;
|
||||
byte TiltAddress = 1;
|
||||
|
||||
public bool Init()
|
||||
{
|
||||
|
||||
if ((PanStartRange - PanEndRange) == 0)
|
||||
{
|
||||
System.Windows.Forms.MessageBox.Show("Invalid Pan Range", "Error");
|
||||
return false;
|
||||
}
|
||||
|
||||
if ((TiltStartRange - TiltEndRange) == 0)
|
||||
{
|
||||
System.Windows.Forms.MessageBox.Show("Invalid Tilt Range", "Error");
|
||||
return false;
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
ComPort.Open();
|
||||
}
|
||||
catch (Exception ex) { System.Windows.Forms.MessageBox.Show("Connect failed " + ex.Message,"Error"); return false; }
|
||||
|
||||
return true;
|
||||
}
|
||||
public bool Setup()
|
||||
{
|
||||
int target = 100;
|
||||
// speed
|
||||
var buffer = new byte[] { 0x87, PanAddress, (byte)(target & 0x7F), (byte)((target >> 7) & 0x7F) };
|
||||
ComPort.Write(buffer, 0, buffer.Length);
|
||||
|
||||
buffer = new byte[] { 0x87, TiltAddress, (byte)(target & 0x7F), (byte)((target >> 7) & 0x7F) };
|
||||
ComPort.Write(buffer, 0, buffer.Length);
|
||||
|
||||
// accel
|
||||
target = 5;
|
||||
buffer = new byte[] { 0x89, PanAddress, (byte)(target & 0x7F), (byte)((target >> 7) & 0x7F) };
|
||||
ComPort.Write(buffer, 0, buffer.Length);
|
||||
|
||||
buffer = new byte[] { 0x89, TiltAddress, (byte)(target & 0x7F), (byte)((target >> 7) & 0x7F) };
|
||||
ComPort.Write(buffer, 0, buffer.Length);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
double wrap_180(double input)
|
||||
{
|
||||
if (input > 180)
|
||||
return input - 360;
|
||||
if (input < -180)
|
||||
return input + 360;
|
||||
return input;
|
||||
}
|
||||
|
||||
double wrap_range(double input,double range)
|
||||
{
|
||||
if (input > range)
|
||||
return input - 360;
|
||||
if (input < -range)
|
||||
return input + 360;
|
||||
return input;
|
||||
}
|
||||
|
||||
public bool Pan(double Angle)
|
||||
{
|
||||
double range = Math.Abs(PanStartRange - PanEndRange);
|
||||
|
||||
// get relative center based on tracking center
|
||||
double rangeleft = PanStartRange - TrimPan;
|
||||
double rangeright = PanEndRange - TrimPan;
|
||||
double centerpos = 127;
|
||||
|
||||
// get the output angle the tracker needs to point and constrain the output to the allowed options
|
||||
short PointAtAngle = Constrain(wrap_180(Angle - TrimPan), PanStartRange, PanEndRange);
|
||||
|
||||
// conver the angle into a 0-255 value
|
||||
byte target = (byte)((((PointAtAngle / range) * 2.0) * 127 + centerpos) * _panreverse);
|
||||
|
||||
//Console.WriteLine("P " + Angle + " " + target + " " + PointAtAngle);
|
||||
|
||||
var buffer = new byte[] { 0xff,PanAddress,target};
|
||||
ComPort.Write(buffer, 0, buffer.Length);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
public bool Tilt(double Angle)
|
||||
{
|
||||
double range = Math.Abs(TiltStartRange - TiltEndRange);
|
||||
|
||||
short PointAtAngle = Constrain((Angle - TrimTilt), TiltStartRange, TiltEndRange);
|
||||
|
||||
byte target = (byte)((((PointAtAngle / range ) * 2) * 127 + 127) * _tiltreverse);
|
||||
|
||||
//Console.WriteLine("T " + Angle + " " + target + " " + PointAtAngle);
|
||||
|
||||
var buffer = new byte[] { 0xff, TiltAddress, target };
|
||||
ComPort.Write(buffer, 0, buffer.Length);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
public bool PanAndTilt(double pan, double tilt)
|
||||
{
|
||||
if (Tilt(tilt) && Pan(pan))
|
||||
return true;
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
public bool Close()
|
||||
{
|
||||
try
|
||||
{
|
||||
ComPort.Close();
|
||||
}
|
||||
catch { }
|
||||
return true;
|
||||
}
|
||||
|
||||
short Constrain(double input, double min, double max)
|
||||
{
|
||||
if (input < min)
|
||||
return (short)min;
|
||||
if (input > max)
|
||||
return (short)max;
|
||||
return (short)input;
|
||||
}
|
||||
}
|
||||
}
|
247
Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs
generated
Normal file
247
Tools/ArdupilotMegaPlanner/Antenna/Tracker.Designer.cs
generated
Normal file
@ -0,0 +1,247 @@
|
||||
namespace ArdupilotMega.Antenna
|
||||
{
|
||||
partial class Tracker
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Windows Form Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Tracker));
|
||||
this.CMB_interface = new System.Windows.Forms.ComboBox();
|
||||
this.label1 = new System.Windows.Forms.Label();
|
||||
this.CMB_baudrate = new System.Windows.Forms.ComboBox();
|
||||
this.CMB_serialport = new System.Windows.Forms.ComboBox();
|
||||
this.BUT_connect = new ArdupilotMega.MyButton();
|
||||
this.TRK_pantrim = new System.Windows.Forms.TrackBar();
|
||||
this.TXT_panrange = new System.Windows.Forms.TextBox();
|
||||
this.label3 = new System.Windows.Forms.Label();
|
||||
this.label4 = new System.Windows.Forms.Label();
|
||||
this.label5 = new System.Windows.Forms.Label();
|
||||
this.label6 = new System.Windows.Forms.Label();
|
||||
this.TXT_tiltrange = new System.Windows.Forms.TextBox();
|
||||
this.TRK_tilttrim = new System.Windows.Forms.TrackBar();
|
||||
this.label2 = new System.Windows.Forms.Label();
|
||||
this.label7 = new System.Windows.Forms.Label();
|
||||
((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.TRK_tilttrim)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// CMB_interface
|
||||
//
|
||||
this.CMB_interface.FormattingEnabled = true;
|
||||
this.CMB_interface.Items.AddRange(new object[] {
|
||||
"Maestro"});
|
||||
this.CMB_interface.Location = new System.Drawing.Point(83, 10);
|
||||
this.CMB_interface.Name = "CMB_interface";
|
||||
this.CMB_interface.Size = new System.Drawing.Size(121, 21);
|
||||
this.CMB_interface.TabIndex = 0;
|
||||
this.CMB_interface.Text = "Maestro";
|
||||
//
|
||||
// label1
|
||||
//
|
||||
this.label1.AutoSize = true;
|
||||
this.label1.Location = new System.Drawing.Point(13, 13);
|
||||
this.label1.Name = "label1";
|
||||
this.label1.Size = new System.Drawing.Size(49, 13);
|
||||
this.label1.TabIndex = 1;
|
||||
this.label1.Text = "Interface";
|
||||
//
|
||||
// CMB_baudrate
|
||||
//
|
||||
this.CMB_baudrate.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
|
||||
this.CMB_baudrate.FormattingEnabled = true;
|
||||
this.CMB_baudrate.Items.AddRange(new object[] {
|
||||
"4800",
|
||||
"9600",
|
||||
"14400",
|
||||
"19200",
|
||||
"28800",
|
||||
"38400",
|
||||
"57600",
|
||||
"115200"});
|
||||
this.CMB_baudrate.Location = new System.Drawing.Point(337, 9);
|
||||
this.CMB_baudrate.Name = "CMB_baudrate";
|
||||
this.CMB_baudrate.Size = new System.Drawing.Size(121, 21);
|
||||
this.CMB_baudrate.TabIndex = 5;
|
||||
//
|
||||
// CMB_serialport
|
||||
//
|
||||
this.CMB_serialport.DropDownStyle = System.Windows.Forms.ComboBoxStyle.DropDownList;
|
||||
this.CMB_serialport.FormattingEnabled = true;
|
||||
this.CMB_serialport.Location = new System.Drawing.Point(210, 10);
|
||||
this.CMB_serialport.Name = "CMB_serialport";
|
||||
this.CMB_serialport.Size = new System.Drawing.Size(121, 21);
|
||||
this.CMB_serialport.TabIndex = 3;
|
||||
//
|
||||
// BUT_connect
|
||||
//
|
||||
this.BUT_connect.Location = new System.Drawing.Point(476, 9);
|
||||
this.BUT_connect.Name = "BUT_connect";
|
||||
this.BUT_connect.Size = new System.Drawing.Size(75, 23);
|
||||
this.BUT_connect.TabIndex = 4;
|
||||
this.BUT_connect.Text = "Connect";
|
||||
this.BUT_connect.UseVisualStyleBackColor = true;
|
||||
this.BUT_connect.Click += new System.EventHandler(this.BUT_connect_Click);
|
||||
//
|
||||
// TRK_pantrim
|
||||
//
|
||||
this.TRK_pantrim.Location = new System.Drawing.Point(153, 65);
|
||||
this.TRK_pantrim.Maximum = 180;
|
||||
this.TRK_pantrim.Minimum = -180;
|
||||
this.TRK_pantrim.Name = "TRK_pantrim";
|
||||
this.TRK_pantrim.Size = new System.Drawing.Size(375, 45);
|
||||
this.TRK_pantrim.TabIndex = 6;
|
||||
this.TRK_pantrim.Scroll += new System.EventHandler(this.TRK_pantrim_Scroll);
|
||||
//
|
||||
// TXT_panrange
|
||||
//
|
||||
this.TXT_panrange.Location = new System.Drawing.Point(83, 65);
|
||||
this.TXT_panrange.Name = "TXT_panrange";
|
||||
this.TXT_panrange.Size = new System.Drawing.Size(64, 20);
|
||||
this.TXT_panrange.TabIndex = 7;
|
||||
this.TXT_panrange.Text = "180";
|
||||
//
|
||||
// label3
|
||||
//
|
||||
this.label3.AutoSize = true;
|
||||
this.label3.Location = new System.Drawing.Point(331, 49);
|
||||
this.label3.Name = "label3";
|
||||
this.label3.Size = new System.Drawing.Size(38, 13);
|
||||
this.label3.TabIndex = 10;
|
||||
this.label3.Text = "Center";
|
||||
//
|
||||
// label4
|
||||
//
|
||||
this.label4.AutoSize = true;
|
||||
this.label4.Location = new System.Drawing.Point(83, 49);
|
||||
this.label4.Name = "label4";
|
||||
this.label4.Size = new System.Drawing.Size(56, 13);
|
||||
this.label4.TabIndex = 11;
|
||||
this.label4.Text = "Range -/+";
|
||||
//
|
||||
// label5
|
||||
//
|
||||
this.label5.AutoSize = true;
|
||||
this.label5.Location = new System.Drawing.Point(83, 125);
|
||||
this.label5.Name = "label5";
|
||||
this.label5.Size = new System.Drawing.Size(56, 13);
|
||||
this.label5.TabIndex = 17;
|
||||
this.label5.Text = "Range -/+";
|
||||
//
|
||||
// label6
|
||||
//
|
||||
this.label6.AutoSize = true;
|
||||
this.label6.Location = new System.Drawing.Point(331, 125);
|
||||
this.label6.Name = "label6";
|
||||
this.label6.Size = new System.Drawing.Size(38, 13);
|
||||
this.label6.TabIndex = 16;
|
||||
this.label6.Text = "Center";
|
||||
//
|
||||
// TXT_tiltrange
|
||||
//
|
||||
this.TXT_tiltrange.Location = new System.Drawing.Point(83, 141);
|
||||
this.TXT_tiltrange.Name = "TXT_tiltrange";
|
||||
this.TXT_tiltrange.Size = new System.Drawing.Size(64, 20);
|
||||
this.TXT_tiltrange.TabIndex = 13;
|
||||
this.TXT_tiltrange.Text = "90";
|
||||
//
|
||||
// TRK_tilttrim
|
||||
//
|
||||
this.TRK_tilttrim.Location = new System.Drawing.Point(153, 141);
|
||||
this.TRK_tilttrim.Maximum = 90;
|
||||
this.TRK_tilttrim.Minimum = -90;
|
||||
this.TRK_tilttrim.Name = "TRK_tilttrim";
|
||||
this.TRK_tilttrim.Size = new System.Drawing.Size(375, 45);
|
||||
this.TRK_tilttrim.TabIndex = 12;
|
||||
this.TRK_tilttrim.Value = 45;
|
||||
this.TRK_tilttrim.Scroll += new System.EventHandler(this.TRK_tilttrim_Scroll);
|
||||
//
|
||||
// label2
|
||||
//
|
||||
this.label2.AutoSize = true;
|
||||
this.label2.Location = new System.Drawing.Point(13, 68);
|
||||
this.label2.Name = "label2";
|
||||
this.label2.Size = new System.Drawing.Size(26, 13);
|
||||
this.label2.TabIndex = 18;
|
||||
this.label2.Text = "Pan";
|
||||
//
|
||||
// label7
|
||||
//
|
||||
this.label7.AutoSize = true;
|
||||
this.label7.Location = new System.Drawing.Point(13, 144);
|
||||
this.label7.Name = "label7";
|
||||
this.label7.Size = new System.Drawing.Size(21, 13);
|
||||
this.label7.TabIndex = 19;
|
||||
this.label7.Text = "Tilt";
|
||||
//
|
||||
// Tracker
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.ClientSize = new System.Drawing.Size(569, 195);
|
||||
this.Controls.Add(this.label7);
|
||||
this.Controls.Add(this.label2);
|
||||
this.Controls.Add(this.label5);
|
||||
this.Controls.Add(this.label6);
|
||||
this.Controls.Add(this.TXT_tiltrange);
|
||||
this.Controls.Add(this.TRK_tilttrim);
|
||||
this.Controls.Add(this.label4);
|
||||
this.Controls.Add(this.label3);
|
||||
this.Controls.Add(this.TXT_panrange);
|
||||
this.Controls.Add(this.TRK_pantrim);
|
||||
this.Controls.Add(this.CMB_baudrate);
|
||||
this.Controls.Add(this.BUT_connect);
|
||||
this.Controls.Add(this.CMB_serialport);
|
||||
this.Controls.Add(this.label1);
|
||||
this.Controls.Add(this.CMB_interface);
|
||||
this.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
|
||||
this.Name = "Tracker";
|
||||
this.Text = "Tracker";
|
||||
((System.ComponentModel.ISupportInitialize)(this.TRK_pantrim)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.TRK_tilttrim)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private System.Windows.Forms.ComboBox CMB_interface;
|
||||
private System.Windows.Forms.Label label1;
|
||||
private System.Windows.Forms.ComboBox CMB_baudrate;
|
||||
private MyButton BUT_connect;
|
||||
private System.Windows.Forms.ComboBox CMB_serialport;
|
||||
private System.Windows.Forms.TrackBar TRK_pantrim;
|
||||
private System.Windows.Forms.TextBox TXT_panrange;
|
||||
private System.Windows.Forms.Label label3;
|
||||
private System.Windows.Forms.Label label4;
|
||||
private System.Windows.Forms.Label label5;
|
||||
private System.Windows.Forms.Label label6;
|
||||
private System.Windows.Forms.TextBox TXT_tiltrange;
|
||||
private System.Windows.Forms.TrackBar TRK_tilttrim;
|
||||
private System.Windows.Forms.Label label2;
|
||||
private System.Windows.Forms.Label label7;
|
||||
}
|
||||
}
|
115
Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
Normal file
115
Tools/ArdupilotMegaPlanner/Antenna/Tracker.cs
Normal file
@ -0,0 +1,115 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Data;
|
||||
using System.Drawing;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArdupilotMega.Antenna
|
||||
{
|
||||
public partial class Tracker : Form
|
||||
{
|
||||
System.Threading.Thread t12;
|
||||
static bool threadrun = false;
|
||||
static ITrackerOutput tracker;
|
||||
|
||||
public Tracker()
|
||||
{
|
||||
InitializeComponent();
|
||||
|
||||
MainV2.fixtheme(this);
|
||||
|
||||
CMB_serialport.DataSource = SerialPort.GetPortNames();
|
||||
|
||||
if (threadrun)
|
||||
{
|
||||
BUT_connect.Text = "Disconnect";
|
||||
}
|
||||
}
|
||||
|
||||
private void BUT_connect_Click(object sender, EventArgs e)
|
||||
{
|
||||
if (threadrun)
|
||||
{
|
||||
threadrun = false;
|
||||
BUT_connect.Text = "Connect";
|
||||
tracker.Close();
|
||||
return;
|
||||
}
|
||||
|
||||
if (tracker != null && tracker.ComPort != null && tracker.ComPort.IsOpen)
|
||||
{
|
||||
tracker.ComPort.Close();
|
||||
}
|
||||
|
||||
tracker = new ArdupilotMega.Antenna.Maestro();
|
||||
|
||||
try
|
||||
{
|
||||
tracker.ComPort = new SerialPort()
|
||||
{
|
||||
PortName = CMB_serialport.Text,
|
||||
BaudRate = int.Parse(CMB_baudrate.Text)
|
||||
};
|
||||
}
|
||||
catch (Exception ex) { MessageBox.Show("Bad Port settings " + ex.Message); return; }
|
||||
|
||||
try
|
||||
{
|
||||
tracker.PanStartRange = int.Parse(TXT_panrange.Text) / 2 * -1;
|
||||
tracker.PanEndRange = int.Parse(TXT_panrange.Text) / 2;
|
||||
tracker.TrimPan = TRK_pantrim.Value;
|
||||
|
||||
tracker.TiltStartRange = int.Parse(TXT_tiltrange.Text) / 2 * -1;
|
||||
tracker.TiltEndRange = int.Parse(TXT_tiltrange.Text) / 2;
|
||||
tracker.TrimTilt = TRK_tilttrim.Value;
|
||||
|
||||
}
|
||||
catch (Exception ex) { MessageBox.Show("Bad User input " + ex.Message); return; }
|
||||
|
||||
if (tracker.Init())
|
||||
{
|
||||
if (tracker.Setup())
|
||||
{
|
||||
tracker.PanAndTilt(0, 0);
|
||||
|
||||
t12 = new System.Threading.Thread(new System.Threading.ThreadStart(mainloop))
|
||||
{
|
||||
IsBackground = true,
|
||||
Name = "Antenna Tracker"
|
||||
};
|
||||
t12.Start();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void mainloop()
|
||||
{
|
||||
threadrun = true;
|
||||
while (threadrun)
|
||||
{
|
||||
try
|
||||
{
|
||||
// 10 hz - position updates default to 3 hz on the stream rate
|
||||
tracker.PanAndTilt(MainV2.cs.AZToMAV, MainV2.cs.ELToMAV);
|
||||
System.Threading.Thread.Sleep(100);
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
}
|
||||
|
||||
private void TRK_pantrim_Scroll(object sender, EventArgs e)
|
||||
{
|
||||
if (tracker != null)
|
||||
tracker.TrimPan = TRK_pantrim.Value;
|
||||
}
|
||||
|
||||
private void TRK_tilttrim_Scroll(object sender, EventArgs e)
|
||||
{
|
||||
if (tracker != null)
|
||||
tracker.TrimTilt = TRK_tilttrim.Value;
|
||||
}
|
||||
}
|
||||
}
|
197
Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx
Normal file
197
Tools/ArdupilotMegaPlanner/Antenna/Tracker.resx
Normal file
@ -0,0 +1,197 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>
|
||||
AAABAAEAICAAAAEAIACoEAAAFgAAACgAAAAgAAAAQAAAAAEAIAAAAAAAABAAABILAAASCwAAAAAAAAAA
|
||||
AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADOxkjAtnoOAKpJ4vyiK
|
||||
c+8nh3D/J4Zv/yeHcP8oi3PvKpJ4vy6fg4AzsZIwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
|
||||
AAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADjGo2AyspPfLZ+D/yiQ
|
||||
d/8hlXj/G6F9/xeqg/8XqYL/GKqD/xuhfv8ilnn/KZB3/y2fhP8yspPfN8ajYAAAAAAAAAAAAAAAAAAA
|
||||
AAAAAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADvRrDA1vpzfL6uN/yel
|
||||
hP8XvJD/DMyY/wfQl/8FzJP/A8qS/wPJkf8EypL/BsyU/wnRmP8PzZn/Gb2R/yemhP8tqoz/Mb2a3zbQ
|
||||
qkAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAA4y6ZgMbWV/yin
|
||||
iP8WwZP/Btqf/wDPlf8AyI7/A8aP/yfNnv9T2LP/UNax/03XsP8506b/G8ya/wHKkf8F0Zf/CNuf/xLB
|
||||
kv8fpYT/J7KQ/y7IomAAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAANcajny+w
|
||||
kf8hqoj/CNSd/wDRlf8Axor/Hcyd/3Lhwf+p7Nj/o+vV/57m0/+X5dD/k+TN/4/jzf+K5Mz/fuHH/0PW
|
||||
rf8HzJT/ANCT/wDRlv8OpX//HayI/yrFn58AAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAADDC
|
||||
nmAtro7/H62J/wPWmv8Ay47/AMaO/3XhxP+e6tT/mObP/5Pjy/+Q4sr/jODJ/4ffx/+C3MT/f9vC/3nb
|
||||
wf9y2r7/adq7/2DauP8ZzZv/Fdae/8T/9/9WxKj/HKuI/y7IomAAAAAAAAAAAAAAAAD///8AAAAAAAAA
|
||||
AAAiuZMwKKyM/x6ohf8C1Zr/AMmL/wHGjv+49OL///////////9+3ML/f9zD/4Dcwv9+28L/e9rA/3bZ
|
||||
vv9w1rr/Z9S4/17Rs/9Qz63/Qcyn/3LewP////////////n///8MpH7/JbKP/zXQqUAAAAAAAAAAAP//
|
||||
/wAAAAAAAAAAABymhN8dnn//BNGa/wDKjP8AxY3/sfHf/////////////////2nXt/9w1rv/c9e8/3TX
|
||||
vP9x17z/a9W5/2TTtf9Y0K//SMyp/zXFoP9i07X/////////////////f/LR/wDQlf8epYT/Mb2a3wAA
|
||||
AAAAAAAA////AAAAAAADlnJgFZR1/wq4iv8AzpH/AMCD/4rmzf//////////////////////WdGv/2PU
|
||||
tf9p1rf/atS4/2nUtv9i0rT/Vc+u/0fKpv8zxZz/Ws+w//////////////////////8GyJL/ANCS/xLB
|
||||
kv8tq4z/OMajYAAAAAD///8AAAAAAACHZt8NkW//ANKV/wDChP9i27r//////////////////////9Dx
|
||||
6P9MzKn/Vc+v/17Rsv9g0rP/XNCx/1XNrv9Fyaf/McSd/1fPr///////////////////////QM2m/ynK
|
||||
oP8JzJX/C9yh/ymmhf80spPfAAAAAP///wAAcUwwAHtc/wCrfP8AyIv/AMKK////////////////////
|
||||
/////////////5Dgyv9Gyqb/TMyq/07Nq/9MzKn/Qcmj/y/Fnf9Wzq3//////////////////////57k
|
||||
0v8av5T/Lceg/yzOo/8M05v/Hr6T/zCghf80spIw////AABoRYAAclT/AL2H/wDBhf9R1rL/////////
|
||||
////////4vfw//////////////////H8+P9KzKn/Ocah/zTFnv8qwpj/Us2t////////////////////
|
||||
////////DLqM/yDBlv8wxp//OM6m/xPPm/8Xz53/LZF5/y+fg4////8AAGNAvwB7Wf8Aw4j/ALyC/4bj
|
||||
yP+g5tL/g93E/2HSsv9Pzqz/Us6s//////////////////////9Yzq//Gr2S/0jLp///////////////
|
||||
/////////////yrDm/8SvI//JMGY/zDHn/81zKT/Is2e/xTUnf8nl3v/LJJ5v////wAAXz3vAIlg/wDA
|
||||
hf8AuoD/quzZ/5Hjyv9628D/ada2/1jRsP9Jy6f/a9a4//////////////////////+Y4s7/////////
|
||||
//////////////////+c4tD/AbaH/xW8kf8jwZj/LcWd/y/Jn/8kzJ3/E9Ca/yGjgf8ri3Tv////AABd
|
||||
PP8Ak2b/AL6D/w/Ekv+m6tf/j+HJ/3vawP9p1rf/W9Gx/0rNqf85yJ//Nsaf////////////////////
|
||||
/////////////////////////////wCwe/8AtoT/ELqP/xu+k/8jwZj/KMeb/yHKm/8QzZf/HqyG/ymI
|
||||
cf////8AAF07/wCSZP8AvYL/GMWU/6Dn1P+K38f/ddi+/27Wuf+E3MX/leHN/6fm1f+l5tX/neLQ////
|
||||
////////////////////////////////////////j9/J/27Vuv9Tzq7/JsKY/xa/kv8aw5T/FcaW/wvL
|
||||
lf8aqoT/J4dw/////wAAXTv/AJFk/wC9gP8GwY3/mObQ/5rkz/+26dv/y/Hl/8Dt3/+06tz/pebV/5bg
|
||||
zP+g5NL//////////////v///f7+//7+/v//////7fn2////////////tOnb/6Ll0v+v6Nj/jeDI/zXK
|
||||
o/8IxJD/BMqS/xaqgv8lh2//////AABeO+8AgVf/AL1//wDBif/R9uv/1PPq/8Tv5P+36t3/rujY/6Lk
|
||||
0v+U4cv/jt7J//j8+///////+/38//f8+//2+/r/+Pz7//3+/v/m9/P/9Pv6//D6+P9/28L/jd7J/5jj
|
||||
z/+h5dL/qOvX/4Hmyf8f1J//E596/yOJcO////8AAGA8vwB3U/8p06P/hufM/8Ty5f/D7+T/s+vb/6bm
|
||||
1P+c4c//j9/K/4vcyP/t+fb///7///j8/P/0+/r/8vr5//P7+f/1+/r/+/39///////i9fL/ZNO1/3HW
|
||||
vP992sH/htzG/4vhyv+S5dD/mO7W/6X74v80noT/Io90v////wAAZkCAAHla/33ny/945cb/nunV/7Xr
|
||||
3v+l5tT/luDN/4ndxv992cL/1vLq//v9/P/1+/n/8vv4//L69//z+/j/9Pv5/7Xo2//x+vn/////////
|
||||
//+y59n/aNS3/3LWvP932r//fNzD/4Ljyf+J7ND/l/bd/yORdf8knH6A////AABuRzAAdlT/Xc6x/23o
|
||||
xv9s4MH/qurZ/5jiz/+I3cb/edjA/8ju5f/3/Pv/8vv4//H6+P/y+/j/6/f0/7np3v/7/fz//v7+/6fk
|
||||
1f+56tz///////////9h0bT/aNW4/23Wu/9v3L//dOLG/37w0f9m1rn/Hpt8/ymujTD///8AAAAAAACD
|
||||
X98po4X/Z+7K/1vgvP+A4sf/jOHK/3rZwv+r59f/9Pv6/+/69//v+vf/8vr4/9fy6/9n0rf/VM6t/6Di
|
||||
0v/N7+f/adO4/1PMrf9t1Lr/i9zI/1/Rs/9h0rX/ZNe4/2bbvf9s5sb/ePfV/z2ylf8lrozfAAAAAP//
|
||||
/wAAAAAAAJNsYAWQbf9U1rP/Vee//0rYsf993sb/pebV//P7+v/s+Pb/6/f1/+749v+s5tj/Vc2u/1jP
|
||||
r/9ZzrD/btW5/1bOr/9Wza//Vs6v/1fOr/9Z0LD/WdCy/1vTtP9d1rX/Xt+8/2btyP9k4L//IaaF/y7D
|
||||
nmAAAAAA////AAAAAAAAAAAAD6J9zyCjgv9S68L/P9+0/2Pevv/5////7/v6/+v59//j9/L/gtvF/1PN
|
||||
r/9Wz7D/Wc+x/1nQsf9Zz7H/WM6w/1fPsP9UzrD/VM+w/1TPrv9U0a//U9Oy/1Tatv9Z5sD/Y/LL/zSx
|
||||
lP8qupbPAAAAAAAAAAD///8AAAAAAAAAAAAYto4wGaeE/y23lP8+5rn/6/////j////w//3/ve/i/2bV
|
||||
uP9Tzq7/Vc+v/1jPsP9Z0LL/WM+w/1fOsf9Wz7D/Us2w/1HOrf9Qzq3/T9Cu/0zSr/9M2LP/TeC5/1bt
|
||||
xP9HxaX/KLKQ/zTPqDAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAkvpdgG6iF/y++m//e/////P///3rl
|
||||
yf9G0K3/VdKy/1bPsf9Wz7H/Vs6w/1bPsP9Sza//Ucyu/0/Nrf9NzKz/S82s/0fOrP9G0a7/QdWv/0Le
|
||||
tP9I6L7/Q8Ok/yitjP8yyKJgAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAmwJlgG6iF/yK3
|
||||
kP8k3q7/H9el/x7Pn/8tzKT/Q9Cs/1HQsP9Q0K7/TM6u/0nMrf9Hzaz/RMyp/0LNqf8+zqn/ONGo/zTV
|
||||
qf833rD/O+S4/zvCof8orIv/MMSfYAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAA
|
||||
AAAkvpdgG6iE/xukgv8gy53/HNql/xzRn/8czJz/HcmZ/yXJnP8qyp7/Lcqg/yzLn/8nypz/JMqc/yTO
|
||||
n/8l1KT/KN2r/y3Tpv8nq4n/JaqJ/yzAm2AAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAA
|
||||
AAAAAAAAAAAAAAAAAAAato8wFKN/zxCScv8RnHn/DbqM/wjIlP8GyZT/BsaS/wbFkf8GxZH/B8WR/wfH
|
||||
k/8IypX/DMmV/xG3jP8WoX3/Fph2/xqkgs8ft5EwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA////AAAA
|
||||
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJVvYACGZM8Aelr/AHlZ/wCFX/8AiWL/AJlr/wCb
|
||||
bP8AlGf/AI5k/wB/W/8AeFj/AHtb/wCHZd8ClXBgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
|
||||
AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAABwSzAAaESAAGI/vwBf
|
||||
Pd8AXTz/AF08/wBdPP8AXz3fAGJAvwBoRIAAcUswAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
|
||||
AAAAAAAAAAAAAP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
|
||||
/wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
|
||||
/wD///8A////AP///wD///8A/+AD//+AAP/+AAA//AAAH/gAAA/wAAAH4AAAA+AAAAPAAAABwAAAAYAA
|
||||
AACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAwAAAAcAAAAHgAAAD4AAAA/AA
|
||||
AAf4AAAP/AAAH/4AAD//gAD//+AD//////8=
|
||||
</value>
|
||||
</data>
|
||||
</root>
|
@ -1,15 +1,15 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Reflection;
|
||||
using System.Management;
|
||||
using System.Windows.Forms;
|
||||
using System.Threading;
|
||||
using log4net;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
class ArduinoDetect
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
/// <summary>
|
||||
/// detects STK version 1 or 2
|
||||
/// </summary>
|
||||
@ -27,7 +27,7 @@ namespace ArdupilotMega
|
||||
serialPort.BaudRate = 57600;
|
||||
serialPort.Open();
|
||||
|
||||
System.Threading.Thread.Sleep(100);
|
||||
Thread.Sleep(100);
|
||||
|
||||
int a = 0;
|
||||
while (a < 20) // 20 * 50 = 1 sec
|
||||
@ -36,7 +36,7 @@ namespace ArdupilotMega
|
||||
serialPort.DiscardInBuffer();
|
||||
serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
|
||||
a++;
|
||||
System.Threading.Thread.Sleep(50);
|
||||
Thread.Sleep(50);
|
||||
|
||||
//Console.WriteLine("btr {0}", serialPort.BytesToRead);
|
||||
if (serialPort.BytesToRead >= 2)
|
||||
@ -53,15 +53,15 @@ namespace ArdupilotMega
|
||||
|
||||
serialPort.Close();
|
||||
|
||||
Console.WriteLine("Not a 1280");
|
||||
log.Warn("Not a 1280");
|
||||
|
||||
System.Threading.Thread.Sleep(500);
|
||||
Thread.Sleep(500);
|
||||
|
||||
serialPort.DtrEnable = true;
|
||||
serialPort.BaudRate = 115200;
|
||||
serialPort.Open();
|
||||
|
||||
System.Threading.Thread.Sleep(100);
|
||||
Thread.Sleep(100);
|
||||
|
||||
a = 0;
|
||||
while (a < 4)
|
||||
@ -69,7 +69,7 @@ namespace ArdupilotMega
|
||||
byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 };
|
||||
temp = ArduinoDetect.genstkv2packet(serialPort, temp);
|
||||
a++;
|
||||
System.Threading.Thread.Sleep(50);
|
||||
Thread.Sleep(50);
|
||||
|
||||
try
|
||||
{
|
||||
@ -81,11 +81,13 @@ namespace ArdupilotMega
|
||||
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
catch
|
||||
{
|
||||
}
|
||||
}
|
||||
|
||||
serialPort.Close();
|
||||
Console.WriteLine("Not a 2560");
|
||||
log.Warn("Not a 2560");
|
||||
return "";
|
||||
}
|
||||
|
||||
@ -106,7 +108,7 @@ namespace ArdupilotMega
|
||||
serialPort.BaudRate = 57600;
|
||||
serialPort.Open();
|
||||
|
||||
System.Threading.Thread.Sleep(100);
|
||||
Thread.Sleep(100);
|
||||
|
||||
int a = 0;
|
||||
while (a < 20) // 20 * 50 = 1 sec
|
||||
@ -115,7 +117,7 @@ namespace ArdupilotMega
|
||||
serialPort.DiscardInBuffer();
|
||||
serialPort.Write(new byte[] { (byte)'0', (byte)' ' }, 0, 2);
|
||||
a++;
|
||||
System.Threading.Thread.Sleep(50);
|
||||
Thread.Sleep(50);
|
||||
|
||||
//Console.WriteLine("btr {0}", serialPort.BytesToRead);
|
||||
if (serialPort.BytesToRead >= 2)
|
||||
@ -132,15 +134,15 @@ namespace ArdupilotMega
|
||||
|
||||
serialPort.Close();
|
||||
|
||||
Console.WriteLine("Not a 1280");
|
||||
log.Warn("Not a 1280");
|
||||
|
||||
System.Threading.Thread.Sleep(500);
|
||||
Thread.Sleep(500);
|
||||
|
||||
serialPort.DtrEnable = true;
|
||||
serialPort.BaudRate = 115200;
|
||||
serialPort.Open();
|
||||
|
||||
System.Threading.Thread.Sleep(100);
|
||||
Thread.Sleep(100);
|
||||
|
||||
a = 0;
|
||||
while (a < 4)
|
||||
@ -148,7 +150,7 @@ namespace ArdupilotMega
|
||||
byte[] temp = new byte[] { 0x6, 0, 0, 0, 0 };
|
||||
temp = ArduinoDetect.genstkv2packet(serialPort, temp);
|
||||
a++;
|
||||
System.Threading.Thread.Sleep(50);
|
||||
Thread.Sleep(50);
|
||||
|
||||
try
|
||||
{
|
||||
@ -192,7 +194,7 @@ namespace ArdupilotMega
|
||||
}
|
||||
|
||||
serialPort.Close();
|
||||
Console.WriteLine("Not a 2560");
|
||||
log.Warn("Not a 2560");
|
||||
return "";
|
||||
}
|
||||
|
||||
@ -281,11 +283,11 @@ namespace ArdupilotMega
|
||||
key = buffer[pos];
|
||||
pos++;
|
||||
|
||||
Console.Write("{0:X4}: key {1} size {2}\n ", pos - 2, key, size + 1);
|
||||
log.InfoFormat("{0:X4}: key {1} size {2}\n ", pos - 2, key, size + 1);
|
||||
|
||||
if (key == 0xff)
|
||||
{
|
||||
Console.WriteLine("end sentinal at {0}", pos - 2);
|
||||
log.InfoFormat("end sentinal at {0}", pos - 2);
|
||||
break;
|
||||
}
|
||||
|
||||
@ -301,7 +303,6 @@ namespace ArdupilotMega
|
||||
Console.Write(" {0:X2}", buffer[pos]);
|
||||
pos++;
|
||||
}
|
||||
Console.WriteLine();
|
||||
}
|
||||
}
|
||||
|
||||
@ -325,7 +326,7 @@ namespace ArdupilotMega
|
||||
|
||||
if (key == 0xff)
|
||||
{
|
||||
Console.WriteLine("end sentinal at {0}", pos - 2);
|
||||
log.InfoFormat("end sentinal at {0}", pos - 2);
|
||||
break;
|
||||
}
|
||||
|
||||
@ -341,7 +342,6 @@ namespace ArdupilotMega
|
||||
Console.Write(" {0:X2}", buffer[pos]);
|
||||
pos++;
|
||||
}
|
||||
Console.WriteLine();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -1,8 +1,10 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Reflection;
|
||||
using System.Text;
|
||||
using System.IO.Ports;
|
||||
using System.Threading;
|
||||
using log4net;
|
||||
|
||||
// Written by Michael Oborne
|
||||
|
||||
@ -10,6 +12,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
class ArduinoSTK : SerialPort, ArduinoComms
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
public event ProgressEventHandler Progress;
|
||||
|
||||
public new void Open()
|
||||
@ -48,7 +51,7 @@ namespace ArdupilotMega
|
||||
a++;
|
||||
Thread.Sleep(50);
|
||||
|
||||
Console.WriteLine("btr {0}", this.BytesToRead);
|
||||
log.InfoFormat("btr {0}", this.BytesToRead);
|
||||
if (this.BytesToRead >= 2)
|
||||
{
|
||||
byte b1 = (byte)this.ReadByte();
|
||||
@ -96,14 +99,14 @@ namespace ArdupilotMega
|
||||
{
|
||||
byte b1 = (byte)this.ReadByte();
|
||||
byte b2 = (byte)this.ReadByte();
|
||||
Console.WriteLine("bytes {0:X} {1:X}", b1, b2);
|
||||
log.DebugFormat("bytes {0:X} {1:X}", b1, b2);
|
||||
|
||||
if (b1 == 0x14 && b2 == 0x10)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
}
|
||||
Console.WriteLine("btr {0}", this.BytesToRead);
|
||||
log.DebugFormat("btr {0}", this.BytesToRead);
|
||||
Thread.Sleep(10);
|
||||
a++;
|
||||
}
|
||||
@ -210,7 +213,7 @@ namespace ArdupilotMega
|
||||
|
||||
byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'F' };
|
||||
this.Write(command, 0, command.Length);
|
||||
Console.WriteLine((startfrom + (length - totalleft)) + " - " + sending);
|
||||
log.Info((startfrom + (length - totalleft)) + " - " + sending);
|
||||
this.Write(data, startfrom + (length - totalleft), sending);
|
||||
command = new byte[] { (byte)' ' };
|
||||
this.Write(command, 0, command.Length);
|
||||
@ -223,7 +226,7 @@ namespace ArdupilotMega
|
||||
|
||||
if (!sync())
|
||||
{
|
||||
Console.WriteLine("No Sync");
|
||||
log.Info("No Sync");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@ -247,7 +250,7 @@ namespace ArdupilotMega
|
||||
throw new Exception("Address must be an even number");
|
||||
}
|
||||
|
||||
Console.WriteLine("Sending address " + ((ushort)(address / 2)));
|
||||
log.Info("Sending address " + ((ushort)(address / 2)));
|
||||
|
||||
address /= 2;
|
||||
address = (ushort)address;
|
||||
@ -257,6 +260,7 @@ namespace ArdupilotMega
|
||||
|
||||
return sync();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Upload data at preset address
|
||||
/// </summary>
|
||||
@ -294,7 +298,7 @@ namespace ArdupilotMega
|
||||
|
||||
byte[] command = new byte[] { (byte)'d', (byte)(sending >> 8), (byte)(sending & 0xff), (byte)'E' };
|
||||
this.Write(command, 0, command.Length);
|
||||
Console.WriteLine((startfrom + (length - totalleft)) + " - " + sending);
|
||||
log.Info((startfrom + (length - totalleft)) + " - " + sending);
|
||||
this.Write(data, startfrom + (length - totalleft), sending);
|
||||
command = new byte[] { (byte)' ' };
|
||||
this.Write(command, 0, command.Length);
|
||||
@ -303,7 +307,7 @@ namespace ArdupilotMega
|
||||
|
||||
if (!sync())
|
||||
{
|
||||
Console.WriteLine("No Sync");
|
||||
log.Info("No Sync");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
@ -1,8 +1,10 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Reflection;
|
||||
using System.Text;
|
||||
using System.IO.Ports;
|
||||
using System.Threading;
|
||||
using log4net;
|
||||
|
||||
// Written by Michael Oborne
|
||||
|
||||
@ -10,6 +12,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
class ArduinoSTKv2 : SerialPort,ArduinoComms
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
public event ProgressEventHandler Progress;
|
||||
|
||||
public new void Open()
|
||||
@ -250,7 +253,7 @@ namespace ArdupilotMega
|
||||
|
||||
byte[] command = new byte[] { (byte)0x13, (byte)(sending >> 8), (byte)(sending & 0xff) };
|
||||
|
||||
Console.WriteLine((startfrom + (length - totalleft)) + " - " + sending);
|
||||
log.InfoFormat((startfrom + (length - totalleft)) + " - " + sending);
|
||||
|
||||
Array.Resize<byte>(ref command, sending + 10); // sending + head
|
||||
|
||||
@ -266,7 +269,7 @@ namespace ArdupilotMega
|
||||
|
||||
if (command[1] != 0)
|
||||
{
|
||||
Console.WriteLine("No Sync");
|
||||
log.InfoFormat("No Sync");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@ -290,7 +293,7 @@ namespace ArdupilotMega
|
||||
throw new Exception("Address must be an even number");
|
||||
}
|
||||
|
||||
Console.WriteLine("Sending address " + ((address / 2)));
|
||||
log.InfoFormat("Sending address " + ((address / 2)));
|
||||
|
||||
int tempstart = address / 2; // words
|
||||
byte[] temp = new byte[] { 0x6, (byte)((tempstart >> 24) & 0xff), (byte)((tempstart >> 16) & 0xff), (byte)((tempstart >> 8) & 0xff), (byte)((tempstart >> 0) & 0xff) };
|
||||
@ -342,7 +345,7 @@ namespace ArdupilotMega
|
||||
|
||||
byte[] command = new byte[] { (byte)0x15, (byte)(sending >> 8), (byte)(sending & 0xff) };
|
||||
|
||||
Console.WriteLine((startfrom + (length - totalleft)) + " - " + sending);
|
||||
log.InfoFormat((startfrom + (length - totalleft)) + " - " + sending);
|
||||
|
||||
Array.Resize<byte>(ref command, sending + 10); // sending + head
|
||||
|
||||
@ -358,7 +361,7 @@ namespace ArdupilotMega
|
||||
|
||||
if (command[1] != 0)
|
||||
{
|
||||
Console.WriteLine("No Sync");
|
||||
log.InfoFormat("No Sync");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
@ -51,7 +51,7 @@
|
||||
<CheckForOverflowUnderflow>false</CheckForOverflowUnderflow>
|
||||
<NoStdLib>false</NoStdLib>
|
||||
<UseVSHostingProcess>true</UseVSHostingProcess>
|
||||
<FileAlignment>1024</FileAlignment>
|
||||
<FileAlignment>512</FileAlignment>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup Condition=" '$(Configuration)|$(Platform)' == 'Release|x86' ">
|
||||
<PlatformTarget>x86</PlatformTarget>
|
||||
@ -68,7 +68,7 @@
|
||||
<DebugSymbols>true</DebugSymbols>
|
||||
<NoStdLib>false</NoStdLib>
|
||||
<UseVSHostingProcess>true</UseVSHostingProcess>
|
||||
<FileAlignment>1024</FileAlignment>
|
||||
<FileAlignment>512</FileAlignment>
|
||||
</PropertyGroup>
|
||||
<PropertyGroup>
|
||||
<StartupObject>ArdupilotMega.Program</StartupObject>
|
||||
@ -147,6 +147,10 @@
|
||||
<Reference Include="KMLib">
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\kml-library\KmlTestbed\bin\Release\KMLib.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="log4net, Version=1.2.11.0, Culture=neutral, PublicKeyToken=669e0ddf0bb1aa2a, processorArchitecture=MSIL">
|
||||
<SpecificVersion>False</SpecificVersion>
|
||||
<HintPath>Lib\log4net.dll</HintPath>
|
||||
</Reference>
|
||||
<Reference Include="MetaDataExtractor">
|
||||
<HintPath>..\..\..\..\..\Desktop\DIYDrones\myquad\MetaDataExtractorCSharp240d\bin\Release\MetaDataExtractor.dll</HintPath>
|
||||
</Reference>
|
||||
@ -225,6 +229,27 @@
|
||||
</Reference>
|
||||
</ItemGroup>
|
||||
<ItemGroup>
|
||||
<Compile Include="Antenna\ITrackerOutput.cs" />
|
||||
<Compile Include="Antenna\Maestro.cs" />
|
||||
<Compile Include="Antenna\Tracker.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Antenna\Tracker.Designer.cs">
|
||||
<DependentUpon>Tracker.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Controls\ProgressReporterDialogue.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Controls\ProgressReporterDialogue.designer.cs">
|
||||
<DependentUpon>ProgressReporterDialogue.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="MagCalib.cs" />
|
||||
<Compile Include="Radio\3DRradio.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Radio\3DRradio.Designer.cs">
|
||||
<DependentUpon>3DRradio.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Controls\AGauge.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
@ -252,18 +277,13 @@
|
||||
<Compile Include="Controls\myGMAP.cs">
|
||||
<SubType>UserControl</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Controls\ProgressReporter.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Controls\ProgressReporter.designer.cs">
|
||||
<DependentUpon>ProgressReporter.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Controls\XorPlus.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
<Compile Include="Controls\XorPlus.Designer.cs">
|
||||
<DependentUpon>XorPlus.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Radio\IHex.cs" />
|
||||
<Compile Include="Mavlink\MavlinkCRC.cs" />
|
||||
<Compile Include="Mavlink\MavlinkUtil.cs" />
|
||||
<Compile Include="SerialInput.cs">
|
||||
@ -423,6 +443,7 @@
|
||||
<Compile Include="Setup\Setup.Designer.cs">
|
||||
<DependentUpon>Setup.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Speech.cs" />
|
||||
<Compile Include="Splash.cs">
|
||||
<SubType>Form</SubType>
|
||||
</Compile>
|
||||
@ -437,6 +458,17 @@
|
||||
<Compile Include="temp.Designer.cs">
|
||||
<DependentUpon>temp.cs</DependentUpon>
|
||||
</Compile>
|
||||
<Compile Include="Radio\Uploader.cs" />
|
||||
<Compile Include="LangUtility.cs" />
|
||||
<EmbeddedResource Include="Antenna\Tracker.resx">
|
||||
<DependentUpon>Tracker.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Controls\ProgressReporterDialogue.resx">
|
||||
<DependentUpon>ProgressReporterDialogue.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Radio\3DRradio.resx">
|
||||
<DependentUpon>3DRradio.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Controls\AGauge.resx">
|
||||
<DependentUpon>AGauge.cs</DependentUpon>
|
||||
<SubType>Designer</SubType>
|
||||
@ -447,9 +479,6 @@
|
||||
<EmbeddedResource Include="Controls\ImageLabel.resx">
|
||||
<DependentUpon>ImageLabel.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Controls\ProgressReporter.resx">
|
||||
<DependentUpon>ProgressReporter.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
<EmbeddedResource Include="Controls\XorPlus.resx">
|
||||
<DependentUpon>XorPlus.cs</DependentUpon>
|
||||
</EmbeddedResource>
|
||||
@ -830,6 +859,7 @@
|
||||
<Content Include="mavcmd.xml">
|
||||
<CopyToOutputDirectory>Always</CopyToOutputDirectory>
|
||||
</Content>
|
||||
<None Include="Resources\y6.png" />
|
||||
<None Include="Resources\new frames-13.png" />
|
||||
<None Include="Resources\new frames-12.png" />
|
||||
<None Include="Resources\new frames-11.png" />
|
||||
|
@ -11,6 +11,6 @@
|
||||
<UpdateUrlHistory />
|
||||
</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\Desktop\DIYDrones\myquad\MetaDataExtractorCSharp240d\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\;C:\Users\hog\Desktop\DIYDrones\myquad\MetaDataExtractorCSharp240d\bin\Release\;C:\Users\hog\Documents\Visual Studio 2010\Projects\ArdupilotMega\ArdupilotMega\Lib\</ReferencePath>
|
||||
</PropertyGroup>
|
||||
</Project>
|
@ -5,8 +5,6 @@ Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "ArdupilotMega", "ArdupilotM
|
||||
EndProject
|
||||
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "Updater", "Updater\Updater.csproj", "{E64A1A41-A5B0-458E-8284-BB63705354DA}"
|
||||
EndProject
|
||||
Project("{FAE04EC0-301F-11D3-BF4B-00C04F79EFBC}") = "ArduinoCPP", "..\..\ArduinoCPP\ArduinoCPP.csproj", "{C38A02C5-3179-4047-8DC3-945341008A74}"
|
||||
EndProject
|
||||
Global
|
||||
GlobalSection(SolutionConfigurationPlatforms) = preSolution
|
||||
Debug|Any CPU = Debug|Any CPU
|
||||
@ -43,18 +41,6 @@ Global
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|Win32.ActiveCfg = Release|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|x86.ActiveCfg = Release|x86
|
||||
{E64A1A41-A5B0-458E-8284-BB63705354DA}.Release|x86.Build.0 = Release|x86
|
||||
{C38A02C5-3179-4047-8DC3-945341008A74}.Debug|Any CPU.ActiveCfg = Debug|x86
|
||||
{C38A02C5-3179-4047-8DC3-945341008A74}.Debug|Mixed Platforms.ActiveCfg = Debug|x86
|
||||
{C38A02C5-3179-4047-8DC3-945341008A74}.Debug|Mixed Platforms.Build.0 = Debug|x86
|
||||
{C38A02C5-3179-4047-8DC3-945341008A74}.Debug|Win32.ActiveCfg = Debug|x86
|
||||
{C38A02C5-3179-4047-8DC3-945341008A74}.Debug|x86.ActiveCfg = Debug|x86
|
||||
{C38A02C5-3179-4047-8DC3-945341008A74}.Debug|x86.Build.0 = Debug|x86
|
||||
{C38A02C5-3179-4047-8DC3-945341008A74}.Release|Any CPU.ActiveCfg = Release|x86
|
||||
{C38A02C5-3179-4047-8DC3-945341008A74}.Release|Mixed Platforms.ActiveCfg = Release|x86
|
||||
{C38A02C5-3179-4047-8DC3-945341008A74}.Release|Mixed Platforms.Build.0 = Release|x86
|
||||
{C38A02C5-3179-4047-8DC3-945341008A74}.Release|Win32.ActiveCfg = Release|x86
|
||||
{C38A02C5-3179-4047-8DC3-945341008A74}.Release|x86.ActiveCfg = Release|x86
|
||||
{C38A02C5-3179-4047-8DC3-945341008A74}.Release|x86.Build.0 = Release|x86
|
||||
EndGlobalSection
|
||||
GlobalSection(SolutionProperties) = preSolution
|
||||
HideSolutionNode = FALSE
|
||||
|
174
Tools/ArdupilotMegaPlanner/Camera.Designer.cs
generated
174
Tools/ArdupilotMegaPlanner/Camera.Designer.cs
generated
@ -28,6 +28,7 @@
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Camera));
|
||||
this.num_agl = new System.Windows.Forms.NumericUpDown();
|
||||
this.label2 = new System.Windows.Forms.Label();
|
||||
this.num_focallength = new System.Windows.Forms.NumericUpDown();
|
||||
@ -74,15 +75,13 @@
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.num_agl.Location = new System.Drawing.Point(12, 38);
|
||||
resources.ApplyResources(this.num_agl, "num_agl");
|
||||
this.num_agl.Maximum = new decimal(new int[] {
|
||||
10000,
|
||||
0,
|
||||
0,
|
||||
0});
|
||||
this.num_agl.Name = "num_agl";
|
||||
this.num_agl.Size = new System.Drawing.Size(64, 20);
|
||||
this.num_agl.TabIndex = 1;
|
||||
this.num_agl.Value = new decimal(new int[] {
|
||||
200,
|
||||
0,
|
||||
@ -92,12 +91,8 @@
|
||||
//
|
||||
// label2
|
||||
//
|
||||
this.label2.AutoSize = true;
|
||||
this.label2.Location = new System.Drawing.Point(82, 40);
|
||||
resources.ApplyResources(this.label2, "label2");
|
||||
this.label2.Name = "label2";
|
||||
this.label2.Size = new System.Drawing.Size(72, 13);
|
||||
this.label2.TabIndex = 4;
|
||||
this.label2.Text = "Height m (agl)";
|
||||
//
|
||||
// num_focallength
|
||||
//
|
||||
@ -107,7 +102,7 @@
|
||||
0,
|
||||
0,
|
||||
65536});
|
||||
this.num_focallength.Location = new System.Drawing.Point(12, 64);
|
||||
resources.ApplyResources(this.num_focallength, "num_focallength");
|
||||
this.num_focallength.Maximum = new decimal(new int[] {
|
||||
180,
|
||||
0,
|
||||
@ -119,8 +114,6 @@
|
||||
0,
|
||||
0});
|
||||
this.num_focallength.Name = "num_focallength";
|
||||
this.num_focallength.Size = new System.Drawing.Size(64, 20);
|
||||
this.num_focallength.TabIndex = 6;
|
||||
this.num_focallength.Value = new decimal(new int[] {
|
||||
5,
|
||||
0,
|
||||
@ -130,181 +123,113 @@
|
||||
//
|
||||
// TXT_fovH
|
||||
//
|
||||
this.TXT_fovH.Location = new System.Drawing.Point(361, 12);
|
||||
resources.ApplyResources(this.TXT_fovH, "TXT_fovH");
|
||||
this.TXT_fovH.Name = "TXT_fovH";
|
||||
this.TXT_fovH.Size = new System.Drawing.Size(100, 20);
|
||||
this.TXT_fovH.TabIndex = 10;
|
||||
//
|
||||
// TXT_fovV
|
||||
//
|
||||
this.TXT_fovV.Location = new System.Drawing.Point(361, 39);
|
||||
resources.ApplyResources(this.TXT_fovV, "TXT_fovV");
|
||||
this.TXT_fovV.Name = "TXT_fovV";
|
||||
this.TXT_fovV.Size = new System.Drawing.Size(100, 20);
|
||||
this.TXT_fovV.TabIndex = 11;
|
||||
//
|
||||
// TXT_fovAV
|
||||
//
|
||||
this.TXT_fovAV.Location = new System.Drawing.Point(361, 92);
|
||||
resources.ApplyResources(this.TXT_fovAV, "TXT_fovAV");
|
||||
this.TXT_fovAV.Name = "TXT_fovAV";
|
||||
this.TXT_fovAV.Size = new System.Drawing.Size(100, 20);
|
||||
this.TXT_fovAV.TabIndex = 14;
|
||||
//
|
||||
// TXT_fovAH
|
||||
//
|
||||
this.TXT_fovAH.Location = new System.Drawing.Point(361, 65);
|
||||
resources.ApplyResources(this.TXT_fovAH, "TXT_fovAH");
|
||||
this.TXT_fovAH.Name = "TXT_fovAH";
|
||||
this.TXT_fovAH.Size = new System.Drawing.Size(100, 20);
|
||||
this.TXT_fovAH.TabIndex = 13;
|
||||
//
|
||||
// TXT_cmpixel
|
||||
//
|
||||
this.TXT_cmpixel.Location = new System.Drawing.Point(361, 118);
|
||||
resources.ApplyResources(this.TXT_cmpixel, "TXT_cmpixel");
|
||||
this.TXT_cmpixel.Name = "TXT_cmpixel";
|
||||
this.TXT_cmpixel.Size = new System.Drawing.Size(100, 20);
|
||||
this.TXT_cmpixel.TabIndex = 16;
|
||||
//
|
||||
// TXT_imgwidth
|
||||
//
|
||||
this.TXT_imgwidth.Location = new System.Drawing.Point(12, 90);
|
||||
resources.ApplyResources(this.TXT_imgwidth, "TXT_imgwidth");
|
||||
this.TXT_imgwidth.Name = "TXT_imgwidth";
|
||||
this.TXT_imgwidth.Size = new System.Drawing.Size(64, 20);
|
||||
this.TXT_imgwidth.TabIndex = 17;
|
||||
this.TXT_imgwidth.Text = "4608";
|
||||
this.TXT_imgwidth.TextChanged += new System.EventHandler(this.TXT_imgwidth_TextChanged);
|
||||
//
|
||||
// TXT_imgheight
|
||||
//
|
||||
this.TXT_imgheight.Location = new System.Drawing.Point(12, 116);
|
||||
resources.ApplyResources(this.TXT_imgheight, "TXT_imgheight");
|
||||
this.TXT_imgheight.Name = "TXT_imgheight";
|
||||
this.TXT_imgheight.Size = new System.Drawing.Size(64, 20);
|
||||
this.TXT_imgheight.TabIndex = 18;
|
||||
this.TXT_imgheight.Text = "3456";
|
||||
this.TXT_imgheight.TextChanged += new System.EventHandler(this.TXT_imgheight_TextChanged);
|
||||
//
|
||||
// label1
|
||||
//
|
||||
this.label1.AutoSize = true;
|
||||
this.label1.Location = new System.Drawing.Point(82, 71);
|
||||
resources.ApplyResources(this.label1, "label1");
|
||||
this.label1.Name = "label1";
|
||||
this.label1.Size = new System.Drawing.Size(69, 13);
|
||||
this.label1.TabIndex = 19;
|
||||
this.label1.Text = "Focal Length";
|
||||
//
|
||||
// label6
|
||||
//
|
||||
this.label6.AutoSize = true;
|
||||
this.label6.Location = new System.Drawing.Point(298, 19);
|
||||
resources.ApplyResources(this.label6, "label6");
|
||||
this.label6.Name = "label6";
|
||||
this.label6.Size = new System.Drawing.Size(56, 13);
|
||||
this.label6.TabIndex = 21;
|
||||
this.label6.Text = "FOV H (m)";
|
||||
//
|
||||
// label7
|
||||
//
|
||||
this.label7.AutoSize = true;
|
||||
this.label7.Location = new System.Drawing.Point(299, 72);
|
||||
resources.ApplyResources(this.label7, "label7");
|
||||
this.label7.Name = "label7";
|
||||
this.label7.Size = new System.Drawing.Size(45, 13);
|
||||
this.label7.TabIndex = 22;
|
||||
this.label7.Text = "Angle H";
|
||||
//
|
||||
// label8
|
||||
//
|
||||
this.label8.AutoSize = true;
|
||||
this.label8.Location = new System.Drawing.Point(300, 99);
|
||||
resources.ApplyResources(this.label8, "label8");
|
||||
this.label8.Name = "label8";
|
||||
this.label8.Size = new System.Drawing.Size(44, 13);
|
||||
this.label8.TabIndex = 23;
|
||||
this.label8.Text = "Angle V";
|
||||
//
|
||||
// label10
|
||||
//
|
||||
this.label10.AutoSize = true;
|
||||
this.label10.Location = new System.Drawing.Point(299, 46);
|
||||
resources.ApplyResources(this.label10, "label10");
|
||||
this.label10.Name = "label10";
|
||||
this.label10.Size = new System.Drawing.Size(55, 13);
|
||||
this.label10.TabIndex = 25;
|
||||
this.label10.Text = "FOV V (m)";
|
||||
//
|
||||
// label12
|
||||
//
|
||||
this.label12.AutoSize = true;
|
||||
this.label12.Location = new System.Drawing.Point(299, 125);
|
||||
resources.ApplyResources(this.label12, "label12");
|
||||
this.label12.Name = "label12";
|
||||
this.label12.Size = new System.Drawing.Size(50, 13);
|
||||
this.label12.TabIndex = 27;
|
||||
this.label12.Text = "CM/Pixel";
|
||||
//
|
||||
// label13
|
||||
//
|
||||
this.label13.AutoSize = true;
|
||||
this.label13.Location = new System.Drawing.Point(82, 93);
|
||||
resources.ApplyResources(this.label13, "label13");
|
||||
this.label13.Name = "label13";
|
||||
this.label13.Size = new System.Drawing.Size(60, 13);
|
||||
this.label13.TabIndex = 28;
|
||||
this.label13.Text = "Pixel Width";
|
||||
//
|
||||
// label14
|
||||
//
|
||||
this.label14.AutoSize = true;
|
||||
this.label14.Location = new System.Drawing.Point(82, 119);
|
||||
resources.ApplyResources(this.label14, "label14");
|
||||
this.label14.Name = "label14";
|
||||
this.label14.Size = new System.Drawing.Size(63, 13);
|
||||
this.label14.TabIndex = 29;
|
||||
this.label14.Text = "Pixel Height";
|
||||
//
|
||||
// label3
|
||||
//
|
||||
this.label3.AutoSize = true;
|
||||
this.label3.Location = new System.Drawing.Point(82, 171);
|
||||
resources.ApplyResources(this.label3, "label3");
|
||||
this.label3.Name = "label3";
|
||||
this.label3.Size = new System.Drawing.Size(74, 13);
|
||||
this.label3.TabIndex = 33;
|
||||
this.label3.Text = "Sensor Height";
|
||||
//
|
||||
// label4
|
||||
//
|
||||
this.label4.AutoSize = true;
|
||||
this.label4.Location = new System.Drawing.Point(82, 145);
|
||||
resources.ApplyResources(this.label4, "label4");
|
||||
this.label4.Name = "label4";
|
||||
this.label4.Size = new System.Drawing.Size(71, 13);
|
||||
this.label4.TabIndex = 32;
|
||||
this.label4.Text = "Sensor Width";
|
||||
//
|
||||
// TXT_sensheight
|
||||
//
|
||||
this.TXT_sensheight.Location = new System.Drawing.Point(12, 168);
|
||||
resources.ApplyResources(this.TXT_sensheight, "TXT_sensheight");
|
||||
this.TXT_sensheight.Name = "TXT_sensheight";
|
||||
this.TXT_sensheight.Size = new System.Drawing.Size(64, 20);
|
||||
this.TXT_sensheight.TabIndex = 31;
|
||||
this.TXT_sensheight.Text = "4.62";
|
||||
this.TXT_sensheight.TextChanged += new System.EventHandler(this.TXT_sensheight_TextChanged);
|
||||
//
|
||||
// TXT_senswidth
|
||||
//
|
||||
this.TXT_senswidth.Location = new System.Drawing.Point(12, 142);
|
||||
resources.ApplyResources(this.TXT_senswidth, "TXT_senswidth");
|
||||
this.TXT_senswidth.Name = "TXT_senswidth";
|
||||
this.TXT_senswidth.Size = new System.Drawing.Size(64, 20);
|
||||
this.TXT_senswidth.TabIndex = 30;
|
||||
this.TXT_senswidth.Text = "6.16";
|
||||
this.TXT_senswidth.TextChanged += new System.EventHandler(this.TXT_senswidth_TextChanged);
|
||||
//
|
||||
// label5
|
||||
//
|
||||
this.label5.AutoSize = true;
|
||||
this.label5.Location = new System.Drawing.Point(82, 201);
|
||||
resources.ApplyResources(this.label5, "label5");
|
||||
this.label5.Name = "label5";
|
||||
this.label5.Size = new System.Drawing.Size(44, 13);
|
||||
this.label5.TabIndex = 35;
|
||||
this.label5.Text = "Overlap";
|
||||
//
|
||||
// num_overlap
|
||||
//
|
||||
this.num_overlap.DecimalPlaces = 1;
|
||||
this.num_overlap.Location = new System.Drawing.Point(12, 194);
|
||||
resources.ApplyResources(this.num_overlap, "num_overlap");
|
||||
this.num_overlap.Name = "num_overlap";
|
||||
this.num_overlap.Size = new System.Drawing.Size(64, 20);
|
||||
this.num_overlap.TabIndex = 34;
|
||||
this.num_overlap.Value = new decimal(new int[] {
|
||||
60,
|
||||
0,
|
||||
@ -314,20 +239,14 @@
|
||||
//
|
||||
// label15
|
||||
//
|
||||
this.label15.AutoSize = true;
|
||||
this.label15.Location = new System.Drawing.Point(82, 227);
|
||||
resources.ApplyResources(this.label15, "label15");
|
||||
this.label15.Name = "label15";
|
||||
this.label15.Size = new System.Drawing.Size(42, 13);
|
||||
this.label15.TabIndex = 37;
|
||||
this.label15.Text = "Sidelap";
|
||||
//
|
||||
// num_sidelap
|
||||
//
|
||||
this.num_sidelap.DecimalPlaces = 1;
|
||||
this.num_sidelap.Location = new System.Drawing.Point(12, 220);
|
||||
resources.ApplyResources(this.num_sidelap, "num_sidelap");
|
||||
this.num_sidelap.Name = "num_sidelap";
|
||||
this.num_sidelap.Size = new System.Drawing.Size(64, 20);
|
||||
this.num_sidelap.TabIndex = 36;
|
||||
this.num_sidelap.Value = new decimal(new int[] {
|
||||
30,
|
||||
0,
|
||||
@ -337,73 +256,51 @@
|
||||
//
|
||||
// CHK_camdirection
|
||||
//
|
||||
this.CHK_camdirection.AutoSize = true;
|
||||
resources.ApplyResources(this.CHK_camdirection, "CHK_camdirection");
|
||||
this.CHK_camdirection.Checked = true;
|
||||
this.CHK_camdirection.CheckState = System.Windows.Forms.CheckState.Checked;
|
||||
this.CHK_camdirection.Location = new System.Drawing.Point(13, 247);
|
||||
this.CHK_camdirection.Name = "CHK_camdirection";
|
||||
this.CHK_camdirection.Size = new System.Drawing.Size(150, 17);
|
||||
this.CHK_camdirection.TabIndex = 38;
|
||||
this.CHK_camdirection.Text = "Camera top facing forward";
|
||||
this.CHK_camdirection.UseVisualStyleBackColor = true;
|
||||
this.CHK_camdirection.CheckedChanged += new System.EventHandler(this.CHK_camdirection_CheckedChanged);
|
||||
//
|
||||
// label9
|
||||
//
|
||||
this.label9.AutoSize = true;
|
||||
this.label9.Location = new System.Drawing.Point(261, 198);
|
||||
resources.ApplyResources(this.label9, "label9");
|
||||
this.label9.Name = "label9";
|
||||
this.label9.Size = new System.Drawing.Size(86, 13);
|
||||
this.label9.TabIndex = 42;
|
||||
this.label9.Text = "Across Flight line";
|
||||
//
|
||||
// label11
|
||||
//
|
||||
this.label11.AutoSize = true;
|
||||
this.label11.Location = new System.Drawing.Point(261, 171);
|
||||
resources.ApplyResources(this.label11, "label11");
|
||||
this.label11.Name = "label11";
|
||||
this.label11.Size = new System.Drawing.Size(94, 13);
|
||||
this.label11.TabIndex = 41;
|
||||
this.label11.Text = "Flight line distance";
|
||||
//
|
||||
// TXT_distacflphotos
|
||||
//
|
||||
this.TXT_distacflphotos.Location = new System.Drawing.Point(361, 195);
|
||||
resources.ApplyResources(this.TXT_distacflphotos, "TXT_distacflphotos");
|
||||
this.TXT_distacflphotos.Name = "TXT_distacflphotos";
|
||||
this.TXT_distacflphotos.Size = new System.Drawing.Size(100, 20);
|
||||
this.TXT_distacflphotos.TabIndex = 40;
|
||||
//
|
||||
// TXT_distflphotos
|
||||
//
|
||||
this.TXT_distflphotos.Location = new System.Drawing.Point(361, 168);
|
||||
resources.ApplyResources(this.TXT_distflphotos, "TXT_distflphotos");
|
||||
this.TXT_distflphotos.Name = "TXT_distflphotos";
|
||||
this.TXT_distflphotos.Size = new System.Drawing.Size(100, 20);
|
||||
this.TXT_distflphotos.TabIndex = 39;
|
||||
//
|
||||
// CMB_camera
|
||||
//
|
||||
this.CMB_camera.FormattingEnabled = true;
|
||||
this.CMB_camera.Location = new System.Drawing.Point(13, 13);
|
||||
resources.ApplyResources(this.CMB_camera, "CMB_camera");
|
||||
this.CMB_camera.Name = "CMB_camera";
|
||||
this.CMB_camera.Size = new System.Drawing.Size(143, 21);
|
||||
this.CMB_camera.TabIndex = 43;
|
||||
this.CMB_camera.SelectedIndexChanged += new System.EventHandler(this.CMB_camera_SelectedIndexChanged);
|
||||
//
|
||||
// BUT_save
|
||||
//
|
||||
this.BUT_save.Location = new System.Drawing.Point(163, 10);
|
||||
resources.ApplyResources(this.BUT_save, "BUT_save");
|
||||
this.BUT_save.Name = "BUT_save";
|
||||
this.BUT_save.Size = new System.Drawing.Size(75, 23);
|
||||
this.BUT_save.TabIndex = 44;
|
||||
this.BUT_save.Text = "Save";
|
||||
this.BUT_save.UseVisualStyleBackColor = true;
|
||||
this.BUT_save.Click += new System.EventHandler(this.BUT_save_Click);
|
||||
//
|
||||
// Camera
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
resources.ApplyResources(this, "$this");
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.ClientSize = new System.Drawing.Size(473, 275);
|
||||
this.Controls.Add(this.BUT_save);
|
||||
this.Controls.Add(this.CMB_camera);
|
||||
this.Controls.Add(this.label9);
|
||||
@ -438,7 +335,6 @@
|
||||
this.Controls.Add(this.label2);
|
||||
this.Controls.Add(this.num_agl);
|
||||
this.Name = "Camera";
|
||||
this.Text = "Camera";
|
||||
this.Load += new System.EventHandler(this.Camera_Load);
|
||||
((System.ComponentModel.ISupportInitialize)(this.num_agl)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.num_focallength)).EndInit();
|
||||
|
@ -117,4 +117,828 @@
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<data name="num_agl.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>12, 38</value>
|
||||
</data>
|
||||
<data name="num_agl.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>64, 20</value>
|
||||
</data>
|
||||
<assembly alias="mscorlib" name="mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="num_agl.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name=">>num_agl.Name" xml:space="preserve">
|
||||
<value>num_agl</value>
|
||||
</data>
|
||||
<data name=">>num_agl.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>num_agl.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>num_agl.ZOrder" xml:space="preserve">
|
||||
<value>32</value>
|
||||
</data>
|
||||
<data name="label2.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label2.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>82, 40</value>
|
||||
</data>
|
||||
<data name="label2.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>72, 13</value>
|
||||
</data>
|
||||
<data name="label2.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>4</value>
|
||||
</data>
|
||||
<data name="label2.Text" xml:space="preserve">
|
||||
<value>Height m (agl)</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>$this</value>
|
||||
</data>
|
||||
<data name=">>label2.ZOrder" xml:space="preserve">
|
||||
<value>31</value>
|
||||
</data>
|
||||
<data name="num_focallength.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>12, 64</value>
|
||||
</data>
|
||||
<data name="num_focallength.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>64, 20</value>
|
||||
</data>
|
||||
<data name="num_focallength.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>6</value>
|
||||
</data>
|
||||
<data name=">>num_focallength.Name" xml:space="preserve">
|
||||
<value>num_focallength</value>
|
||||
</data>
|
||||
<data name=">>num_focallength.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>num_focallength.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>num_focallength.ZOrder" xml:space="preserve">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="TXT_fovH.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>361, 12</value>
|
||||
</data>
|
||||
<data name="TXT_fovH.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>100, 20</value>
|
||||
</data>
|
||||
<data name="TXT_fovH.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>10</value>
|
||||
</data>
|
||||
<data name=">>TXT_fovH.Name" xml:space="preserve">
|
||||
<value>TXT_fovH</value>
|
||||
</data>
|
||||
<data name=">>TXT_fovH.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_fovH.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_fovH.ZOrder" xml:space="preserve">
|
||||
<value>29</value>
|
||||
</data>
|
||||
<data name="TXT_fovV.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>361, 39</value>
|
||||
</data>
|
||||
<data name="TXT_fovV.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>100, 20</value>
|
||||
</data>
|
||||
<data name="TXT_fovV.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>11</value>
|
||||
</data>
|
||||
<data name=">>TXT_fovV.Name" xml:space="preserve">
|
||||
<value>TXT_fovV</value>
|
||||
</data>
|
||||
<data name=">>TXT_fovV.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_fovV.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_fovV.ZOrder" xml:space="preserve">
|
||||
<value>28</value>
|
||||
</data>
|
||||
<data name="TXT_fovAV.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>361, 92</value>
|
||||
</data>
|
||||
<data name="TXT_fovAV.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>100, 20</value>
|
||||
</data>
|
||||
<data name="TXT_fovAV.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>14</value>
|
||||
</data>
|
||||
<data name=">>TXT_fovAV.Name" xml:space="preserve">
|
||||
<value>TXT_fovAV</value>
|
||||
</data>
|
||||
<data name=">>TXT_fovAV.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_fovAV.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_fovAV.ZOrder" xml:space="preserve">
|
||||
<value>26</value>
|
||||
</data>
|
||||
<data name="TXT_fovAH.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>361, 65</value>
|
||||
</data>
|
||||
<data name="TXT_fovAH.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>100, 20</value>
|
||||
</data>
|
||||
<data name="TXT_fovAH.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>13</value>
|
||||
</data>
|
||||
<data name=">>TXT_fovAH.Name" xml:space="preserve">
|
||||
<value>TXT_fovAH</value>
|
||||
</data>
|
||||
<data name=">>TXT_fovAH.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_fovAH.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_fovAH.ZOrder" xml:space="preserve">
|
||||
<value>27</value>
|
||||
</data>
|
||||
<data name="TXT_cmpixel.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>361, 118</value>
|
||||
</data>
|
||||
<data name="TXT_cmpixel.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>100, 20</value>
|
||||
</data>
|
||||
<data name="TXT_cmpixel.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>16</value>
|
||||
</data>
|
||||
<data name=">>TXT_cmpixel.Name" xml:space="preserve">
|
||||
<value>TXT_cmpixel</value>
|
||||
</data>
|
||||
<data name=">>TXT_cmpixel.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_cmpixel.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_cmpixel.ZOrder" xml:space="preserve">
|
||||
<value>25</value>
|
||||
</data>
|
||||
<data name="TXT_imgwidth.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>12, 90</value>
|
||||
</data>
|
||||
<data name="TXT_imgwidth.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>64, 20</value>
|
||||
</data>
|
||||
<data name="TXT_imgwidth.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>17</value>
|
||||
</data>
|
||||
<data name="TXT_imgwidth.Text" xml:space="preserve">
|
||||
<value>4608</value>
|
||||
</data>
|
||||
<data name=">>TXT_imgwidth.Name" xml:space="preserve">
|
||||
<value>TXT_imgwidth</value>
|
||||
</data>
|
||||
<data name=">>TXT_imgwidth.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_imgwidth.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_imgwidth.ZOrder" xml:space="preserve">
|
||||
<value>24</value>
|
||||
</data>
|
||||
<data name="TXT_imgheight.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>12, 116</value>
|
||||
</data>
|
||||
<data name="TXT_imgheight.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>64, 20</value>
|
||||
</data>
|
||||
<data name="TXT_imgheight.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>18</value>
|
||||
</data>
|
||||
<data name="TXT_imgheight.Text" xml:space="preserve">
|
||||
<value>3456</value>
|
||||
</data>
|
||||
<data name=">>TXT_imgheight.Name" xml:space="preserve">
|
||||
<value>TXT_imgheight</value>
|
||||
</data>
|
||||
<data name=">>TXT_imgheight.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_imgheight.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_imgheight.ZOrder" xml:space="preserve">
|
||||
<value>23</value>
|
||||
</data>
|
||||
<data name="label1.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label1.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>82, 71</value>
|
||||
</data>
|
||||
<data name="label1.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>69, 13</value>
|
||||
</data>
|
||||
<data name="label1.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>19</value>
|
||||
</data>
|
||||
<data name="label1.Text" xml:space="preserve">
|
||||
<value>Focal Length</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>$this</value>
|
||||
</data>
|
||||
<data name=">>label1.ZOrder" xml:space="preserve">
|
||||
<value>22</value>
|
||||
</data>
|
||||
<data name="label6.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label6.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>298, 19</value>
|
||||
</data>
|
||||
<data name="label6.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>56, 13</value>
|
||||
</data>
|
||||
<data name="label6.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>21</value>
|
||||
</data>
|
||||
<data name="label6.Text" xml:space="preserve">
|
||||
<value>FOV H (m)</value>
|
||||
</data>
|
||||
<data name=">>label6.Name" xml:space="preserve">
|
||||
<value>label6</value>
|
||||
</data>
|
||||
<data name=">>label6.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=">>label6.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label6.ZOrder" xml:space="preserve">
|
||||
<value>21</value>
|
||||
</data>
|
||||
<data name="label7.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label7.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>299, 72</value>
|
||||
</data>
|
||||
<data name="label7.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>45, 13</value>
|
||||
</data>
|
||||
<data name="label7.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>22</value>
|
||||
</data>
|
||||
<data name="label7.Text" xml:space="preserve">
|
||||
<value>Angle H</value>
|
||||
</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>$this</value>
|
||||
</data>
|
||||
<data name=">>label7.ZOrder" xml:space="preserve">
|
||||
<value>20</value>
|
||||
</data>
|
||||
<data name="label8.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label8.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>300, 99</value>
|
||||
</data>
|
||||
<data name="label8.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>44, 13</value>
|
||||
</data>
|
||||
<data name="label8.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>23</value>
|
||||
</data>
|
||||
<data name="label8.Text" xml:space="preserve">
|
||||
<value>Angle V</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>$this</value>
|
||||
</data>
|
||||
<data name=">>label8.ZOrder" xml:space="preserve">
|
||||
<value>19</value>
|
||||
</data>
|
||||
<data name="label10.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label10.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>299, 46</value>
|
||||
</data>
|
||||
<data name="label10.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>55, 13</value>
|
||||
</data>
|
||||
<data name="label10.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>25</value>
|
||||
</data>
|
||||
<data name="label10.Text" xml:space="preserve">
|
||||
<value>FOV V (m)</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>$this</value>
|
||||
</data>
|
||||
<data name=">>label10.ZOrder" xml:space="preserve">
|
||||
<value>18</value>
|
||||
</data>
|
||||
<data name="label12.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label12.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>299, 125</value>
|
||||
</data>
|
||||
<data name="label12.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>50, 13</value>
|
||||
</data>
|
||||
<data name="label12.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>27</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>CM/Pixel</value>
|
||||
</data>
|
||||
<data name=">>label12.Name" xml:space="preserve">
|
||||
<value>label12</value>
|
||||
</data>
|
||||
<data name=">>label12.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=">>label12.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label12.ZOrder" xml:space="preserve">
|
||||
<value>17</value>
|
||||
</data>
|
||||
<data name="label13.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label13.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>82, 93</value>
|
||||
</data>
|
||||
<data name="label13.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>60, 13</value>
|
||||
</data>
|
||||
<data name="label13.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>28</value>
|
||||
</data>
|
||||
<data name="label13.Text" xml:space="preserve">
|
||||
<value>Pixel Width</value>
|
||||
</data>
|
||||
<data name=">>label13.Name" xml:space="preserve">
|
||||
<value>label13</value>
|
||||
</data>
|
||||
<data name=">>label13.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=">>label13.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label13.ZOrder" xml:space="preserve">
|
||||
<value>16</value>
|
||||
</data>
|
||||
<data name="label14.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label14.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>82, 119</value>
|
||||
</data>
|
||||
<data name="label14.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>63, 13</value>
|
||||
</data>
|
||||
<data name="label14.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>29</value>
|
||||
</data>
|
||||
<data name="label14.Text" xml:space="preserve">
|
||||
<value>Pixel Height</value>
|
||||
</data>
|
||||
<data name=">>label14.Name" xml:space="preserve">
|
||||
<value>label14</value>
|
||||
</data>
|
||||
<data name=">>label14.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=">>label14.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label14.ZOrder" xml:space="preserve">
|
||||
<value>15</value>
|
||||
</data>
|
||||
<data name="label3.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label3.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>82, 171</value>
|
||||
</data>
|
||||
<data name="label3.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>74, 13</value>
|
||||
</data>
|
||||
<data name="label3.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>33</value>
|
||||
</data>
|
||||
<data name="label3.Text" xml:space="preserve">
|
||||
<value>Sensor Height</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>$this</value>
|
||||
</data>
|
||||
<data name=">>label3.ZOrder" xml:space="preserve">
|
||||
<value>11</value>
|
||||
</data>
|
||||
<data name="label4.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label4.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>82, 145</value>
|
||||
</data>
|
||||
<data name="label4.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>71, 13</value>
|
||||
</data>
|
||||
<data name="label4.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>32</value>
|
||||
</data>
|
||||
<data name="label4.Text" xml:space="preserve">
|
||||
<value>Sensor Width</value>
|
||||
</data>
|
||||
<data name=">>label4.Name" xml:space="preserve">
|
||||
<value>label4</value>
|
||||
</data>
|
||||
<data name=">>label4.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=">>label4.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label4.ZOrder" xml:space="preserve">
|
||||
<value>12</value>
|
||||
</data>
|
||||
<data name="TXT_sensheight.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>12, 168</value>
|
||||
</data>
|
||||
<data name="TXT_sensheight.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>64, 20</value>
|
||||
</data>
|
||||
<data name="TXT_sensheight.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>31</value>
|
||||
</data>
|
||||
<data name="TXT_sensheight.Text" xml:space="preserve">
|
||||
<value>4.62</value>
|
||||
</data>
|
||||
<data name=">>TXT_sensheight.Name" xml:space="preserve">
|
||||
<value>TXT_sensheight</value>
|
||||
</data>
|
||||
<data name=">>TXT_sensheight.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_sensheight.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_sensheight.ZOrder" xml:space="preserve">
|
||||
<value>13</value>
|
||||
</data>
|
||||
<data name="TXT_senswidth.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>12, 142</value>
|
||||
</data>
|
||||
<data name="TXT_senswidth.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>64, 20</value>
|
||||
</data>
|
||||
<data name="TXT_senswidth.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>30</value>
|
||||
</data>
|
||||
<data name="TXT_senswidth.Text" xml:space="preserve">
|
||||
<value>6.16</value>
|
||||
</data>
|
||||
<data name=">>TXT_senswidth.Name" xml:space="preserve">
|
||||
<value>TXT_senswidth</value>
|
||||
</data>
|
||||
<data name=">>TXT_senswidth.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_senswidth.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_senswidth.ZOrder" xml:space="preserve">
|
||||
<value>14</value>
|
||||
</data>
|
||||
<data name="label5.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label5.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>82, 201</value>
|
||||
</data>
|
||||
<data name="label5.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>44, 13</value>
|
||||
</data>
|
||||
<data name="label5.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>35</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>Overlap</value>
|
||||
</data>
|
||||
<data name=">>label5.Name" xml:space="preserve">
|
||||
<value>label5</value>
|
||||
</data>
|
||||
<data name=">>label5.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=">>label5.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label5.ZOrder" xml:space="preserve">
|
||||
<value>9</value>
|
||||
</data>
|
||||
<data name="num_overlap.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>12, 194</value>
|
||||
</data>
|
||||
<data name="num_overlap.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>64, 20</value>
|
||||
</data>
|
||||
<data name="num_overlap.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>34</value>
|
||||
</data>
|
||||
<data name=">>num_overlap.Name" xml:space="preserve">
|
||||
<value>num_overlap</value>
|
||||
</data>
|
||||
<data name=">>num_overlap.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>num_overlap.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>num_overlap.ZOrder" xml:space="preserve">
|
||||
<value>10</value>
|
||||
</data>
|
||||
<data name="label15.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label15.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>82, 227</value>
|
||||
</data>
|
||||
<data name="label15.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>42, 13</value>
|
||||
</data>
|
||||
<data name="label15.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>37</value>
|
||||
</data>
|
||||
<data name="label15.Text" xml:space="preserve">
|
||||
<value>Sidelap</value>
|
||||
</data>
|
||||
<data name=">>label15.Name" xml:space="preserve">
|
||||
<value>label15</value>
|
||||
</data>
|
||||
<data name=">>label15.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=">>label15.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>label15.ZOrder" xml:space="preserve">
|
||||
<value>7</value>
|
||||
</data>
|
||||
<data name="num_sidelap.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>12, 220</value>
|
||||
</data>
|
||||
<data name="num_sidelap.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>64, 20</value>
|
||||
</data>
|
||||
<data name="num_sidelap.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>36</value>
|
||||
</data>
|
||||
<data name=">>num_sidelap.Name" xml:space="preserve">
|
||||
<value>num_sidelap</value>
|
||||
</data>
|
||||
<data name=">>num_sidelap.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>num_sidelap.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>num_sidelap.ZOrder" xml:space="preserve">
|
||||
<value>8</value>
|
||||
</data>
|
||||
<data name="CHK_camdirection.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="CHK_camdirection.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>13, 247</value>
|
||||
</data>
|
||||
<data name="CHK_camdirection.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>150, 17</value>
|
||||
</data>
|
||||
<data name="CHK_camdirection.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>38</value>
|
||||
</data>
|
||||
<data name="CHK_camdirection.Text" xml:space="preserve">
|
||||
<value>Camera top facing forward</value>
|
||||
</data>
|
||||
<data name=">>CHK_camdirection.Name" xml:space="preserve">
|
||||
<value>CHK_camdirection</value>
|
||||
</data>
|
||||
<data name=">>CHK_camdirection.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>CHK_camdirection.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CHK_camdirection.ZOrder" xml:space="preserve">
|
||||
<value>6</value>
|
||||
</data>
|
||||
<data name="label9.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label9.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>261, 198</value>
|
||||
</data>
|
||||
<data name="label9.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>86, 13</value>
|
||||
</data>
|
||||
<data name="label9.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>42</value>
|
||||
</data>
|
||||
<data name="label9.Text" xml:space="preserve">
|
||||
<value>Across Flight line</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>$this</value>
|
||||
</data>
|
||||
<data name=">>label9.ZOrder" xml:space="preserve">
|
||||
<value>2</value>
|
||||
</data>
|
||||
<data name="label11.AutoSize" type="System.Boolean, mscorlib">
|
||||
<value>True</value>
|
||||
</data>
|
||||
<data name="label11.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>261, 171</value>
|
||||
</data>
|
||||
<data name="label11.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>94, 13</value>
|
||||
</data>
|
||||
<data name="label11.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>41</value>
|
||||
</data>
|
||||
<data name="label11.Text" xml:space="preserve">
|
||||
<value>Flight line distance</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>$this</value>
|
||||
</data>
|
||||
<data name=">>label11.ZOrder" xml:space="preserve">
|
||||
<value>3</value>
|
||||
</data>
|
||||
<data name="TXT_distacflphotos.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>361, 195</value>
|
||||
</data>
|
||||
<data name="TXT_distacflphotos.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>100, 20</value>
|
||||
</data>
|
||||
<data name="TXT_distacflphotos.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>40</value>
|
||||
</data>
|
||||
<data name=">>TXT_distacflphotos.Name" xml:space="preserve">
|
||||
<value>TXT_distacflphotos</value>
|
||||
</data>
|
||||
<data name=">>TXT_distacflphotos.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_distacflphotos.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_distacflphotos.ZOrder" xml:space="preserve">
|
||||
<value>4</value>
|
||||
</data>
|
||||
<data name="TXT_distflphotos.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>361, 168</value>
|
||||
</data>
|
||||
<data name="TXT_distflphotos.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>100, 20</value>
|
||||
</data>
|
||||
<data name="TXT_distflphotos.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>39</value>
|
||||
</data>
|
||||
<data name=">>TXT_distflphotos.Name" xml:space="preserve">
|
||||
<value>TXT_distflphotos</value>
|
||||
</data>
|
||||
<data name=">>TXT_distflphotos.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_distflphotos.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>TXT_distflphotos.ZOrder" xml:space="preserve">
|
||||
<value>5</value>
|
||||
</data>
|
||||
<data name="CMB_camera.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>13, 13</value>
|
||||
</data>
|
||||
<data name="CMB_camera.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>143, 21</value>
|
||||
</data>
|
||||
<data name="CMB_camera.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>43</value>
|
||||
</data>
|
||||
<data name=">>CMB_camera.Name" xml:space="preserve">
|
||||
<value>CMB_camera</value>
|
||||
</data>
|
||||
<data name=">>CMB_camera.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
<data name=">>CMB_camera.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>CMB_camera.ZOrder" xml:space="preserve">
|
||||
<value>1</value>
|
||||
</data>
|
||||
<data name="BUT_save.Location" type="System.Drawing.Point, System.Drawing">
|
||||
<value>163, 10</value>
|
||||
</data>
|
||||
<data name="BUT_save.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>75, 23</value>
|
||||
</data>
|
||||
<data name="BUT_save.TabIndex" type="System.Int32, mscorlib">
|
||||
<value>44</value>
|
||||
</data>
|
||||
<data name="BUT_save.Text" xml:space="preserve">
|
||||
<value>Save</value>
|
||||
</data>
|
||||
<data name=">>BUT_save.Name" xml:space="preserve">
|
||||
<value>BUT_save</value>
|
||||
</data>
|
||||
<data name=">>BUT_save.Type" xml:space="preserve">
|
||||
<value>ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||
</data>
|
||||
<data name=">>BUT_save.Parent" xml:space="preserve">
|
||||
<value>$this</value>
|
||||
</data>
|
||||
<data name=">>BUT_save.ZOrder" xml:space="preserve">
|
||||
<value>0</value>
|
||||
</data>
|
||||
<metadata name="$this.Localizable" type="System.Boolean, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089">
|
||||
<value>True</value>
|
||||
</metadata>
|
||||
<data name="$this.AutoScaleDimensions" type="System.Drawing.SizeF, System.Drawing">
|
||||
<value>6, 13</value>
|
||||
</data>
|
||||
<data name="$this.ClientSize" type="System.Drawing.Size, System.Drawing">
|
||||
<value>473, 275</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>Camera</value>
|
||||
</data>
|
||||
<data name=">>$this.Name" xml:space="preserve">
|
||||
<value>Camera</value>
|
||||
</data>
|
||||
<data name=">>$this.Type" xml:space="preserve">
|
||||
<value>System.Windows.Forms.Form, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</data>
|
||||
</root>
|
@ -12,10 +12,13 @@ using GMap.NET;
|
||||
using GMap.NET.WindowsForms;
|
||||
using GMap.NET.WindowsForms.Markers;
|
||||
|
||||
using System.Security.Cryptography.X509Certificates;
|
||||
|
||||
using System.Net;
|
||||
using System.Net.Sockets;
|
||||
using System.Xml; // config file
|
||||
using System.Runtime.InteropServices; // dll imports
|
||||
using log4net;
|
||||
using ZedGraph; // Graphs
|
||||
using ArdupilotMega;
|
||||
using System.Reflection;
|
||||
@ -118,13 +121,19 @@ namespace ArdupilotMega
|
||||
g.TranslateTransform(LocalPosition.X, LocalPosition.Y);
|
||||
|
||||
int length = 500;
|
||||
|
||||
g.DrawLine(new Pen(Color.Red, 2), 0.0f, 0.0f, (float)Math.Cos((heading - 90) * deg2rad) * length, (float)Math.Sin((heading - 90) * deg2rad) * length);
|
||||
// anti NaN
|
||||
try
|
||||
{
|
||||
g.DrawLine(new Pen(Color.Red, 2), 0.0f, 0.0f, (float)Math.Cos((heading - 90) * deg2rad) * length, (float)Math.Sin((heading - 90) * deg2rad) * length);
|
||||
}
|
||||
catch { }
|
||||
g.DrawLine(new Pen(Color.Green, 2), 0.0f, 0.0f, (float)Math.Cos((nav_bearing - 90) * deg2rad) * length, (float)Math.Sin((nav_bearing - 90) * deg2rad) * length);
|
||||
g.DrawLine(new Pen(Color.Black, 2), 0.0f, 0.0f, (float)Math.Cos((cog - 90) * deg2rad) * length, (float)Math.Sin((cog - 90) * deg2rad) * length);
|
||||
g.DrawLine(new Pen(Color.Orange, 2), 0.0f, 0.0f, (float)Math.Cos((target - 90) * deg2rad) * length, (float)Math.Sin((target - 90) * deg2rad) * length);
|
||||
|
||||
// anti NaN
|
||||
try {
|
||||
g.RotateTransform(heading);
|
||||
} catch{}
|
||||
g.DrawImageUnscaled(global::ArdupilotMega.Properties.Resources.planeicon, global::ArdupilotMega.Properties.Resources.planeicon.Width / -2, global::ArdupilotMega.Properties.Resources.planeicon.Height / -2);
|
||||
|
||||
g.Transform = temp;
|
||||
@ -157,14 +166,21 @@ namespace ArdupilotMega
|
||||
g.TranslateTransform(LocalPosition.X, LocalPosition.Y);
|
||||
|
||||
int length = 500;
|
||||
|
||||
g.DrawLine(new Pen(Color.Red, 2), 0.0f, 0.0f, (float)Math.Cos((heading - 90) * deg2rad) * length, (float)Math.Sin((heading - 90) * deg2rad) * length);
|
||||
// anti NaN
|
||||
try
|
||||
{
|
||||
g.DrawLine(new Pen(Color.Red, 2), 0.0f, 0.0f, (float)Math.Cos((heading - 90) * deg2rad) * length, (float)Math.Sin((heading - 90) * deg2rad) * length);
|
||||
}
|
||||
catch { }
|
||||
//g.DrawLine(new Pen(Color.Green, 2), 0.0f, 0.0f, (float)Math.Cos((nav_bearing - 90) * deg2rad) * length, (float)Math.Sin((nav_bearing - 90) * deg2rad) * length);
|
||||
g.DrawLine(new Pen(Color.Black, 2), 0.0f, 0.0f, (float)Math.Cos((cog - 90) * deg2rad) * length, (float)Math.Sin((cog - 90) * deg2rad) * length);
|
||||
g.DrawLine(new Pen(Color.Orange, 2), 0.0f, 0.0f, (float)Math.Cos((target - 90) * deg2rad) * length, (float)Math.Sin((target - 90) * deg2rad) * length);
|
||||
|
||||
|
||||
g.RotateTransform(heading);
|
||||
// anti NaN
|
||||
try
|
||||
{
|
||||
g.RotateTransform(heading);
|
||||
}
|
||||
catch { }
|
||||
g.DrawImageUnscaled(global::ArdupilotMega.Properties.Resources.quadicon, global::ArdupilotMega.Properties.Resources.quadicon.Width / -2 + 2, global::ArdupilotMega.Properties.Resources.quadicon.Height / -2);
|
||||
|
||||
g.Transform = temp;
|
||||
@ -198,6 +214,13 @@ namespace ArdupilotMega
|
||||
this.Lng = pll.Lng;
|
||||
}
|
||||
|
||||
public PointLatLngAlt(Locationwp locwp)
|
||||
{
|
||||
this.Lat = locwp.lat;
|
||||
this.Lng = locwp.lng;
|
||||
this.Alt = locwp.alt;
|
||||
}
|
||||
|
||||
public PointLatLngAlt(PointLatLngAlt plla)
|
||||
{
|
||||
this.Lat = plla.Lat;
|
||||
@ -254,8 +277,18 @@ namespace ArdupilotMega
|
||||
}
|
||||
}
|
||||
|
||||
class NoCheckCertificatePolicy : ICertificatePolicy
|
||||
{
|
||||
public bool CheckValidationResult(ServicePoint srvPoint, X509Certificate certificate, WebRequest request, int certificateProblem)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
public class Common
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
public enum distances
|
||||
{
|
||||
Meters,
|
||||
@ -299,6 +332,59 @@ namespace ArdupilotMega
|
||||
OF_LOITER = 10
|
||||
}
|
||||
|
||||
public enum ac2ch7modes
|
||||
{
|
||||
CH7_DO_NOTHING = 0,
|
||||
CH7_SET_HOVER = 1,
|
||||
CH7_FLIP = 2,
|
||||
CH7_SIMPLE_MODE = 3,
|
||||
CH7_RTL = 4,
|
||||
CH7_AUTO_TRIM = 5,
|
||||
CH7_ADC_FILTER = 6,
|
||||
CH7_SAVE_WP = 7
|
||||
}
|
||||
|
||||
public enum ac2ch6modes
|
||||
{
|
||||
// CH_6 Tuning
|
||||
// -----------
|
||||
CH6_NONE = 0,
|
||||
// Attitude
|
||||
CH6_STABILIZE_KP = 1,
|
||||
CH6_STABILIZE_KI = 2,
|
||||
CH6_YAW_KP = 3,
|
||||
// Rate
|
||||
CH6_RATE_KP = 4,
|
||||
CH6_RATE_KI = 5,
|
||||
CH6_RATE_KD = 21,
|
||||
CH6_YAW_RATE_KP = 6,
|
||||
// Altitude rate controller
|
||||
CH6_THROTTLE_KP = 7,
|
||||
// Extras
|
||||
CH6_TOP_BOTTOM_RATIO = 8,
|
||||
CH6_RELAY = 9,
|
||||
CH6_TRAVERSE_SPEED = 10,
|
||||
|
||||
CH6_NAV_P = 11,
|
||||
CH6_LOITER_P = 12,
|
||||
CH6_HELI_EXTERNAL_GYRO = 13,
|
||||
|
||||
// altitude controller
|
||||
CH6_THR_HOLD_KP = 14,
|
||||
CH6_Z_GAIN = 15,
|
||||
CH6_DAMP = 16,
|
||||
|
||||
// optical flow controller
|
||||
CH6_OPTFLOW_KP = 17,
|
||||
CH6_OPTFLOW_KI = 18,
|
||||
CH6_OPTFLOW_KD = 19,
|
||||
|
||||
CH6_NAV_I = 20,
|
||||
|
||||
CH6_LOITER_RATE_P = 22
|
||||
}
|
||||
|
||||
|
||||
public static void linearRegression()
|
||||
{
|
||||
double[] values = { 4.8, 4.8, 4.5, 3.9, 4.4, 3.6, 3.6, 2.9, 3.5, 3.0, 2.5, 2.2, 2.6, 2.1, 2.2 };
|
||||
@ -328,9 +414,9 @@ namespace ArdupilotMega
|
||||
double a = v1 / v2;
|
||||
double b = yAvg - a * xAvg;
|
||||
|
||||
Console.WriteLine("y = ax + b");
|
||||
Console.WriteLine("a = {0}, the slope of the trend line.", Math.Round(a, 2));
|
||||
Console.WriteLine("b = {0}, the intercept of the trend line.", Math.Round(b, 2));
|
||||
log.Debug("y = ax + b");
|
||||
log.DebugFormat("a = {0}, the slope of the trend line.", Math.Round(a, 2));
|
||||
log.DebugFormat("b = {0}, the intercept of the trend line.", Math.Round(b, 2));
|
||||
|
||||
//Console.ReadLine();
|
||||
}
|
||||
@ -477,10 +563,15 @@ namespace ArdupilotMega
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
public static bool getFilefromNet(string url,string saveto) {
|
||||
try
|
||||
{
|
||||
// this is for mono to a ssl server
|
||||
ServicePointManager.CertificatePolicy = new NoCheckCertificatePolicy();
|
||||
|
||||
// Create a request using a URL that can receive a post.
|
||||
WebRequest request = WebRequest.Create(url);
|
||||
request.Timeout = 5000;
|
||||
@ -489,8 +580,8 @@ namespace ArdupilotMega
|
||||
// Get the response.
|
||||
WebResponse response = request.GetResponse();
|
||||
// Display the status.
|
||||
Console.WriteLine(((HttpWebResponse)response).StatusDescription);
|
||||
if (((HttpWebResponse)response).StatusDescription != "200")
|
||||
log.Info(((HttpWebResponse)response).StatusDescription);
|
||||
if (((HttpWebResponse)response).StatusCode != HttpStatusCode.OK)
|
||||
return false;
|
||||
// Get the stream containing content returned by the server.
|
||||
Stream dataStream = response.GetResponseStream();
|
||||
@ -500,14 +591,14 @@ namespace ArdupilotMega
|
||||
|
||||
byte[] buf1 = new byte[1024];
|
||||
|
||||
FileStream fs = new FileStream(saveto+".new", FileMode.Create);
|
||||
FileStream fs = new FileStream(saveto + ".new", FileMode.Create);
|
||||
|
||||
DateTime dt = DateTime.Now;
|
||||
|
||||
while (dataStream.CanRead && bytes > 0)
|
||||
{
|
||||
Application.DoEvents();
|
||||
Console.WriteLine(saveto + " " + bytes);
|
||||
log.Info(saveto + " " + bytes);
|
||||
int len = dataStream.Read(buf1, 0, buf1.Length);
|
||||
bytes -= len;
|
||||
fs.Write(buf1, 0, len);
|
||||
@ -522,7 +613,7 @@ namespace ArdupilotMega
|
||||
|
||||
return true;
|
||||
}
|
||||
catch { return false; }
|
||||
catch (Exception ex) { log.Info("getFilefromNet(): " + ex.ToString()); return false; }
|
||||
}
|
||||
|
||||
public static Type getModes()
|
||||
@ -617,7 +708,11 @@ namespace ArdupilotMega
|
||||
|
||||
MainV2.fixtheme(form);
|
||||
|
||||
return form.ShowDialog();
|
||||
DialogResult dialogResult =form.ShowDialog();
|
||||
|
||||
form.Dispose();
|
||||
|
||||
return dialogResult;
|
||||
}
|
||||
|
||||
static void chk_CheckStateChanged(object sender, EventArgs e)
|
||||
@ -667,11 +762,17 @@ namespace ArdupilotMega
|
||||
|
||||
MainV2.fixtheme(form);
|
||||
|
||||
DialogResult dialogResult = form.ShowDialog();
|
||||
DialogResult dialogResult = DialogResult.Cancel;
|
||||
|
||||
dialogResult = form.ShowDialog();
|
||||
|
||||
if (dialogResult == DialogResult.OK)
|
||||
{
|
||||
value = textBox.Text;
|
||||
}
|
||||
|
||||
form.Dispose();
|
||||
|
||||
return dialogResult;
|
||||
}
|
||||
|
||||
|
@ -8,7 +8,13 @@ namespace ArdupilotMega
|
||||
{
|
||||
class SerialPort : System.IO.Ports.SerialPort,ICommsSerial
|
||||
{
|
||||
public new void Open()
|
||||
{
|
||||
if (base.IsOpen)
|
||||
return;
|
||||
|
||||
base.Open();
|
||||
}
|
||||
|
||||
public void toggleDTR()
|
||||
{
|
||||
|
@ -1,16 +1,19 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Reflection;
|
||||
using System.Text;
|
||||
using System.IO.Ports;
|
||||
using System.Threading;
|
||||
using System.Net; // dns, ip address
|
||||
using System.Net.Sockets; // tcplistner
|
||||
using log4net;
|
||||
|
||||
namespace System.IO.Ports
|
||||
{
|
||||
public class TcpSerial : ArdupilotMega.ICommsSerial
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
TcpClient client = new TcpClient();
|
||||
IPEndPoint RemoteIpEndPoint = new IPEndPoint(IPAddress.Any, 0);
|
||||
byte[] rbuffer = new byte[0];
|
||||
@ -73,12 +76,19 @@ namespace System.IO.Ports
|
||||
{
|
||||
if (client.Client.Connected)
|
||||
{
|
||||
Console.WriteLine("tcpserial socket already open");
|
||||
log.Warn("tcpserial socket already open");
|
||||
return;
|
||||
}
|
||||
|
||||
string dest = Port;
|
||||
string host = "127.0.0.1";
|
||||
|
||||
if (ArdupilotMega.MainV2.config["TCP_port"] != null)
|
||||
dest = ArdupilotMega.MainV2.config["TCP_port"].ToString();
|
||||
|
||||
if (ArdupilotMega.MainV2.config["TCP_host"] != null)
|
||||
host = ArdupilotMega.MainV2.config["TCP_host"].ToString();
|
||||
|
||||
if (Windows.Forms.DialogResult.Cancel == ArdupilotMega.Common.InputBox("remote host", "Enter host name/ip (ensure remote end is already started)", ref host))
|
||||
{
|
||||
throw new Exception("Canceled by request");
|
||||
@ -89,6 +99,9 @@ namespace System.IO.Ports
|
||||
}
|
||||
Port = dest;
|
||||
|
||||
ArdupilotMega.MainV2.config["TCP_port"] = Port;
|
||||
ArdupilotMega.MainV2.config["TCP_host"] = host;
|
||||
|
||||
client = new TcpClient(host, int.Parse(Port));
|
||||
|
||||
client.NoDelay = true;
|
||||
@ -186,7 +199,7 @@ namespace System.IO.Ports
|
||||
VerifyConnected();
|
||||
int size = client.Available;
|
||||
byte[] crap = new byte[size];
|
||||
Console.WriteLine("TcpSerial DiscardInBuffer {0}",size);
|
||||
log.InfoFormat("TcpSerial DiscardInBuffer {0}",size);
|
||||
Read(crap, 0, size);
|
||||
}
|
||||
|
||||
|
@ -1,16 +1,15 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Reflection;
|
||||
using System.Text;
|
||||
using System.IO.Ports;
|
||||
using System.Threading;
|
||||
using System.Net; // dns, ip address
|
||||
using System.Net.Sockets; // tcplistner
|
||||
using log4net;
|
||||
using ArdupilotMega.Controls;
|
||||
|
||||
namespace System.IO.Ports
|
||||
{
|
||||
public class UdpSerial : ArdupilotMega.ICommsSerial
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
UdpClient client = new UdpClient();
|
||||
IPEndPoint RemoteIpEndPoint = new IPEndPoint(IPAddress.Any, 0);
|
||||
byte[] rbuffer = new byte[0];
|
||||
@ -61,7 +60,7 @@ namespace System.IO.Ports
|
||||
get { return client.Available + rbuffer.Length - rbufferread; }
|
||||
}
|
||||
|
||||
public bool IsOpen { get { return client.Client.Connected; } }
|
||||
public bool IsOpen { get { if (client.Client == null) return false; return client.Client.Connected; } }
|
||||
|
||||
public bool DtrEnable
|
||||
{
|
||||
@ -73,41 +72,80 @@ namespace System.IO.Ports
|
||||
{
|
||||
if (client.Client.Connected)
|
||||
{
|
||||
Console.WriteLine("udpserial socket already open");
|
||||
log.Info("udpserial socket already open");
|
||||
return;
|
||||
}
|
||||
|
||||
ProgressReporterDialogue frmProgressReporter = new ProgressReporterDialogue
|
||||
{
|
||||
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
|
||||
Text = "Connecting Mavlink UDP"
|
||||
};
|
||||
|
||||
frmProgressReporter.DoWork += frmProgressReporter_DoWork;
|
||||
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Connecting Mavlink UDP");
|
||||
|
||||
ArdupilotMega.MainV2.fixtheme(frmProgressReporter);
|
||||
|
||||
frmProgressReporter.RunBackgroundOperationAsync();
|
||||
|
||||
|
||||
}
|
||||
|
||||
void frmProgressReporter_DoWork(object sender, ArdupilotMega.Controls.ProgressWorkerEventArgs e)
|
||||
{
|
||||
string dest = Port;
|
||||
|
||||
if (ArdupilotMega.MainV2.config["UDP_port"] != null)
|
||||
dest = ArdupilotMega.MainV2.config["UDP_port"].ToString();
|
||||
|
||||
ArdupilotMega.Common.InputBox("Listern Port", "Enter Local port (ensure remote end is already sending)", ref dest);
|
||||
Port = dest;
|
||||
|
||||
ArdupilotMega.MainV2.config["UDP_port"] = Port;
|
||||
|
||||
client = new UdpClient(int.Parse(Port));
|
||||
|
||||
int timeout = 5;
|
||||
while (timeout > 0)
|
||||
{
|
||||
if (BytesToRead > 0)
|
||||
break;
|
||||
System.Threading.Thread.Sleep(1000);
|
||||
timeout--;
|
||||
}
|
||||
if (BytesToRead == 0)
|
||||
return;
|
||||
while (true)
|
||||
{
|
||||
((ProgressReporterDialogue)sender).UpdateProgressAndStatus(-1, "Waiting for UDP");
|
||||
System.Threading.Thread.Sleep(500);
|
||||
|
||||
if (((ProgressReporterDialogue)sender).doWorkArgs.CancelRequested)
|
||||
{
|
||||
((ProgressReporterDialogue)sender).doWorkArgs.CancelAcknowledged = true;
|
||||
try
|
||||
{
|
||||
client.Close();
|
||||
}
|
||||
catch { }
|
||||
return;
|
||||
}
|
||||
|
||||
if (BytesToRead > 0)
|
||||
break;
|
||||
}
|
||||
|
||||
if (BytesToRead == 0)
|
||||
return;
|
||||
|
||||
try
|
||||
{
|
||||
client.Receive(ref RemoteIpEndPoint);
|
||||
Console.WriteLine("NetSerial connecting to {0} : {1}", RemoteIpEndPoint.Address, RemoteIpEndPoint.Port);
|
||||
log.InfoFormat("NetSerial connecting to {0} : {1}", RemoteIpEndPoint.Address, RemoteIpEndPoint.Port);
|
||||
client.Connect(RemoteIpEndPoint);
|
||||
}
|
||||
catch (Exception e) {
|
||||
if (client != null && client.Client.Connected) { client.Close(); }
|
||||
Console.WriteLine(e.ToString());
|
||||
catch (Exception ex)
|
||||
{
|
||||
if (client != null && client.Client.Connected)
|
||||
{
|
||||
client.Close();
|
||||
}
|
||||
log.Info(ex.ToString());
|
||||
System.Windows.Forms.MessageBox.Show("Please check your Firewall settings\nPlease try running this command\n1. Run the following command in an elevated command prompt to disable Windows Firewall temporarily:\n \nNetsh advfirewall set allprofiles state off\n \nNote: This is just for test; please turn it back on with the command 'Netsh advfirewall set allprofiles state on'.\n");
|
||||
throw new Exception("The socket/serialproxy is closed " + e);
|
||||
}
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
void VerifyConnected()
|
||||
@ -208,7 +246,7 @@ namespace System.IO.Ports
|
||||
VerifyConnected();
|
||||
int size = client.Available;
|
||||
byte[] crap = new byte[size];
|
||||
Console.WriteLine("UdpSerial DiscardInBuffer {0}",size);
|
||||
log.InfoFormat("UdpSerial DiscardInBuffer {0}",size);
|
||||
Read(crap, 0, size);
|
||||
}
|
||||
|
||||
@ -249,7 +287,7 @@ namespace System.IO.Ports
|
||||
|
||||
public void Close()
|
||||
{
|
||||
if (client.Client.Connected)
|
||||
if (client.Client != null && client.Client.Connected)
|
||||
{
|
||||
client.Client.Close();
|
||||
client.Close();
|
||||
|
215
Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs
Normal file
215
Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.cs
Normal file
@ -0,0 +1,215 @@
|
||||
using System;
|
||||
using System.ComponentModel;
|
||||
using System.Threading;
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArdupilotMega.Controls
|
||||
{
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// Form that is shown to the user during a background operation
|
||||
/// </summary>
|
||||
/// <remarks>
|
||||
/// Performs operation excplicitely on a threadpool thread due to
|
||||
/// Mono not playing nice with the BackgroundWorker
|
||||
/// </remarks>
|
||||
public partial class ProgressReporterDialogue : Form
|
||||
{
|
||||
private Exception workerException;
|
||||
public ProgressWorkerEventArgs doWorkArgs;
|
||||
|
||||
public delegate void DoWorkEventHandler(object sender, ProgressWorkerEventArgs e);
|
||||
|
||||
// This is the event that will be raised on the BG thread
|
||||
public event DoWorkEventHandler DoWork;
|
||||
|
||||
public ProgressReporterDialogue()
|
||||
{
|
||||
InitializeComponent();
|
||||
doWorkArgs = new ProgressWorkerEventArgs();
|
||||
this.btnClose.Visible = false;
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Called at setup - will kick off the background process on a thread pool thread
|
||||
/// </summary>
|
||||
public void RunBackgroundOperationAsync()
|
||||
{
|
||||
ThreadPool.QueueUserWorkItem(RunBackgroundOperation);
|
||||
this.ShowDialog();
|
||||
}
|
||||
|
||||
private void RunBackgroundOperation(object o)
|
||||
{
|
||||
Thread.CurrentThread.Name = "ProgressReporterDialogue Background thread";
|
||||
try
|
||||
{
|
||||
if (this.DoWork != null) this.DoWork(this, doWorkArgs);
|
||||
}
|
||||
catch(Exception e)
|
||||
{
|
||||
// The background operation thew an exception.
|
||||
// Examine the work args, if there is an error, then display that and the exception details
|
||||
// Otherwise display 'Unexpected error' and exception details
|
||||
ShowDoneWithError(e, doWorkArgs.ErrorMessage);
|
||||
return;
|
||||
}
|
||||
|
||||
if (doWorkArgs.CancelRequested && doWorkArgs.CancelAcknowledged)
|
||||
{
|
||||
ShowDoneCancelled();
|
||||
return;
|
||||
}
|
||||
|
||||
if (!string.IsNullOrEmpty(doWorkArgs.ErrorMessage))
|
||||
{
|
||||
ShowDoneWithError(null, doWorkArgs.ErrorMessage);
|
||||
return;
|
||||
}
|
||||
|
||||
if (doWorkArgs.CancelRequested)
|
||||
{
|
||||
ShowDoneWithError(null, "Operation could not cancel");
|
||||
return;
|
||||
}
|
||||
|
||||
ShowDone();
|
||||
}
|
||||
|
||||
// Called as a possible last operation of the bg thread that was cancelled
|
||||
// - Hide progress bar
|
||||
// - Set label text
|
||||
private void ShowDoneCancelled()
|
||||
{
|
||||
this.Invoke((MethodInvoker)delegate
|
||||
{
|
||||
this.progressBar1.Visible = false;
|
||||
this.lblProgressMessage.Text = "Cancelled";
|
||||
this.btnClose.Visible = true;
|
||||
});
|
||||
}
|
||||
|
||||
// Called as a possible last operation of the bg thread
|
||||
// - Set progress bar to 100%
|
||||
// - Wait a little bit to allow the Aero progress animatiom to catch up
|
||||
// - Signal that we can close
|
||||
private void ShowDone()
|
||||
{
|
||||
this.Invoke((MethodInvoker) delegate
|
||||
{
|
||||
this.progressBar1.Style = ProgressBarStyle.Continuous;
|
||||
this.progressBar1.Value = 100;
|
||||
this.btnCancel.Visible = false;
|
||||
this.btnClose.Visible = false;
|
||||
});
|
||||
|
||||
Thread.Sleep(1000);
|
||||
|
||||
this.BeginInvoke((MethodInvoker) this.Close);
|
||||
}
|
||||
|
||||
// Called as a possible last operation of the bg thread
|
||||
// There was an exception on the worker event, so:
|
||||
// - Show the error message supplied by the worker, or a default message
|
||||
// - Make visible the error icon
|
||||
// - Make the progress bar invisible to make room for:
|
||||
// - Add the exception details and stack trace in an expansion panel
|
||||
// - Change the Cancel button to 'Close', so that the user can look at the exception message a bit
|
||||
private void ShowDoneWithError(Exception exception, string doWorkArgs)
|
||||
{
|
||||
var errMessage = doWorkArgs ?? "There was an unexpected error";
|
||||
|
||||
if (this.InvokeRequired)
|
||||
{
|
||||
this.Invoke((MethodInvoker) delegate
|
||||
{
|
||||
this.Text = "Error";
|
||||
this.lblProgressMessage.Left = 65;
|
||||
this.lblProgressMessage.Text = errMessage;
|
||||
this.imgWarning.Visible = true;
|
||||
this.progressBar1.Visible = false;
|
||||
this.btnCancel.Visible = false;
|
||||
this.btnClose.Visible = true;
|
||||
this.linkLabel1.Visible = exception != null;
|
||||
this.workerException = exception;
|
||||
});
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
private void btnCancel_Click(object sender, EventArgs e)
|
||||
{
|
||||
// User wants to cancel -
|
||||
// * Set the text of the Cancel button to 'Close'
|
||||
// * Set the cancel button to disabled, will enable it and let the user dismiss the dialogue
|
||||
// when the async operation is complete
|
||||
// * Set the status text to 'Cancelling...'
|
||||
// * Set the progress bar to marquee, we don't know how long the worker will take to cancel
|
||||
// * Signal the worker.
|
||||
this.btnCancel.Visible = false;
|
||||
this.lblProgressMessage.Text = "Cancelling...";
|
||||
this.progressBar1.Style = ProgressBarStyle.Marquee;
|
||||
|
||||
doWorkArgs.CancelRequested = true;
|
||||
}
|
||||
|
||||
|
||||
private void btn_Close_Click(object sender, EventArgs e)
|
||||
{
|
||||
// we have already cancelled, and this now a 'close' button
|
||||
this.Close();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Called from the BG thread
|
||||
/// </summary>
|
||||
/// <param name="progress">progress in %, -1 means inderteminate</param>
|
||||
/// <param name="status"></param>
|
||||
public void UpdateProgressAndStatus(int progress, string status)
|
||||
{
|
||||
// we don't let the worker update progress when a cancel has been
|
||||
// requested, unless the cancel has been acknowleged, so we know that
|
||||
// this progress update pertains to the cancellation cleanup
|
||||
if (doWorkArgs.CancelRequested && !doWorkArgs.CancelAcknowledged)
|
||||
return;
|
||||
|
||||
if (this.InvokeRequired)
|
||||
{
|
||||
|
||||
this.Invoke((MethodInvoker) delegate
|
||||
{
|
||||
|
||||
lblProgressMessage.Text = status;
|
||||
if (progress == -1)
|
||||
{
|
||||
this.progressBar1.Style = ProgressBarStyle.Marquee;
|
||||
}
|
||||
else
|
||||
{
|
||||
this.progressBar1.Style = ProgressBarStyle.Continuous;
|
||||
this.progressBar1.Value = progress;
|
||||
}
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
private void linkLabel1_LinkClicked(object sender, LinkLabelLinkClickedEventArgs e)
|
||||
{
|
||||
var message = this.workerException.Message
|
||||
+ Environment.NewLine + Environment.NewLine
|
||||
+ this.workerException.StackTrace;
|
||||
|
||||
MessageBox.Show(message,"Exception Details",MessageBoxButtons.OK,MessageBoxIcon.Information);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
public class ProgressWorkerEventArgs : EventArgs
|
||||
{
|
||||
public string ErrorMessage;
|
||||
public volatile bool CancelRequested;
|
||||
public volatile bool CancelAcknowledged;
|
||||
}
|
||||
}
|
141
Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.designer.cs
generated
Normal file
141
Tools/ArdupilotMegaPlanner/Controls/ProgressReporterDialogue.designer.cs
generated
Normal file
@ -0,0 +1,141 @@
|
||||
using System;
|
||||
using System.ComponentModel;
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArdupilotMega.Controls
|
||||
{
|
||||
partial class ProgressReporterDialogue
|
||||
{
|
||||
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Windows Form Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.progressBar1 = new System.Windows.Forms.ProgressBar();
|
||||
this.lblProgressMessage = new System.Windows.Forms.Label();
|
||||
this.btnCancel = new System.Windows.Forms.Button();
|
||||
this.imgWarning = new System.Windows.Forms.PictureBox();
|
||||
this.linkLabel1 = new System.Windows.Forms.LinkLabel();
|
||||
this.btnClose = new System.Windows.Forms.Button();
|
||||
((System.ComponentModel.ISupportInitialize)(this.imgWarning)).BeginInit();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// progressBar1
|
||||
//
|
||||
this.progressBar1.Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left)
|
||||
| System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.progressBar1.Location = new System.Drawing.Point(11, 90);
|
||||
this.progressBar1.Name = "progressBar1";
|
||||
this.progressBar1.Size = new System.Drawing.Size(277, 13);
|
||||
this.progressBar1.TabIndex = 0;
|
||||
//
|
||||
// lblProgressMessage
|
||||
//
|
||||
this.lblProgressMessage.Anchor = ((System.Windows.Forms.AnchorStyles)((((System.Windows.Forms.AnchorStyles.Top | System.Windows.Forms.AnchorStyles.Bottom)
|
||||
| System.Windows.Forms.AnchorStyles.Left)
|
||||
| System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.lblProgressMessage.Location = new System.Drawing.Point(13, 13);
|
||||
this.lblProgressMessage.Name = "lblProgressMessage";
|
||||
this.lblProgressMessage.Size = new System.Drawing.Size(275, 74);
|
||||
this.lblProgressMessage.TabIndex = 1;
|
||||
this.lblProgressMessage.TextAlign = System.Drawing.ContentAlignment.MiddleLeft;
|
||||
//
|
||||
// btnCancel
|
||||
//
|
||||
this.btnCancel.Location = new System.Drawing.Point(213, 109);
|
||||
this.btnCancel.Name = "btnCancel";
|
||||
this.btnCancel.Size = new System.Drawing.Size(75, 23);
|
||||
this.btnCancel.TabIndex = 2;
|
||||
this.btnCancel.Text = "Cancel";
|
||||
this.btnCancel.UseVisualStyleBackColor = true;
|
||||
this.btnCancel.Click += new System.EventHandler(this.btnCancel_Click);
|
||||
//
|
||||
// imgWarning
|
||||
//
|
||||
this.imgWarning.Image = global::ArdupilotMega.Properties.Resources.iconWarning48;
|
||||
this.imgWarning.Location = new System.Drawing.Point(13, 22);
|
||||
this.imgWarning.Name = "imgWarning";
|
||||
this.imgWarning.Size = new System.Drawing.Size(48, 48);
|
||||
this.imgWarning.TabIndex = 3;
|
||||
this.imgWarning.TabStop = false;
|
||||
this.imgWarning.Visible = false;
|
||||
//
|
||||
// linkLabel1
|
||||
//
|
||||
this.linkLabel1.AutoSize = true;
|
||||
this.linkLabel1.Location = new System.Drawing.Point(240, 90);
|
||||
this.linkLabel1.Name = "linkLabel1";
|
||||
this.linkLabel1.Size = new System.Drawing.Size(48, 13);
|
||||
this.linkLabel1.TabIndex = 4;
|
||||
this.linkLabel1.TabStop = true;
|
||||
this.linkLabel1.Text = "Details...";
|
||||
this.linkLabel1.Visible = false;
|
||||
this.linkLabel1.LinkClicked += new System.Windows.Forms.LinkLabelLinkClickedEventHandler(this.linkLabel1_LinkClicked);
|
||||
//
|
||||
// btn_Close
|
||||
//
|
||||
this.btnClose.Location = new System.Drawing.Point(213, 109);
|
||||
this.btnClose.Name = "btnClose";
|
||||
this.btnClose.Size = new System.Drawing.Size(75, 23);
|
||||
this.btnClose.TabIndex = 5;
|
||||
this.btnClose.Text = "Close";
|
||||
this.btnClose.UseVisualStyleBackColor = true;
|
||||
this.btnClose.Click += new System.EventHandler(this.btn_Close_Click);
|
||||
//
|
||||
// ProgressReporterDialogue
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.ClientSize = new System.Drawing.Size(306, 144);
|
||||
this.ControlBox = false;
|
||||
this.Controls.Add(this.btnClose);
|
||||
this.Controls.Add(this.linkLabel1);
|
||||
this.Controls.Add(this.imgWarning);
|
||||
this.Controls.Add(this.btnCancel);
|
||||
this.Controls.Add(this.lblProgressMessage);
|
||||
this.Controls.Add(this.progressBar1);
|
||||
this.FormBorderStyle = System.Windows.Forms.FormBorderStyle.FixedToolWindow;
|
||||
this.MaximizeBox = false;
|
||||
this.MinimizeBox = false;
|
||||
this.Name = "ProgressReporterDialogue";
|
||||
this.SizeGripStyle = System.Windows.Forms.SizeGripStyle.Hide;
|
||||
this.StartPosition = System.Windows.Forms.FormStartPosition.CenterParent;
|
||||
this.Text = "Progress";
|
||||
((System.ComponentModel.ISupportInitialize)(this.imgWarning)).EndInit();
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private ProgressBar progressBar1;
|
||||
private System.Windows.Forms.Label lblProgressMessage;
|
||||
private Button btnCancel;
|
||||
private PictureBox imgWarning;
|
||||
private LinkLabel linkLabel1;
|
||||
private Button btnClose;
|
||||
}
|
||||
}
|
@ -0,0 +1,120 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
</root>
|
@ -1,13 +1,16 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Reflection;
|
||||
using System.Text;
|
||||
using System.ComponentModel;
|
||||
using ArdupilotMega.Mavlink;
|
||||
using log4net;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public class CurrentState : ICloneable
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
// multipliers
|
||||
public float multiplierdist = 1;
|
||||
public float multiplierspeed = 1;
|
||||
@ -194,7 +197,7 @@ namespace ArdupilotMega
|
||||
public float DistToMAV
|
||||
{
|
||||
get
|
||||
{
|
||||
{
|
||||
// shrinking factor for longitude going to poles direction
|
||||
double rads = Math.Abs(HomeLocation.Lat) * 0.0174532925;
|
||||
double scaleLongDown = Math.Cos(rads);
|
||||
@ -224,7 +227,7 @@ namespace ArdupilotMega
|
||||
public float AZToMAV
|
||||
{
|
||||
get
|
||||
{
|
||||
{
|
||||
// shrinking factor for longitude going to poles direction
|
||||
double rads = Math.Abs(HomeLocation.Lat) * 0.0174532925;
|
||||
double scaleLongDown = Math.Cos(rads);
|
||||
@ -314,11 +317,11 @@ namespace ArdupilotMega
|
||||
|
||||
try
|
||||
{
|
||||
while (messages.Count > 5)
|
||||
{
|
||||
messages.RemoveAt(0);
|
||||
}
|
||||
messages.Add(logdata + "\n");
|
||||
while (messages.Count > 5)
|
||||
{
|
||||
messages.RemoveAt(0);
|
||||
}
|
||||
messages.Add(logdata + "\n");
|
||||
|
||||
}
|
||||
catch { }
|
||||
@ -578,7 +581,7 @@ namespace ArdupilotMega
|
||||
|
||||
packetdropremote = sysstatus.packet_drop;
|
||||
|
||||
if (oldmode != mode && MainV2.speechenable && MainV2.getConfig("speechmodeenabled") == "True")
|
||||
if (oldmode != mode && MainV2.speechenable && MainV2.talk != null && MainV2.getConfig("speechmodeenabled") == "True")
|
||||
{
|
||||
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechmode")));
|
||||
}
|
||||
@ -729,7 +732,7 @@ namespace ArdupilotMega
|
||||
|
||||
wpno = wpcur.seq;
|
||||
|
||||
if (oldwp != wpno && MainV2.speechenable && MainV2.getConfig("speechwaypointenabled") == "True")
|
||||
if (oldwp != wpno && MainV2.speechenable && MainV2.talk != null && MainV2.getConfig("speechwaypointenabled") == "True")
|
||||
{
|
||||
MainV2.talk.SpeakAsync(Common.speechConversion(MainV2.getConfig("speechwaypoint")));
|
||||
}
|
||||
@ -858,7 +861,7 @@ namespace ArdupilotMega
|
||||
//Console.WriteLine(DateTime.Now.Millisecond + " done ");
|
||||
}
|
||||
}
|
||||
catch { Console.WriteLine("CurrentState Binding error"); }
|
||||
catch { log.InfoFormat("CurrentState Binding error"); }
|
||||
}
|
||||
|
||||
public object Clone()
|
||||
@ -898,4 +901,4 @@ namespace ArdupilotMega
|
||||
//low pass the outputs for better results!
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
@ -47,7 +47,7 @@
|
||||
<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-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.4 Quad</name>
|
||||
<name>ArduCopter V2.4.1 Quad</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG QUAD_FRAME
|
||||
|
||||
@ -58,7 +58,7 @@
|
||||
<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-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.4 Tri</name>
|
||||
<name>ArduCopter V2.4.1 Tri</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG TRI_FRAME
|
||||
|
||||
@ -69,7 +69,7 @@
|
||||
<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-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.4 Hexa X</name>
|
||||
<name>ArduCopter V2.4.1 Hexa X</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG HEXA_FRAME
|
||||
|
||||
@ -80,7 +80,7 @@
|
||||
<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-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.4 Y6</name>
|
||||
<name>ArduCopter V2.4.1 Y6</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG Y6_FRAME
|
||||
|
||||
@ -91,7 +91,7 @@
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-1280.hex</url>
|
||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-2560.hex</url2560>
|
||||
<url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.4 Octa V</name>
|
||||
<name>ArduCopter V2.4.1 Octa V</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG OCTA_FRAME
|
||||
#define FRAME_ORIENTATION V_FRAME
|
||||
@ -103,7 +103,7 @@
|
||||
<url>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-1280.hex</url>
|
||||
<url2560>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-2560.hex</url2560>
|
||||
<url2560-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.4 Octa X</name>
|
||||
<name>ArduCopter V2.4.1 Octa X</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG OCTA_FRAME
|
||||
|
||||
@ -162,7 +162,7 @@
|
||||
<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-2>http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560-2.hex</url2560-2>
|
||||
<name>ArduCopter V2.4 Quad Hil</name>
|
||||
<name>ArduCopter V2.4.1 Quad Hil</name>
|
||||
<desc>
|
||||
#define FRAME_CONFIG QUAD_FRAME
|
||||
#define FRAME_ORIENTATION PLUS_FRAME
|
||||
|
@ -30,8 +30,8 @@
|
||||
{
|
||||
this.components = new System.ComponentModel.Container();
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(Configuration));
|
||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle1 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle2 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle3 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||
System.Windows.Forms.DataGridViewCellStyle dataGridViewCellStyle4 = new System.Windows.Forms.DataGridViewCellStyle();
|
||||
this.Params = new System.Windows.Forms.DataGridView();
|
||||
this.Command = new System.Windows.Forms.DataGridViewTextBoxColumn();
|
||||
this.Value = new System.Windows.Forms.DataGridViewTextBoxColumn();
|
||||
@ -141,6 +141,8 @@
|
||||
this.RLL2SRV_P = new System.Windows.Forms.NumericUpDown();
|
||||
this.label52 = new System.Windows.Forms.Label();
|
||||
this.TabAC = new System.Windows.Forms.TabPage();
|
||||
this.TUNE_LOW = new System.Windows.Forms.NumericUpDown();
|
||||
this.TUNE_HIGH = new System.Windows.Forms.NumericUpDown();
|
||||
this.myLabel2 = new ArdupilotMega.MyLabel();
|
||||
this.TUNE = new System.Windows.Forms.ComboBox();
|
||||
this.myLabel1 = new ArdupilotMega.MyLabel();
|
||||
@ -345,6 +347,8 @@
|
||||
((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_I)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_P)).BeginInit();
|
||||
this.TabAC.SuspendLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.TUNE_LOW)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.TUNE_HIGH)).BeginInit();
|
||||
this.groupBox5.SuspendLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.THR_RATE_D)).BeginInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.THR_RATE_IMAX)).BeginInit();
|
||||
@ -403,14 +407,14 @@
|
||||
this.Params.AllowUserToAddRows = false;
|
||||
this.Params.AllowUserToDeleteRows = false;
|
||||
resources.ApplyResources(this.Params, "Params");
|
||||
dataGridViewCellStyle1.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
||||
dataGridViewCellStyle1.BackColor = System.Drawing.Color.Maroon;
|
||||
dataGridViewCellStyle1.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
|
||||
dataGridViewCellStyle1.ForeColor = System.Drawing.Color.White;
|
||||
dataGridViewCellStyle1.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
||||
dataGridViewCellStyle1.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
||||
dataGridViewCellStyle1.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
|
||||
this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle1;
|
||||
dataGridViewCellStyle3.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
||||
dataGridViewCellStyle3.BackColor = System.Drawing.Color.Maroon;
|
||||
dataGridViewCellStyle3.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
|
||||
dataGridViewCellStyle3.ForeColor = System.Drawing.Color.White;
|
||||
dataGridViewCellStyle3.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
||||
dataGridViewCellStyle3.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
||||
dataGridViewCellStyle3.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
|
||||
this.Params.ColumnHeadersDefaultCellStyle = dataGridViewCellStyle3;
|
||||
this.Params.ColumnHeadersHeightSizeMode = System.Windows.Forms.DataGridViewColumnHeadersHeightSizeMode.AutoSize;
|
||||
this.Params.Columns.AddRange(new System.Windows.Forms.DataGridViewColumn[] {
|
||||
this.Command,
|
||||
@ -419,14 +423,14 @@
|
||||
this.mavScale,
|
||||
this.RawValue});
|
||||
this.Params.Name = "Params";
|
||||
dataGridViewCellStyle2.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
||||
dataGridViewCellStyle2.BackColor = System.Drawing.SystemColors.ActiveCaption;
|
||||
dataGridViewCellStyle2.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
|
||||
dataGridViewCellStyle2.ForeColor = System.Drawing.SystemColors.WindowText;
|
||||
dataGridViewCellStyle2.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
||||
dataGridViewCellStyle2.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
||||
dataGridViewCellStyle2.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
|
||||
this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle2;
|
||||
dataGridViewCellStyle4.Alignment = System.Windows.Forms.DataGridViewContentAlignment.MiddleLeft;
|
||||
dataGridViewCellStyle4.BackColor = System.Drawing.SystemColors.ActiveCaption;
|
||||
dataGridViewCellStyle4.Font = new System.Drawing.Font("Microsoft Sans Serif", 8.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
|
||||
dataGridViewCellStyle4.ForeColor = System.Drawing.SystemColors.WindowText;
|
||||
dataGridViewCellStyle4.SelectionBackColor = System.Drawing.SystemColors.Highlight;
|
||||
dataGridViewCellStyle4.SelectionForeColor = System.Drawing.SystemColors.HighlightText;
|
||||
dataGridViewCellStyle4.WrapMode = System.Windows.Forms.DataGridViewTriState.True;
|
||||
this.Params.RowHeadersDefaultCellStyle = dataGridViewCellStyle4;
|
||||
this.Params.RowHeadersVisible = false;
|
||||
this.Params.CellValueChanged += new System.Windows.Forms.DataGridViewCellEventHandler(this.Params_CellValueChanged);
|
||||
//
|
||||
@ -1087,6 +1091,8 @@
|
||||
//
|
||||
// TabAC
|
||||
//
|
||||
this.TabAC.Controls.Add(this.TUNE_LOW);
|
||||
this.TabAC.Controls.Add(this.TUNE_HIGH);
|
||||
this.TabAC.Controls.Add(this.myLabel2);
|
||||
this.TabAC.Controls.Add(this.TUNE);
|
||||
this.TabAC.Controls.Add(this.myLabel1);
|
||||
@ -1106,6 +1112,16 @@
|
||||
resources.ApplyResources(this.TabAC, "TabAC");
|
||||
this.TabAC.Name = "TabAC";
|
||||
//
|
||||
// TUNE_LOW
|
||||
//
|
||||
resources.ApplyResources(this.TUNE_LOW, "TUNE_LOW");
|
||||
this.TUNE_LOW.Name = "TUNE_LOW";
|
||||
//
|
||||
// TUNE_HIGH
|
||||
//
|
||||
resources.ApplyResources(this.TUNE_HIGH, "TUNE_HIGH");
|
||||
this.TUNE_HIGH.Name = "TUNE_HIGH";
|
||||
//
|
||||
// myLabel2
|
||||
//
|
||||
resources.ApplyResources(this.myLabel2, "myLabel2");
|
||||
@ -1138,7 +1154,8 @@
|
||||
resources.GetString("TUNE.Items17"),
|
||||
resources.GetString("TUNE.Items18"),
|
||||
resources.GetString("TUNE.Items19"),
|
||||
resources.GetString("TUNE.Items20")});
|
||||
resources.GetString("TUNE.Items20"),
|
||||
resources.GetString("TUNE.Items21")});
|
||||
resources.ApplyResources(this.TUNE, "TUNE");
|
||||
this.TUNE.Name = "TUNE";
|
||||
//
|
||||
@ -2190,6 +2207,8 @@
|
||||
((System.ComponentModel.ISupportInitialize)(this.RLL2SRV_P)).EndInit();
|
||||
this.TabAC.ResumeLayout(false);
|
||||
this.TabAC.PerformLayout();
|
||||
((System.ComponentModel.ISupportInitialize)(this.TUNE_LOW)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.TUNE_HIGH)).EndInit();
|
||||
this.groupBox5.ResumeLayout(false);
|
||||
((System.ComponentModel.ISupportInitialize)(this.THR_RATE_D)).EndInit();
|
||||
((System.ComponentModel.ISupportInitialize)(this.THR_RATE_IMAX)).EndInit();
|
||||
@ -2500,5 +2519,7 @@
|
||||
private System.Windows.Forms.Label label29;
|
||||
private System.Windows.Forms.NumericUpDown STAB_D;
|
||||
private System.Windows.Forms.Label lblSTAB_D;
|
||||
private System.Windows.Forms.NumericUpDown TUNE_LOW;
|
||||
private System.Windows.Forms.NumericUpDown TUNE_HIGH;
|
||||
}
|
||||
}
|
||||
|
@ -95,6 +95,10 @@ namespace ArdupilotMega.GCSViews
|
||||
if (tooltips.Count == 0)
|
||||
readToolTips();
|
||||
|
||||
// ensure the fields are populated before setting them
|
||||
CH7_OPT.DataSource = Enum.GetNames(typeof(Common.ac2ch7modes));
|
||||
TUNE.DataSource = Enum.GetNames(typeof(Common.ac2ch6modes));
|
||||
|
||||
// prefill all fields
|
||||
param = MainV2.comPort.param;
|
||||
processToScreen();
|
||||
@ -164,6 +168,7 @@ namespace ArdupilotMega.GCSViews
|
||||
// set distance/speed unit states
|
||||
CMB_distunits.DataSource = Enum.GetNames(typeof(Common.distances));
|
||||
CMB_speedunits.DataSource = Enum.GetNames(typeof(Common.speeds));
|
||||
|
||||
if (MainV2.config["distunits"] != null)
|
||||
CMB_distunits.Text = MainV2.config["distunits"].ToString();
|
||||
if (MainV2.config["speedunits"] != null)
|
||||
@ -173,26 +178,20 @@ namespace ArdupilotMega.GCSViews
|
||||
CultureInfo ci = null;
|
||||
foreach (string name in new string[] { "en-US", "zh-Hans", "zh-TW", "ru-RU", "Fr", "Pl", "it-IT", "es-ES" })
|
||||
{
|
||||
ci = MainV2.getcultureinfo(name);
|
||||
ci = CultureInfoEx.GetCultureInfo(name);
|
||||
if (ci != null)
|
||||
languages.Add(ci);
|
||||
}
|
||||
|
||||
CMB_language.DisplayMember = "DisplayName";
|
||||
CMB_language.DataSource = languages;
|
||||
bool match = false;
|
||||
for (int i = 0; i < languages.Count && !match; i++)
|
||||
ci = Thread.CurrentThread.CurrentUICulture;
|
||||
for (int i = 0; i < languages.Count; i++)
|
||||
{
|
||||
ci = Thread.CurrentThread.CurrentUICulture;
|
||||
while (!ci.Equals(CultureInfo.InvariantCulture))
|
||||
if (ci.IsChildOf(languages[i]))
|
||||
{
|
||||
if (ci.Equals(languages[i]))
|
||||
{
|
||||
CMB_language.SelectedIndex = i;
|
||||
match = true;
|
||||
break;
|
||||
}
|
||||
ci = ci.Parent;
|
||||
CMB_language.SelectedIndex = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
CMB_language.SelectedIndexChanged += CMB_language_SelectedIndexChanged;
|
||||
@ -237,7 +236,9 @@ namespace ArdupilotMega.GCSViews
|
||||
string data = resources.GetString("MAVParam");
|
||||
|
||||
if (data == null)
|
||||
return;
|
||||
{
|
||||
data = global::ArdupilotMega.Properties.Resources.MAVParam;
|
||||
}
|
||||
|
||||
string[] tips = data.Split(new char[] { '\r', '\n' }, StringSplitOptions.RemoveEmptyEntries);
|
||||
|
||||
@ -555,23 +556,23 @@ namespace ArdupilotMega.GCSViews
|
||||
if (text.Length > 0)
|
||||
{
|
||||
if (text[0].GetType() == typeof(NumericUpDown))
|
||||
{
|
||||
decimal option = (decimal)(float.Parse(Params[e.ColumnIndex, e.RowIndex].Value.ToString()));
|
||||
((NumericUpDown)text[0]).Value = option;
|
||||
((NumericUpDown)text[0]).BackColor = Color.Green;
|
||||
}
|
||||
{
|
||||
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 (text[0].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;
|
||||
}
|
||||
{
|
||||
int option = (int)(float.Parse(Params[e.ColumnIndex, e.RowIndex].Value.ToString()));
|
||||
((ComboBox)text[0]).SelectedIndex = option;
|
||||
((ComboBox)text[0]).BackColor = Color.Green;
|
||||
}
|
||||
}
|
||||
}
|
||||
catch { ((Control)text[0]).BackColor = Color.Red; }
|
||||
|
||||
Params.Focus();
|
||||
}
|
||||
}
|
||||
|
||||
private void BUT_load_Click(object sender, EventArgs e)
|
||||
{
|
||||
@ -599,12 +600,12 @@ namespace ArdupilotMega.GCSViews
|
||||
continue;
|
||||
|
||||
if (index2 != -1)
|
||||
line = line.Replace(',','.');
|
||||
line = line.Replace(',', '.');
|
||||
|
||||
string name = line.Substring(0, index);
|
||||
float value = float.Parse(line.Substring(index + 1), new System.Globalization.CultureInfo("en-US"));
|
||||
|
||||
MAVLink.modifyParamForDisplay(true,name,ref value);
|
||||
MAVLink.modifyParamForDisplay(true, name, ref value);
|
||||
|
||||
// set param table as well
|
||||
foreach (DataGridViewRow row in Params.Rows)
|
||||
@ -759,6 +760,8 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
MainV2.cam.Start();
|
||||
|
||||
MainV2.config["video_options"] = CMB_videoresolutions.SelectedIndex;
|
||||
|
||||
BUT_videostart.Enabled = false;
|
||||
}
|
||||
catch (Exception ex) { MessageBox.Show("Camera Fail: " + ex.Message); }
|
||||
@ -813,9 +816,10 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
DsError.ThrowExceptionForHR(hr);
|
||||
}
|
||||
catch (Exception ex) {
|
||||
MessageBox.Show("Can not add video source\n" + ex.ToString());
|
||||
return;
|
||||
catch (Exception ex)
|
||||
{
|
||||
MessageBox.Show("Can not add video source\n" + ex.ToString());
|
||||
return;
|
||||
}
|
||||
|
||||
// Find the stream config interface
|
||||
@ -844,6 +848,11 @@ namespace ArdupilotMega.GCSViews
|
||||
DsUtils.FreeAMMediaType(media);
|
||||
|
||||
CMB_videoresolutions.DataSource = modes;
|
||||
|
||||
if (MainV2.getConfig("video_options") != "" && CMB_videosources.Text != "")
|
||||
{
|
||||
CMB_videoresolutions.SelectedIndex = int.Parse(MainV2.getConfig("video_options"));
|
||||
}
|
||||
}
|
||||
|
||||
private void CHK_hudshow_CheckedChanged(object sender, EventArgs e)
|
||||
@ -940,7 +949,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
}
|
||||
catch { MessageBox.Show("Error: getting param list"); }
|
||||
|
||||
@ -1154,5 +1163,25 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
protected override bool ProcessCmdKey(ref Message msg, Keys keyData)
|
||||
{
|
||||
if (keyData == Keys.F5)
|
||||
{
|
||||
BUT_rerequestparams_Click(BUT_rerequestparams, null);
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.S))
|
||||
{
|
||||
BUT_writePIDS_Click(BUT_writePIDS, null);
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.O))
|
||||
{
|
||||
BUT_load_Click(BUT_load, null);
|
||||
return true;
|
||||
}
|
||||
return base.ProcessCmdKey(ref msg, keyData);
|
||||
}
|
||||
}
|
||||
}
|
File diff suppressed because it is too large
Load Diff
@ -727,30 +727,33 @@
|
||||
<data name="groupBox8.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="TabAPM2.ToolTip" xml:space="preserve">
|
||||
<data name="TabAP.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="ACRO_PIT_IMAX.ToolTip" xml:space="preserve">
|
||||
<data name="myLabel2.Text" xml:space="preserve">
|
||||
<value>Ch6 选项</value>
|
||||
</data>
|
||||
<data name="myLabel2.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label27.ToolTip" xml:space="preserve">
|
||||
<data name="TUNE.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="ACRO_PIT_I.ToolTip" xml:space="preserve">
|
||||
<data name="myLabel1.Text" xml:space="preserve">
|
||||
<value>Ch7 选项</value>
|
||||
</data>
|
||||
<data name="myLabel1.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="CH7_OPT.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="THR_RATE_D.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label29.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="ACRO_PIT_P.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label33.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="groupBox17.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label14.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
@ -769,30 +772,12 @@
|
||||
<data name="label25.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="groupBox5.Text" xml:space="preserve">
|
||||
<value>油门比率</value>
|
||||
</data>
|
||||
<data name="groupBox5.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="ACRO_RLL_IMAX.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label40.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="ACRO_RLL_I.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label44.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="ACRO_RLL_P.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label48.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="groupBox18.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="CHK_lockrollpitch.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>122, 17</value>
|
||||
</data>
|
||||
@ -802,6 +787,12 @@
|
||||
<data name="CHK_lockrollpitch.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="NAV_LAT_D.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label27.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="WP_SPEED_MAX.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
@ -838,25 +829,7 @@
|
||||
<data name="groupBox4.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="XTRK_ANGLE_CD1.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label10.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="XTRACK_IMAX.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label11.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="XTRACK_I.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label17.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="XTRACK_P.ToolTip" xml:space="preserve">
|
||||
<data name="XTRK_GAIN_SC1.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label18.ToolTip" xml:space="preserve">
|
||||
@ -934,9 +907,18 @@
|
||||
<data name="label35.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="groupBox20.Text" xml:space="preserve">
|
||||
<value>稳定偏航</value>
|
||||
</data>
|
||||
<data name="groupBox20.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="STAB_D.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="lblSTAB_D.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="STB_PIT_IMAX.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
@ -955,6 +937,9 @@
|
||||
<data name="label42.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="groupBox21.Text" xml:space="preserve">
|
||||
<value>稳定俯仰</value>
|
||||
</data>
|
||||
<data name="groupBox21.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
@ -976,9 +961,18 @@
|
||||
<data name="label46.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="groupBox22.Text" xml:space="preserve">
|
||||
<value>稳定侧倾</value>
|
||||
</data>
|
||||
<data name="groupBox22.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="RATE_YAW_D.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label10.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="RATE_YAW_IMAX.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
@ -997,9 +991,18 @@
|
||||
<data name="label82.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="groupBox23.Text" xml:space="preserve">
|
||||
<value>比率偏航</value>
|
||||
</data>
|
||||
<data name="groupBox23.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="RATE_PIT_D.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label11.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="RATE_PIT_IMAX.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
@ -1018,9 +1021,18 @@
|
||||
<data name="label87.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="groupBox24.Text" xml:space="preserve">
|
||||
<value>比率俯仰</value>
|
||||
</data>
|
||||
<data name="groupBox24.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="RATE_RLL_D.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label17.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="RATE_RLL_IMAX.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
@ -1039,10 +1051,13 @@
|
||||
<data name="label91.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="groupBox25.Text" xml:space="preserve">
|
||||
<value>比率侧倾</value>
|
||||
</data>
|
||||
<data name="groupBox25.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="TabAC2.ToolTip" xml:space="preserve">
|
||||
<data name="TabAC.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="label26.Text" xml:space="preserve">
|
||||
@ -1357,8 +1372,4 @@
|
||||
<data name="$this.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="MAVParam" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\MAVParam.zh-Hans.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;utf-8</value>
|
||||
</data>
|
||||
</root>
|
@ -1,28 +1,24 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Data;
|
||||
using System.Drawing;
|
||||
using System.Text;
|
||||
using System.Reflection;
|
||||
using System.Windows.Forms;
|
||||
using System.Text.RegularExpressions;
|
||||
using System.IO.Ports;
|
||||
using System.IO;
|
||||
using System.Runtime.InteropServices;
|
||||
using System.Xml;
|
||||
using System.Net;
|
||||
using log4net;
|
||||
|
||||
namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
partial class Firmware : MyUserControl
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
|
||||
protected override bool ProcessCmdKey(ref Message msg, Keys keyData)
|
||||
{
|
||||
if (keyData == (Keys.Control | Keys.C))
|
||||
{
|
||||
OpenFileDialog fd = new OpenFileDialog();
|
||||
fd.Filter = "Firmware (*.hex)|*.hex";
|
||||
var fd = new OpenFileDialog {Filter = "Firmware (*.hex)|*.hex"};
|
||||
fd.ShowDialog();
|
||||
if (File.Exists(fd.FileName))
|
||||
{
|
||||
@ -69,7 +65,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
internal void Firmware_Load(object sender, EventArgs e)
|
||||
{
|
||||
Console.WriteLine("FW load");
|
||||
log.Info("FW load");
|
||||
|
||||
string url = "";
|
||||
string url2560 = "";
|
||||
@ -141,11 +137,14 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
}
|
||||
|
||||
List<string> list = new List<string>();
|
||||
|
||||
}
|
||||
catch (Exception ex) { MessageBox.Show("Failed to get Firmware List : " + ex.Message); }
|
||||
Console.WriteLine("FW load done");
|
||||
catch (Exception ex)
|
||||
{
|
||||
MessageBox.Show("Failed to get Firmware List : " + ex.Message);
|
||||
}
|
||||
log.Info("FW load done");
|
||||
|
||||
}
|
||||
|
||||
void updateDisplayName(software temp)
|
||||
@ -192,7 +191,7 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
else
|
||||
{
|
||||
Console.WriteLine("No Home " + temp.name + " " + temp.url);
|
||||
log.Info("No Home " + temp.name + " " + temp.url);
|
||||
}
|
||||
}
|
||||
|
||||
@ -354,7 +353,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
|
||||
|
||||
Console.WriteLine("Detected a " + board);
|
||||
log.Info("Detected a " + board);
|
||||
|
||||
string baseurl = "";
|
||||
if (board == "2560")
|
||||
@ -375,7 +374,7 @@ namespace ArdupilotMega.GCSViews
|
||||
return;
|
||||
}
|
||||
|
||||
Console.WriteLine("Using " + baseurl);
|
||||
log.Info("Using " + baseurl);
|
||||
|
||||
// Create a request using a URL that can receive a post.
|
||||
WebRequest request = WebRequest.Create(baseurl);
|
||||
@ -387,7 +386,7 @@ namespace ArdupilotMega.GCSViews
|
||||
// Get the response.
|
||||
WebResponse response = request.GetResponse();
|
||||
// Display the status.
|
||||
Console.WriteLine(((HttpWebResponse)response).StatusDescription);
|
||||
log.Info(((HttpWebResponse)response).StatusDescription);
|
||||
// Get the stream containing content returned by the server.
|
||||
dataStream = response.GetResponseStream();
|
||||
|
||||
@ -425,7 +424,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
progress.Value = 100;
|
||||
this.Refresh();
|
||||
Console.WriteLine("Downloaded");
|
||||
log.Info("Downloaded");
|
||||
}
|
||||
catch (Exception ex) { lbl_status.Text = "Failed download"; MessageBox.Show("Failed to download new firmware : " + ex.ToString()); return; }
|
||||
|
||||
@ -443,9 +442,18 @@ namespace ArdupilotMega.GCSViews
|
||||
sr = new StreamReader(filename);
|
||||
FLASH = readIntelHEXv2(sr);
|
||||
sr.Close();
|
||||
Console.WriteLine("\n\nSize: {0}\n\n", FLASH.Length);
|
||||
log.InfoFormat("\n\nSize: {0}\n\n", FLASH.Length);
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
if (sr != null)
|
||||
{
|
||||
sr.Dispose();
|
||||
}
|
||||
lbl_status.Text = "Failed read HEX";
|
||||
MessageBox.Show("Failed to read firmware.hex : " + ex.Message);
|
||||
return;
|
||||
}
|
||||
catch (Exception ex) { if (sr != null) { sr.Dispose(); } lbl_status.Text = "Failed read HEX"; MessageBox.Show("Failed to read firmware.hex : " + ex.Message); return; }
|
||||
ArduinoComms port = new ArduinoSTK();
|
||||
|
||||
if (board == "1280")
|
||||
@ -460,8 +468,10 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
else if (board == "2560" || board == "2560-2")
|
||||
{
|
||||
port = new ArduinoSTKv2();
|
||||
port.BaudRate = 115200;
|
||||
port = new ArduinoSTKv2
|
||||
{
|
||||
BaudRate = 115200
|
||||
};
|
||||
}
|
||||
port.DataBits = 8;
|
||||
port.StopBits = StopBits.One;
|
||||
@ -478,7 +488,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
if (port.connectAP())
|
||||
{
|
||||
Console.WriteLine("starting");
|
||||
log.Info("starting");
|
||||
lbl_status.Text = "Uploading " + FLASH.Length + " bytes to APM";
|
||||
progress.Value = 0;
|
||||
this.Refresh();
|
||||
@ -486,7 +496,7 @@ namespace ArdupilotMega.GCSViews
|
||||
// this is enough to make ap_var reset
|
||||
//port.upload(new byte[256], 0, 2, 0);
|
||||
|
||||
port.Progress += new ProgressEventHandler(port_Progress);
|
||||
port.Progress += port_Progress;
|
||||
|
||||
if (!port.uploadflash(FLASH, 0, FLASH.Length, 0))
|
||||
{
|
||||
@ -500,7 +510,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
progress.Value = 100;
|
||||
|
||||
Console.WriteLine("Uploaded");
|
||||
log.Info("Uploaded");
|
||||
|
||||
this.Refresh();
|
||||
|
||||
@ -518,7 +528,7 @@ namespace ArdupilotMega.GCSViews
|
||||
progress.Value = (int)((start / (float)FLASH.Length) * 100);
|
||||
progress.Refresh();
|
||||
port.setaddress(start);
|
||||
Console.WriteLine("Downloading " + length + " at " + start);
|
||||
log.Info("Downloading " + length + " at " + start);
|
||||
port.downloadflash(length).CopyTo(flashverify, start);
|
||||
start += length;
|
||||
}
|
||||
@ -575,14 +585,19 @@ namespace ArdupilotMega.GCSViews
|
||||
progress.Value = 100;
|
||||
lbl_status.Text = "Done";
|
||||
}
|
||||
catch (Exception ex) { lbl_status.Text = "Failed upload"; MessageBox.Show("Check port settings or Port in use? " + ex.ToString()); port.Close(); }
|
||||
catch (Exception ex)
|
||||
{
|
||||
lbl_status.Text = "Failed upload";
|
||||
MessageBox.Show("Check port settings or Port in use? " + ex);
|
||||
port.Close();
|
||||
}
|
||||
flashing = false;
|
||||
MainV2.givecomport = false;
|
||||
}
|
||||
|
||||
void port_Progress(int progress,string status)
|
||||
{
|
||||
Console.WriteLine("Progress {0} ", progress);
|
||||
log.InfoFormat("Progress {0} ", progress);
|
||||
this.progress.Value = progress;
|
||||
this.progress.Refresh();
|
||||
}
|
||||
@ -607,7 +622,7 @@ namespace ArdupilotMega.GCSViews
|
||||
int length = Convert.ToInt32(line.Substring(1, 2), 16);
|
||||
int address = Convert.ToInt32(line.Substring(3, 4), 16);
|
||||
int option = Convert.ToInt32(line.Substring(7, 2), 16);
|
||||
Console.WriteLine("len {0} add {1} opt {2}", length, address, option);
|
||||
log.InfoFormat("len {0} add {1} opt {2}", length, address, option);
|
||||
|
||||
if (option == 0)
|
||||
{
|
||||
|
@ -55,7 +55,7 @@
|
||||
this.zg1 = new ZedGraph.ZedGraphControl();
|
||||
this.lbl_winddir = new ArdupilotMega.MyLabel();
|
||||
this.lbl_windvel = new ArdupilotMega.MyLabel();
|
||||
this.gMapControl1 = new myGMAP();
|
||||
this.gMapControl1 = new ArdupilotMega.myGMAP();
|
||||
this.panel1 = new System.Windows.Forms.Panel();
|
||||
this.TXT_lat = new ArdupilotMega.MyLabel();
|
||||
this.Zoomlevel = new System.Windows.Forms.NumericUpDown();
|
||||
|
@ -75,12 +75,14 @@ namespace ArdupilotMega.GCSViews
|
||||
public static GMapControl mymap = null;
|
||||
|
||||
|
||||
PointLatLngAlt GuidedModeWP = new PointLatLngAlt();
|
||||
public static PointLatLngAlt GuidedModeWP = new PointLatLngAlt();
|
||||
|
||||
AviWriter aviwriter;
|
||||
|
||||
public SplitContainer MainHcopy = null;
|
||||
|
||||
public static FlightData instance;
|
||||
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
threadrun = 0;
|
||||
@ -94,6 +96,8 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
InitializeComponent();
|
||||
|
||||
instance = this;
|
||||
|
||||
mymap = gMapControl1;
|
||||
myhud = hud1;
|
||||
MainHcopy = MainH;
|
||||
@ -271,6 +275,7 @@ namespace ArdupilotMega.GCSViews
|
||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_POSITION, MainV2.cs.rateposition); // request gps
|
||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA1, MainV2.cs.rateattitude); // request attitude
|
||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA2, MainV2.cs.rateattitude); // request vfr
|
||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_EXTRA3, MainV2.cs.ratesensors); // request extra stuff - tridge
|
||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RAW_SENSORS, MainV2.cs.ratesensors); // request raw sensor
|
||||
comPort.requestDatastream((byte)ArdupilotMega.MAVLink.MAV_DATA_STREAM.MAV_DATA_STREAM_RC_CHANNELS, MainV2.cs.raterc); // request rc info
|
||||
}
|
||||
@ -1013,11 +1018,27 @@ namespace ArdupilotMega.GCSViews
|
||||
if (MainV2.comPort.logreadmode)
|
||||
{
|
||||
MainV2.comPort.logreadmode = false;
|
||||
ZedGraphTimer.Stop();
|
||||
}
|
||||
else
|
||||
{
|
||||
BUT_clear_track_Click(sender, e);
|
||||
MainV2.comPort.logreadmode = true;
|
||||
list1.Clear();
|
||||
list2.Clear();
|
||||
list3.Clear();
|
||||
list4.Clear();
|
||||
list5.Clear();
|
||||
list6.Clear();
|
||||
list7.Clear();
|
||||
list8.Clear();
|
||||
list9.Clear();
|
||||
list10.Clear();
|
||||
tickStart = Environment.TickCount;
|
||||
|
||||
zg1.GraphPane.XAxis.Scale.Min = 0;
|
||||
zg1.GraphPane.XAxis.Scale.Max = 1;
|
||||
ZedGraphTimer.Start();
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1391,7 +1391,7 @@
|
||||
<value>gMapControl1</value>
|
||||
</data>
|
||||
<data name=">>gMapControl1.Type" xml:space="preserve">
|
||||
<value>GMap.NET.WindowsForms.GMapControl, GMap.NET.WindowsForms, Version=1.5.5.5, Culture=neutral, PublicKeyToken=b85b9027b614afef</value>
|
||||
<value>ArdupilotMega.myGMAP, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc</value>
|
||||
</data>
|
||||
<data name=">>gMapControl1.Parent" xml:space="preserve">
|
||||
<value>splitContainer1.Panel2</value>
|
||||
|
@ -18,6 +18,7 @@ using System.Resources;
|
||||
using System.Reflection;
|
||||
using System.ComponentModel;
|
||||
using System.Threading;
|
||||
using log4net;
|
||||
using SharpKml.Base;
|
||||
using SharpKml.Dom;
|
||||
|
||||
@ -27,6 +28,7 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
partial class FlightPlanner : MyUserControl
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
int selectedrow = 0;
|
||||
bool quickadd = false;
|
||||
bool isonline = true;
|
||||
@ -598,7 +600,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
void Commands_DataError(object sender, DataGridViewDataErrorEventArgs e)
|
||||
{
|
||||
Console.WriteLine(e.Exception.ToString() + " " + e.Context + " col " + e.ColumnIndex);
|
||||
log.Info(e.Exception.ToString() + " " + e.Context + " col " + e.ColumnIndex);
|
||||
e.Cancel = false;
|
||||
e.ThrowException = false;
|
||||
//throw new NotImplementedException();
|
||||
@ -700,7 +702,7 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
try
|
||||
{
|
||||
Console.WriteLine(Element.ToString() + " " + Element.Parent);
|
||||
log.Info(Element.ToString() + " " + Element.Parent);
|
||||
}
|
||||
catch { }
|
||||
|
||||
@ -924,7 +926,7 @@ namespace ArdupilotMega.GCSViews
|
||||
drawnpolygons.Markers.Add(m);
|
||||
drawnpolygons.Markers.Add(mBorders);
|
||||
}
|
||||
catch (Exception ex) { Console.WriteLine(ex.ToString()); }
|
||||
catch (Exception ex) { log.Info(ex.ToString()); }
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
@ -1052,7 +1054,7 @@ namespace ArdupilotMega.GCSViews
|
||||
System.Diagnostics.Debug.WriteLine(temp - System.Diagnostics.Stopwatch.GetTimestamp());
|
||||
}
|
||||
}
|
||||
catch (Exception e) { Console.WriteLine("writekml - bad wp data " + e.ToString()); }
|
||||
catch (Exception e) { log.Info("writekml - bad wp data " + e.ToString()); }
|
||||
}
|
||||
|
||||
if (usable > 0)
|
||||
@ -1128,7 +1130,7 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
Console.WriteLine(ex.ToString());
|
||||
log.Info(ex.ToString());
|
||||
}
|
||||
|
||||
System.Diagnostics.Debug.WriteLine(DateTime.Now);
|
||||
@ -1193,69 +1195,82 @@ namespace ArdupilotMega.GCSViews
|
||||
/// <param name="sender"></param>
|
||||
/// <param name="e"></param>
|
||||
internal void BUT_read_Click(object sender, EventArgs e)
|
||||
{
|
||||
Controls.ProgressReporterDialogue frmProgressReporter = new Controls.ProgressReporterDialogue
|
||||
{
|
||||
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
|
||||
Text = "Receiving WP's"
|
||||
};
|
||||
|
||||
frmProgressReporter.DoWork += getWPs;
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Receiving WP's");
|
||||
|
||||
MainV2.fixtheme(frmProgressReporter);
|
||||
|
||||
frmProgressReporter.RunBackgroundOperationAsync();
|
||||
}
|
||||
|
||||
void getWPs(object sender, Controls.ProgressWorkerEventArgs e)
|
||||
{
|
||||
|
||||
List<Locationwp> cmds = new List<Locationwp>();
|
||||
int error = 0;
|
||||
|
||||
System.Threading.Thread t12 = new System.Threading.Thread(delegate()
|
||||
try
|
||||
{
|
||||
try
|
||||
MAVLink port = MainV2.comPort;
|
||||
|
||||
if (!port.BaseStream.IsOpen)
|
||||
{
|
||||
MAVLink port = MainV2.comPort;
|
||||
|
||||
if (!port.BaseStream.IsOpen)
|
||||
{
|
||||
throw new Exception("Please Connect First!");
|
||||
}
|
||||
|
||||
MainV2.givecomport = true;
|
||||
|
||||
param = port.param;
|
||||
|
||||
Console.WriteLine("Getting WP #");
|
||||
int cmdcount = port.getWPCount();
|
||||
|
||||
for (ushort a = 0; a < cmdcount; a++)
|
||||
{
|
||||
Console.WriteLine("Getting WP" + a);
|
||||
cmds.Add(port.getWP(a));
|
||||
}
|
||||
|
||||
port.setWPACK();
|
||||
|
||||
Console.WriteLine("Done");
|
||||
throw new Exception("Please Connect First!");
|
||||
}
|
||||
catch (Exception ex) { error = 1; MessageBox.Show("Error : " + ex.ToString()); }
|
||||
try
|
||||
|
||||
MainV2.givecomport = true;
|
||||
|
||||
param = port.param;
|
||||
|
||||
log.Info("Getting WP #");
|
||||
|
||||
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(0, "Getting WP count");
|
||||
|
||||
int cmdcount = port.getWPCount();
|
||||
|
||||
for (ushort a = 0; a < cmdcount; a++)
|
||||
{
|
||||
this.BeginInvoke((System.Threading.ThreadStart)delegate()
|
||||
log.Info("Getting WP" + a);
|
||||
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(a * 100 / cmdcount, "Getting WP " + a);
|
||||
cmds.Add(port.getWP(a));
|
||||
}
|
||||
|
||||
port.setWPACK();
|
||||
|
||||
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(100, "Done");
|
||||
|
||||
log.Info("Done");
|
||||
}
|
||||
catch (Exception ex) { error = 1; MessageBox.Show("Error : " + ex.ToString()); }
|
||||
try
|
||||
{
|
||||
this.BeginInvoke((MethodInvoker)delegate()
|
||||
{
|
||||
if (error == 0)
|
||||
{
|
||||
if (error == 0)
|
||||
try
|
||||
{
|
||||
try
|
||||
{
|
||||
processToScreen(cmds);
|
||||
}
|
||||
catch (Exception exx) { Console.WriteLine(exx.ToString()); }
|
||||
processToScreen(cmds);
|
||||
}
|
||||
catch (Exception exx) { log.Info(exx.ToString()); }
|
||||
}
|
||||
|
||||
MainV2.givecomport = false;
|
||||
MainV2.givecomport = false;
|
||||
|
||||
BUT_read.Enabled = true;
|
||||
BUT_read.Enabled = true;
|
||||
|
||||
writeKML();
|
||||
writeKML();
|
||||
|
||||
});
|
||||
}
|
||||
catch (Exception exx) { Console.WriteLine(exx.ToString()); }
|
||||
});
|
||||
t12.IsBackground = true;
|
||||
t12.Name = "Read wps";
|
||||
t12.Start();
|
||||
MainV2.threads.Add(t12);
|
||||
|
||||
BUT_read.Enabled = false;
|
||||
});
|
||||
}
|
||||
catch (Exception exx) { log.Info(exx.ToString()); }
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
@ -1290,111 +1305,118 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
}
|
||||
|
||||
System.Threading.Thread t12 = new System.Threading.Thread(delegate()
|
||||
Controls.ProgressReporterDialogue frmProgressReporter = new Controls.ProgressReporterDialogue
|
||||
{
|
||||
try
|
||||
{
|
||||
MAVLink port = MainV2.comPort;
|
||||
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
|
||||
Text = "Sending WP's"
|
||||
};
|
||||
|
||||
if (!port.BaseStream.IsOpen)
|
||||
{
|
||||
throw new Exception("Please Connect First!");
|
||||
}
|
||||
frmProgressReporter.DoWork += saveWPs;
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Sending WP's");
|
||||
|
||||
MainV2.givecomport = true;
|
||||
MainV2.fixtheme(frmProgressReporter);
|
||||
|
||||
Locationwp home = new Locationwp();
|
||||
frmProgressReporter.RunBackgroundOperationAsync();
|
||||
|
||||
try
|
||||
{
|
||||
home.id = (byte)MAVLink.MAV_CMD.WAYPOINT;
|
||||
home.lat = (float.Parse(TXT_homelat.Text));
|
||||
home.lng = (float.Parse(TXT_homelng.Text));
|
||||
home.alt = (float.Parse(TXT_homealt.Text) / MainV2.cs.multiplierdist); // use saved home
|
||||
}
|
||||
catch { throw new Exception("Your home location is invalid"); }
|
||||
|
||||
port.setWPTotal((ushort)(Commands.Rows.Count + 1)); // + home
|
||||
|
||||
port.setWP(home, (ushort)0, MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL, 0);
|
||||
|
||||
MAVLink.MAV_FRAME frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT;
|
||||
|
||||
// process grid to memory eeprom
|
||||
for (int a = 0; a < Commands.Rows.Count - 0; a++)
|
||||
{
|
||||
Locationwp temp = new Locationwp();
|
||||
temp.id = (byte)(int)Enum.Parse(typeof(MAVLink.MAV_CMD), Commands.Rows[a].Cells[Command.Index].Value.ToString(), false);
|
||||
temp.p1 = float.Parse(Commands.Rows[a].Cells[Param1.Index].Value.ToString());
|
||||
if (temp.id < (byte)MAVLink.MAV_CMD.LAST || temp.id == (byte)MAVLink.MAV_CMD.DO_SET_HOME)
|
||||
{
|
||||
if (CHK_altmode.Checked)
|
||||
{
|
||||
frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL;
|
||||
}
|
||||
else
|
||||
{
|
||||
frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT;
|
||||
}
|
||||
}
|
||||
|
||||
temp.alt = (float)(double.Parse(Commands.Rows[a].Cells[Alt.Index].Value.ToString()) / MainV2.cs.multiplierdist);
|
||||
temp.lat = (float)(double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()));
|
||||
temp.lng = (float)(double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()));
|
||||
|
||||
temp.p2 = (float)(double.Parse(Commands.Rows[a].Cells[Param2.Index].Value.ToString()));
|
||||
temp.p3 = (float)(double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()));
|
||||
temp.p4 = (float)(double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()));
|
||||
|
||||
port.setWP(temp, (ushort)(a + 1), frame, 0);
|
||||
}
|
||||
|
||||
port.setWPACK();
|
||||
|
||||
|
||||
if (CHK_holdalt.Checked)
|
||||
{
|
||||
port.setParam("ALT_HOLD_RTL", int.Parse(TXT_DefaultAlt.Text) / MainV2.cs.multiplierdist);
|
||||
}
|
||||
else
|
||||
{
|
||||
port.setParam("ALT_HOLD_RTL", -1);
|
||||
}
|
||||
|
||||
port.setParam("WP_RADIUS", (byte)int.Parse(TXT_WPRad.Text) / MainV2.cs.multiplierdist);
|
||||
|
||||
try
|
||||
{
|
||||
port.setParam("WP_LOITER_RAD", (byte)(int.Parse(TXT_loiterrad.Text) / MainV2.cs.multiplierdist));
|
||||
}
|
||||
catch
|
||||
{
|
||||
port.setParam("LOITER_RAD", (byte)int.Parse(TXT_loiterrad.Text) / MainV2.cs.multiplierdist);
|
||||
}
|
||||
|
||||
}
|
||||
catch (Exception ex) { MessageBox.Show("Error : " + ex.ToString()); }
|
||||
|
||||
MainV2.givecomport = false;
|
||||
|
||||
try
|
||||
{
|
||||
this.BeginInvoke((System.Threading.ThreadStart)delegate()
|
||||
{
|
||||
BUT_write.Enabled = true;
|
||||
});
|
||||
}
|
||||
catch { }
|
||||
|
||||
});
|
||||
t12.IsBackground = true;
|
||||
t12.Name = "Write wps";
|
||||
t12.Start();
|
||||
MainV2.threads.Add(t12);
|
||||
|
||||
MainMap.Focus();
|
||||
|
||||
BUT_write.Enabled = false;
|
||||
}
|
||||
|
||||
void saveWPs(object sender, Controls.ProgressWorkerEventArgs e)
|
||||
{
|
||||
try
|
||||
{
|
||||
MAVLink port = MainV2.comPort;
|
||||
|
||||
if (!port.BaseStream.IsOpen)
|
||||
{
|
||||
throw new Exception("Please Connect First!");
|
||||
}
|
||||
|
||||
MainV2.givecomport = true;
|
||||
|
||||
Locationwp home = new Locationwp();
|
||||
|
||||
try
|
||||
{
|
||||
home.id = (byte)MAVLink.MAV_CMD.WAYPOINT;
|
||||
home.lat = (float.Parse(TXT_homelat.Text));
|
||||
home.lng = (float.Parse(TXT_homelng.Text));
|
||||
home.alt = (float.Parse(TXT_homealt.Text) / MainV2.cs.multiplierdist); // use saved home
|
||||
}
|
||||
catch { throw new Exception("Your home location is invalid"); }
|
||||
|
||||
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(0, "Set Total WPs ");
|
||||
|
||||
port.setWPTotal((ushort)(Commands.Rows.Count + 1)); // + home
|
||||
|
||||
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(0, "Set Home");
|
||||
|
||||
port.setWP(home, (ushort)0, MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL, 0);
|
||||
|
||||
MAVLink.MAV_FRAME frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT;
|
||||
|
||||
// process grid to memory eeprom
|
||||
for (int a = 0; a < Commands.Rows.Count - 0; a++)
|
||||
{
|
||||
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(a * 100 / Commands.Rows.Count, "Setting WP " + a);
|
||||
|
||||
Locationwp temp = new Locationwp();
|
||||
temp.id = (byte)(int)Enum.Parse(typeof(MAVLink.MAV_CMD), Commands.Rows[a].Cells[Command.Index].Value.ToString(), false);
|
||||
temp.p1 = float.Parse(Commands.Rows[a].Cells[Param1.Index].Value.ToString());
|
||||
if (temp.id < (byte)MAVLink.MAV_CMD.LAST || temp.id == (byte)MAVLink.MAV_CMD.DO_SET_HOME)
|
||||
{
|
||||
if (CHK_altmode.Checked)
|
||||
{
|
||||
frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL;
|
||||
}
|
||||
else
|
||||
{
|
||||
frame = MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT;
|
||||
}
|
||||
}
|
||||
|
||||
temp.alt = (float)(double.Parse(Commands.Rows[a].Cells[Alt.Index].Value.ToString()) / MainV2.cs.multiplierdist);
|
||||
temp.lat = (float)(double.Parse(Commands.Rows[a].Cells[Lat.Index].Value.ToString()));
|
||||
temp.lng = (float)(double.Parse(Commands.Rows[a].Cells[Lon.Index].Value.ToString()));
|
||||
|
||||
temp.p2 = (float)(double.Parse(Commands.Rows[a].Cells[Param2.Index].Value.ToString()));
|
||||
temp.p3 = (float)(double.Parse(Commands.Rows[a].Cells[Param3.Index].Value.ToString()));
|
||||
temp.p4 = (float)(double.Parse(Commands.Rows[a].Cells[Param4.Index].Value.ToString()));
|
||||
|
||||
port.setWP(temp, (ushort)(a + 1), frame, 0);
|
||||
}
|
||||
|
||||
port.setWPACK();
|
||||
|
||||
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(95, "Setting Params");
|
||||
|
||||
if (CHK_holdalt.Checked)
|
||||
{
|
||||
port.setParam("ALT_HOLD_RTL", int.Parse(TXT_DefaultAlt.Text) / MainV2.cs.multiplierdist);
|
||||
}
|
||||
else
|
||||
{
|
||||
port.setParam("ALT_HOLD_RTL", -1);
|
||||
}
|
||||
|
||||
port.setParam("WP_RADIUS", (byte)int.Parse(TXT_WPRad.Text) / MainV2.cs.multiplierdist);
|
||||
|
||||
try
|
||||
{
|
||||
port.setParam("WP_LOITER_RAD", (byte)(int.Parse(TXT_loiterrad.Text) / MainV2.cs.multiplierdist));
|
||||
}
|
||||
catch
|
||||
{
|
||||
port.setParam("LOITER_RAD", (byte)int.Parse(TXT_loiterrad.Text) / MainV2.cs.multiplierdist);
|
||||
}
|
||||
|
||||
((Controls.ProgressReporterDialogue)sender).UpdateProgressAndStatus(100, "Done.");
|
||||
}
|
||||
catch (Exception ex) { MainV2.givecomport = false; throw ex; }
|
||||
|
||||
MainV2.givecomport = false;
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
@ -1486,29 +1508,44 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
}
|
||||
|
||||
log.Info("Setting wp params");
|
||||
|
||||
string hold_alt = ((int)((float)param["ALT_HOLD_RTL"] * MainV2.cs.multiplierdist)).ToString();
|
||||
|
||||
log.Info("param ALT_HOLD_RTL " + hold_alt);
|
||||
|
||||
if (!hold_alt.Equals("-1"))
|
||||
{
|
||||
TXT_DefaultAlt.Text = hold_alt;
|
||||
}
|
||||
|
||||
TXT_WPRad.Text = ((int)((float)param["WP_RADIUS"] * MainV2.cs.multiplierdist)).ToString();
|
||||
|
||||
log.Info("param WP_RADIUS " + TXT_WPRad.Text);
|
||||
|
||||
try
|
||||
{
|
||||
TXT_loiterrad.Text = ((int)((float)param["LOITER_RADIUS"] * MainV2.cs.multiplierdist)).ToString();
|
||||
if (param["LOITER_RADIUS"] != null)
|
||||
TXT_loiterrad.Text = ((int)((float)param["LOITER_RADIUS"] * MainV2.cs.multiplierdist)).ToString();
|
||||
|
||||
if (param["WP_LOITER_RAD"] != null)
|
||||
TXT_loiterrad.Text = ((int)((float)param["WP_LOITER_RAD"] * MainV2.cs.multiplierdist)).ToString();
|
||||
|
||||
log.Info("param LOITER_RADIUS " + TXT_loiterrad.Text);
|
||||
}
|
||||
catch
|
||||
{
|
||||
TXT_loiterrad.Text = ((int)((float)param["WP_LOITER_RAD"] * MainV2.cs.multiplierdist)).ToString();
|
||||
|
||||
}
|
||||
CHK_holdalt.Checked = Convert.ToBoolean((float)param["ALT_HOLD_RTL"] > 0);
|
||||
log.Info("param ALT_HOLD_RTL " + CHK_holdalt.Checked.ToString());
|
||||
|
||||
}
|
||||
catch (Exception) { } // if there is no valid home
|
||||
catch (Exception ex) { log.Info(ex.ToString()); } // if there is no valid home
|
||||
|
||||
if (Commands.RowCount > 0)
|
||||
{
|
||||
log.Info("remove home from list");
|
||||
Commands.Rows.Remove(Commands.Rows[0]); // remove home row
|
||||
}
|
||||
|
||||
@ -2523,7 +2560,7 @@ namespace ArdupilotMega.GCSViews
|
||||
double x = bottomleft.Lat - Math.Abs(fulllatdiff);
|
||||
double y = bottomleft.Lng - Math.Abs(fulllngdiff);
|
||||
|
||||
Console.WriteLine("{0} < {1} {2} < {3}", x, (topright.Lat), y, (topright.Lng));
|
||||
log.InfoFormat("{0} < {1} {2} < {3}", x, (topright.Lat), y, (topright.Lng));
|
||||
|
||||
while (x < (topright.Lat + Math.Abs(fulllatdiff)) && y < (topright.Lng + Math.Abs(fulllngdiff)))
|
||||
{
|
||||
|
@ -24,7 +24,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
public void BUT_updatecheck_Click(object sender, EventArgs e)
|
||||
{
|
||||
MainV2.doupdate();
|
||||
MainV2.DoUpdate();
|
||||
}
|
||||
|
||||
private void CHK_showconsole_CheckedChanged(object sender, EventArgs e)
|
||||
|
@ -9,6 +9,7 @@ using System.IO.Ports;
|
||||
using System.IO;
|
||||
using System.Xml; // config file
|
||||
using System.Runtime.InteropServices; // dll imports
|
||||
using log4net;
|
||||
using ZedGraph; // Graphs
|
||||
using ArdupilotMega;
|
||||
using ArdupilotMega.Mavlink;
|
||||
@ -21,6 +22,7 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
public partial class Simulation : MyUserControl
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
MAVLink comPort = MainV2.comPort;
|
||||
UdpClient XplanesSEND;
|
||||
UdpClient MavLink;
|
||||
@ -570,7 +572,6 @@ namespace ArdupilotMega.GCSViews
|
||||
// re-request servo data
|
||||
if (!(lastdata.AddSeconds(8) > DateTime.Now))
|
||||
{
|
||||
Console.WriteLine("REQ streams - sim");
|
||||
try
|
||||
{
|
||||
if (CHK_quad.Checked && !RAD_aerosimrc.Checked)// || chkSensor.Checked && RAD_JSBSim.Checked)
|
||||
@ -610,12 +611,6 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
Byte[] receiveBytes = MavLink.Receive(ref RemoteIpEndPoint);
|
||||
|
||||
Console.WriteLine("sending " + receiveBytes[5]);
|
||||
|
||||
if (receiveBytes[5] == 39)
|
||||
{
|
||||
Console.WriteLine("wp no " + receiveBytes[9]); // ??
|
||||
}
|
||||
|
||||
comPort.BaseStream.Write(receiveBytes, 0, receiveBytes.Length);
|
||||
}
|
||||
@ -633,7 +628,7 @@ namespace ArdupilotMega.GCSViews
|
||||
processArduPilot();
|
||||
}
|
||||
}
|
||||
catch (Exception ex) { Console.WriteLine("SIM Main loop exception " + ex.ToString()); }
|
||||
catch (Exception ex) { log.Info("SIM Main loop exception " + ex.ToString()); }
|
||||
|
||||
if (hzcounttime.Second != DateTime.Now.Second)
|
||||
{
|
||||
@ -689,7 +684,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
JSBSimSEND.Client.Send(System.Text.Encoding.ASCII.GetBytes("resume\r\n"));
|
||||
}
|
||||
catch { Console.WriteLine("JSB console fail"); }
|
||||
catch { log.Info("JSB console fail"); }
|
||||
}
|
||||
|
||||
private void SetupUDPXplanes()
|
||||
@ -1348,7 +1343,7 @@ namespace ArdupilotMega.GCSViews
|
||||
|
||||
quad.update(ref m, lastfdmdata);
|
||||
}
|
||||
catch (Exception e) { Console.WriteLine("Quad hill error " + e.ToString()); }
|
||||
catch (Exception e) { log.Info("Quad hill error " + e.ToString()); }
|
||||
|
||||
byte[] FlightGear = new byte[8 * 11];// StructureToByteArray(fg);
|
||||
|
||||
@ -1385,7 +1380,7 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
XplanesSEND.Send(FlightGear, FlightGear.Length);
|
||||
}
|
||||
catch (Exception) { Console.WriteLine("Socket Write failed, FG closed?"); }
|
||||
catch (Exception) { log.Info("Socket Write failed, FG closed?"); }
|
||||
|
||||
updateScreenDisplay(lastfdmdata.latitude, lastfdmdata.longitude, lastfdmdata.altitude * .3048, lastfdmdata.phi, lastfdmdata.theta, lastfdmdata.psi, lastfdmdata.psi, m[0], m[1], m[2], m[3]);
|
||||
|
||||
@ -1491,7 +1486,7 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
}
|
||||
}
|
||||
catch (Exception e) { Console.WriteLine("Error updateing screen stuff " + e.ToString()); }
|
||||
catch (Exception e) { log.Info("Error updateing screen stuff " + e.ToString()); }
|
||||
|
||||
packetssent++;
|
||||
|
||||
@ -1580,7 +1575,7 @@ namespace ArdupilotMega.GCSViews
|
||||
{
|
||||
XplanesSEND.Send(FlightGear, FlightGear.Length);
|
||||
}
|
||||
catch (Exception) { Console.WriteLine("Socket Write failed, FG closed?"); }
|
||||
catch (Exception) { log.Info("Socket Write failed, FG closed?"); }
|
||||
|
||||
}
|
||||
|
||||
@ -1661,7 +1656,7 @@ namespace ArdupilotMega.GCSViews
|
||||
XplanesSEND.Send(Xplane, Xplane.Length);
|
||||
|
||||
}
|
||||
catch (Exception e) { Console.WriteLine("Xplanes udp send error " + e.Message); }
|
||||
catch (Exception e) { log.Info("Xplanes udp send error " + e.Message); }
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -122,7 +122,7 @@
|
||||
<value>86, 17</value>
|
||||
</data>
|
||||
<data name="CHKREV_roll.Text" xml:space="preserve">
|
||||
<value>横滚舵反向</value>
|
||||
<value>侧倾舵反向</value>
|
||||
</data>
|
||||
<data name="CHKREV_roll.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
@ -278,7 +278,7 @@
|
||||
<value>31, 13</value>
|
||||
</data>
|
||||
<data name="label5.Text" xml:space="preserve">
|
||||
<value>横滚</value>
|
||||
<value>侧倾</value>
|
||||
</data>
|
||||
<data name="label5.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
@ -350,7 +350,7 @@
|
||||
<value>31, 13</value>
|
||||
</data>
|
||||
<data name="label12.Text" xml:space="preserve">
|
||||
<value>横滚</value>
|
||||
<value>侧倾</value>
|
||||
</data>
|
||||
<data name="label12.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
@ -464,7 +464,7 @@
|
||||
<value>55, 13</value>
|
||||
</data>
|
||||
<data name="label22.Text" xml:space="preserve">
|
||||
<value>横滚增益</value>
|
||||
<value>侧倾增益</value>
|
||||
</data>
|
||||
<data name="label22.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
@ -505,15 +505,36 @@
|
||||
<data name="CHKdisplayall.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="CHKgraphroll.Text" xml:space="preserve">
|
||||
<value>显示侧倾</value>
|
||||
</data>
|
||||
<data name="CHKgraphroll.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="CHKgraphpitch.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>74, 17</value>
|
||||
</data>
|
||||
<data name="CHKgraphpitch.Text" xml:space="preserve">
|
||||
<value>显示俯仰</value>
|
||||
</data>
|
||||
<data name="CHKgraphpitch.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="CHKgraphrudder.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>86, 17</value>
|
||||
</data>
|
||||
<data name="CHKgraphrudder.Text" xml:space="preserve">
|
||||
<value>显示方向舵</value>
|
||||
</data>
|
||||
<data name="CHKgraphrudder.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="CHKgraphthrottle.Size" type="System.Drawing.Size, System.Drawing">
|
||||
<value>74, 17</value>
|
||||
</data>
|
||||
<data name="CHKgraphthrottle.Text" xml:space="preserve">
|
||||
<value>显示油门</value>
|
||||
</data>
|
||||
<data name="CHKgraphthrottle.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
@ -568,6 +589,9 @@
|
||||
<data name="CHK_heli.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="CHK_xplane10.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
<data name="$this.ToolTip" xml:space="preserve">
|
||||
<value />
|
||||
</data>
|
||||
|
@ -146,7 +146,11 @@ namespace ArdupilotMega.GCSViews
|
||||
}
|
||||
}
|
||||
// do not change this \r is correct - no \n
|
||||
if (cmd == "+++")
|
||||
comPort.Write(Encoding.ASCII.GetBytes(cmd), 0, cmd.Length);
|
||||
else {
|
||||
comPort.Write(Encoding.ASCII.GetBytes(cmd + "\r"), 0, cmd.Length + 1);
|
||||
}
|
||||
}
|
||||
catch { MessageBox.Show("Error writing to com port"); }
|
||||
}
|
||||
|
@ -1,7 +1,9 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Reflection;
|
||||
using System.Text;
|
||||
using log4net;
|
||||
using YLScsDrawing.Drawing3d;
|
||||
using ArdupilotMega.HIL;
|
||||
|
||||
@ -101,6 +103,7 @@ namespace ArdupilotMega.HIL
|
||||
|
||||
public class QuadCopter : Aircraft
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
QuadCopter self;
|
||||
|
||||
int framecount = 0;
|
||||
|
@ -11,7 +11,7 @@ using System.Drawing.Imaging;
|
||||
using System.Threading;
|
||||
|
||||
using System.Drawing.Drawing2D;
|
||||
|
||||
using log4net;
|
||||
using OpenTK;
|
||||
using OpenTK.Graphics.OpenGL;
|
||||
using OpenTK.Graphics;
|
||||
@ -24,6 +24,8 @@ namespace hud
|
||||
{
|
||||
public class HUD : GLControl
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(
|
||||
System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
|
||||
object paintlock = new object();
|
||||
object streamlock = new object();
|
||||
MemoryStream _streamjpg = new MemoryStream();
|
||||
@ -44,6 +46,8 @@ namespace hud
|
||||
|
||||
bool started = false;
|
||||
|
||||
public bool SixteenXNine = false;
|
||||
|
||||
public HUD()
|
||||
{
|
||||
if (this.DesignMode)
|
||||
@ -189,10 +193,10 @@ namespace hud
|
||||
{
|
||||
|
||||
GraphicsMode test = this.GraphicsMode;
|
||||
Console.WriteLine(test.ToString());
|
||||
Console.WriteLine("Vendor: " + GL.GetString(StringName.Vendor));
|
||||
Console.WriteLine("Version: " + GL.GetString(StringName.Version));
|
||||
Console.WriteLine("Device: " + GL.GetString(StringName.Renderer));
|
||||
log.Info(test.ToString());
|
||||
log.Info("Vendor: " + GL.GetString(StringName.Vendor));
|
||||
log.Info("Version: " + GL.GetString(StringName.Version));
|
||||
log.Info("Device: " + GL.GetString(StringName.Renderer));
|
||||
//Console.WriteLine("Extensions: " + GL.GetString(StringName.Extensions));
|
||||
|
||||
int[] viewPort = new int[4];
|
||||
@ -212,7 +216,7 @@ namespace hud
|
||||
GL.Enable(EnableCap.Blend);
|
||||
|
||||
}
|
||||
catch (Exception ex) { Console.WriteLine("HUD opengl onload " + ex.ToString()); }
|
||||
catch (Exception ex) { log.Info("HUD opengl onload " + ex.ToString()); }
|
||||
|
||||
try
|
||||
{
|
||||
@ -266,7 +270,7 @@ namespace hud
|
||||
|
||||
if (inOnPaint)
|
||||
{
|
||||
Console.WriteLine("Was in onpaint Hud th:" + System.Threading.Thread.CurrentThread.Name + " in " + otherthread);
|
||||
log.Info("Was in onpaint Hud th:" + System.Threading.Thread.CurrentThread.Name + " in " + otherthread);
|
||||
return;
|
||||
}
|
||||
|
||||
@ -295,7 +299,7 @@ namespace hud
|
||||
}
|
||||
|
||||
}
|
||||
catch (Exception ex) { Console.WriteLine(ex.ToString()); }
|
||||
catch (Exception ex) { log.Info(ex.ToString()); }
|
||||
|
||||
inOnPaint = false;
|
||||
|
||||
@ -676,6 +680,7 @@ namespace hud
|
||||
|
||||
void doPaint(PaintEventArgs e)
|
||||
{
|
||||
bool isNaN = false;
|
||||
try
|
||||
{
|
||||
if (graphicsObjectGDIP == null || !opengl && (objBitmap.Width != this.Width || objBitmap.Height != this.Height))
|
||||
@ -709,9 +714,22 @@ namespace hud
|
||||
bgon = true;
|
||||
}
|
||||
|
||||
|
||||
if (float.IsNaN(_roll) || float.IsNaN(_pitch) || float.IsNaN(_heading))
|
||||
{
|
||||
isNaN = true;
|
||||
|
||||
_roll = 0;
|
||||
_pitch = 0;
|
||||
_heading = 0;
|
||||
}
|
||||
|
||||
graphicsObject.TranslateTransform(this.Width / 2, this.Height / 2);
|
||||
|
||||
graphicsObject.RotateTransform(-_roll);
|
||||
|
||||
|
||||
graphicsObject.RotateTransform(-_roll);
|
||||
|
||||
|
||||
int fontsize = this.Height / 30; // = 10
|
||||
int fontoffset = fontsize - 10;
|
||||
@ -1272,6 +1290,11 @@ namespace hud
|
||||
|
||||
drawstring(graphicsObject, gps, font, fontsize + 2, whiteBrush, this.Width - 10 * fontsize, this.Height - 30 - fontoffset);
|
||||
|
||||
|
||||
if (isNaN)
|
||||
drawstring(graphicsObject, "NaN Error " + DateTime.Now, font, this.Height / 30 + 10, Brushes.Red, 50, 50);
|
||||
|
||||
|
||||
if (!opengl)
|
||||
{
|
||||
e.Graphics.DrawImageUnscaled(objBitmap, 0, 0);
|
||||
@ -1304,8 +1327,7 @@ namespace hud
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
Console.WriteLine("hud error "+ex.ToString());
|
||||
//MessageBox.Show(ex.ToString());
|
||||
log.Info("hud error "+ex.ToString());
|
||||
}
|
||||
}
|
||||
|
||||
@ -1513,7 +1535,7 @@ namespace hud
|
||||
base.OnHandleCreated(e);
|
||||
}
|
||||
}
|
||||
catch (Exception ex) { Console.WriteLine(ex.ToString()); opengl = false; } // macs fail here
|
||||
catch (Exception ex) { log.Info(ex.ToString()); opengl = false; } // macs fail here
|
||||
}
|
||||
|
||||
protected override void OnHandleDestroyed(EventArgs e)
|
||||
@ -1525,14 +1547,25 @@ namespace hud
|
||||
base.OnHandleDestroyed(e);
|
||||
}
|
||||
}
|
||||
catch (Exception ex) { Console.WriteLine(ex.ToString()); opengl = false; }
|
||||
catch (Exception ex) { log.Info(ex.ToString()); opengl = false; }
|
||||
}
|
||||
|
||||
protected override void OnResize(EventArgs e)
|
||||
{
|
||||
if (DesignMode || !started)
|
||||
return;
|
||||
this.Height = (int)(this.Width / 1.333f);
|
||||
|
||||
|
||||
if (SixteenXNine)
|
||||
{
|
||||
this.Height = (int)(this.Width / 1.777f);
|
||||
}
|
||||
else
|
||||
{
|
||||
// 4x3
|
||||
this.Height = (int)(this.Width / 1.333f);
|
||||
}
|
||||
|
||||
base.OnResize(e);
|
||||
|
||||
graphicsObjectGDIP = Graphics.FromImage(objBitmap);
|
||||
|
@ -3,6 +3,7 @@ using System.Collections.Generic;
|
||||
using System.Collections;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using log4net;
|
||||
using Microsoft.DirectX.DirectInput;
|
||||
using System.Reflection;
|
||||
|
||||
@ -10,6 +11,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
public class Joystick
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
Device joystick;
|
||||
JoystickState state;
|
||||
public bool enabled = false;
|
||||
@ -148,12 +150,12 @@ namespace ArdupilotMega
|
||||
{
|
||||
//Console.WriteLine("Name: " + property.Name + ", Value: " + property.GetValue(obj, null));
|
||||
|
||||
Console.WriteLine("test name {0} old {1} new {2} ", property.Name, values[property.Name], int.Parse(property.GetValue(nextstate, null).ToString()));
|
||||
Console.WriteLine("{0} {1}", (int)values[property.Name], (int.Parse(property.GetValue(nextstate, null).ToString()) + threshold));
|
||||
log.InfoFormat("test name {0} old {1} new {2} ", property.Name, values[property.Name], int.Parse(property.GetValue(nextstate, null).ToString()));
|
||||
log.InfoFormat("{0} {1}", (int)values[property.Name], (int.Parse(property.GetValue(nextstate, null).ToString()) + threshold));
|
||||
if ((int)values[property.Name] > (int.Parse(property.GetValue(nextstate, null).ToString()) + threshold) ||
|
||||
(int)values[property.Name] < (int.Parse(property.GetValue(nextstate, null).ToString()) - threshold))
|
||||
{
|
||||
Console.WriteLine("{0}", property.Name);
|
||||
log.Info(property.Name);
|
||||
joystick.Unacquire();
|
||||
return (joystickaxis)Enum.Parse(typeof(joystickaxis), property.Name);
|
||||
}
|
||||
@ -337,7 +339,7 @@ namespace ArdupilotMega
|
||||
|
||||
//Console.WriteLine("{0} {1} {2} {3}", MainV2.cs.rcoverridech1, MainV2.cs.rcoverridech2, MainV2.cs.rcoverridech3, MainV2.cs.rcoverridech4);
|
||||
}
|
||||
catch (Exception ex) { Console.WriteLine("Joystick thread error "+ex.ToString()); } // so we cant fall out
|
||||
catch (Exception ex) { log.Info("Joystick thread error "+ex.ToString()); } // so we cant fall out
|
||||
}
|
||||
}
|
||||
|
||||
@ -484,7 +486,7 @@ namespace ArdupilotMega
|
||||
state = joystick.CurrentJoystickState;
|
||||
|
||||
ushort ans = pickchannel(channel, JoyChannels[channel].axis, JoyChannels[channel].reverse, JoyChannels[channel].expo);
|
||||
Console.WriteLine("{0} = {1} = {2}",channel,ans, state.X);
|
||||
log.DebugFormat("{0} = {1} = {2}",channel,ans, state.X);
|
||||
return ans;
|
||||
}
|
||||
|
||||
|
64
Tools/ArdupilotMegaPlanner/LangUtility.cs
Normal file
64
Tools/ArdupilotMegaPlanner/LangUtility.cs
Normal file
@ -0,0 +1,64 @@
|
||||
//this file contains some simple extension methods
|
||||
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Globalization;
|
||||
using System.ComponentModel;
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
static class CultureInfoEx
|
||||
{
|
||||
public static CultureInfo GetCultureInfo(string name)
|
||||
{
|
||||
try { return new CultureInfo(name); }
|
||||
catch (Exception) { return null; }
|
||||
}
|
||||
|
||||
public static bool IsChildOf(this CultureInfo cX, CultureInfo cY)
|
||||
{
|
||||
|
||||
if (cX == null || cY == null)
|
||||
return false;
|
||||
|
||||
CultureInfo c = cX;
|
||||
while (!c.Equals(CultureInfo.InvariantCulture))
|
||||
{
|
||||
if (c.Equals(cY))
|
||||
return true;
|
||||
c = c.Parent;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
static class ComponentResourceManagerEx
|
||||
{
|
||||
public static void ApplyResource(this ComponentResourceManager rm, Control ctrl)
|
||||
{
|
||||
rm.ApplyResources(ctrl, ctrl.Name);
|
||||
foreach (Control subctrl in ctrl.Controls)
|
||||
ApplyResource(rm, subctrl);
|
||||
|
||||
if (ctrl.ContextMenu != null)
|
||||
ApplyResource(rm, ctrl.ContextMenu);
|
||||
|
||||
|
||||
if (ctrl is DataGridView)
|
||||
{
|
||||
foreach (DataGridViewColumn col in (ctrl as DataGridView).Columns)
|
||||
rm.ApplyResources(col, col.Name);
|
||||
}
|
||||
}
|
||||
|
||||
public static void ApplyResource(this ComponentResourceManager rm, Menu menu)
|
||||
{
|
||||
rm.ApplyResources(menu, menu.Name);
|
||||
foreach (MenuItem submenu in menu.MenuItems)
|
||||
ApplyResource(rm, submenu);
|
||||
}
|
||||
}
|
||||
}
|
@ -3,6 +3,7 @@ using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Data;
|
||||
using System.Drawing;
|
||||
using System.Reflection;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using System.IO.Ports;
|
||||
@ -15,16 +16,17 @@ using Core.Geometry;
|
||||
using ICSharpCode.SharpZipLib.Zip;
|
||||
using ICSharpCode.SharpZipLib.Checksums;
|
||||
using ICSharpCode.SharpZipLib.Core;
|
||||
using log4net;
|
||||
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public partial class Log : Form
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
ICommsSerial comPort;
|
||||
int logcount = 0;
|
||||
serialstatus status = serialstatus.Connecting;
|
||||
byte[] buffer = new byte[4000];
|
||||
StreamWriter sw;
|
||||
int currentlog = 0;
|
||||
bool threadrun = true;
|
||||
@ -72,14 +74,15 @@ namespace ArdupilotMega
|
||||
comPort.toggleDTR();
|
||||
//comPort.Open();
|
||||
}
|
||||
catch (Exception)
|
||||
catch (Exception ex)
|
||||
{
|
||||
log.Error("Error opening comport", ex);
|
||||
MessageBox.Show("Error opening comport");
|
||||
}
|
||||
|
||||
System.Threading.Thread t11 = new System.Threading.Thread(delegate()
|
||||
var t11 = new System.Threading.Thread(delegate()
|
||||
{
|
||||
DateTime start = DateTime.Now;
|
||||
var start = DateTime.Now;
|
||||
|
||||
threadrun = true;
|
||||
|
||||
@ -87,9 +90,11 @@ namespace ArdupilotMega
|
||||
|
||||
try
|
||||
{
|
||||
comPort.Write("\n\n\n\n");
|
||||
comPort.Write("\n\n\n\n"); // more in "connecting"
|
||||
}
|
||||
catch
|
||||
{
|
||||
}
|
||||
catch { }
|
||||
|
||||
while (threadrun)
|
||||
{
|
||||
@ -105,11 +110,13 @@ namespace ArdupilotMega
|
||||
comPort_DataReceived((object)null, (SerialDataReceivedEventArgs)null);
|
||||
}
|
||||
}
|
||||
catch (Exception ex) { Console.WriteLine("crash in comport reader " + ex.ToString()); } // cant exit unless told to
|
||||
catch (Exception ex)
|
||||
{
|
||||
log.Error("crash in comport reader " + ex);
|
||||
} // cant exit unless told to
|
||||
}
|
||||
Console.WriteLine("Comport thread close");
|
||||
});
|
||||
t11.Name = "comport reader";
|
||||
log.Info("Comport thread close");
|
||||
}) {Name = "comport reader"};
|
||||
t11.Start();
|
||||
MainV2.threads.Add(t11);
|
||||
|
||||
@ -187,8 +194,14 @@ namespace ArdupilotMega
|
||||
{
|
||||
case serialstatus.Connecting:
|
||||
|
||||
if (line.Contains("reset to FLY") || line.Contains("interactive setup") || line.Contains("CLI:") || line.Contains("Ardu"))
|
||||
if (line.Contains("ENTER") || line.Contains("GROUND START") || line.Contains("reset to FLY") || line.Contains("interactive setup") || line.Contains("CLI") || line.Contains("Ardu"))
|
||||
{
|
||||
try
|
||||
{
|
||||
comPort.Write("\n\n\n\n");
|
||||
}
|
||||
catch { }
|
||||
|
||||
comPort.Write("logs\r");
|
||||
status = serialstatus.Done;
|
||||
}
|
||||
@ -276,7 +289,7 @@ namespace ArdupilotMega
|
||||
|
||||
Console.Write(line);
|
||||
|
||||
TXT_seriallog.AppendText(line);
|
||||
TXT_seriallog.AppendText(line.Replace((char)0x0,' '));
|
||||
|
||||
// auto scroll
|
||||
if (TXT_seriallog.TextLength >= 10000)
|
||||
@ -297,7 +310,7 @@ namespace ArdupilotMega
|
||||
}
|
||||
}
|
||||
|
||||
Console.WriteLine("exit while");
|
||||
log.Info("exit while");
|
||||
}
|
||||
catch (Exception ex) { MessageBox.Show("Error reading data" + ex.ToString()); }
|
||||
}
|
||||
@ -526,7 +539,7 @@ namespace ArdupilotMega
|
||||
|
||||
Style style2 = new Style();
|
||||
Color color = Color.FromArgb(0xff, (stylecode >> 16) & 0xff, (stylecode >> 8) & 0xff, (stylecode >> 0) & 0xff);
|
||||
Console.WriteLine("colour " + color.ToArgb().ToString("X") + " " + color.ToKnownColor().ToString());
|
||||
log.Info("colour " + color.ToArgb().ToString("X") + " " + color.ToKnownColor().ToString());
|
||||
style2.Add(new LineStyle(color, 4));
|
||||
|
||||
|
||||
|
@ -3,9 +3,11 @@ using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Data;
|
||||
using System.Drawing;
|
||||
using System.Reflection;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using System.IO;
|
||||
using log4net;
|
||||
using ZedGraph; // Graphs
|
||||
using System.Xml;
|
||||
|
||||
@ -13,6 +15,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
public partial class LogBrowse : Form
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
int m_iColumnCount = 0;
|
||||
DataTable m_dtCSV = new DataTable();
|
||||
|
||||
@ -180,7 +183,7 @@ namespace ArdupilotMega
|
||||
if (inner.Name.StartsWith("F"))
|
||||
{
|
||||
dataGridView1.Columns[a].HeaderText = inner.ReadString();
|
||||
Console.WriteLine(a + " " + dataGridView1.Columns[a].HeaderText);
|
||||
log.Info(a + " " + dataGridView1.Columns[a].HeaderText);
|
||||
a++;
|
||||
}
|
||||
|
||||
@ -194,7 +197,7 @@ namespace ArdupilotMega
|
||||
|
||||
}
|
||||
}
|
||||
catch { Console.WriteLine("DGV logbrowse error"); }
|
||||
catch { log.Info("DGV logbrowse error"); }
|
||||
}
|
||||
|
||||
public void CreateChart(ZedGraphControl zgc)
|
||||
@ -308,7 +311,7 @@ namespace ArdupilotMega
|
||||
break;
|
||||
}
|
||||
}
|
||||
catch { error++; Console.WriteLine("Bad Data : " + type + " " + col + " " + a); if (error >= 500) { MessageBox.Show("There is to much bad data - failing"); break; } }
|
||||
catch { error++; log.Info("Bad Data : " + type + " " + col + " " + a); if (error >= 500) { MessageBox.Show("There is to much bad data - failing"); break; } }
|
||||
}
|
||||
a++;
|
||||
}
|
||||
|
@ -9,25 +9,25 @@ using System.Reflection;
|
||||
using System.Reflection.Emit;
|
||||
using System.IO;
|
||||
using System.Drawing;
|
||||
using System.Threading;
|
||||
using ArdupilotMega.Controls;
|
||||
using ArdupilotMega.Mavlink;
|
||||
using System.ComponentModel;
|
||||
using log4net;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public partial class MAVLink
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
public ICommsSerial BaseStream = new SerialPort();
|
||||
|
||||
private const double CONNECT_TIMEOUT_SECONDS = 30;
|
||||
|
||||
/// <summary>
|
||||
/// Used for progress reporting on all internal functions
|
||||
/// </summary>
|
||||
public event ProgressEventHandler Progress;
|
||||
/// <summary>
|
||||
/// progress form to handle connect and param requests
|
||||
/// </summary>
|
||||
ProgressReporter frm;
|
||||
ProgressReporterDialogue frmProgressReporter;
|
||||
|
||||
/// <summary>
|
||||
/// used for outbound packet sending
|
||||
@ -131,22 +131,39 @@ namespace ArdupilotMega
|
||||
if (BaseStream.IsOpen)
|
||||
return;
|
||||
|
||||
//System.Windows.Forms.Form frm = Common.LoadingBox("Mavlink Connecting..", "Mavlink Connecting..");
|
||||
//frm.TopMost = true;
|
||||
frmProgressReporter = new ProgressReporterDialogue
|
||||
{
|
||||
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
|
||||
Text = "Connecting Mavlink"
|
||||
};
|
||||
|
||||
frm = new ProgressReporter();
|
||||
MainV2.fixtheme(frm);
|
||||
this.Progress += new ProgressEventHandler(MAVLink_Progress);
|
||||
//(progress, status) => { frm.updateProgressAndStatus(progress, status); };
|
||||
if (getparams)
|
||||
{
|
||||
frmProgressReporter.DoWork += FrmProgressReporterDoWorkAndParams;
|
||||
}
|
||||
else
|
||||
{
|
||||
frmProgressReporter.DoWork += FrmProgressReporterDoWorkNOParams;
|
||||
}
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Mavlink Connecting...");
|
||||
MainV2.fixtheme(frmProgressReporter);
|
||||
|
||||
frm.StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen;
|
||||
frmProgressReporter.RunBackgroundOperationAsync();
|
||||
}
|
||||
|
||||
frm.Show();
|
||||
void FrmProgressReporterDoWorkAndParams(object sender, ProgressWorkerEventArgs e)
|
||||
{
|
||||
OpenBg(true, e);
|
||||
}
|
||||
|
||||
frm.Focus();
|
||||
void FrmProgressReporterDoWorkNOParams(object sender, ProgressWorkerEventArgs e)
|
||||
{
|
||||
OpenBg(false, e);
|
||||
}
|
||||
|
||||
if (Progress != null)
|
||||
Progress(-1, "Mavlink Connecting...");
|
||||
private void OpenBg(bool getparams, ProgressWorkerEventArgs progressWorkerEventArgs)
|
||||
{
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Mavlink Connecting...");
|
||||
|
||||
// reset
|
||||
sysid = 0;
|
||||
@ -161,6 +178,7 @@ namespace ArdupilotMega
|
||||
|
||||
lock (objlock) // so we dont have random traffic
|
||||
{
|
||||
log.Info("Open port with " + BaseStream.PortName + " " + BaseStream.BaudRate);
|
||||
|
||||
BaseStream.Open();
|
||||
|
||||
@ -168,15 +186,7 @@ namespace ArdupilotMega
|
||||
|
||||
BaseStream.toggleDTR();
|
||||
|
||||
// allow 2560 connect timeout on usb
|
||||
for (int a = 0; a < 1000; a++ ) {
|
||||
System.Threading.Thread.Sleep(1);
|
||||
if (!MainV2.instance.InvokeRequired)
|
||||
{
|
||||
System.Windows.Forms.Application.DoEvents();
|
||||
}
|
||||
}
|
||||
|
||||
Thread.Sleep(1000);
|
||||
}
|
||||
|
||||
byte[] buffer;
|
||||
@ -189,8 +199,9 @@ namespace ArdupilotMega
|
||||
countDown.Elapsed += (sender, e) =>
|
||||
{
|
||||
int secondsRemaining = (deadline - e.SignalTime).Seconds;
|
||||
if (Progress != null)
|
||||
Progress(-1, string.Format("Trying to connect.\nTimeout in {0}", secondsRemaining));
|
||||
//if (Progress != null)
|
||||
// Progress(-1, string.Format("Trying to connect.\nTimeout in {0}", secondsRemaining));
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, string.Format("Trying to connect.\nTimeout in {0}", secondsRemaining));
|
||||
if (secondsRemaining > 0) countDown.Start();
|
||||
};
|
||||
countDown.Start();
|
||||
@ -199,31 +210,35 @@ namespace ArdupilotMega
|
||||
|
||||
while (true)
|
||||
{
|
||||
if (progressWorkerEventArgs.CancelRequested)
|
||||
{
|
||||
progressWorkerEventArgs.CancelAcknowledged = true;
|
||||
countDown.Stop();
|
||||
if (BaseStream.IsOpen)
|
||||
BaseStream.Close();
|
||||
MainV2.givecomport = false;
|
||||
return;
|
||||
}
|
||||
|
||||
// incase we are in setup mode
|
||||
BaseStream.WriteLine("planner\rgcs\r");
|
||||
|
||||
Console.WriteLine(DateTime.Now.Millisecond + " start ");
|
||||
|
||||
/*
|
||||
if (Progress != null)
|
||||
{
|
||||
int secondsRemaining = (start.AddSeconds(CONNECT_TIMEOUT_SECONDS) - DateTime.Now).Seconds;
|
||||
Progress(-1, string.Format("Trying to connect.\nTimeout in {0}", secondsRemaining));
|
||||
}
|
||||
*/
|
||||
log.Info(DateTime.Now.Millisecond + " Start connect loop ");
|
||||
|
||||
if (lastbad[0] == '!' && lastbad[1] == 'G' || lastbad[0] == 'G' && lastbad[1] == '!') // waiting for gps lock
|
||||
{
|
||||
if (Progress != null)
|
||||
Progress(-1, "Waiting for GPS detection..");
|
||||
start = start.AddSeconds(5); // each round is 1.1 seconds
|
||||
//if (Progress != null)
|
||||
// Progress(-1, "Waiting for GPS detection..");
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Waiting for GPS detection..");
|
||||
deadline = deadline.AddSeconds(5); // each round is 1.1 seconds
|
||||
}
|
||||
|
||||
if (DateTime.Now > deadline)
|
||||
{
|
||||
if (Progress != null)
|
||||
Progress(-1, "No Heatbeat Packets");
|
||||
//if (Progress != null)
|
||||
// Progress(-1, "No Heatbeat Packets");
|
||||
this.Close();
|
||||
progressWorkerEventArgs.ErrorMessage = "No Heatbeat Packets Received";
|
||||
throw new Exception("No Mavlink Heartbeat Packets where read from this port - Verify Baud Rate and setup\nIt might also be waiting for GPS Lock\nAPM Planner waits for 2 valid heartbeat packets before connecting");
|
||||
}
|
||||
|
||||
@ -243,7 +258,7 @@ namespace ArdupilotMega
|
||||
|
||||
try
|
||||
{
|
||||
Console.WriteLine("MAv Data: len " + buffer.Length + " btr " + BaseStream.BytesToRead);
|
||||
log.Debug("MAv Data: len " + buffer.Length + " btr " + BaseStream.BytesToRead);
|
||||
}
|
||||
catch { }
|
||||
|
||||
@ -259,7 +274,7 @@ namespace ArdupilotMega
|
||||
sysid = buffer[3];
|
||||
compid = buffer[4];
|
||||
recvpacketcount = buffer[2];
|
||||
Console.WriteLine("ID sys {0} comp {1} ver{2}", sysid, compid, mavlinkversion);
|
||||
log.InfoFormat("ID sys {0} comp {1} ver{2}", sysid, compid, mavlinkversion);
|
||||
break;
|
||||
}
|
||||
|
||||
@ -267,11 +282,20 @@ namespace ArdupilotMega
|
||||
|
||||
countDown.Stop();
|
||||
|
||||
if (Progress != null)
|
||||
Progress(-1, "Getting Params.. (sysid " + sysid + " compid " + compid + ") ");
|
||||
// if (Progress != null)
|
||||
// Progress(-1, "Getting Params.. (sysid " + sysid + " compid " + compid + ") ");
|
||||
frmProgressReporter.UpdateProgressAndStatus(0, "Getting Params.. (sysid " + sysid + " compid " + compid + ") ");
|
||||
|
||||
if (getparams)
|
||||
getParamList();
|
||||
getParamListBG();
|
||||
|
||||
if (frmProgressReporter.doWorkArgs.CancelAcknowledged == true)
|
||||
{
|
||||
MainV2.givecomport = false;
|
||||
if (BaseStream.IsOpen)
|
||||
BaseStream.Close();
|
||||
return;
|
||||
}
|
||||
}
|
||||
catch (Exception e)
|
||||
{
|
||||
@ -281,28 +305,19 @@ namespace ArdupilotMega
|
||||
}
|
||||
catch { }
|
||||
MainV2.givecomport = false;
|
||||
if (Progress != null)
|
||||
Progress(-1, "Connect Failed\n" + e.Message);
|
||||
// if (Progress != null)
|
||||
// Progress(-1, "Connect Failed\n" + e.Message);
|
||||
if (string.IsNullOrEmpty(progressWorkerEventArgs.ErrorMessage))
|
||||
progressWorkerEventArgs.ErrorMessage = "Connect Failed";
|
||||
throw e;
|
||||
}
|
||||
frm.Close();
|
||||
//frmProgressReporter.Close();
|
||||
MainV2.givecomport = false;
|
||||
Console.WriteLine("Done open " + sysid + " " + compid);
|
||||
frmProgressReporter.UpdateProgressAndStatus(100, "Done.");
|
||||
log.Info("Done open " + sysid + " " + compid);
|
||||
packetslost = 0;
|
||||
}
|
||||
|
||||
void MAVLink_Progress(int progress, string status)
|
||||
{
|
||||
if (frm != null)
|
||||
{
|
||||
try
|
||||
{
|
||||
frm.updateProgressAndStatus(progress, status);
|
||||
}
|
||||
catch (Exception ex) { throw ex; }
|
||||
}
|
||||
}
|
||||
|
||||
byte[] getHeartBeat()
|
||||
{
|
||||
DateTime start = DateTime.Now;
|
||||
@ -311,6 +326,7 @@ namespace ArdupilotMega
|
||||
byte[] buffer = readPacket();
|
||||
if (buffer.Length > 5)
|
||||
{
|
||||
log.Info("getHB packet received: " + buffer.Length + " btr " + BaseStream.BytesToRead + " type " + buffer[5] );
|
||||
if (buffer[5] == MAVLINK_MSG_ID_HEARTBEAT)
|
||||
{
|
||||
return buffer;
|
||||
@ -337,7 +353,7 @@ namespace ArdupilotMega
|
||||
}
|
||||
if (!run)
|
||||
{
|
||||
Console.WriteLine("Mavlink : NOT VALID PACKET sendPacket() " + indata.GetType().ToString());
|
||||
log.Info("Mavlink : NOT VALID PACKET sendPacket() " + indata.GetType().ToString());
|
||||
}
|
||||
}
|
||||
|
||||
@ -472,7 +488,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (!param.ContainsKey(paramname))
|
||||
{
|
||||
Console.WriteLine("Param doesnt exist " + paramname);
|
||||
log.Info("Param doesnt exist " + paramname);
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -495,7 +511,7 @@ namespace ArdupilotMega
|
||||
|
||||
generatePacket(MAVLINK_MSG_ID_PARAM_SET, req);
|
||||
|
||||
Console.WriteLine("setParam '{0}' = '{1}' sysid {2} compid {3}", paramname, req.param_value, sysid, compid);
|
||||
log.InfoFormat("setParam '{0}' = '{1}' sysid {2} compid {3}", paramname, req.param_value, sysid, compid);
|
||||
|
||||
DateTime start = DateTime.Now;
|
||||
int retrys = 3;
|
||||
@ -506,7 +522,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("setParam Retry " + retrys);
|
||||
log.Info("setParam Retry " + retrys);
|
||||
generatePacket(MAVLINK_MSG_ID_PARAM_SET, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
@ -534,7 +550,7 @@ namespace ArdupilotMega
|
||||
|
||||
if (st != paramname)
|
||||
{
|
||||
Console.WriteLine("MAVLINK bad param responce - {0} vs {1}", paramname, st);
|
||||
log.InfoFormat("MAVLINK bad param responce - {0} vs {1}", paramname, st);
|
||||
continue;
|
||||
}
|
||||
|
||||
@ -556,19 +572,48 @@ namespace ArdupilotMega
|
||||
|
||||
}
|
||||
*/
|
||||
public void getParamList()
|
||||
{
|
||||
frmProgressReporter = new ProgressReporterDialogue
|
||||
{
|
||||
StartPosition = System.Windows.Forms.FormStartPosition.CenterScreen,
|
||||
Text = "Getting Params"
|
||||
};
|
||||
|
||||
frmProgressReporter.DoWork += FrmProgressReporterGetParams;
|
||||
frmProgressReporter.UpdateProgressAndStatus(-1, "Getting Params...");
|
||||
MainV2.fixtheme(frmProgressReporter);
|
||||
|
||||
frmProgressReporter.RunBackgroundOperationAsync();
|
||||
}
|
||||
|
||||
void FrmProgressReporterGetParams(object sender, ProgressWorkerEventArgs e)
|
||||
{
|
||||
Hashtable old = new Hashtable(param);
|
||||
getParamListBG();
|
||||
if (frmProgressReporter.doWorkArgs.CancelRequested)
|
||||
{
|
||||
param = old;
|
||||
}
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Get param list from apm
|
||||
/// </summary>
|
||||
/// <returns></returns>
|
||||
public Hashtable getParamList()
|
||||
private Hashtable getParamListBG()
|
||||
{
|
||||
MainV2.givecomport = true;
|
||||
List<int> missed = new List<int>();
|
||||
List<int> got = new List<int>();
|
||||
|
||||
// ryan - re start
|
||||
__mavlink_param_request_read_t rereq = new __mavlink_param_request_read_t();
|
||||
rereq.target_system = sysid;
|
||||
rereq.target_component = compid;
|
||||
// clear old
|
||||
param = new Hashtable();
|
||||
|
||||
int retrys = 3;
|
||||
int param_count = 0;
|
||||
int param_total = 5;
|
||||
|
||||
goagain:
|
||||
|
||||
__mavlink_param_request_list_t req = new __mavlink_param_request_list_t();
|
||||
req.target_system = sysid;
|
||||
@ -579,34 +624,31 @@ namespace ArdupilotMega
|
||||
DateTime start = DateTime.Now;
|
||||
DateTime restart = DateTime.Now;
|
||||
|
||||
int retrys = 3;
|
||||
int nextid = 0;
|
||||
int param_count = 0;
|
||||
int param_total = 5;
|
||||
while (param_count < param_total)
|
||||
while (got.Count < param_total)
|
||||
{
|
||||
|
||||
if (frmProgressReporter.doWorkArgs.CancelRequested)
|
||||
{
|
||||
frmProgressReporter.doWorkArgs.CancelAcknowledged = true;
|
||||
MainV2.givecomport = false;
|
||||
frmProgressReporter.doWorkArgs.ErrorMessage = "User Canceled";
|
||||
return param;
|
||||
}
|
||||
|
||||
if (!(start.AddMilliseconds(5000) > DateTime.Now))
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("getParamList Retry {0} sys {1} comp {2}", retrys, sysid, compid);
|
||||
log.InfoFormat("getParamList Retry {0} sys {1} comp {2}", retrys, sysid, compid);
|
||||
generatePacket(MAVLINK_MSG_ID_PARAM_REQUEST_LIST, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
continue;
|
||||
}
|
||||
MainV2.givecomport = false;
|
||||
throw new Exception("Timeout on read - getParamList");
|
||||
}
|
||||
if (!(restart.AddMilliseconds(1000) > DateTime.Now))
|
||||
{
|
||||
rereq.param_id = new byte[] { 0x0, 0x0 };
|
||||
rereq.param_index = (short)nextid;
|
||||
sendPacket(rereq);
|
||||
restart = DateTime.Now;
|
||||
throw new Exception("Timeout on read - getParamList " + param_count +" "+ param_total);
|
||||
}
|
||||
|
||||
System.Windows.Forms.Application.DoEvents();
|
||||
byte[] buffer = readPacket();
|
||||
if (buffer.Length > 5)
|
||||
{
|
||||
@ -619,9 +661,10 @@ namespace ArdupilotMega
|
||||
|
||||
__mavlink_param_value_t par = buffer.ByteArrayToStructure<__mavlink_param_value_t>(6);
|
||||
|
||||
// set new target
|
||||
param_total = (par.param_count);
|
||||
|
||||
|
||||
|
||||
string paramID = System.Text.ASCIIEncoding.ASCII.GetString(par.param_id);
|
||||
|
||||
int pos = paramID.IndexOf('\0');
|
||||
@ -629,47 +672,44 @@ namespace ArdupilotMega
|
||||
{
|
||||
paramID = paramID.Substring(0, pos);
|
||||
}
|
||||
Console.WriteLine(DateTime.Now.Millisecond + " got param " + (par.param_index) + " of " + (param_total - 1) + " name: " + paramID);
|
||||
|
||||
// for out of order udp packets
|
||||
if (BaseStream.GetType() != typeof(UdpSerial))
|
||||
// check if we already have it
|
||||
if (got.Contains(par.param_index))
|
||||
{
|
||||
if (nextid == (par.param_index))
|
||||
{
|
||||
nextid++;
|
||||
if (Progress != null)
|
||||
Progress((par.param_index * 100) / param_total, "Got param " + paramID);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
if (retrys > 0)
|
||||
{
|
||||
generatePacket(MAVLINK_MSG_ID_PARAM_REQUEST_LIST, req);
|
||||
param_count = 0;
|
||||
nextid = 0;
|
||||
retrys--;
|
||||
continue;
|
||||
}
|
||||
Console.WriteLine("Out of order packet. Re-requesting list");
|
||||
missed.Add(nextid); // for later devel
|
||||
MainV2.givecomport = false;
|
||||
throw new Exception("Missed ID expecting " + nextid + " got " + (par.param_index) + "\nPlease try loading again");
|
||||
}
|
||||
//Console.WriteLine("Already got '"+paramID+"'");
|
||||
continue;
|
||||
}
|
||||
|
||||
log.Info(DateTime.Now.Millisecond + " got param " + (par.param_index) + " of " + (param_total - 1) + " name: " + paramID);
|
||||
|
||||
modifyParamForDisplay(true, paramID, ref par.param_value);
|
||||
param[paramID] = (par.param_value);
|
||||
param_count++;
|
||||
got.Add(par.param_index);
|
||||
|
||||
// if (Progress != null)
|
||||
// Progress((param.Count * 100) / param_total, "Got param " + paramID);
|
||||
this.frmProgressReporter.UpdateProgressAndStatus((got.Count * 100) / param_total, "Got param " + paramID);
|
||||
}
|
||||
else
|
||||
{
|
||||
//Console.WriteLine(DateTime.Now + " PC paramlist " + buffer[5] + " " + this.BytesToRead);
|
||||
//Console.WriteLine(DateTime.Now + " PC paramlist " + buffer[5] + " want " + MAVLINK_MSG_ID_PARAM_VALUE + " btr " + BaseStream.BytesToRead);
|
||||
}
|
||||
//stopwatch.Stop();
|
||||
//Console.WriteLine("Time elapsed: {0}", stopwatch.Elapsed);
|
||||
}
|
||||
}
|
||||
|
||||
if (got.Count != param_total)
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
this.frmProgressReporter.UpdateProgressAndStatus((got.Count * 100) / param_total, "Getting missed params");
|
||||
retrys--;
|
||||
goto goagain;
|
||||
}
|
||||
throw new Exception("Missing Params");
|
||||
}
|
||||
MainV2.givecomport = false;
|
||||
return param;
|
||||
}
|
||||
@ -717,7 +757,7 @@ namespace ArdupilotMega
|
||||
generatePacket(MAVLINK_MSG_ID_REQUEST_DATA_STREAM, req);
|
||||
System.Threading.Thread.Sleep(20);
|
||||
generatePacket(MAVLINK_MSG_ID_REQUEST_DATA_STREAM, req);
|
||||
Console.WriteLine("Stopall Done");
|
||||
log.Info("Stopall Done");
|
||||
|
||||
}
|
||||
catch { }
|
||||
@ -765,7 +805,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("setWPCurrent Retry " + retrys);
|
||||
log.Info("setWPCurrent Retry " + retrys);
|
||||
generatePacket(MAVLINK_MSG_ID_MISSION_SET_CURRENT, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
@ -828,7 +868,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("doAction Retry " + retrys);
|
||||
log.Info("doAction Retry " + retrys);
|
||||
generatePacket(MAVLINK_MSG_ID_COMMAND_LONG, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
@ -882,7 +922,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("setWPCurrent Retry " + retrys);
|
||||
log.Info("setWPCurrent Retry " + retrys);
|
||||
generatePacket(MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
@ -940,7 +980,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("doAction Retry " + retrys);
|
||||
log.Info("doAction Retry " + retrys);
|
||||
generatePacket(MAVLINK_MSG_ID_ACTION, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
@ -1056,7 +1096,7 @@ namespace ArdupilotMega
|
||||
return;
|
||||
}
|
||||
|
||||
Console.WriteLine("Request stream {0} at {1} hz : currently {2}", Enum.Parse(typeof(MAV_DATA_STREAM), id.ToString()), hzrate, pps);
|
||||
log.InfoFormat("Request stream {0} at {1} hz : currently {2}", Enum.Parse(typeof(MAV_DATA_STREAM), id.ToString()), hzrate, pps);
|
||||
getDatastream(id, hzrate);
|
||||
}
|
||||
|
||||
@ -1129,7 +1169,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("getWPCount Retry " + retrys + " - giv com " + MainV2.givecomport);
|
||||
log.Info("getWPCount Retry " + retrys + " - giv com " + MainV2.givecomport);
|
||||
generatePacket(MAVLINK_MSG_ID_MISSION_REQUEST_LIST, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
@ -1151,13 +1191,13 @@ namespace ArdupilotMega
|
||||
var count = buffer.ByteArrayToStructure<__mavlink_mission_count_t>(6);
|
||||
|
||||
|
||||
Console.WriteLine("wpcount: " + count.count);
|
||||
log.Info("wpcount: " + count.count);
|
||||
MainV2.givecomport = false;
|
||||
return (byte)count.count; // should be ushort, but apm has limited wp count < byte
|
||||
}
|
||||
else
|
||||
{
|
||||
Console.WriteLine(DateTime.Now + " PC wpcount " + buffer[5] + " need " + MAVLINK_MSG_ID_MISSION_COUNT + " " + this.BaseStream.BytesToRead);
|
||||
log.Info(DateTime.Now + " PC wpcount " + buffer[5] + " need " + MAVLINK_MSG_ID_MISSION_COUNT + " " + this.BaseStream.BytesToRead);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -1180,7 +1220,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("getWPCount Retry " + retrys + " - giv com " + MainV2.givecomport);
|
||||
log.Info("getWPCount Retry " + retrys + " - giv com " + MainV2.givecomport);
|
||||
generatePacket(MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
@ -1197,13 +1237,13 @@ namespace ArdupilotMega
|
||||
if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_COUNT)
|
||||
{
|
||||
|
||||
Console.WriteLine("wpcount: " + buffer[9]);
|
||||
log.Info("wpcount: " + buffer[9]);
|
||||
MainV2.givecomport = false;
|
||||
return buffer[9]; // should be ushort, but apm has limited wp count < byte
|
||||
}
|
||||
else
|
||||
{
|
||||
Console.WriteLine(DateTime.Now + " PC wpcount " + buffer[5] + " need " + MAVLINK_MSG_ID_WAYPOINT_COUNT + " " + this.BaseStream.BytesToRead);
|
||||
log.Info(DateTime.Now + " PC wpcount " + buffer[5] + " need " + MAVLINK_MSG_ID_WAYPOINT_COUNT + " " + this.BaseStream.BytesToRead);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -1241,7 +1281,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("getWP Retry " + retrys);
|
||||
log.Info("getWP Retry " + retrys);
|
||||
generatePacket(MAVLINK_MSG_ID_MISSION_REQUEST, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
@ -1288,7 +1328,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("getWP Retry " + retrys);
|
||||
log.Info("getWP Retry " + retrys);
|
||||
generatePacket(MAVLINK_MSG_ID_WAYPOINT_REQUEST, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
@ -1383,13 +1423,13 @@ namespace ArdupilotMega
|
||||
}
|
||||
}
|
||||
*/
|
||||
Console.WriteLine("getWP {0} {1} {2} {3} {4} opt {5}", loc.id, loc.p1, loc.alt, loc.lat, loc.lng, loc.options);
|
||||
log.InfoFormat("getWP {0} {1} {2} {3} {4} opt {5}", loc.id, loc.p1, loc.alt, loc.lat, loc.lng, loc.options);
|
||||
|
||||
break;
|
||||
}
|
||||
else
|
||||
{
|
||||
Console.WriteLine(DateTime.Now + " PC getwp " + buffer[5]);
|
||||
log.Info(DateTime.Now + " PC getwp " + buffer[5]);
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -1493,7 +1533,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("setWPTotal Retry " + retrys);
|
||||
log.Info("setWPTotal Retry " + retrys);
|
||||
generatePacket(MAVLINK_MSG_ID_MISSION_COUNT, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
@ -1548,7 +1588,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("setWPTotal Retry " + retrys);
|
||||
log.Info("setWPTotal Retry " + retrys);
|
||||
generatePacket(MAVLINK_MSG_ID_WAYPOINT_COUNT, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
@ -1671,7 +1711,7 @@ namespace ArdupilotMega
|
||||
*/
|
||||
req.seq = index;
|
||||
|
||||
Console.WriteLine("setWP {6} frame {0} cmd {1} p1 {2} x {3} y {4} z {5}", req.frame, req.command, req.param1, req.x, req.y, req.z, index);
|
||||
log.InfoFormat("setWP {6} frame {0} cmd {1} p1 {2} x {3} y {4} z {5}", req.frame, req.command, req.param1, req.x, req.y, req.z, index);
|
||||
|
||||
// request
|
||||
#if MAVLINK10
|
||||
@ -1689,7 +1729,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("setWP Retry " + retrys);
|
||||
log.Info("setWP Retry " + retrys);
|
||||
#if MAVLINK10
|
||||
generatePacket(MAVLINK_MSG_ID_MISSION_ITEM, req);
|
||||
#else
|
||||
@ -1713,7 +1753,7 @@ namespace ArdupilotMega
|
||||
var ans = buffer.ByteArrayToStructure<__mavlink_mission_ack_t>(6);
|
||||
|
||||
|
||||
Console.WriteLine("set wp " + index + " ACK 47 : " + buffer[5] + " ans " + Enum.Parse(typeof(MAV_MISSION_RESULT), ans.type.ToString()));
|
||||
log.Info("set wp " + index + " ACK 47 : " + buffer[5] + " ans " + Enum.Parse(typeof(MAV_MISSION_RESULT), ans.type.ToString()));
|
||||
break;
|
||||
}
|
||||
else if (buffer[5] == MAVLINK_MSG_ID_MISSION_REQUEST)
|
||||
@ -1725,13 +1765,13 @@ namespace ArdupilotMega
|
||||
|
||||
if (ans.seq == (index + 1))
|
||||
{
|
||||
Console.WriteLine("set wp doing " + index + " req " + ans.seq + " REQ 40 : " + buffer[5]);
|
||||
log.Info("set wp doing " + index + " req " + ans.seq + " REQ 40 : " + buffer[5]);
|
||||
MainV2.givecomport = false;
|
||||
break;
|
||||
}
|
||||
else
|
||||
{
|
||||
Console.WriteLine("set wp fail doing " + index + " req " + ans.seq + " ACK 47 or REQ 40 : " + buffer[5] + " seq {0} ts {1} tc {2}", req.seq, req.target_system, req.target_component);
|
||||
log.Info("set wp fail doing " + index + " req " + ans.seq + " ACK 47 or REQ 40 : " + buffer[5] + " seq {0} ts {1} tc {2}", req.seq, req.target_system, req.target_component);
|
||||
//break;
|
||||
}
|
||||
}
|
||||
@ -1742,7 +1782,7 @@ namespace ArdupilotMega
|
||||
#else
|
||||
if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_ACK)
|
||||
{ //__mavlink_waypoint_request_t
|
||||
Console.WriteLine("set wp " + index + " ACK 47 : " + buffer[5]);
|
||||
log.Info("set wp " + index + " ACK 47 : " + buffer[5]);
|
||||
break;
|
||||
}
|
||||
else if (buffer[5] == MAVLINK_MSG_ID_WAYPOINT_REQUEST)
|
||||
@ -1751,13 +1791,13 @@ namespace ArdupilotMega
|
||||
|
||||
if (ans.seq == (index + 1))
|
||||
{
|
||||
Console.WriteLine("set wp doing " + index + " req " + ans.seq + " REQ 40 : " + buffer[5]);
|
||||
log.Info("set wp doing " + index + " req " + ans.seq + " REQ 40 : " + buffer[5]);
|
||||
MainV2.givecomport = false;
|
||||
break;
|
||||
}
|
||||
else
|
||||
{
|
||||
Console.WriteLine("set wp fail doing " + index + " req " + ans.seq + " ACK 47 or REQ 40 : " + buffer[5] + " seq {0} ts {1} tc {2}", req.seq, req.target_system, req.target_component);
|
||||
log.InfoFormat("set wp fail doing " + index + " req " + ans.seq + " ACK 47 or REQ 40 : " + buffer[5] + " seq {0} ts {1} tc {2}", req.seq, req.target_system, req.target_component);
|
||||
//break;
|
||||
}
|
||||
}
|
||||
@ -1878,7 +1918,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (readcount > 300)
|
||||
{
|
||||
Console.WriteLine("MAVLink readpacket No valid mavlink packets");
|
||||
log.Info("MAVLink readpacket No valid mavlink packets");
|
||||
break;
|
||||
}
|
||||
readcount++;
|
||||
@ -1913,27 +1953,22 @@ namespace ArdupilotMega
|
||||
{
|
||||
MainV2.cs.datetime = DateTime.Now;
|
||||
|
||||
int to = 0;
|
||||
DateTime to = DateTime.Now.AddMilliseconds(BaseStream.ReadTimeout);
|
||||
|
||||
while (BaseStream.BytesToRead <= 0)
|
||||
{
|
||||
if (to > BaseStream.ReadTimeout)
|
||||
if (DateTime.Now > to)
|
||||
{
|
||||
Console.WriteLine("MAVLINK: wait time out btr {0} len {1}", BaseStream.BytesToRead, length);
|
||||
log.InfoFormat("MAVLINK: S wait time out btr {0} len {1}", BaseStream.BytesToRead, length);
|
||||
throw new Exception("Timeout");
|
||||
}
|
||||
System.Threading.Thread.Sleep(1);
|
||||
if (!MainV2.instance.InvokeRequired)
|
||||
{
|
||||
System.Windows.Forms.Application.DoEvents(); // when connecting this is in the main thread
|
||||
}
|
||||
to++;
|
||||
}
|
||||
if (BaseStream.IsOpen)
|
||||
temp[count] = (byte)BaseStream.ReadByte();
|
||||
}
|
||||
}
|
||||
catch (Exception e) { Console.WriteLine("MAVLink readpacket read error: " + e.Message); break; }
|
||||
catch (Exception e) { log.Info("MAVLink readpacket read error: " + e.Message); break; }
|
||||
|
||||
if (temp[0] != 254 && temp[0] != 'U' || lastbad[0] == 'I' && lastbad[1] == 'M' || lastbad[1] == 'G' || lastbad[1] == 'A') // out of sync "AUTO" "GUIDED" "IMU"
|
||||
{
|
||||
@ -1960,7 +1995,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (sysid != temp[3] || compid != temp[4])
|
||||
{
|
||||
Console.WriteLine("Mavlink Bad Packet (not addressed to this MAV) got {0} {1} vs {2} {3}", temp[3], temp[4], sysid, compid);
|
||||
log.InfoFormat("Mavlink Bad Packet (not addressed to this MAV) got {0} {1} vs {2} {3}", temp[3], temp[4], sysid, compid);
|
||||
return new byte[0];
|
||||
}
|
||||
}
|
||||
@ -1973,21 +2008,15 @@ namespace ArdupilotMega
|
||||
}
|
||||
else
|
||||
{
|
||||
int to = 0;
|
||||
DateTime to = DateTime.Now.AddMilliseconds(BaseStream.ReadTimeout);
|
||||
|
||||
while (BaseStream.BytesToRead < (length - 4))
|
||||
{
|
||||
if (to > 1000)
|
||||
if (DateTime.Now > to)
|
||||
{
|
||||
Console.WriteLine("MAVLINK: wait time out btr {0} len {1}", BaseStream.BytesToRead, length);
|
||||
log.InfoFormat("MAVLINK: L wait time out btr {0} len {1}", BaseStream.BytesToRead, length);
|
||||
break;
|
||||
}
|
||||
System.Threading.Thread.Sleep(1);
|
||||
if (!MainV2.instance.InvokeRequired)
|
||||
{
|
||||
System.Windows.Forms.Application.DoEvents(); // when connecting this is in the main thread
|
||||
}
|
||||
to++;
|
||||
|
||||
//Console.WriteLine("data " + 0 + " " + length + " aval " + BaseStream.BytesToRead);
|
||||
}
|
||||
if (BaseStream.IsOpen)
|
||||
@ -2047,12 +2076,19 @@ namespace ArdupilotMega
|
||||
|
||||
if (temp.Length > 5 && temp[1] != MAVLINK_MESSAGE_LENGTHS[temp[5]])
|
||||
{
|
||||
Console.WriteLine("Mavlink Bad Packet (Len Fail) len {0} pkno {1}", temp.Length, temp[5]);
|
||||
if (MAVLINK_MESSAGE_LENGTHS[temp[5]] == 0) // pass for unknown packets
|
||||
{
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
log.InfoFormat("Mavlink Bad Packet (Len Fail) len {0} pkno {1}", temp.Length, temp[5]);
|
||||
#if MAVLINK10
|
||||
if (temp.Length == 11 && temp[0] == 'U' && temp[5] == 0)
|
||||
throw new Exception("Mavlink 0.9 Heartbeat, Please upgrade your AP, This planner is for Mavlink 1.0\n\n");
|
||||
#endif
|
||||
return new byte[0];
|
||||
return new byte[0];
|
||||
}
|
||||
}
|
||||
|
||||
if (temp.Length < 5 || temp[temp.Length - 1] != (crc >> 8) || temp[temp.Length - 2] != (crc & 0xff))
|
||||
@ -2062,7 +2098,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
packetno = temp[5];
|
||||
}
|
||||
Console.WriteLine("Mavlink Bad Packet (crc fail) len {0} crc {1} pkno {2}", temp.Length, crc, packetno);
|
||||
log.InfoFormat("Mavlink Bad Packet (crc fail) len {0} crc {1} pkno {2}", temp.Length, crc, packetno);
|
||||
return new byte[0];
|
||||
}
|
||||
|
||||
@ -2084,7 +2120,7 @@ namespace ArdupilotMega
|
||||
packetslost += temp[2] - recvpacketcount;
|
||||
}
|
||||
|
||||
Console.WriteLine("lost {0} pkts {1}", temp[2], (int)packetslost);
|
||||
log.InfoFormat("lost {0} pkts {1}", temp[2], (int)packetslost);
|
||||
}
|
||||
|
||||
packetsnotlost++;
|
||||
@ -2119,7 +2155,7 @@ namespace ArdupilotMega
|
||||
int ind = logdata.IndexOf('\0');
|
||||
if (ind != -1)
|
||||
logdata = logdata.Substring(0, ind);
|
||||
Console.WriteLine(DateTime.Now + " " + logdata);
|
||||
log.Info(DateTime.Now + " " + logdata);
|
||||
|
||||
if (MainV2.talk != null && MainV2.config["speechenable"] != null && MainV2.config["speechenable"].ToString() == "True")
|
||||
{
|
||||
@ -2214,7 +2250,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
if (retrys > 0)
|
||||
{
|
||||
Console.WriteLine("getFencePoint Retry " + retrys + " - giv com " + MainV2.givecomport);
|
||||
log.Info("getFencePoint Retry " + retrys + " - giv com " + MainV2.givecomport);
|
||||
generatePacket(MAVLINK_MSG_ID_FENCE_FETCH_POINT, req);
|
||||
start = DateTime.Now;
|
||||
retrys--;
|
||||
@ -2350,7 +2386,7 @@ namespace ArdupilotMega
|
||||
temp[a] = (byte)logplaybackfile.ReadByte();
|
||||
if (temp[0] != 'U' && temp[0] != 254)
|
||||
{
|
||||
Console.WriteLine("lost sync byte {0} pos {1}", temp[0], logplaybackfile.BaseStream.Position);
|
||||
log.InfoFormat("lost sync byte {0} pos {1}", temp[0], logplaybackfile.BaseStream.Position);
|
||||
a = 0;
|
||||
continue;
|
||||
}
|
||||
|
138
Tools/ArdupilotMegaPlanner/MagCalib.cs
Normal file
138
Tools/ArdupilotMegaPlanner/MagCalib.cs
Normal file
@ -0,0 +1,138 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using System.IO;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public class MagCalib
|
||||
{
|
||||
|
||||
//alglib.lsfit.
|
||||
|
||||
public static void doWork()
|
||||
{
|
||||
/*
|
||||
double[,] x = new double[,] { { -1 }, { -0.8 }, { -0.6 }, { -0.4 }, { -0.2 }, { 0 }, { 0.2 }, { 0.4 }, { 0.6 }, { 0.8 }, { 1.0 } };
|
||||
double[] y = new double[] { 0.223130, 0.382893, 0.582748, 0.786628, 0.941765, 1.000000, 0.941765, 0.786628, 0.582748, 0.382893, 0.223130 };
|
||||
double[] c = new double[] { 0.3 };
|
||||
double epsf = 0;
|
||||
double epsx = 0.000001;
|
||||
int maxits = 0;
|
||||
int info;
|
||||
alglib.lsfitstate state;
|
||||
alglib.lsfitreport rep;
|
||||
double diffstep = 0.0001;
|
||||
|
||||
//
|
||||
// Fitting without weights
|
||||
//
|
||||
alglib.lsfitcreatef(x, y, c, diffstep, out state);
|
||||
alglib.lsfitsetcond(state, epsf, epsx, maxits);
|
||||
alglib.lsfitfit(state, function_cx_1_func, null, null);
|
||||
alglib.lsfitresults(state, out info, out c, out rep);
|
||||
System.Console.WriteLine("{0}", info); // EXPECTED: 2
|
||||
System.Console.WriteLine("{0}", alglib.ap.format(c, 1)); // EXPECTED: [1.5]
|
||||
*/
|
||||
|
||||
// based of tridge's work
|
||||
|
||||
Tuple<float, float, float> offset = new Tuple<float, float, float>(0, 0, 0);
|
||||
List<Tuple<float, float, float>> data = new List<Tuple<float, float, float>>();
|
||||
|
||||
|
||||
OpenFileDialog openFileDialog1 = new OpenFileDialog();
|
||||
openFileDialog1.Filter = "*.tlog|*.tlog";
|
||||
openFileDialog1.FilterIndex = 2;
|
||||
openFileDialog1.RestoreDirectory = true;
|
||||
openFileDialog1.Multiselect = true;
|
||||
try
|
||||
{
|
||||
openFileDialog1.InitialDirectory = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + @"logs" + Path.DirectorySeparatorChar;
|
||||
}
|
||||
catch { } // incase dir doesnt exist
|
||||
|
||||
if (openFileDialog1.ShowDialog() == DialogResult.OK)
|
||||
{
|
||||
foreach (string logfile in openFileDialog1.FileNames)
|
||||
{
|
||||
|
||||
MAVLink mine = new MAVLink();
|
||||
mine.logplaybackfile = new BinaryReader(File.Open(logfile, FileMode.Open, FileAccess.Read, FileShare.Read));
|
||||
mine.logreadmode = true;
|
||||
|
||||
mine.packets.Initialize(); // clear
|
||||
|
||||
// gather data
|
||||
while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length)
|
||||
{
|
||||
// bar moves to 100 % in this step
|
||||
//progressBar1.Value = (int)((float)mine.logplaybackfile.BaseStream.Position / (float)mine.logplaybackfile.BaseStream.Length * 100.0f / 1.0f);
|
||||
|
||||
//progressBar1.Refresh();
|
||||
//Application.DoEvents();
|
||||
|
||||
byte[] packet = mine.readPacket();
|
||||
|
||||
var pack = mine.DebugPacket(packet);
|
||||
|
||||
if (pack.GetType() == typeof(MAVLink.__mavlink_sensor_offsets_t))
|
||||
{
|
||||
offset = new Tuple<float,float,float>(
|
||||
((MAVLink.__mavlink_sensor_offsets_t)pack).mag_ofs_x,
|
||||
((MAVLink.__mavlink_sensor_offsets_t)pack).mag_ofs_y,
|
||||
((MAVLink.__mavlink_sensor_offsets_t)pack).mag_ofs_z);
|
||||
}
|
||||
else if (pack.GetType() == typeof(MAVLink.__mavlink_raw_imu_t))
|
||||
{
|
||||
data.Add(new Tuple<float, float, float>(
|
||||
((MAVLink.__mavlink_raw_imu_t)pack).xmag - offset.Item1,
|
||||
((MAVLink.__mavlink_raw_imu_t)pack).ymag - offset.Item2,
|
||||
((MAVLink.__mavlink_raw_imu_t)pack).zmag - offset.Item3));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//progressBar1.Value = 100;
|
||||
|
||||
mine.logreadmode = false;
|
||||
mine.logplaybackfile.Close();
|
||||
mine.logplaybackfile = null;
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public static List<double> sphere_error(double[,] p, double[] data)
|
||||
{
|
||||
double xofs = p[0, 0];
|
||||
double yofs = p[0, 1];
|
||||
double zofs = p[0, 2];
|
||||
double r = p[0, 3];
|
||||
List<double> ret = new List<double>();
|
||||
foreach (var d in data)
|
||||
{
|
||||
//double x, y, z = d;
|
||||
//double err = r - Math.Sqrt(Math.Pow((x + xofs), 2) + Math.Pow((y + yofs), 2) + Math.Pow((z + zofs), 2));
|
||||
//ret.Add(err);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
||||
public static void function_cx_1_func(double[] c, double[] x, ref double func, object obj)
|
||||
{
|
||||
// this callback calculates f(c,x)=exp(-c0*sqr(x0))
|
||||
// where x is a position on X-axis and c is adjustable parameter
|
||||
func = System.Math.Exp(-c[0] * x[0] * x[0]);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
}
|
1
Tools/ArdupilotMegaPlanner/MainV2.Designer.cs
generated
1
Tools/ArdupilotMegaPlanner/MainV2.Designer.cs
generated
@ -134,6 +134,7 @@
|
||||
this.CMB_serialport.Name = "CMB_serialport";
|
||||
this.CMB_serialport.Size = new System.Drawing.Size(150, 76);
|
||||
this.CMB_serialport.SelectedIndexChanged += new System.EventHandler(this.CMB_serialport_SelectedIndexChanged);
|
||||
this.CMB_serialport.Enter += new System.EventHandler(this.CMB_serialport_Enter);
|
||||
this.CMB_serialport.Click += new System.EventHandler(this.CMB_serialport_Click);
|
||||
//
|
||||
// MainMenu
|
||||
|
@ -1,6 +1,7 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Configuration;
|
||||
using System.Data;
|
||||
using System.Drawing;
|
||||
using System.Linq;
|
||||
@ -20,11 +21,14 @@ using System.Globalization;
|
||||
using System.Threading;
|
||||
using System.Net.Sockets;
|
||||
using IronPython.Hosting;
|
||||
using log4net;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public partial class MainV2 : Form
|
||||
{
|
||||
private static readonly ILog log =
|
||||
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
|
||||
[DllImport("user32.dll")]
|
||||
public static extern int FindWindow(string szClass, string szTitle);
|
||||
[DllImport("user32.dll")]
|
||||
@ -41,7 +45,7 @@ namespace ArdupilotMega
|
||||
public static bool MONO = false;
|
||||
|
||||
public static bool speechenable = false;
|
||||
public static SpeechSynthesizer talk = new SpeechSynthesizer();
|
||||
public static Speech talk = null;
|
||||
|
||||
public static Joystick joystick = null;
|
||||
DateTime lastjoystick = DateTime.Now;
|
||||
@ -101,6 +105,9 @@ namespace ArdupilotMega
|
||||
var t = Type.GetType("Mono.Runtime");
|
||||
MONO = (t != null);
|
||||
|
||||
if (!MONO)
|
||||
talk = new Speech();
|
||||
|
||||
//talk.SpeakAsync("Welcome to APM Planner");
|
||||
|
||||
MyRenderer.currentpressed = MenuFlightData;
|
||||
@ -125,8 +132,8 @@ namespace ArdupilotMega
|
||||
CMB_serialport.Items.Add("UDP");
|
||||
if (CMB_serialport.Items.Count > 0)
|
||||
{
|
||||
CMB_serialport.SelectedIndex = 0;
|
||||
CMB_baudrate.SelectedIndex = 7;
|
||||
CMB_serialport.SelectedIndex = 0;
|
||||
}
|
||||
|
||||
splash.Refresh();
|
||||
@ -138,7 +145,7 @@ namespace ArdupilotMega
|
||||
xmlconfig(false);
|
||||
|
||||
if (config.ContainsKey("language") && !string.IsNullOrEmpty((string)config["language"]))
|
||||
changelanguage(getcultureinfo((string)config["language"]));
|
||||
changelanguage(CultureInfoEx.GetCultureInfo((string)config["language"]));
|
||||
|
||||
if (!MONO) // windows only
|
||||
{
|
||||
@ -249,10 +256,18 @@ namespace ArdupilotMega
|
||||
{
|
||||
string[] devs = new string[0];
|
||||
|
||||
|
||||
log.Debug("Geting Comports");
|
||||
|
||||
if (MONO)
|
||||
{
|
||||
if (Directory.Exists("/dev/"))
|
||||
{
|
||||
if (Directory.Exists("/dev/serial/by-id/"))
|
||||
devs = Directory.GetFiles("/dev/serial/by-id/", "*");
|
||||
devs = Directory.GetFiles("/dev/", "*ACM*");
|
||||
devs = Directory.GetFiles("/dev/", "ttyUSB*");
|
||||
}
|
||||
}
|
||||
|
||||
string[] ports = SerialPort.GetPortNames();
|
||||
@ -655,8 +670,12 @@ namespace ArdupilotMega
|
||||
{
|
||||
try
|
||||
{
|
||||
if (talk != null) // cancel all pending speech
|
||||
talk.SpeakAsyncCancelAll();
|
||||
try
|
||||
{
|
||||
if (talk != null) // cancel all pending speech
|
||||
talk.SpeakAsyncCancelAll();
|
||||
}
|
||||
catch { }
|
||||
|
||||
if (comPort.logfile != null)
|
||||
comPort.logfile.Close();
|
||||
@ -664,7 +683,7 @@ namespace ArdupilotMega
|
||||
comPort.BaseStream.DtrEnable = false;
|
||||
comPort.Close();
|
||||
}
|
||||
catch { }
|
||||
catch (Exception ex) { log.Debug(ex.ToString()); }
|
||||
|
||||
this.MenuConnect.BackgroundImage = global::ArdupilotMega.Properties.Resources.connect;
|
||||
}
|
||||
@ -767,7 +786,7 @@ namespace ArdupilotMega
|
||||
|
||||
if ((buffer[0] == 'A' || buffer[0] == 'P') && (buffer[1] == 'A' || buffer[1] == 'P')) // this is the apvar header
|
||||
{
|
||||
Console.WriteLine("Valid eeprom contents");
|
||||
log.Info("Valid eeprom contents");
|
||||
}
|
||||
else
|
||||
{
|
||||
@ -777,6 +796,7 @@ namespace ArdupilotMega
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
log.Debug(ex.ToString());
|
||||
//MessageBox.Show("Can not establish a connection\n\n" + ex.ToString());
|
||||
return;
|
||||
}
|
||||
@ -953,11 +973,11 @@ namespace ArdupilotMega
|
||||
break;
|
||||
}
|
||||
}
|
||||
catch (Exception ee) { Console.WriteLine(ee.Message); } // silent fail on bad entry
|
||||
catch (Exception ee) { log.Info(ee.Message); } // silent fail on bad entry
|
||||
}
|
||||
}
|
||||
}
|
||||
catch (Exception ex) { Console.WriteLine("Bad Config File: " + ex.ToString()); } // bad config file
|
||||
catch (Exception ex) { log.Info("Bad Config File: " + ex.ToString()); } // bad config file
|
||||
}
|
||||
}
|
||||
|
||||
@ -1171,7 +1191,7 @@ namespace ArdupilotMega
|
||||
}
|
||||
catch (Exception e)
|
||||
{
|
||||
Console.WriteLine("Serial Reader fail :" + e.Message);
|
||||
log.Info("Serial Reader fail :" + e.Message);
|
||||
try
|
||||
{
|
||||
comPort.Close();
|
||||
@ -1239,7 +1259,7 @@ namespace ArdupilotMega
|
||||
try
|
||||
{
|
||||
listener = new TcpListener(IPAddress.Any, 56781);
|
||||
System.Threading.Thread t13 = new System.Threading.Thread(new System.Threading.ThreadStart(listernforclients))
|
||||
var t13 = new Thread(listernforclients)
|
||||
{
|
||||
Name = "motion jpg stream",
|
||||
IsBackground = true
|
||||
@ -1249,10 +1269,11 @@ namespace ArdupilotMega
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
log.Error("Error starting TCP listener thread: ", ex);
|
||||
MessageBox.Show(ex.ToString());
|
||||
}
|
||||
|
||||
System.Threading.Thread t12 = new System.Threading.Thread(new ThreadStart(joysticksend))
|
||||
var t12 = new Thread(new ThreadStart(joysticksend))
|
||||
{
|
||||
IsBackground = true,
|
||||
Priority = ThreadPriority.AboveNormal,
|
||||
@ -1260,18 +1281,28 @@ namespace ArdupilotMega
|
||||
};
|
||||
t12.Start();
|
||||
|
||||
System.Threading.Thread t11 = new System.Threading.Thread(new ThreadStart(SerialReader))
|
||||
var t11 = new Thread(SerialReader)
|
||||
{
|
||||
IsBackground = true,
|
||||
Name = "Main Serial reader"
|
||||
};
|
||||
t11.Start();
|
||||
|
||||
try
|
||||
if (Debugger.IsAttached)
|
||||
{
|
||||
checkForUpdate();
|
||||
log.Info("Skipping update test as it appears we are debugging");
|
||||
}
|
||||
else
|
||||
{
|
||||
try
|
||||
{
|
||||
CheckForUpdate();
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
log.Error("Update check failed", ex);
|
||||
}
|
||||
}
|
||||
catch { Console.WriteLine("update check failed"); }
|
||||
}
|
||||
|
||||
public static String ComputeWebSocketHandshakeSecurityHash09(String secWebSocketKey)
|
||||
@ -1302,7 +1333,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
listener.Start();
|
||||
}
|
||||
catch { Console.WriteLine("do you have the planner open already"); return; } // in use
|
||||
catch { log.Info("do you have the planner open already"); return; } // in use
|
||||
// Enter the listening loop.
|
||||
while (true)
|
||||
{
|
||||
@ -1310,10 +1341,10 @@ namespace ArdupilotMega
|
||||
// You could also user server.AcceptSocket() here.
|
||||
try
|
||||
{
|
||||
Console.WriteLine("Listening for client - 1 client at a time");
|
||||
log.Info("Listening for client - 1 client at a time");
|
||||
TcpClient client = listener.AcceptTcpClient();
|
||||
// Get a stream object for reading and writing
|
||||
Console.WriteLine("Accepted Client " + client.Client.RemoteEndPoint.ToString());
|
||||
log.Info("Accepted Client " + client.Client.RemoteEndPoint.ToString());
|
||||
//client.SendBufferSize = 100 * 1024; // 100kb
|
||||
//client.LingerState.Enabled = true;
|
||||
//client.NoDelay = true;
|
||||
@ -1336,7 +1367,7 @@ namespace ArdupilotMega
|
||||
|
||||
int len = stream.Read(request, 0, request.Length);
|
||||
string head = System.Text.ASCIIEncoding.ASCII.GetString(request, 0, len);
|
||||
Console.WriteLine(head);
|
||||
log.Info(head);
|
||||
|
||||
int index = head.IndexOf('\n');
|
||||
|
||||
@ -1372,7 +1403,7 @@ namespace ArdupilotMega
|
||||
while (client.Connected)
|
||||
{
|
||||
System.Threading.Thread.Sleep(200);
|
||||
Console.WriteLine(stream.DataAvailable + " " + client.Available);
|
||||
log.Info(stream.DataAvailable + " " + client.Available);
|
||||
|
||||
while (client.Available > 0)
|
||||
{
|
||||
@ -1443,12 +1474,19 @@ namespace ArdupilotMega
|
||||
|
||||
pmplane.Geometry = model;
|
||||
|
||||
SharpKml.Dom.LookAt la = new SharpKml.Dom.LookAt()
|
||||
{ Altitude = loc.Altitude.Value, Latitude = loc.Latitude.Value, Longitude = loc.Longitude.Value, Tilt = 80,
|
||||
Heading = cs.yaw, AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute, Range = 50};
|
||||
SharpKml.Dom.LookAt la = new SharpKml.Dom.LookAt()
|
||||
{
|
||||
Altitude = loc.Altitude.Value,
|
||||
Latitude = loc.Latitude.Value,
|
||||
Longitude = loc.Longitude.Value,
|
||||
Tilt = 80,
|
||||
Heading = cs.yaw,
|
||||
AltitudeMode = SharpKml.Dom.AltitudeMode.Absolute,
|
||||
Range = 50
|
||||
};
|
||||
|
||||
kml.Viewpoint = la;
|
||||
|
||||
|
||||
kml.AddFeature(pmplane);
|
||||
|
||||
SharpKml.Base.Serializer serializer = new SharpKml.Base.Serializer();
|
||||
@ -1555,7 +1593,7 @@ namespace ArdupilotMega
|
||||
}
|
||||
stream.Close();
|
||||
}
|
||||
catch (Exception ee) { Console.WriteLine("Failed mjpg " + ee.Message); }
|
||||
catch (Exception ee) { log.Info("Failed mjpg " + ee.Message); }
|
||||
}
|
||||
}
|
||||
|
||||
@ -1567,8 +1605,8 @@ namespace ArdupilotMega
|
||||
|
||||
private void MainV2_Resize(object sender, EventArgs e)
|
||||
{
|
||||
Console.WriteLine("myview width " + MyView.Width + " height " + MyView.Height);
|
||||
Console.WriteLine("this width " + this.Width + " height " + this.Height);
|
||||
log.Info("myview width " + MyView.Width + " height " + MyView.Height);
|
||||
log.Info("this width " + this.Width + " height " + this.Height);
|
||||
}
|
||||
|
||||
private void MenuHelp_Click(object sender, EventArgs e)
|
||||
@ -1590,49 +1628,58 @@ namespace ArdupilotMega
|
||||
temp.BackColor = Color.FromArgb(0x26, 0x27, 0x28);
|
||||
}
|
||||
|
||||
static string baseurl = "http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/bin/Release/";
|
||||
|
||||
public static void updatecheck(Label loadinglabel)
|
||||
{
|
||||
var baseurl = ConfigurationManager.AppSettings["UpdateLocation"];
|
||||
try
|
||||
{
|
||||
bool update = updatecheck(loadinglabel, baseurl, "");
|
||||
System.Diagnostics.Process P = new System.Diagnostics.Process();
|
||||
var process = new Process();
|
||||
string exePath = Path.GetDirectoryName(Application.ExecutablePath);
|
||||
if (MONO)
|
||||
{
|
||||
P.StartInfo.FileName = "mono";
|
||||
P.StartInfo.Arguments = " \"" + Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "Updater.exe\"";
|
||||
process.StartInfo.FileName = "mono";
|
||||
process.StartInfo.Arguments = " \"" + exePath + Path.DirectorySeparatorChar + "Updater.exe\"";
|
||||
}
|
||||
else
|
||||
{
|
||||
P.StartInfo.FileName = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "Updater.exe";
|
||||
P.StartInfo.Arguments = "";
|
||||
process.StartInfo.FileName = exePath + Path.DirectorySeparatorChar + "Updater.exe";
|
||||
process.StartInfo.Arguments = "";
|
||||
try
|
||||
{
|
||||
foreach (string newupdater in Directory.GetFiles(Path.GetDirectoryName(Application.ExecutablePath), "Updater.exe*.new"))
|
||||
foreach (string newupdater in Directory.GetFiles(exePath, "Updater.exe*.new"))
|
||||
{
|
||||
File.Copy(newupdater, newupdater.Remove(newupdater.Length - 4), true);
|
||||
File.Delete(newupdater);
|
||||
}
|
||||
}
|
||||
catch (Exception)
|
||||
catch (Exception ex)
|
||||
{
|
||||
log.Error("Exception during update", ex);
|
||||
}
|
||||
}
|
||||
if (loadinglabel != null)
|
||||
updatelabel(loadinglabel,"Starting Updater");
|
||||
Console.WriteLine("Start " + P.StartInfo.FileName + " with " + P.StartInfo.Arguments);
|
||||
P.Start();
|
||||
UpdateLabel(loadinglabel, "Starting Updater");
|
||||
log.Info("Starting new process: " + process.StartInfo.FileName + " with " + process.StartInfo.Arguments);
|
||||
process.Start();
|
||||
log.Info("Quitting existing process");
|
||||
try
|
||||
{
|
||||
Application.Exit();
|
||||
}
|
||||
catch { }
|
||||
catch
|
||||
{
|
||||
}
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
log.Error("Update Failed", ex);
|
||||
MessageBox.Show("Update Failed " + ex.Message);
|
||||
}
|
||||
catch (Exception ex) { MessageBox.Show("Update Failed " + ex.Message); }
|
||||
}
|
||||
|
||||
private static void updatelabel(Label loadinglabel, string text)
|
||||
private static void UpdateLabel(Label loadinglabel, string text)
|
||||
{
|
||||
MainV2.instance.Invoke((MethodInvoker)delegate
|
||||
{
|
||||
@ -1642,92 +1689,106 @@ namespace ArdupilotMega
|
||||
});
|
||||
}
|
||||
|
||||
private static void checkForUpdate()
|
||||
private static void CheckForUpdate()
|
||||
{
|
||||
string path = Path.GetFileNameWithoutExtension(Application.ExecutablePath) + ".exe";
|
||||
var baseurl = ConfigurationManager.AppSettings["UpdateLocation"];
|
||||
string path = Path.GetFileName(Application.ExecutablePath);
|
||||
|
||||
// Create a request using a URL that can receive a post.
|
||||
WebRequest request = WebRequest.Create(baseurl + path);
|
||||
request.Timeout = 5000;
|
||||
Console.Write(baseurl + path + " ");
|
||||
// Set the Method property of the request to POST.
|
||||
request.Method = "HEAD";
|
||||
// Create a request using a URL that can receive a post.
|
||||
string requestUriString = baseurl + path;
|
||||
log.Debug("Checking for update at: " + requestUriString);
|
||||
var webRequest = WebRequest.Create(requestUriString);
|
||||
webRequest.Timeout = 5000;
|
||||
|
||||
((HttpWebRequest)request).IfModifiedSince = File.GetLastWriteTimeUtc(path);
|
||||
// Set the Method property of the request to POST.
|
||||
webRequest.Method = "HEAD";
|
||||
|
||||
// Get the response.
|
||||
WebResponse response = request.GetResponse();
|
||||
// Display the status.
|
||||
Console.WriteLine(((HttpWebResponse)response).StatusDescription);
|
||||
// Get the stream containing content returned by the server.
|
||||
//dataStream = response.GetResponseStream();
|
||||
// Open the stream using a StreamReader for easy access.
|
||||
((HttpWebRequest)webRequest).IfModifiedSince = File.GetLastWriteTimeUtc(path);
|
||||
|
||||
bool getfile = false;
|
||||
// Get the response.
|
||||
var response = webRequest.GetResponse();
|
||||
// Display the status.
|
||||
log.Debug("Response status: " + ((HttpWebResponse)response).StatusDescription);
|
||||
// Get the stream containing content returned by the server.
|
||||
//dataStream = response.GetResponseStream();
|
||||
// Open the stream using a StreamReader for easy access.
|
||||
|
||||
if (File.Exists(path))
|
||||
bool shouldGetFile = false;
|
||||
|
||||
if (File.Exists(path))
|
||||
{
|
||||
var fi = new FileInfo(path);
|
||||
|
||||
log.Info(response.Headers[HttpResponseHeader.ETag]);
|
||||
|
||||
if (fi.Length != response.ContentLength) // && response.Headers[HttpResponseHeader.ETag] != "0")
|
||||
{
|
||||
FileInfo fi = new FileInfo(path);
|
||||
|
||||
Console.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
||||
|
||||
if (fi.Length != response.ContentLength) // && response.Headers[HttpResponseHeader.ETag] != "0")
|
||||
using (var sw = new StreamWriter(path + ".etag"))
|
||||
{
|
||||
StreamWriter sw = new StreamWriter(path + ".etag");
|
||||
sw.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
||||
sw.Close();
|
||||
getfile = true;
|
||||
Console.WriteLine("NEW FILE " + path);
|
||||
}
|
||||
shouldGetFile = true;
|
||||
log.Info("Newer file found: " + path + " " + fi.Length + " vs " + response.ContentLength);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
shouldGetFile = true;
|
||||
log.Info("File does not exist: Getting " + path);
|
||||
// get it
|
||||
}
|
||||
|
||||
response.Close();
|
||||
|
||||
if (shouldGetFile)
|
||||
{
|
||||
var dr = MessageBox.Show("Update Found\n\nDo you wish to update now?", "Update Now", MessageBoxButtons.YesNo);
|
||||
if (dr == DialogResult.Yes)
|
||||
{
|
||||
DoUpdate();
|
||||
}
|
||||
else
|
||||
{
|
||||
getfile = true;
|
||||
Console.WriteLine("NEW FILE " + path);
|
||||
// get it
|
||||
}
|
||||
|
||||
response.Close();
|
||||
|
||||
if (getfile)
|
||||
{
|
||||
DialogResult dr = MessageBox.Show("Update Found\n\nDo you wish to update now?", "Update Now", MessageBoxButtons.YesNo);
|
||||
if (dr == DialogResult.Yes)
|
||||
{
|
||||
doupdate();
|
||||
}
|
||||
else
|
||||
{
|
||||
return;
|
||||
}
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public static void doupdate()
|
||||
public static void DoUpdate()
|
||||
{
|
||||
//System.Threading.Thread t12 = new System.Threading.Thread(delegate()
|
||||
{
|
||||
var loading = new Form
|
||||
{
|
||||
|
||||
Form loading = new Form();
|
||||
loading.Width = 400;
|
||||
loading.Height = 150;
|
||||
loading.StartPosition = FormStartPosition.CenterScreen;
|
||||
loading.TopMost = true;
|
||||
System.ComponentModel.ComponentResourceManager resources = new System.ComponentModel.ComponentResourceManager(typeof(MainV2));
|
||||
loading.Icon = ((System.Drawing.Icon)(resources.GetObject("$this.Icon")));
|
||||
Width = 400,
|
||||
Height = 150,
|
||||
StartPosition = FormStartPosition.CenterScreen,
|
||||
TopMost = true,
|
||||
MinimizeBox = false,
|
||||
MaximizeBox = false
|
||||
};
|
||||
var resources = new ComponentResourceManager(typeof(MainV2));
|
||||
loading.Icon = ((Icon)(resources.GetObject("$this.Icon")));
|
||||
|
||||
Label loadinglabel = new Label();
|
||||
loadinglabel.Location = new System.Drawing.Point(50, 40);
|
||||
loadinglabel.Name = "load";
|
||||
loadinglabel.AutoSize = true;
|
||||
loadinglabel.Text = "Checking...";
|
||||
loadinglabel.Size = new System.Drawing.Size(100, 20);
|
||||
var loadinglabel = new Label
|
||||
{
|
||||
Location = new System.Drawing.Point(50, 40),
|
||||
Name = "load",
|
||||
AutoSize = true,
|
||||
Text = "Checking...",
|
||||
Size = new System.Drawing.Size(100, 20)
|
||||
};
|
||||
|
||||
loading.Controls.Add(loadinglabel);
|
||||
loading.Show();
|
||||
|
||||
try { MainV2.updatecheck(loadinglabel); } catch (Exception ex) { Console.WriteLine(ex.ToString()); }
|
||||
|
||||
try
|
||||
{
|
||||
MainV2.updatecheck(loadinglabel);
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
log.Error("Error in updatecheck", ex);
|
||||
}
|
||||
//);
|
||||
//t12.Name = "Update check thread";
|
||||
@ -1741,7 +1802,7 @@ namespace ArdupilotMega
|
||||
List<string> files = new List<string>();
|
||||
|
||||
// Create a request using a URL that can receive a post.
|
||||
Console.WriteLine(baseurl);
|
||||
log.Info(baseurl);
|
||||
WebRequest request = WebRequest.Create(baseurl);
|
||||
request.Timeout = 10000;
|
||||
// Set the Method property of the request to POST.
|
||||
@ -1751,7 +1812,7 @@ namespace ArdupilotMega
|
||||
// Get the response.
|
||||
WebResponse response = request.GetResponse();
|
||||
// Display the status.
|
||||
Console.WriteLine(((HttpWebResponse)response).StatusDescription);
|
||||
log.Info(((HttpWebResponse)response).StatusDescription);
|
||||
// Get the stream containing content returned by the server.
|
||||
dataStream = response.GetResponseStream();
|
||||
// Open the stream using a StreamReader for easy access.
|
||||
@ -1790,11 +1851,11 @@ namespace ArdupilotMega
|
||||
}
|
||||
if (file.EndsWith("/"))
|
||||
{
|
||||
update = updatecheck(loadinglabel, baseurl + file, subdir.Replace("/", "\\") + file) && update;
|
||||
update = updatecheck(loadinglabel, baseurl + file, subdir.Replace('/', Path.DirectorySeparatorChar) + file) && update;
|
||||
continue;
|
||||
}
|
||||
if (loadinglabel != null)
|
||||
updatelabel(loadinglabel, "Checking " + file);
|
||||
UpdateLabel(loadinglabel, "Checking " + file);
|
||||
|
||||
string path = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + subdir + file;
|
||||
|
||||
@ -1810,7 +1871,7 @@ namespace ArdupilotMega
|
||||
// Get the response.
|
||||
response = request.GetResponse();
|
||||
// Display the status.
|
||||
Console.WriteLine(((HttpWebResponse)response).StatusDescription);
|
||||
log.Info(((HttpWebResponse)response).StatusDescription);
|
||||
// Get the stream containing content returned by the server.
|
||||
//dataStream = response.GetResponseStream();
|
||||
// Open the stream using a StreamReader for easy access.
|
||||
@ -1821,7 +1882,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
FileInfo fi = new FileInfo(path);
|
||||
|
||||
Console.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
||||
log.Info(response.Headers[HttpResponseHeader.ETag]);
|
||||
|
||||
if (fi.Length != response.ContentLength) // && response.Headers[HttpResponseHeader.ETag] != "0")
|
||||
{
|
||||
@ -1829,13 +1890,13 @@ namespace ArdupilotMega
|
||||
sw.WriteLine(response.Headers[HttpResponseHeader.ETag]);
|
||||
sw.Close();
|
||||
getfile = true;
|
||||
Console.WriteLine("NEW FILE " + file);
|
||||
log.Info("NEW FILE " + file);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
getfile = true;
|
||||
Console.WriteLine("NEW FILE " + file);
|
||||
log.Info("NEW FILE " + file);
|
||||
// get it
|
||||
}
|
||||
|
||||
@ -1858,7 +1919,7 @@ namespace ArdupilotMega
|
||||
}
|
||||
}
|
||||
if (loadinglabel != null)
|
||||
updatelabel(loadinglabel, "Getting " + file);
|
||||
UpdateLabel(loadinglabel, "Getting " + file);
|
||||
|
||||
// from head
|
||||
long bytes = response.ContentLength;
|
||||
@ -1870,10 +1931,10 @@ namespace ArdupilotMega
|
||||
// Get the response.
|
||||
response = request.GetResponse();
|
||||
// Display the status.
|
||||
Console.WriteLine(((HttpWebResponse)response).StatusDescription);
|
||||
log.Info(((HttpWebResponse)response).StatusDescription);
|
||||
// Get the stream containing content returned by the server.
|
||||
dataStream = response.GetResponseStream();
|
||||
|
||||
|
||||
long contlen = bytes;
|
||||
|
||||
byte[] buf1 = new byte[1024];
|
||||
@ -1891,12 +1952,12 @@ namespace ArdupilotMega
|
||||
if (dt.Second != DateTime.Now.Second)
|
||||
{
|
||||
if (loadinglabel != null)
|
||||
updatelabel(loadinglabel, "Getting " + file + ": " + (((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%"); //+ Math.Abs(bytes) + " bytes");
|
||||
UpdateLabel(loadinglabel, "Getting " + file + ": " + (((double)(contlen - bytes) / (double)contlen) * 100).ToString("0.0") + "%"); //+ Math.Abs(bytes) + " bytes");
|
||||
dt = DateTime.Now;
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
Console.WriteLine(file + " " + bytes);
|
||||
log.Info(file + " " + bytes);
|
||||
int len = dataStream.Read(buf1, 0, 1024);
|
||||
if (len == 0)
|
||||
break;
|
||||
@ -1945,6 +2006,13 @@ namespace ArdupilotMega
|
||||
frm.Show();
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.A)) // test
|
||||
{
|
||||
Form frm = new _3DRradio();
|
||||
fixtheme(frm);
|
||||
frm.Show();
|
||||
return true;
|
||||
}
|
||||
if (keyData == (Keys.Control | Keys.T)) // for override connect
|
||||
{
|
||||
try
|
||||
@ -1996,51 +2064,13 @@ namespace ArdupilotMega
|
||||
{
|
||||
ComponentResourceManager rm = new ComponentResourceManager(view.GetType());
|
||||
foreach (Control ctrl in view.Controls)
|
||||
applyresource(rm, ctrl);
|
||||
rm.ApplyResource(ctrl);
|
||||
rm.ApplyResources(view, "$this");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
private void applyresource(ComponentResourceManager rm, Control ctrl)
|
||||
{
|
||||
rm.ApplyResources(ctrl, ctrl.Name);
|
||||
foreach (Control subctrl in ctrl.Controls)
|
||||
applyresource(rm, subctrl);
|
||||
|
||||
if (ctrl.ContextMenu != null)
|
||||
applyresource(rm, ctrl.ContextMenu);
|
||||
|
||||
|
||||
if (ctrl is DataGridView)
|
||||
{
|
||||
foreach (DataGridViewColumn col in (ctrl as DataGridView).Columns)
|
||||
rm.ApplyResources(col, col.Name);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
private void applyresource(ComponentResourceManager rm, Menu menu)
|
||||
{
|
||||
rm.ApplyResources(menu, menu.Name);
|
||||
foreach (MenuItem submenu in menu.MenuItems)
|
||||
applyresource(rm, submenu);
|
||||
}
|
||||
|
||||
public static CultureInfo getcultureinfo(string name)
|
||||
{
|
||||
try
|
||||
{
|
||||
return new CultureInfo(name);
|
||||
}
|
||||
catch (Exception)
|
||||
{
|
||||
return null;
|
||||
}
|
||||
}
|
||||
|
||||
private void MainV2_FormClosing(object sender, FormClosingEventArgs e)
|
||||
{
|
||||
config["MainHeight"] = this.Height;
|
||||
@ -2130,5 +2160,10 @@ namespace ArdupilotMega
|
||||
}
|
||||
catch (Exception) { }
|
||||
}
|
||||
|
||||
private void CMB_serialport_Enter(object sender, EventArgs e)
|
||||
{
|
||||
CMB_serialport_Click(sender, e);
|
||||
}
|
||||
}
|
||||
}
|
@ -3,6 +3,7 @@ using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Runtime.InteropServices;
|
||||
using System.Text;
|
||||
using log4net;
|
||||
|
||||
namespace ArdupilotMega.Mavlink
|
||||
{
|
||||
@ -11,6 +12,8 @@ namespace ArdupilotMega.Mavlink
|
||||
/// </summary>
|
||||
public static class MavlinkUtil
|
||||
{
|
||||
private static readonly ILog log =
|
||||
LogManager.GetLogger(System.Reflection.MethodBase.GetCurrentMethod().DeclaringType);
|
||||
/// <summary>
|
||||
/// Create a new mavlink packet object from a byte array as recieved over mavlink
|
||||
/// Endianess will be detetected using packet inspection
|
||||
@ -55,7 +58,7 @@ namespace ArdupilotMega.Mavlink
|
||||
}
|
||||
catch (Exception ex)
|
||||
{
|
||||
Console.WriteLine("ByteArrayToStructure FAIL: error " + ex);
|
||||
log.Error("ByteArrayToStructure FAIL", ex);
|
||||
}
|
||||
|
||||
obj = Marshal.PtrToStructure(i, obj.GetType());
|
||||
@ -105,7 +108,10 @@ namespace ArdupilotMega.Mavlink
|
||||
// copy byte array to ptr
|
||||
Marshal.Copy(temparray, startoffset, i, len);
|
||||
}
|
||||
catch (Exception ex) { Console.WriteLine("ByteArrayToStructure FAIL: error " + ex.ToString()); }
|
||||
catch (Exception ex)
|
||||
{
|
||||
log.Error("ByteArrayToStructure FAIL", ex);
|
||||
}
|
||||
|
||||
obj = Marshal.PtrToStructure(i, obj.GetType());
|
||||
|
||||
|
206
Tools/ArdupilotMegaPlanner/MavlinkLog.zh-Hans.resx
Normal file
206
Tools/ArdupilotMegaPlanner/MavlinkLog.zh-Hans.resx
Normal file
@ -0,0 +1,206 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<data name="BUT_redokml.Text" xml:space="preserve">
|
||||
<value>创建 KML</value>
|
||||
</data>
|
||||
<data name="BUT_humanreadable.Text" xml:space="preserve">
|
||||
<value>转换为文本</value>
|
||||
</data>
|
||||
<assembly alias="System.Drawing" name="System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a" />
|
||||
<data name="$this.Icon" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>
|
||||
AAABAAEAICAAAAEAIACoEAAAFgAAACgAAAAgAAAAQAAAAAEAIAAAAAAAABAAABILAAASCwAAAAAAAAAA
|
||||
AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADOxkjAtnoOAKpJ4vyiK
|
||||
c+8nh3D/J4Zv/yeHcP8oi3PvKpJ4vy6fg4AzsZIwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
|
||||
AAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADjGo2AyspPfLZ+D/yiQ
|
||||
d/8hlXj/G6F9/xeqg/8XqYL/GKqD/xuhfv8ilnn/KZB3/y2fhP8yspPfN8ajYAAAAAAAAAAAAAAAAAAA
|
||||
AAAAAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADvRrDA1vpzfL6uN/yel
|
||||
hP8XvJD/DMyY/wfQl/8FzJP/A8qS/wPJkf8EypL/BsyU/wnRmP8PzZn/Gb2R/yemhP8tqoz/Mb2a3zbQ
|
||||
qkAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAA4y6ZgMbWV/yin
|
||||
iP8WwZP/Btqf/wDPlf8AyI7/A8aP/yfNnv9T2LP/UNax/03XsP8506b/G8ya/wHKkf8F0Zf/CNuf/xLB
|
||||
kv8fpYT/J7KQ/y7IomAAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAAAAAANcajny+w
|
||||
kf8hqoj/CNSd/wDRlf8Axor/Hcyd/3Lhwf+p7Nj/o+vV/57m0/+X5dD/k+TN/4/jzf+K5Mz/fuHH/0PW
|
||||
rf8HzJT/ANCT/wDRlv8OpX//HayI/yrFn58AAAAAAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAADDC
|
||||
nmAtro7/H62J/wPWmv8Ay47/AMaO/3XhxP+e6tT/mObP/5Pjy/+Q4sr/jODJ/4ffx/+C3MT/f9vC/3nb
|
||||
wf9y2r7/adq7/2DauP8ZzZv/Fdae/8T/9/9WxKj/HKuI/y7IomAAAAAAAAAAAAAAAAD///8AAAAAAAAA
|
||||
AAAiuZMwKKyM/x6ohf8C1Zr/AMmL/wHGjv+49OL///////////9+3ML/f9zD/4Dcwv9+28L/e9rA/3bZ
|
||||
vv9w1rr/Z9S4/17Rs/9Qz63/Qcyn/3LewP////////////n///8MpH7/JbKP/zXQqUAAAAAAAAAAAP//
|
||||
/wAAAAAAAAAAABymhN8dnn//BNGa/wDKjP8AxY3/sfHf/////////////////2nXt/9w1rv/c9e8/3TX
|
||||
vP9x17z/a9W5/2TTtf9Y0K//SMyp/zXFoP9i07X/////////////////f/LR/wDQlf8epYT/Mb2a3wAA
|
||||
AAAAAAAA////AAAAAAADlnJgFZR1/wq4iv8AzpH/AMCD/4rmzf//////////////////////WdGv/2PU
|
||||
tf9p1rf/atS4/2nUtv9i0rT/Vc+u/0fKpv8zxZz/Ws+w//////////////////////8GyJL/ANCS/xLB
|
||||
kv8tq4z/OMajYAAAAAD///8AAAAAAACHZt8NkW//ANKV/wDChP9i27r//////////////////////9Dx
|
||||
6P9MzKn/Vc+v/17Rsv9g0rP/XNCx/1XNrv9Fyaf/McSd/1fPr///////////////////////QM2m/ynK
|
||||
oP8JzJX/C9yh/ymmhf80spPfAAAAAP///wAAcUwwAHtc/wCrfP8AyIv/AMKK////////////////////
|
||||
/////////////5Dgyv9Gyqb/TMyq/07Nq/9MzKn/Qcmj/y/Fnf9Wzq3//////////////////////57k
|
||||
0v8av5T/Lceg/yzOo/8M05v/Hr6T/zCghf80spIw////AABoRYAAclT/AL2H/wDBhf9R1rL/////////
|
||||
////////4vfw//////////////////H8+P9KzKn/Ocah/zTFnv8qwpj/Us2t////////////////////
|
||||
////////DLqM/yDBlv8wxp//OM6m/xPPm/8Xz53/LZF5/y+fg4////8AAGNAvwB7Wf8Aw4j/ALyC/4bj
|
||||
yP+g5tL/g93E/2HSsv9Pzqz/Us6s//////////////////////9Yzq//Gr2S/0jLp///////////////
|
||||
/////////////yrDm/8SvI//JMGY/zDHn/81zKT/Is2e/xTUnf8nl3v/LJJ5v////wAAXz3vAIlg/wDA
|
||||
hf8AuoD/quzZ/5Hjyv9628D/ada2/1jRsP9Jy6f/a9a4//////////////////////+Y4s7/////////
|
||||
//////////////////+c4tD/AbaH/xW8kf8jwZj/LcWd/y/Jn/8kzJ3/E9Ca/yGjgf8ri3Tv////AABd
|
||||
PP8Ak2b/AL6D/w/Ekv+m6tf/j+HJ/3vawP9p1rf/W9Gx/0rNqf85yJ//Nsaf////////////////////
|
||||
/////////////////////////////wCwe/8AtoT/ELqP/xu+k/8jwZj/KMeb/yHKm/8QzZf/HqyG/ymI
|
||||
cf////8AAF07/wCSZP8AvYL/GMWU/6Dn1P+K38f/ddi+/27Wuf+E3MX/leHN/6fm1f+l5tX/neLQ////
|
||||
////////////////////////////////////////j9/J/27Vuv9Tzq7/JsKY/xa/kv8aw5T/FcaW/wvL
|
||||
lf8aqoT/J4dw/////wAAXTv/AJFk/wC9gP8GwY3/mObQ/5rkz/+26dv/y/Hl/8Dt3/+06tz/pebV/5bg
|
||||
zP+g5NL//////////////v///f7+//7+/v//////7fn2////////////tOnb/6Ll0v+v6Nj/jeDI/zXK
|
||||
o/8IxJD/BMqS/xaqgv8lh2//////AABeO+8AgVf/AL1//wDBif/R9uv/1PPq/8Tv5P+36t3/rujY/6Lk
|
||||
0v+U4cv/jt7J//j8+///////+/38//f8+//2+/r/+Pz7//3+/v/m9/P/9Pv6//D6+P9/28L/jd7J/5jj
|
||||
z/+h5dL/qOvX/4Hmyf8f1J//E596/yOJcO////8AAGA8vwB3U/8p06P/hufM/8Ty5f/D7+T/s+vb/6bm
|
||||
1P+c4c//j9/K/4vcyP/t+fb///7///j8/P/0+/r/8vr5//P7+f/1+/r/+/39///////i9fL/ZNO1/3HW
|
||||
vP992sH/htzG/4vhyv+S5dD/mO7W/6X74v80noT/Io90v////wAAZkCAAHla/33ny/945cb/nunV/7Xr
|
||||
3v+l5tT/luDN/4ndxv992cL/1vLq//v9/P/1+/n/8vv4//L69//z+/j/9Pv5/7Xo2//x+vn/////////
|
||||
//+y59n/aNS3/3LWvP932r//fNzD/4Ljyf+J7ND/l/bd/yORdf8knH6A////AABuRzAAdlT/Xc6x/23o
|
||||
xv9s4MH/qurZ/5jiz/+I3cb/edjA/8ju5f/3/Pv/8vv4//H6+P/y+/j/6/f0/7np3v/7/fz//v7+/6fk
|
||||
1f+56tz///////////9h0bT/aNW4/23Wu/9v3L//dOLG/37w0f9m1rn/Hpt8/ymujTD///8AAAAAAACD
|
||||
X98po4X/Z+7K/1vgvP+A4sf/jOHK/3rZwv+r59f/9Pv6/+/69//v+vf/8vr4/9fy6/9n0rf/VM6t/6Di
|
||||
0v/N7+f/adO4/1PMrf9t1Lr/i9zI/1/Rs/9h0rX/ZNe4/2bbvf9s5sb/ePfV/z2ylf8lrozfAAAAAP//
|
||||
/wAAAAAAAJNsYAWQbf9U1rP/Vee//0rYsf993sb/pebV//P7+v/s+Pb/6/f1/+749v+s5tj/Vc2u/1jP
|
||||
r/9ZzrD/btW5/1bOr/9Wza//Vs6v/1fOr/9Z0LD/WdCy/1vTtP9d1rX/Xt+8/2btyP9k4L//IaaF/y7D
|
||||
nmAAAAAA////AAAAAAAAAAAAD6J9zyCjgv9S68L/P9+0/2Pevv/5////7/v6/+v59//j9/L/gtvF/1PN
|
||||
r/9Wz7D/Wc+x/1nQsf9Zz7H/WM6w/1fPsP9UzrD/VM+w/1TPrv9U0a//U9Oy/1Tatv9Z5sD/Y/LL/zSx
|
||||
lP8qupbPAAAAAAAAAAD///8AAAAAAAAAAAAYto4wGaeE/y23lP8+5rn/6/////j////w//3/ve/i/2bV
|
||||
uP9Tzq7/Vc+v/1jPsP9Z0LL/WM+w/1fOsf9Wz7D/Us2w/1HOrf9Qzq3/T9Cu/0zSr/9M2LP/TeC5/1bt
|
||||
xP9HxaX/KLKQ/zTPqDAAAAAAAAAAAP///wAAAAAAAAAAAAAAAAAkvpdgG6iF/y++m//e/////P///3rl
|
||||
yf9G0K3/VdKy/1bPsf9Wz7H/Vs6w/1bPsP9Sza//Ucyu/0/Nrf9NzKz/S82s/0fOrP9G0a7/QdWv/0Le
|
||||
tP9I6L7/Q8Ok/yitjP8yyKJgAAAAAAAAAAAAAAAA////AAAAAAAAAAAAAAAAAAAAAAAmwJlgG6iF/yK3
|
||||
kP8k3q7/H9el/x7Pn/8tzKT/Q9Cs/1HQsP9Q0K7/TM6u/0nMrf9Hzaz/RMyp/0LNqf8+zqn/ONGo/zTV
|
||||
qf833rD/O+S4/zvCof8orIv/MMSfYAAAAAAAAAAAAAAAAAAAAAD///8AAAAAAAAAAAAAAAAAAAAAAAAA
|
||||
AAAkvpdgG6iE/xukgv8gy53/HNql/xzRn/8czJz/HcmZ/yXJnP8qyp7/Lcqg/yzLn/8nypz/JMqc/yTO
|
||||
n/8l1KT/KN2r/y3Tpv8nq4n/JaqJ/yzAm2AAAAAAAAAAAAAAAAAAAAAAAAAAAP///wAAAAAAAAAAAAAA
|
||||
AAAAAAAAAAAAAAAAAAAato8wFKN/zxCScv8RnHn/DbqM/wjIlP8GyZT/BsaS/wbFkf8GxZH/B8WR/wfH
|
||||
k/8IypX/DMmV/xG3jP8WoX3/Fph2/xqkgs8ft5EwAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA////AAAA
|
||||
AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJVvYACGZM8Aelr/AHlZ/wCFX/8AiWL/AJlr/wCb
|
||||
bP8AlGf/AI5k/wB/W/8AeFj/AHtb/wCHZd8ClXBgAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
|
||||
AAD///8AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAABwSzAAaESAAGI/vwBf
|
||||
Pd8AXTz/AF08/wBdPP8AXz3fAGJAvwBoRIAAcUswAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA
|
||||
AAAAAAAAAAAAAP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
|
||||
/wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP///wD///8A////AP//
|
||||
/wD///8A////AP///wD///8A/+AD//+AAP/+AAA//AAAH/gAAA/wAAAH4AAAA+AAAAPAAAABwAAAAYAA
|
||||
AACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAgAAAAIAAAACAAAAAwAAAAcAAAAHgAAAD4AAAA/AA
|
||||
AAf4AAAP/AAAH/4AAD//gAD//+AD//////8=
|
||||
</value>
|
||||
</data>
|
||||
<data name="$this.Text" xml:space="preserve">
|
||||
<value>记录</value>
|
||||
</data>
|
||||
</root>
|
@ -5,12 +5,15 @@ using System.Net;
|
||||
using System.IO;
|
||||
using System.Text;
|
||||
using System.Threading;
|
||||
using log4net;
|
||||
using log4net.Config;
|
||||
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
static class Program
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger("Program");
|
||||
|
||||
/// <summary>
|
||||
/// The main entry point for the application.
|
||||
@ -21,23 +24,33 @@ namespace ArdupilotMega
|
||||
//System.Threading.Thread.CurrentThread.CurrentUICulture = new System.Globalization.CultureInfo("en-US");
|
||||
//System.Threading.Thread.CurrentThread.CurrentCulture = new System.Globalization.CultureInfo("en-US");
|
||||
|
||||
Application.ThreadException += new System.Threading.ThreadExceptionEventHandler(Application_ThreadException);
|
||||
Application.ThreadException += Application_ThreadException;
|
||||
|
||||
Application.Idle += new EventHandler(Application_Idle);
|
||||
Application.Idle += Application_Idle;
|
||||
|
||||
//MagCalib.doWork();
|
||||
|
||||
//return;
|
||||
|
||||
//MessageBox.Show("NOTE: This version may break advanced mission scripting");
|
||||
|
||||
//Common.linearRegression();
|
||||
|
||||
Application.EnableVisualStyles();
|
||||
XmlConfigurator.Configure();
|
||||
log.Info("******************* Logging Configured *******************");
|
||||
Application.SetCompatibleTextRenderingDefault(false);
|
||||
try
|
||||
{
|
||||
System.Threading.Thread.CurrentThread.Name = "Base Thread";
|
||||
Thread.CurrentThread.Name = "Base Thread";
|
||||
|
||||
Application.Run(new MainV2());
|
||||
}
|
||||
catch (Exception ex) { Console.WriteLine(ex.ToString()); }
|
||||
catch (Exception ex)
|
||||
{
|
||||
log.Fatal("Fatal app exception",ex);
|
||||
Console.WriteLine(ex.ToString());
|
||||
}
|
||||
}
|
||||
|
||||
static void Application_Idle(object sender, EventArgs e)
|
||||
@ -48,6 +61,9 @@ namespace ArdupilotMega
|
||||
static void Application_ThreadException(object sender, System.Threading.ThreadExceptionEventArgs e)
|
||||
{
|
||||
Exception ex = e.Exception;
|
||||
|
||||
log.Debug(ex.ToString());
|
||||
|
||||
if (ex.Message == "The port is closed.") {
|
||||
MessageBox.Show("Serial connection has been lost");
|
||||
return;
|
||||
@ -71,7 +87,7 @@ namespace ArdupilotMega
|
||||
MessageBox.Show("You are missing some DLL's. Please extract the zip file somewhere. OR Use the update feature from the menu");
|
||||
return;
|
||||
}
|
||||
DialogResult dr = MessageBox.Show("An error has occurred\nReport this Error??? "+ex.ToString(), "Send Error", MessageBoxButtons.YesNo);
|
||||
DialogResult dr = MessageBox.Show("An error has occurred\n"+ex.ToString() + "\n\nReport this Error???", "Send Error", MessageBoxButtons.YesNo);
|
||||
if (DialogResult.Yes == dr)
|
||||
{
|
||||
try
|
||||
@ -111,7 +127,10 @@ namespace ArdupilotMega
|
||||
dataStream.Close();
|
||||
response.Close();
|
||||
}
|
||||
catch { MessageBox.Show("Error sending Error report!! Youre most likerly are not on the internet"); }
|
||||
catch
|
||||
{
|
||||
MessageBox.Show("Error sending Error report!! Youre most likerly are not on the internet");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -34,5 +34,5 @@ using System.Resources;
|
||||
// by using the '*' as shown below:
|
||||
// [assembly: AssemblyVersion("1.0.*")]
|
||||
[assembly: AssemblyVersion("1.0.0.0")]
|
||||
[assembly: AssemblyFileVersion("1.1.40")]
|
||||
[assembly: AssemblyFileVersion("1.1.46")]
|
||||
[assembly: NeutralResourcesLanguageAttribute("")]
|
||||
|
@ -214,6 +214,35 @@ namespace ArdupilotMega.Properties {
|
||||
}
|
||||
}
|
||||
|
||||
public static System.Drawing.Bitmap iconWarning32 {
|
||||
get {
|
||||
object obj = ResourceManager.GetObject("iconWarning32", resourceCulture);
|
||||
return ((System.Drawing.Bitmap)(obj));
|
||||
}
|
||||
}
|
||||
|
||||
public static System.Drawing.Bitmap iconWarning48 {
|
||||
get {
|
||||
object obj = ResourceManager.GetObject("iconWarning48", resourceCulture);
|
||||
return ((System.Drawing.Bitmap)(obj));
|
||||
}
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Looks up a localized string similar to == MAVLink Parameters == (this is a copy fo the wiki page FYI)
|
||||
///
|
||||
///This is a list of all the user-modifiable MAVLink parameters and what they do. You can modify them via the MAVLink parameters window in any compatible GCS, such as the Mission Planner, HK GCS or !QGroundControl.
|
||||
///
|
||||
///It includes both fixed wing (APM) and rotary wing (!ArduCopter) parameters. Some may only be relevant for one platform or another.
|
||||
///
|
||||
///|| *EEPROM variable name* || *Min* || *Max* || *Default* || *Multiplier* || *Enabled (0 = no, 1 = yes)* [rest of string was truncated]";.
|
||||
/// </summary>
|
||||
public static string MAVParam {
|
||||
get {
|
||||
return ResourceManager.GetString("MAVParam", resourceCulture);
|
||||
}
|
||||
}
|
||||
|
||||
public static System.Drawing.Bitmap octo {
|
||||
get {
|
||||
object obj = ResourceManager.GetObject("octo", resourceCulture);
|
||||
|
@ -181,9 +181,6 @@
|
||||
<data name="hexa" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\frames-07.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<data name="y6" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\frames-08.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<data name="planeicon" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\planetracker.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
@ -1201,7 +1198,6 @@
|
||||
<data name="opticalflow" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\BR-0016-01-3T.jpg;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="hil" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\new frames-10.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
@ -1220,4 +1216,17 @@
|
||||
<data name="octov" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\new frames-06.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<data name="iconWarning32" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\iconWarning32.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<data name="iconWarning48" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\iconWarning48.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<data name="y6" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\y6.png;System.Drawing.Bitmap, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a</value>
|
||||
</data>
|
||||
<assembly alias="System.Windows.Forms" name="System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089" />
|
||||
<data name="MAVParam" type="System.Resources.ResXFileRef, System.Windows.Forms">
|
||||
<value>..\Resources\MAVParam.txt;System.String, mscorlib, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089;Windows-1252</value>
|
||||
</data>
|
||||
</root>
|
65
Tools/ArdupilotMegaPlanner/Protocol.cs
Normal file
65
Tools/ArdupilotMegaPlanner/Protocol.cs
Normal file
@ -0,0 +1,65 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Collections;
|
||||
using System.IO;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
partial interface Protocol
|
||||
{
|
||||
byte[][] packets { get; set; }
|
||||
|
||||
PointLatLngAlt[] wps { get; set; }
|
||||
|
||||
ICommsSerial BaseStream { get; set; }
|
||||
|
||||
int bps { get; set; }
|
||||
bool debugmavlink { get; set; }
|
||||
|
||||
DateTime lastvalidpacket {get;set;}
|
||||
|
||||
bool logreadmode { get; set; }
|
||||
DateTime lastlogread { get; set; }
|
||||
BinaryReader logplaybackfile { get; set; }
|
||||
BinaryWriter logfile { get; set; }
|
||||
|
||||
byte sysid { get; set; }
|
||||
byte compid { get; set; }
|
||||
Hashtable param { get; set; }
|
||||
|
||||
void UpdateCurrentSettings(ref CurrentState cs);
|
||||
|
||||
void Close();
|
||||
|
||||
void Open();
|
||||
void Open(bool getparams);
|
||||
|
||||
void sendPacket(object indata);
|
||||
bool Write(string line);
|
||||
bool setParam(string paramname, float value);
|
||||
Hashtable getParamList();
|
||||
void modifyParamForDisplay(bool fromapm, string paramname, ref float value);
|
||||
|
||||
void stopall(bool forget);
|
||||
void setWPACK();
|
||||
bool setWPCurrent(ushort index);
|
||||
bool doAction(byte actionid); // MAV_ACTION
|
||||
|
||||
void requestDatastream(byte id, byte hzrate);
|
||||
byte getWPCount();
|
||||
Locationwp getWP(ushort index);
|
||||
object DebugPacket(byte[] datin);
|
||||
object DebugPacket(byte[] datin, ref string text);
|
||||
void setWPTotal(ushort wp_total);
|
||||
void setWP(Locationwp loc, ushort index, byte frame, byte current); //MAV_FRAME
|
||||
|
||||
void setMountConfigure(byte mountmode, bool stabroll, bool stabpitch, bool stabyaw); //MAV_MOUNT_MODE
|
||||
void setMountControl(double pa, double pb, double pc, bool islatlng);
|
||||
void setMode(string modein);
|
||||
byte[] readPacket();
|
||||
|
||||
bool translateMode(string modein, ref object navmode, ref object mode);
|
||||
}
|
||||
}
|
661
Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs
generated
Normal file
661
Tools/ArdupilotMegaPlanner/Radio/3DRradio.Designer.cs
generated
Normal file
@ -0,0 +1,661 @@
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
partial class _3DRradio
|
||||
{
|
||||
/// <summary>
|
||||
/// Required designer variable.
|
||||
/// </summary>
|
||||
private System.ComponentModel.IContainer components = null;
|
||||
|
||||
/// <summary>
|
||||
/// Clean up any resources being used.
|
||||
/// </summary>
|
||||
/// <param name="disposing">true if managed resources should be disposed; otherwise, false.</param>
|
||||
protected override void Dispose(bool disposing)
|
||||
{
|
||||
if (disposing && (components != null))
|
||||
{
|
||||
components.Dispose();
|
||||
}
|
||||
base.Dispose(disposing);
|
||||
}
|
||||
|
||||
#region Windows Form Designer generated code
|
||||
|
||||
/// <summary>
|
||||
/// Required method for Designer support - do not modify
|
||||
/// the contents of this method with the code editor.
|
||||
/// </summary>
|
||||
private void InitializeComponent()
|
||||
{
|
||||
this.components = new System.ComponentModel.Container();
|
||||
this.Progressbar = new System.Windows.Forms.ProgressBar();
|
||||
this.S1 = new System.Windows.Forms.ComboBox();
|
||||
this.label1 = new System.Windows.Forms.Label();
|
||||
this.S0 = new System.Windows.Forms.TextBox();
|
||||
this.label2 = new System.Windows.Forms.Label();
|
||||
this.label3 = new System.Windows.Forms.Label();
|
||||
this.S2 = new System.Windows.Forms.ComboBox();
|
||||
this.label4 = new System.Windows.Forms.Label();
|
||||
this.S3 = new System.Windows.Forms.ComboBox();
|
||||
this.label5 = new System.Windows.Forms.Label();
|
||||
this.S4 = new System.Windows.Forms.ComboBox();
|
||||
this.label6 = new System.Windows.Forms.Label();
|
||||
this.S5 = new System.Windows.Forms.CheckBox();
|
||||
this.label7 = new System.Windows.Forms.Label();
|
||||
this.S6 = new System.Windows.Forms.CheckBox();
|
||||
this.label8 = new System.Windows.Forms.Label();
|
||||
this.S7 = new System.Windows.Forms.CheckBox();
|
||||
this.toolTip1 = new System.Windows.Forms.ToolTip(this.components);
|
||||
this.RS7 = new System.Windows.Forms.CheckBox();
|
||||
this.RS6 = new System.Windows.Forms.CheckBox();
|
||||
this.RS5 = new System.Windows.Forms.CheckBox();
|
||||
this.RS4 = new System.Windows.Forms.ComboBox();
|
||||
this.RS3 = new System.Windows.Forms.ComboBox();
|
||||
this.RS2 = new System.Windows.Forms.ComboBox();
|
||||
this.RS1 = new System.Windows.Forms.ComboBox();
|
||||
this.RS0 = new System.Windows.Forms.TextBox();
|
||||
this.label9 = new System.Windows.Forms.Label();
|
||||
this.label10 = new System.Windows.Forms.Label();
|
||||
this.RTI = new System.Windows.Forms.TextBox();
|
||||
this.ATI = new System.Windows.Forms.TextBox();
|
||||
this.RSSI = new System.Windows.Forms.TextBox();
|
||||
this.label11 = new System.Windows.Forms.Label();
|
||||
this.label12 = new System.Windows.Forms.Label();
|
||||
this.BUT_savesettings = new ArdupilotMega.MyButton();
|
||||
this.BUT_getcurrent = new ArdupilotMega.MyButton();
|
||||
this.lbl_status = new System.Windows.Forms.Label();
|
||||
this.BUT_upload = new ArdupilotMega.MyButton();
|
||||
this.BUT_syncS2 = new ArdupilotMega.MyButton();
|
||||
this.BUT_syncS3 = new ArdupilotMega.MyButton();
|
||||
this.BUT_syncS5 = new ArdupilotMega.MyButton();
|
||||
this.SuspendLayout();
|
||||
//
|
||||
// Progressbar
|
||||
//
|
||||
this.Progressbar.Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left)
|
||||
| System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.Progressbar.Location = new System.Drawing.Point(12, 402);
|
||||
this.Progressbar.Name = "Progressbar";
|
||||
this.Progressbar.Size = new System.Drawing.Size(294, 36);
|
||||
this.Progressbar.TabIndex = 2;
|
||||
//
|
||||
// S1
|
||||
//
|
||||
this.S1.FormattingEnabled = true;
|
||||
this.S1.Items.AddRange(new object[] {
|
||||
"115",
|
||||
"111",
|
||||
"57",
|
||||
"38",
|
||||
"19",
|
||||
"9",
|
||||
"4",
|
||||
"2",
|
||||
"1"});
|
||||
this.S1.Location = new System.Drawing.Point(87, 141);
|
||||
this.S1.Name = "S1";
|
||||
this.S1.Size = new System.Drawing.Size(80, 21);
|
||||
this.S1.TabIndex = 4;
|
||||
this.toolTip1.SetToolTip(this.S1, "Serial Baud Rate 57 = 57600");
|
||||
//
|
||||
// label1
|
||||
//
|
||||
this.label1.AutoSize = true;
|
||||
this.label1.Location = new System.Drawing.Point(15, 149);
|
||||
this.label1.Name = "label1";
|
||||
this.label1.Size = new System.Drawing.Size(32, 13);
|
||||
this.label1.TabIndex = 5;
|
||||
this.label1.Text = "Baud";
|
||||
//
|
||||
// S0
|
||||
//
|
||||
this.S0.Location = new System.Drawing.Point(87, 115);
|
||||
this.S0.Name = "S0";
|
||||
this.S0.ReadOnly = true;
|
||||
this.S0.Size = new System.Drawing.Size(80, 20);
|
||||
this.S0.TabIndex = 7;
|
||||
//
|
||||
// label2
|
||||
//
|
||||
this.label2.AutoSize = true;
|
||||
this.label2.Location = new System.Drawing.Point(15, 122);
|
||||
this.label2.Name = "label2";
|
||||
this.label2.Size = new System.Drawing.Size(39, 13);
|
||||
this.label2.TabIndex = 8;
|
||||
this.label2.Text = "Format";
|
||||
//
|
||||
// label3
|
||||
//
|
||||
this.label3.AutoSize = true;
|
||||
this.label3.Location = new System.Drawing.Point(15, 176);
|
||||
this.label3.Name = "label3";
|
||||
this.label3.Size = new System.Drawing.Size(53, 13);
|
||||
this.label3.TabIndex = 10;
|
||||
this.label3.Text = "Air Speed";
|
||||
//
|
||||
// S2
|
||||
//
|
||||
this.S2.FormattingEnabled = true;
|
||||
this.S2.Items.AddRange(new object[] {
|
||||
"192",
|
||||
"160",
|
||||
"128",
|
||||
"96",
|
||||
"64",
|
||||
"32",
|
||||
"16"});
|
||||
this.S2.Location = new System.Drawing.Point(87, 168);
|
||||
this.S2.Name = "S2";
|
||||
this.S2.Size = new System.Drawing.Size(80, 21);
|
||||
this.S2.TabIndex = 9;
|
||||
this.toolTip1.SetToolTip(this.S2, "the inter-radio data rate in rounded kbps. So 128 means");
|
||||
//
|
||||
// label4
|
||||
//
|
||||
this.label4.AutoSize = true;
|
||||
this.label4.Location = new System.Drawing.Point(15, 203);
|
||||
this.label4.Name = "label4";
|
||||
this.label4.Size = new System.Drawing.Size(38, 13);
|
||||
this.label4.TabIndex = 12;
|
||||
this.label4.Text = "Net ID";
|
||||
//
|
||||
// S3
|
||||
//
|
||||
this.S3.FormattingEnabled = true;
|
||||
this.S3.Items.AddRange(new object[] {
|
||||
"1",
|
||||
"2",
|
||||
"3",
|
||||
"4",
|
||||
"5",
|
||||
"6",
|
||||
"7",
|
||||
"8",
|
||||
"9",
|
||||
"10",
|
||||
"11",
|
||||
"12",
|
||||
"13",
|
||||
"14",
|
||||
"15",
|
||||
"16",
|
||||
"17",
|
||||
"18",
|
||||
"19",
|
||||
"20",
|
||||
"21",
|
||||
"22",
|
||||
"23",
|
||||
"24",
|
||||
"25",
|
||||
"26",
|
||||
"27",
|
||||
"28",
|
||||
"29",
|
||||
"30"});
|
||||
this.S3.Location = new System.Drawing.Point(87, 195);
|
||||
this.S3.Name = "S3";
|
||||
this.S3.Size = new System.Drawing.Size(80, 21);
|
||||
this.S3.TabIndex = 11;
|
||||
this.toolTip1.SetToolTip(this.S3, "a 16 bit \'network ID\'. This is used to seed the frequency");
|
||||
//
|
||||
// label5
|
||||
//
|
||||
this.label5.AutoSize = true;
|
||||
this.label5.Location = new System.Drawing.Point(15, 230);
|
||||
this.label5.Name = "label5";
|
||||
this.label5.Size = new System.Drawing.Size(52, 13);
|
||||
this.label5.TabIndex = 14;
|
||||
this.label5.Text = "Tx Power";
|
||||
//
|
||||
// S4
|
||||
//
|
||||
this.S4.FormattingEnabled = true;
|
||||
this.S4.Items.AddRange(new object[] {
|
||||
"0",
|
||||
"1",
|
||||
"2",
|
||||
"3",
|
||||
"4",
|
||||
"5",
|
||||
"6",
|
||||
"7",
|
||||
"8",
|
||||
"9",
|
||||
"10",
|
||||
"11",
|
||||
"12",
|
||||
"13",
|
||||
"14",
|
||||
"15",
|
||||
"16",
|
||||
"17",
|
||||
"18",
|
||||
"19",
|
||||
"20"});
|
||||
this.S4.Location = new System.Drawing.Point(87, 222);
|
||||
this.S4.Name = "S4";
|
||||
this.S4.Size = new System.Drawing.Size(80, 21);
|
||||
this.S4.TabIndex = 13;
|
||||
this.toolTip1.SetToolTip(this.S4, "the transmit power in dBm. 20dBm is 100mW. It is useful to");
|
||||
//
|
||||
// label6
|
||||
//
|
||||
this.label6.AutoSize = true;
|
||||
this.label6.Location = new System.Drawing.Point(15, 257);
|
||||
this.label6.Name = "label6";
|
||||
this.label6.Size = new System.Drawing.Size(28, 13);
|
||||
this.label6.TabIndex = 16;
|
||||
this.label6.Text = "ECC";
|
||||
//
|
||||
// S5
|
||||
//
|
||||
this.S5.Location = new System.Drawing.Point(87, 249);
|
||||
this.S5.Name = "S5";
|
||||
this.S5.Size = new System.Drawing.Size(80, 21);
|
||||
this.S5.TabIndex = 15;
|
||||
this.toolTip1.SetToolTip(this.S5, "to enable/disable the golay error correcting code. It defaults");
|
||||
//
|
||||
// label7
|
||||
//
|
||||
this.label7.AutoSize = true;
|
||||
this.label7.Location = new System.Drawing.Point(15, 284);
|
||||
this.label7.Name = "label7";
|
||||
this.label7.Size = new System.Drawing.Size(44, 13);
|
||||
this.label7.TabIndex = 18;
|
||||
this.label7.Text = "Mavlink";
|
||||
//
|
||||
// S6
|
||||
//
|
||||
this.S6.Location = new System.Drawing.Point(87, 276);
|
||||
this.S6.Name = "S6";
|
||||
this.S6.Size = new System.Drawing.Size(80, 21);
|
||||
this.S6.TabIndex = 17;
|
||||
this.toolTip1.SetToolTip(this.S6, "enables/disables MAVLink packet framing. This tries to align");
|
||||
//
|
||||
// label8
|
||||
//
|
||||
this.label8.AutoSize = true;
|
||||
this.label8.Location = new System.Drawing.Point(15, 311);
|
||||
this.label8.Name = "label8";
|
||||
this.label8.Size = new System.Drawing.Size(68, 13);
|
||||
this.label8.TabIndex = 20;
|
||||
this.label8.Text = "Op Pre Send";
|
||||
//
|
||||
// S7
|
||||
//
|
||||
this.S7.Location = new System.Drawing.Point(87, 303);
|
||||
this.S7.Name = "S7";
|
||||
this.S7.Size = new System.Drawing.Size(80, 21);
|
||||
this.S7.TabIndex = 19;
|
||||
this.toolTip1.SetToolTip(this.S7, "enables/disables \"opportunistic resend\". When enabled the");
|
||||
//
|
||||
// RS7
|
||||
//
|
||||
this.RS7.Location = new System.Drawing.Point(201, 303);
|
||||
this.RS7.Name = "RS7";
|
||||
this.RS7.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS7.TabIndex = 29;
|
||||
this.toolTip1.SetToolTip(this.RS7, "enables/disables \"opportunistic resend\". When enabled the");
|
||||
//
|
||||
// RS6
|
||||
//
|
||||
this.RS6.Location = new System.Drawing.Point(201, 276);
|
||||
this.RS6.Name = "RS6";
|
||||
this.RS6.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS6.TabIndex = 28;
|
||||
this.toolTip1.SetToolTip(this.RS6, "enables/disables MAVLink packet framing. This tries to align");
|
||||
//
|
||||
// RS5
|
||||
//
|
||||
this.RS5.Location = new System.Drawing.Point(201, 249);
|
||||
this.RS5.Name = "RS5";
|
||||
this.RS5.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS5.TabIndex = 27;
|
||||
this.toolTip1.SetToolTip(this.RS5, "to enable/disable the golay error correcting code. It defaults");
|
||||
//
|
||||
// RS4
|
||||
//
|
||||
this.RS4.FormattingEnabled = true;
|
||||
this.RS4.Items.AddRange(new object[] {
|
||||
"0",
|
||||
"1",
|
||||
"2",
|
||||
"3",
|
||||
"4",
|
||||
"5",
|
||||
"6",
|
||||
"7",
|
||||
"8",
|
||||
"9",
|
||||
"10",
|
||||
"11",
|
||||
"12",
|
||||
"13",
|
||||
"14",
|
||||
"15",
|
||||
"16",
|
||||
"17",
|
||||
"18",
|
||||
"19",
|
||||
"20"});
|
||||
this.RS4.Location = new System.Drawing.Point(201, 222);
|
||||
this.RS4.Name = "RS4";
|
||||
this.RS4.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS4.TabIndex = 26;
|
||||
this.toolTip1.SetToolTip(this.RS4, "the transmit power in dBm. 20dBm is 100mW. It is useful to");
|
||||
//
|
||||
// RS3
|
||||
//
|
||||
this.RS3.FormattingEnabled = true;
|
||||
this.RS3.Items.AddRange(new object[] {
|
||||
"1",
|
||||
"2",
|
||||
"3",
|
||||
"4",
|
||||
"5",
|
||||
"6",
|
||||
"7",
|
||||
"8",
|
||||
"9",
|
||||
"10",
|
||||
"11",
|
||||
"12",
|
||||
"13",
|
||||
"14",
|
||||
"15",
|
||||
"16",
|
||||
"17",
|
||||
"18",
|
||||
"19",
|
||||
"20",
|
||||
"21",
|
||||
"22",
|
||||
"23",
|
||||
"24",
|
||||
"25",
|
||||
"26",
|
||||
"27",
|
||||
"28",
|
||||
"29",
|
||||
"30"});
|
||||
this.RS3.Location = new System.Drawing.Point(201, 195);
|
||||
this.RS3.Name = "RS3";
|
||||
this.RS3.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS3.TabIndex = 25;
|
||||
this.toolTip1.SetToolTip(this.RS3, "a 16 bit \'network ID\'. This is used to seed the frequency");
|
||||
//
|
||||
// RS2
|
||||
//
|
||||
this.RS2.FormattingEnabled = true;
|
||||
this.RS2.Items.AddRange(new object[] {
|
||||
"192",
|
||||
"160",
|
||||
"128",
|
||||
"96",
|
||||
"64",
|
||||
"32",
|
||||
"16"});
|
||||
this.RS2.Location = new System.Drawing.Point(201, 168);
|
||||
this.RS2.Name = "RS2";
|
||||
this.RS2.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS2.TabIndex = 24;
|
||||
this.toolTip1.SetToolTip(this.RS2, "the inter-radio data rate in rounded kbps. So 128 means");
|
||||
//
|
||||
// RS1
|
||||
//
|
||||
this.RS1.FormattingEnabled = true;
|
||||
this.RS1.Items.AddRange(new object[] {
|
||||
"115",
|
||||
"111",
|
||||
"57",
|
||||
"38",
|
||||
"19",
|
||||
"9",
|
||||
"4",
|
||||
"2",
|
||||
"1"});
|
||||
this.RS1.Location = new System.Drawing.Point(201, 141);
|
||||
this.RS1.Name = "RS1";
|
||||
this.RS1.Size = new System.Drawing.Size(80, 21);
|
||||
this.RS1.TabIndex = 22;
|
||||
this.toolTip1.SetToolTip(this.RS1, "Serial Baud Rate 57 = 57600");
|
||||
//
|
||||
// RS0
|
||||
//
|
||||
this.RS0.Location = new System.Drawing.Point(201, 115);
|
||||
this.RS0.Name = "RS0";
|
||||
this.RS0.ReadOnly = true;
|
||||
this.RS0.Size = new System.Drawing.Size(80, 20);
|
||||
this.RS0.TabIndex = 23;
|
||||
//
|
||||
// label9
|
||||
//
|
||||
this.label9.AutoSize = true;
|
||||
this.label9.Location = new System.Drawing.Point(108, 9);
|
||||
this.label9.Name = "label9";
|
||||
this.label9.Size = new System.Drawing.Size(33, 13);
|
||||
this.label9.TabIndex = 30;
|
||||
this.label9.Text = "Local";
|
||||
//
|
||||
// label10
|
||||
//
|
||||
this.label10.AutoSize = true;
|
||||
this.label10.Location = new System.Drawing.Point(225, 9);
|
||||
this.label10.Name = "label10";
|
||||
this.label10.Size = new System.Drawing.Size(44, 13);
|
||||
this.label10.TabIndex = 31;
|
||||
this.label10.Text = "Remote";
|
||||
//
|
||||
// RTI
|
||||
//
|
||||
this.RTI.Location = new System.Drawing.Point(201, 25);
|
||||
this.RTI.Name = "RTI";
|
||||
this.RTI.ReadOnly = true;
|
||||
this.RTI.Size = new System.Drawing.Size(80, 20);
|
||||
this.RTI.TabIndex = 33;
|
||||
//
|
||||
// ATI
|
||||
//
|
||||
this.ATI.Location = new System.Drawing.Point(87, 25);
|
||||
this.ATI.Name = "ATI";
|
||||
this.ATI.ReadOnly = true;
|
||||
this.ATI.Size = new System.Drawing.Size(80, 20);
|
||||
this.ATI.TabIndex = 32;
|
||||
//
|
||||
// RSSI
|
||||
//
|
||||
this.RSSI.Location = new System.Drawing.Point(87, 51);
|
||||
this.RSSI.Multiline = true;
|
||||
this.RSSI.Name = "RSSI";
|
||||
this.RSSI.ReadOnly = true;
|
||||
this.RSSI.Size = new System.Drawing.Size(194, 58);
|
||||
this.RSSI.TabIndex = 34;
|
||||
//
|
||||
// label11
|
||||
//
|
||||
this.label11.AutoSize = true;
|
||||
this.label11.Location = new System.Drawing.Point(15, 32);
|
||||
this.label11.Name = "label11";
|
||||
this.label11.Size = new System.Drawing.Size(42, 13);
|
||||
this.label11.TabIndex = 36;
|
||||
this.label11.Text = "Version";
|
||||
//
|
||||
// label12
|
||||
//
|
||||
this.label12.AutoSize = true;
|
||||
this.label12.Location = new System.Drawing.Point(15, 58);
|
||||
this.label12.Name = "label12";
|
||||
this.label12.Size = new System.Drawing.Size(32, 13);
|
||||
this.label12.TabIndex = 37;
|
||||
this.label12.Text = "RSSI";
|
||||
//
|
||||
// BUT_savesettings
|
||||
//
|
||||
this.BUT_savesettings.Location = new System.Drawing.Point(99, 330);
|
||||
this.BUT_savesettings.Name = "BUT_savesettings";
|
||||
this.BUT_savesettings.Size = new System.Drawing.Size(75, 39);
|
||||
this.BUT_savesettings.TabIndex = 21;
|
||||
this.BUT_savesettings.Text = "Save Settings";
|
||||
this.BUT_savesettings.UseVisualStyleBackColor = true;
|
||||
this.BUT_savesettings.Click += new System.EventHandler(this.BUT_savesettings_Click);
|
||||
//
|
||||
// BUT_getcurrent
|
||||
//
|
||||
this.BUT_getcurrent.Location = new System.Drawing.Point(18, 330);
|
||||
this.BUT_getcurrent.Name = "BUT_getcurrent";
|
||||
this.BUT_getcurrent.Size = new System.Drawing.Size(75, 39);
|
||||
this.BUT_getcurrent.TabIndex = 6;
|
||||
this.BUT_getcurrent.Text = "Load Settings";
|
||||
this.BUT_getcurrent.UseVisualStyleBackColor = true;
|
||||
this.BUT_getcurrent.Click += new System.EventHandler(this.BUT_getcurrent_Click);
|
||||
//
|
||||
// lbl_status
|
||||
//
|
||||
this.lbl_status.Anchor = ((System.Windows.Forms.AnchorStyles)(((System.Windows.Forms.AnchorStyles.Bottom | System.Windows.Forms.AnchorStyles.Left)
|
||||
| System.Windows.Forms.AnchorStyles.Right)));
|
||||
this.lbl_status.BackColor = System.Drawing.Color.Transparent;
|
||||
this.lbl_status.Location = new System.Drawing.Point(12, 374);
|
||||
this.lbl_status.Name = "lbl_status";
|
||||
this.lbl_status.Size = new System.Drawing.Size(294, 22);
|
||||
this.lbl_status.TabIndex = 3;
|
||||
//
|
||||
// BUT_upload
|
||||
//
|
||||
this.BUT_upload.Location = new System.Drawing.Point(180, 330);
|
||||
this.BUT_upload.Name = "BUT_upload";
|
||||
this.BUT_upload.Size = new System.Drawing.Size(127, 39);
|
||||
this.BUT_upload.TabIndex = 0;
|
||||
this.BUT_upload.Text = "Upload Firmware (Local)";
|
||||
this.BUT_upload.UseVisualStyleBackColor = true;
|
||||
this.BUT_upload.Click += new System.EventHandler(this.BUT_upload_Click);
|
||||
//
|
||||
// BUT_syncS2
|
||||
//
|
||||
this.BUT_syncS2.Location = new System.Drawing.Point(173, 168);
|
||||
this.BUT_syncS2.Name = "BUT_syncS2";
|
||||
this.BUT_syncS2.Size = new System.Drawing.Size(22, 23);
|
||||
this.BUT_syncS2.TabIndex = 38;
|
||||
this.BUT_syncS2.Text = ">";
|
||||
this.BUT_syncS2.UseVisualStyleBackColor = true;
|
||||
this.BUT_syncS2.Click += new System.EventHandler(this.BUT_syncS2_Click);
|
||||
//
|
||||
// BUT_syncS3
|
||||
//
|
||||
this.BUT_syncS3.Location = new System.Drawing.Point(173, 195);
|
||||
this.BUT_syncS3.Name = "BUT_syncS3";
|
||||
this.BUT_syncS3.Size = new System.Drawing.Size(22, 23);
|
||||
this.BUT_syncS3.TabIndex = 39;
|
||||
this.BUT_syncS3.Text = ">";
|
||||
this.BUT_syncS3.UseVisualStyleBackColor = true;
|
||||
this.BUT_syncS3.Click += new System.EventHandler(this.BUT_syncS3_Click);
|
||||
//
|
||||
// BUT_syncS5
|
||||
//
|
||||
this.BUT_syncS5.Location = new System.Drawing.Point(173, 247);
|
||||
this.BUT_syncS5.Name = "BUT_syncS5";
|
||||
this.BUT_syncS5.Size = new System.Drawing.Size(22, 23);
|
||||
this.BUT_syncS5.TabIndex = 40;
|
||||
this.BUT_syncS5.Text = ">";
|
||||
this.BUT_syncS5.UseVisualStyleBackColor = true;
|
||||
this.BUT_syncS5.Click += new System.EventHandler(this.BUT_syncS5_Click);
|
||||
//
|
||||
// _3DRradio
|
||||
//
|
||||
this.AutoScaleDimensions = new System.Drawing.SizeF(6F, 13F);
|
||||
this.AutoScaleMode = System.Windows.Forms.AutoScaleMode.Font;
|
||||
this.ClientSize = new System.Drawing.Size(318, 444);
|
||||
this.Controls.Add(this.BUT_syncS5);
|
||||
this.Controls.Add(this.BUT_syncS3);
|
||||
this.Controls.Add(this.BUT_syncS2);
|
||||
this.Controls.Add(this.label12);
|
||||
this.Controls.Add(this.label11);
|
||||
this.Controls.Add(this.RSSI);
|
||||
this.Controls.Add(this.RTI);
|
||||
this.Controls.Add(this.ATI);
|
||||
this.Controls.Add(this.label10);
|
||||
this.Controls.Add(this.label9);
|
||||
this.Controls.Add(this.RS7);
|
||||
this.Controls.Add(this.RS6);
|
||||
this.Controls.Add(this.RS5);
|
||||
this.Controls.Add(this.RS4);
|
||||
this.Controls.Add(this.RS3);
|
||||
this.Controls.Add(this.RS2);
|
||||
this.Controls.Add(this.RS0);
|
||||
this.Controls.Add(this.RS1);
|
||||
this.Controls.Add(this.BUT_savesettings);
|
||||
this.Controls.Add(this.label8);
|
||||
this.Controls.Add(this.S7);
|
||||
this.Controls.Add(this.label7);
|
||||
this.Controls.Add(this.S6);
|
||||
this.Controls.Add(this.label6);
|
||||
this.Controls.Add(this.S5);
|
||||
this.Controls.Add(this.label5);
|
||||
this.Controls.Add(this.S4);
|
||||
this.Controls.Add(this.label4);
|
||||
this.Controls.Add(this.S3);
|
||||
this.Controls.Add(this.label3);
|
||||
this.Controls.Add(this.S2);
|
||||
this.Controls.Add(this.label2);
|
||||
this.Controls.Add(this.S0);
|
||||
this.Controls.Add(this.BUT_getcurrent);
|
||||
this.Controls.Add(this.label1);
|
||||
this.Controls.Add(this.S1);
|
||||
this.Controls.Add(this.lbl_status);
|
||||
this.Controls.Add(this.Progressbar);
|
||||
this.Controls.Add(this.BUT_upload);
|
||||
this.MaximizeBox = false;
|
||||
this.MinimizeBox = false;
|
||||
this.MinimumSize = new System.Drawing.Size(334, 482);
|
||||
this.Name = "_3DRradio";
|
||||
this.Text = "3DRradio";
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
}
|
||||
|
||||
#endregion
|
||||
|
||||
private MyButton BUT_upload;
|
||||
private System.Windows.Forms.ProgressBar Progressbar;
|
||||
private System.Windows.Forms.Label lbl_status;
|
||||
private System.Windows.Forms.ComboBox S1;
|
||||
private System.Windows.Forms.Label label1;
|
||||
private MyButton BUT_getcurrent;
|
||||
private System.Windows.Forms.TextBox S0;
|
||||
private System.Windows.Forms.Label label2;
|
||||
private System.Windows.Forms.Label label3;
|
||||
private System.Windows.Forms.ComboBox S2;
|
||||
private System.Windows.Forms.Label label4;
|
||||
private System.Windows.Forms.ComboBox S3;
|
||||
private System.Windows.Forms.Label label5;
|
||||
private System.Windows.Forms.ComboBox S4;
|
||||
private System.Windows.Forms.Label label6;
|
||||
private System.Windows.Forms.CheckBox S5;
|
||||
private System.Windows.Forms.Label label7;
|
||||
private System.Windows.Forms.CheckBox S6;
|
||||
private System.Windows.Forms.Label label8;
|
||||
private System.Windows.Forms.CheckBox S7;
|
||||
private MyButton BUT_savesettings;
|
||||
private System.Windows.Forms.ToolTip toolTip1;
|
||||
private System.Windows.Forms.CheckBox RS7;
|
||||
private System.Windows.Forms.CheckBox RS6;
|
||||
private System.Windows.Forms.CheckBox RS5;
|
||||
private System.Windows.Forms.ComboBox RS4;
|
||||
private System.Windows.Forms.ComboBox RS3;
|
||||
private System.Windows.Forms.ComboBox RS2;
|
||||
private System.Windows.Forms.TextBox RS0;
|
||||
private System.Windows.Forms.ComboBox RS1;
|
||||
private System.Windows.Forms.Label label9;
|
||||
private System.Windows.Forms.Label label10;
|
||||
private System.Windows.Forms.TextBox RTI;
|
||||
private System.Windows.Forms.TextBox ATI;
|
||||
private System.Windows.Forms.TextBox RSSI;
|
||||
private System.Windows.Forms.Label label11;
|
||||
private System.Windows.Forms.Label label12;
|
||||
private MyButton BUT_syncS2;
|
||||
private MyButton BUT_syncS3;
|
||||
private MyButton BUT_syncS5;
|
||||
}
|
||||
}
|
612
Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs
Normal file
612
Tools/ArdupilotMegaPlanner/Radio/3DRradio.cs
Normal file
@ -0,0 +1,612 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.ComponentModel;
|
||||
using System.Data;
|
||||
using System.Drawing;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Windows.Forms;
|
||||
using System.Net;
|
||||
using System.IO;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public partial class _3DRradio : Form
|
||||
{
|
||||
public delegate void LogEventHandler(string message, int level = 0);
|
||||
|
||||
public delegate void ProgressEventHandler(double completed);
|
||||
|
||||
string firmwarefile = Path.GetDirectoryName(Application.ExecutablePath) + Path.DirectorySeparatorChar + "radio.hm_trp.hex";
|
||||
|
||||
public _3DRradio()
|
||||
{
|
||||
InitializeComponent();
|
||||
|
||||
S3.DataSource = Enumerable.Range(0, 500).ToArray();
|
||||
RS3.DataSource = S3.DataSource;
|
||||
}
|
||||
|
||||
bool getFirmware()
|
||||
{
|
||||
//https://raw.github.com/tridge/SiK/master/Firmware/dst/radio.hm_trp.hex
|
||||
|
||||
return Common.getFilefromNet("https://raw.github.com/tridge/SiK/master/Firmware/dst/radio.hm_trp.hex", firmwarefile);
|
||||
}
|
||||
|
||||
void Sleep(int mstimeout)
|
||||
{
|
||||
DateTime endtime = DateTime.Now.AddMilliseconds(mstimeout);
|
||||
|
||||
while (DateTime.Now < endtime)
|
||||
{
|
||||
System.Threading.Thread.Sleep(1);
|
||||
Application.DoEvents();
|
||||
}
|
||||
}
|
||||
|
||||
private void BUT_upload_Click(object sender, EventArgs e)
|
||||
{
|
||||
ArduinoSTK comPort = new ArduinoSTK();
|
||||
|
||||
uploader.Uploader uploader = new uploader.Uploader();
|
||||
|
||||
try
|
||||
{
|
||||
comPort.PortName = MainV2.comPort.BaseStream.PortName;
|
||||
comPort.BaudRate = 115200;
|
||||
|
||||
comPort.Open();
|
||||
|
||||
}
|
||||
catch { MessageBox.Show("Invalid ComPort or in use"); return; }
|
||||
|
||||
bool bootloadermode = false;
|
||||
|
||||
uploader.ProgressEvent += new ProgressEventHandler(uploader_ProgressEvent);
|
||||
uploader.LogEvent += new LogEventHandler(uploader_LogEvent);
|
||||
|
||||
try
|
||||
{
|
||||
uploader_ProgressEvent(0);
|
||||
uploader_LogEvent("Trying Bootloader Mode");
|
||||
uploader.port = comPort;
|
||||
uploader.connect_and_sync();
|
||||
uploader_LogEvent("In Bootloader Mode");
|
||||
bootloadermode = true;
|
||||
}
|
||||
catch {
|
||||
comPort.Close();
|
||||
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
|
||||
comPort.Open();
|
||||
uploader_LogEvent("Trying Firmware Mode");
|
||||
bootloadermode = false;
|
||||
}
|
||||
|
||||
|
||||
|
||||
if (bootloadermode || doConnect(comPort))
|
||||
{
|
||||
if (getFirmware())
|
||||
{
|
||||
uploader.IHex iHex = new uploader.IHex();
|
||||
|
||||
iHex.LogEvent += new LogEventHandler(iHex_LogEvent);
|
||||
|
||||
iHex.ProgressEvent += new ProgressEventHandler(iHex_ProgressEvent);
|
||||
|
||||
try
|
||||
{
|
||||
iHex.load(firmwarefile);
|
||||
}
|
||||
catch { MessageBox.Show("Bad Firmware File"); goto exit; }
|
||||
|
||||
if (!bootloadermode)
|
||||
{
|
||||
try
|
||||
{
|
||||
comPort.Write("AT&UPDATE\r\n");
|
||||
string left = comPort.ReadExisting();
|
||||
Console.WriteLine(left);
|
||||
Sleep(700);
|
||||
comPort.BaudRate = 115200;
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
try
|
||||
{
|
||||
uploader.upload(comPort, iHex);
|
||||
}
|
||||
catch (Exception ex) { MessageBox.Show("Upload Failed " + ex.Message); }
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Failed to download new firmware");
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Failed to identify Radio");
|
||||
}
|
||||
|
||||
exit:
|
||||
if (comPort.IsOpen)
|
||||
comPort.Close();
|
||||
|
||||
}
|
||||
|
||||
void iHex_ProgressEvent(double completed)
|
||||
{
|
||||
try
|
||||
{
|
||||
Progressbar.Value = (int)(completed * 100);
|
||||
Application.DoEvents();
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
void uploader_LogEvent(string message, int level = 0)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (level == 0)
|
||||
{
|
||||
Console.Write(message);
|
||||
lbl_status.Text = message;
|
||||
Application.DoEvents();
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
void iHex_LogEvent(string message, int level = 0)
|
||||
{
|
||||
try
|
||||
{
|
||||
if (level == 0)
|
||||
{
|
||||
lbl_status.Text = message;
|
||||
Console.WriteLine(message);
|
||||
Application.DoEvents();
|
||||
}
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
void uploader_ProgressEvent(double completed)
|
||||
{
|
||||
try
|
||||
{
|
||||
Progressbar.Value = (int)(completed * 100);
|
||||
Application.DoEvents();
|
||||
}
|
||||
catch { }
|
||||
}
|
||||
|
||||
private void BUT_savesettings_Click(object sender, EventArgs e)
|
||||
{
|
||||
ArdupilotMega.ICommsSerial comPort = new SerialPort();
|
||||
|
||||
try {
|
||||
comPort.PortName = MainV2.comPort.BaseStream.PortName;
|
||||
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
|
||||
|
||||
comPort.ReadTimeout = 4000;
|
||||
|
||||
comPort.Open();
|
||||
|
||||
|
||||
}
|
||||
catch { MessageBox.Show("Invalid ComPort or in use"); return; }
|
||||
|
||||
lbl_status.Text = "Connecting";
|
||||
|
||||
if (doConnect(comPort))
|
||||
{
|
||||
comPort.DiscardInBuffer();
|
||||
|
||||
lbl_status.Text = "Doing Command";
|
||||
|
||||
if (RTI.Text != "")
|
||||
{
|
||||
|
||||
// remote
|
||||
string answer = doCommand(comPort, "RTI5");
|
||||
|
||||
string[] items = answer.Split('\n');
|
||||
|
||||
foreach (string item in items)
|
||||
{
|
||||
if (item.StartsWith("S"))
|
||||
{
|
||||
string[] values = item.Split(':', '=');
|
||||
|
||||
if (values.Length == 3)
|
||||
{
|
||||
Control[] controls = this.Controls.Find("R" + values[0].Trim(), false);
|
||||
|
||||
if (controls.Length > 0)
|
||||
{
|
||||
if (controls[0].GetType() == typeof(CheckBox))
|
||||
{
|
||||
string value = ((CheckBox)controls[0]).Checked ? "1" : "0";
|
||||
|
||||
if (value != values[2].Trim())
|
||||
{
|
||||
string cmdanswer = doCommand(comPort, "RT" + values[0].Trim() + "=" + value + "\r");
|
||||
|
||||
if (cmdanswer.Contains("OK"))
|
||||
{
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Set Command error");
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (controls[0].Text != values[2].Trim() && controls[0].Text != "")
|
||||
{
|
||||
string cmdanswer = doCommand(comPort, "RT" + values[0].Trim() + "=" + controls[0].Text + "\r");
|
||||
|
||||
if (cmdanswer.Contains("OK"))
|
||||
{
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Set Command error");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// write it
|
||||
doCommand(comPort, "RT&W");
|
||||
|
||||
// return to normal mode
|
||||
doCommand(comPort, "RTZ");
|
||||
|
||||
Sleep(100);
|
||||
}
|
||||
|
||||
comPort.DiscardInBuffer();
|
||||
{
|
||||
//local
|
||||
string answer = doCommand(comPort, "ATI5");
|
||||
|
||||
string[] items = answer.Split('\n');
|
||||
|
||||
foreach (string item in items)
|
||||
{
|
||||
if (item.StartsWith("S"))
|
||||
{
|
||||
string[] values = item.Split(':', '=');
|
||||
|
||||
if (values.Length == 3)
|
||||
{
|
||||
Control[] controls = this.Controls.Find(values[0].Trim(), false);
|
||||
|
||||
if (controls.Length > 0)
|
||||
{
|
||||
if (controls[0].GetType() == typeof(CheckBox))
|
||||
{
|
||||
string value = ((CheckBox)controls[0]).Checked ? "1" : "0";
|
||||
|
||||
if (value != values[2].Trim())
|
||||
{
|
||||
string cmdanswer = doCommand(comPort, "AT" + values[0].Trim() + "=" + value + "\r");
|
||||
|
||||
if (cmdanswer.Contains("OK"))
|
||||
{
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Set Command error");
|
||||
}
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (controls[0].Text != values[2].Trim())
|
||||
{
|
||||
string cmdanswer = doCommand(comPort, "AT" + values[0].Trim() + "=" + controls[0].Text + "\r");
|
||||
|
||||
if (cmdanswer.Contains("OK"))
|
||||
{
|
||||
|
||||
}
|
||||
else
|
||||
{
|
||||
MessageBox.Show("Set Command error");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// write it
|
||||
doCommand(comPort, "AT&W");
|
||||
|
||||
|
||||
// return to normal mode
|
||||
doCommand(comPort, "ATZ");
|
||||
}
|
||||
|
||||
lbl_status.Text = "Done";
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
// return to normal mode
|
||||
doCommand(comPort, "ATZ");
|
||||
|
||||
lbl_status.Text = "Fail";
|
||||
MessageBox.Show("Failed to enter command mode");
|
||||
}
|
||||
|
||||
|
||||
comPort.Close();
|
||||
}
|
||||
|
||||
|
||||
private void BUT_getcurrent_Click(object sender, EventArgs e)
|
||||
{
|
||||
ArdupilotMega.ICommsSerial comPort = new SerialPort();
|
||||
|
||||
try
|
||||
{
|
||||
comPort.PortName = MainV2.comPort.BaseStream.PortName;
|
||||
comPort.BaudRate = MainV2.comPort.BaseStream.BaudRate;
|
||||
|
||||
comPort.ReadTimeout = 4000;
|
||||
|
||||
comPort.Open();
|
||||
|
||||
|
||||
}
|
||||
catch { MessageBox.Show("Invalid ComPort or in use"); return; }
|
||||
|
||||
lbl_status.Text = "Connecting";
|
||||
|
||||
if (doConnect(comPort))
|
||||
{
|
||||
comPort.DiscardInBuffer();
|
||||
|
||||
lbl_status.Text = "Doing Command ATI & RTI";
|
||||
|
||||
ATI.Text = doCommand(comPort, "ATI1").Trim();
|
||||
|
||||
RTI.Text = doCommand(comPort, "RTI1").Trim();
|
||||
|
||||
RSSI.Text = doCommand(comPort, "ATI7").Trim();
|
||||
|
||||
lbl_status.Text = "Doing Command ATI5";
|
||||
|
||||
string answer = doCommand(comPort, "ATI5");
|
||||
|
||||
string[] items = answer.Split('\n');
|
||||
|
||||
foreach (string item in items)
|
||||
{
|
||||
if (item.StartsWith("S"))
|
||||
{
|
||||
string[] values = item.Split(':', '=');
|
||||
|
||||
if (values.Length == 3)
|
||||
{
|
||||
Control[] controls = this.Controls.Find(values[0].Trim(), false);
|
||||
|
||||
if (controls.Length > 0)
|
||||
{
|
||||
if (controls[0].GetType() == typeof(CheckBox))
|
||||
{
|
||||
((CheckBox)controls[0]).Checked = values[2].Trim() == "1";
|
||||
}
|
||||
else
|
||||
{
|
||||
controls[0].Text = values[2].Trim();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// remote
|
||||
foreach (Control ctl in this.Controls)
|
||||
{
|
||||
if (ctl.Name.StartsWith("RS") && ctl.Name != "RSSI")
|
||||
ctl.ResetText();
|
||||
}
|
||||
|
||||
|
||||
comPort.DiscardInBuffer();
|
||||
|
||||
lbl_status.Text = "Doing Command RTI5";
|
||||
|
||||
answer = doCommand(comPort, "RTI5");
|
||||
|
||||
items = answer.Split('\n');
|
||||
|
||||
foreach (string item in items)
|
||||
{
|
||||
if (item.StartsWith("S"))
|
||||
{
|
||||
string[] values = item.Split(':', '=');
|
||||
|
||||
if (values.Length == 3)
|
||||
{
|
||||
Control[] controls = this.Controls.Find("R" + values[0].Trim(), false);
|
||||
|
||||
if (controls[0].GetType() == typeof(CheckBox))
|
||||
{
|
||||
((CheckBox)controls[0]).Checked = values[2].Trim() == "1";
|
||||
}
|
||||
else if (controls[0].GetType() == typeof(TextBox))
|
||||
{
|
||||
((TextBox)controls[0]).Text = values[2].Trim();
|
||||
}
|
||||
else if (controls[0].GetType() == typeof(ComboBox))
|
||||
{
|
||||
((ComboBox)controls[0]).SelectedText = values[2].Trim();
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
Console.WriteLine("Odd config line :" + item);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// off hook
|
||||
doCommand(comPort, "ATO");
|
||||
|
||||
lbl_status.Text = "Done";
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
// off hook
|
||||
doCommand(comPort, "ATO");
|
||||
|
||||
lbl_status.Text = "Fail";
|
||||
MessageBox.Show("Failed to enter command mode");
|
||||
}
|
||||
|
||||
comPort.Close();
|
||||
}
|
||||
|
||||
string Serial_ReadLine(ArdupilotMega.ICommsSerial comPort)
|
||||
{
|
||||
StringBuilder sb = new StringBuilder();
|
||||
DateTime Deadline = DateTime.Now.AddMilliseconds(comPort.ReadTimeout);
|
||||
|
||||
while (DateTime.Now < Deadline)
|
||||
{
|
||||
if (comPort.BytesToRead > 0)
|
||||
{
|
||||
byte data = (byte)comPort.ReadByte();
|
||||
sb.Append((char)data);
|
||||
if (data == '\n')
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return sb.ToString();
|
||||
}
|
||||
|
||||
string doCommand(ArdupilotMega.ICommsSerial comPort, string cmd, int level = 0)
|
||||
{
|
||||
if (!comPort.IsOpen)
|
||||
return "";
|
||||
|
||||
comPort.ReadTimeout = 1000;
|
||||
// setup to known state
|
||||
comPort.Write("\r\n");
|
||||
// alow some time to gather thoughts
|
||||
Sleep(100);
|
||||
// ignore all existing data
|
||||
comPort.DiscardInBuffer();
|
||||
lbl_status.Text = "Doing Command " + cmd;
|
||||
Console.WriteLine("Doing Command " + cmd);
|
||||
// write command
|
||||
comPort.Write(cmd + "\r\n");
|
||||
// read echoed line or existing data
|
||||
string temp;
|
||||
try
|
||||
{
|
||||
temp = Serial_ReadLine(comPort);
|
||||
}
|
||||
catch { temp = comPort.ReadExisting(); }
|
||||
Console.WriteLine("cmd " + cmd + " echo " + temp);
|
||||
// delay for command
|
||||
Sleep(500);
|
||||
// get responce
|
||||
string ans = "";
|
||||
while (comPort.BytesToRead > 0)
|
||||
{
|
||||
try
|
||||
{
|
||||
ans = ans + Serial_ReadLine(comPort) + "\n";
|
||||
}
|
||||
catch { ans = ans + comPort.ReadExisting() + "\n"; }
|
||||
Sleep(50);
|
||||
|
||||
if (ans.Length > 500)
|
||||
{
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
Console.WriteLine("responce " + level + " " + ans.Replace('\0',' '));
|
||||
|
||||
// try again
|
||||
if (ans == "" && level == 0)
|
||||
return doCommand(comPort, cmd, 1);
|
||||
|
||||
return ans;
|
||||
}
|
||||
|
||||
bool doConnect(ArdupilotMega.ICommsSerial comPort)
|
||||
{
|
||||
// clear buffer
|
||||
comPort.DiscardInBuffer();
|
||||
// setup a known enviroment
|
||||
comPort.Write("\r\n");
|
||||
// wait
|
||||
Sleep(1100);
|
||||
// send config string
|
||||
comPort.Write("+++");
|
||||
// wait
|
||||
Sleep(1100);
|
||||
// check for config responce "OK"
|
||||
Console.WriteLine("Connect btr " + comPort.BytesToRead + " baud " + comPort.BaudRate);
|
||||
string conn = comPort.ReadExisting();
|
||||
Console.WriteLine("Connect first responce " + conn.Replace('\0',' ') + " " + conn.Length);
|
||||
if (conn.Contains("OK"))
|
||||
{
|
||||
//return true;
|
||||
}
|
||||
else
|
||||
{
|
||||
// cleanup incase we are already in cmd mode
|
||||
comPort.Write("\r\n");
|
||||
}
|
||||
|
||||
string version = doCommand(comPort, "ATI");
|
||||
|
||||
Console.Write("Connect Version: " + version.Trim() + "\n");
|
||||
|
||||
if (version.Contains("on HM-TRP"))
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
private void BUT_syncS2_Click(object sender, EventArgs e)
|
||||
{
|
||||
RS2.Text = S2.Text;
|
||||
}
|
||||
|
||||
private void BUT_syncS3_Click(object sender, EventArgs e)
|
||||
{
|
||||
RS3.Text = S3.Text;
|
||||
}
|
||||
|
||||
private void BUT_syncS5_Click(object sender, EventArgs e)
|
||||
{
|
||||
RS5.Checked = S5.Checked;
|
||||
}
|
||||
}
|
||||
}
|
123
Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx
Normal file
123
Tools/ArdupilotMegaPlanner/Radio/3DRradio.resx
Normal file
@ -0,0 +1,123 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<root>
|
||||
<!--
|
||||
Microsoft ResX Schema
|
||||
|
||||
Version 2.0
|
||||
|
||||
The primary goals of this format is to allow a simple XML format
|
||||
that is mostly human readable. The generation and parsing of the
|
||||
various data types are done through the TypeConverter classes
|
||||
associated with the data types.
|
||||
|
||||
Example:
|
||||
|
||||
... ado.net/XML headers & schema ...
|
||||
<resheader name="resmimetype">text/microsoft-resx</resheader>
|
||||
<resheader name="version">2.0</resheader>
|
||||
<resheader name="reader">System.Resources.ResXResourceReader, System.Windows.Forms, ...</resheader>
|
||||
<resheader name="writer">System.Resources.ResXResourceWriter, System.Windows.Forms, ...</resheader>
|
||||
<data name="Name1"><value>this is my long string</value><comment>this is a comment</comment></data>
|
||||
<data name="Color1" type="System.Drawing.Color, System.Drawing">Blue</data>
|
||||
<data name="Bitmap1" mimetype="application/x-microsoft.net.object.binary.base64">
|
||||
<value>[base64 mime encoded serialized .NET Framework object]</value>
|
||||
</data>
|
||||
<data name="Icon1" type="System.Drawing.Icon, System.Drawing" mimetype="application/x-microsoft.net.object.bytearray.base64">
|
||||
<value>[base64 mime encoded string representing a byte array form of the .NET Framework object]</value>
|
||||
<comment>This is a comment</comment>
|
||||
</data>
|
||||
|
||||
There are any number of "resheader" rows that contain simple
|
||||
name/value pairs.
|
||||
|
||||
Each data row contains a name, and value. The row also contains a
|
||||
type or mimetype. Type corresponds to a .NET class that support
|
||||
text/value conversion through the TypeConverter architecture.
|
||||
Classes that don't support this are serialized and stored with the
|
||||
mimetype set.
|
||||
|
||||
The mimetype is used for serialized objects, and tells the
|
||||
ResXResourceReader how to depersist the object. This is currently not
|
||||
extensible. For a given mimetype the value must be set accordingly:
|
||||
|
||||
Note - application/x-microsoft.net.object.binary.base64 is the format
|
||||
that the ResXResourceWriter will generate, however the reader can
|
||||
read any of the formats listed below.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.binary.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Binary.BinaryFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.soap.base64
|
||||
value : The object must be serialized with
|
||||
: System.Runtime.Serialization.Formatters.Soap.SoapFormatter
|
||||
: and then encoded with base64 encoding.
|
||||
|
||||
mimetype: application/x-microsoft.net.object.bytearray.base64
|
||||
value : The object must be serialized into a byte array
|
||||
: using a System.ComponentModel.TypeConverter
|
||||
: and then encoded with base64 encoding.
|
||||
-->
|
||||
<xsd:schema id="root" xmlns="" xmlns:xsd="http://www.w3.org/2001/XMLSchema" xmlns:msdata="urn:schemas-microsoft-com:xml-msdata">
|
||||
<xsd:import namespace="http://www.w3.org/XML/1998/namespace" />
|
||||
<xsd:element name="root" msdata:IsDataSet="true">
|
||||
<xsd:complexType>
|
||||
<xsd:choice maxOccurs="unbounded">
|
||||
<xsd:element name="metadata">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" use="required" type="xsd:string" />
|
||||
<xsd:attribute name="type" type="xsd:string" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="assembly">
|
||||
<xsd:complexType>
|
||||
<xsd:attribute name="alias" type="xsd:string" />
|
||||
<xsd:attribute name="name" type="xsd:string" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="data">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
<xsd:element name="comment" type="xsd:string" minOccurs="0" msdata:Ordinal="2" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" msdata:Ordinal="1" />
|
||||
<xsd:attribute name="type" type="xsd:string" msdata:Ordinal="3" />
|
||||
<xsd:attribute name="mimetype" type="xsd:string" msdata:Ordinal="4" />
|
||||
<xsd:attribute ref="xml:space" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
<xsd:element name="resheader">
|
||||
<xsd:complexType>
|
||||
<xsd:sequence>
|
||||
<xsd:element name="value" type="xsd:string" minOccurs="0" msdata:Ordinal="1" />
|
||||
</xsd:sequence>
|
||||
<xsd:attribute name="name" type="xsd:string" use="required" />
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:choice>
|
||||
</xsd:complexType>
|
||||
</xsd:element>
|
||||
</xsd:schema>
|
||||
<resheader name="resmimetype">
|
||||
<value>text/microsoft-resx</value>
|
||||
</resheader>
|
||||
<resheader name="version">
|
||||
<value>2.0</value>
|
||||
</resheader>
|
||||
<resheader name="reader">
|
||||
<value>System.Resources.ResXResourceReader, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<resheader name="writer">
|
||||
<value>System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089</value>
|
||||
</resheader>
|
||||
<metadata name="toolTip1.TrayLocation" type="System.Drawing.Point, System.Drawing, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b03f5f7f11d50a3a">
|
||||
<value>17, 17</value>
|
||||
</metadata>
|
||||
</root>
|
147
Tools/ArdupilotMegaPlanner/Radio/IHex.cs
Normal file
147
Tools/ArdupilotMegaPlanner/Radio/IHex.cs
Normal file
@ -0,0 +1,147 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.IO;
|
||||
|
||||
namespace uploader
|
||||
{
|
||||
public class IHex : SortedList<UInt32, byte[]>
|
||||
{
|
||||
public event ArdupilotMega._3DRradio.LogEventHandler LogEvent;
|
||||
|
||||
public event ArdupilotMega._3DRradio.ProgressEventHandler ProgressEvent;
|
||||
|
||||
private SortedList<UInt32, UInt32> merge_index;
|
||||
|
||||
public IHex ()
|
||||
{
|
||||
merge_index = new SortedList<UInt32, UInt32> ();
|
||||
}
|
||||
|
||||
public void load (string fromPath)
|
||||
{
|
||||
StreamReader sr = new StreamReader (fromPath);
|
||||
UInt32 loadedSize = 0;
|
||||
|
||||
// discard anything we might previous have loaded
|
||||
Clear ();
|
||||
merge_index.Clear ();
|
||||
|
||||
log (string.Format ("reading from {0}\n", Path.GetFileName(fromPath)));
|
||||
|
||||
while (!sr.EndOfStream) {
|
||||
string line = sr.ReadLine ();
|
||||
|
||||
// every line must start with a :
|
||||
if (!line.StartsWith (":"))
|
||||
throw new Exception ("invalid IntelHex file");
|
||||
|
||||
if (ProgressEvent != null)
|
||||
ProgressEvent(sr.BaseStream.Position / (double)sr.BaseStream.Length);
|
||||
|
||||
// parse the record type and data length, assume ihex8
|
||||
// ignore the checksum
|
||||
byte length = Convert.ToByte (line.Substring (1, 2), 16);
|
||||
UInt32 address = Convert.ToUInt32 (line.Substring (3, 4), 16);
|
||||
byte rtype = Convert.ToByte (line.Substring (7, 2), 16);
|
||||
|
||||
// handle type zero (data) records
|
||||
if (rtype == 0) {
|
||||
byte[] b = new byte[length];
|
||||
string hexbytes = line.Substring (9, length * 2);
|
||||
|
||||
// convert hex bytes
|
||||
for (int i = 0; i < length; i++) {
|
||||
b [i] = Convert.ToByte (hexbytes.Substring (i * 2, 2), 16);
|
||||
}
|
||||
|
||||
log (string.Format ("ihex: 0x{0:X}: {1}\n", address, length), 1);
|
||||
loadedSize += length;
|
||||
|
||||
// and add to the list of ranges
|
||||
insert (address, b);
|
||||
}
|
||||
}
|
||||
if (Count < 1)
|
||||
throw new Exception ("no data in IntelHex file");
|
||||
log (string.Format ("read {0} bytes from {1}\n", loadedSize, fromPath));
|
||||
}
|
||||
|
||||
private void log (string message, int level = 0)
|
||||
{
|
||||
if (LogEvent != null)
|
||||
LogEvent (message, level);
|
||||
}
|
||||
|
||||
private void idx_record (UInt32 start, byte[] data)
|
||||
{
|
||||
UInt32 len = (UInt32)data.GetLength (0);
|
||||
|
||||
merge_index.Add (start + len, start);
|
||||
}
|
||||
|
||||
private void idx_remove (UInt32 start, byte[] data)
|
||||
{
|
||||
UInt32 len = (UInt32)data.GetLength (0);
|
||||
|
||||
merge_index.Remove (start + len);
|
||||
}
|
||||
|
||||
private bool idx_find (UInt32 start, out UInt32 other)
|
||||
{
|
||||
return merge_index.TryGetValue (start, out other);
|
||||
}
|
||||
|
||||
public void insert (UInt32 key, byte[] data)
|
||||
{
|
||||
UInt32 other;
|
||||
byte[] mergedata;
|
||||
|
||||
// value of the key that would come after this one
|
||||
other = key;
|
||||
other += (UInt32)data.GetLength (0);
|
||||
|
||||
// can we merge with the next block
|
||||
if (TryGetValue (other, out mergedata)) {
|
||||
int oldlen = data.GetLength (0);
|
||||
|
||||
// remove the next entry, we are going to merge with it
|
||||
Remove (other);
|
||||
|
||||
// remove its index entry as well
|
||||
idx_remove (other, mergedata);
|
||||
|
||||
log (string.Format ("ihex: merging {0:X}/{1} with next {2:X}/{3}\n",
|
||||
key, data.GetLength (0),
|
||||
other, mergedata.GetLength (0)), 1);
|
||||
|
||||
// resize the data array and append data from the next block
|
||||
Array.Resize (ref data, data.GetLength (0) + mergedata.GetLength (0));
|
||||
Array.Copy (mergedata, 0, data, oldlen, mergedata.GetLength (0));
|
||||
}
|
||||
|
||||
// look up a possible adjacent preceding block in the merge index
|
||||
if (idx_find (key, out other)) {
|
||||
|
||||
mergedata = this [other];
|
||||
int oldlen = mergedata.GetLength (0);
|
||||
Remove (other);
|
||||
idx_remove (other, mergedata);
|
||||
|
||||
log (string.Format ("ihex: merging {0:X}/{1} with prev {2:X}/{3}\n",
|
||||
key, data.GetLength (0),
|
||||
other, mergedata.GetLength (0)), 1);
|
||||
|
||||
Array.Resize (ref mergedata, data.GetLength (0) + mergedata.GetLength (0));
|
||||
Array.Copy (data, 0, mergedata, oldlen, data.GetLength (0));
|
||||
key = other;
|
||||
data = mergedata;
|
||||
}
|
||||
|
||||
// add the merged block
|
||||
Add (key, data);
|
||||
idx_record (key, data);
|
||||
log (string.Format ("ihex: adding {0:X}/{1}\n", key, data.GetLength (0)), 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
449
Tools/ArdupilotMegaPlanner/Radio/Uploader.cs
Normal file
449
Tools/ArdupilotMegaPlanner/Radio/Uploader.cs
Normal file
@ -0,0 +1,449 @@
|
||||
using System;
|
||||
using System.IO.Ports;
|
||||
using System.Collections.Generic;
|
||||
|
||||
namespace uploader
|
||||
{
|
||||
public class Uploader
|
||||
{
|
||||
public event ArdupilotMega._3DRradio.LogEventHandler LogEvent;
|
||||
public event ArdupilotMega._3DRradio.ProgressEventHandler ProgressEvent;
|
||||
|
||||
private int bytes_to_process;
|
||||
private int bytes_processed;
|
||||
public SerialPort port;
|
||||
|
||||
private enum Code : byte
|
||||
{
|
||||
// response codes
|
||||
OK = 0x10,
|
||||
FAILED = 0x11,
|
||||
INSYNC = 0x12,
|
||||
|
||||
// protocol commands
|
||||
EOC = 0x20,
|
||||
GET_SYNC = 0x21,
|
||||
GET_DEVICE = 0x22, // returns DEVICE_ID and FREQ bytes
|
||||
CHIP_ERASE = 0x23,
|
||||
LOAD_ADDRESS = 0x24,
|
||||
PROG_FLASH = 0x25,
|
||||
READ_FLASH = 0x26,
|
||||
PROG_MULTI = 0x27,
|
||||
READ_MULTI = 0x28,
|
||||
REBOOT = 0x30,
|
||||
|
||||
// protocol constants
|
||||
PROG_MULTI_MAX = 64, // maximum number of bytes in a PROG_MULTI command
|
||||
READ_MULTI_MAX = 255, // largest read that can be requested
|
||||
|
||||
// device IDs XXX should come with the firmware image...
|
||||
DEVICE_ID_RF50 = 0x4d,
|
||||
DEVICE_ID_HM_TRP= 0x4e,
|
||||
|
||||
// frequency code bytes XXX should come with the firmware image...
|
||||
FREQ_NONE = 0xf0,
|
||||
FREQ_433 = 0x43,
|
||||
FREQ_470 = 0x47,
|
||||
FREQ_868 = 0x86,
|
||||
FREQ_915 = 0x91,
|
||||
};
|
||||
|
||||
public Uploader ()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
/// <summary>
|
||||
/// Upload the specified image_data.
|
||||
/// </summary>
|
||||
/// <param name='image_data'>
|
||||
/// Image_data to be uploaded.
|
||||
/// </param>
|
||||
public void upload (SerialPort on_port, IHex image_data)
|
||||
{
|
||||
progress (0);
|
||||
|
||||
port = on_port;
|
||||
|
||||
try {
|
||||
connect_and_sync ();
|
||||
upload_and_verify (image_data);
|
||||
cmdReboot ();
|
||||
} catch (Exception e) {
|
||||
if (port.IsOpen)
|
||||
port.Close ();
|
||||
throw e;
|
||||
}
|
||||
}
|
||||
|
||||
public void connect_and_sync ()
|
||||
{
|
||||
// configure the port
|
||||
port.ReadTimeout = 2000; // must be longer than full flash erase time (~1s)
|
||||
|
||||
// synchronise with the bootloader
|
||||
//
|
||||
// The second sync attempt here is mostly laziness, though it does verify that we
|
||||
// can send more than one packet.
|
||||
//
|
||||
for (int i = 0; i < 3; i++) {
|
||||
if (cmdSync ())
|
||||
break;
|
||||
log (string.Format ("sync({0}) failed\n", i), 1);
|
||||
}
|
||||
if (!cmdSync ()) {
|
||||
log ("FAIL: could not synchronise with the bootloader");
|
||||
throw new Exception ("SYNC FAIL");
|
||||
}
|
||||
checkDevice ();
|
||||
|
||||
log ("connected to bootloader\n");
|
||||
}
|
||||
|
||||
private void upload_and_verify (IHex image_data)
|
||||
{
|
||||
|
||||
// erase the program area first
|
||||
log ("erasing program flash\n");
|
||||
cmdErase ();
|
||||
|
||||
// progress fractions
|
||||
bytes_to_process = 0;
|
||||
foreach (byte[] bytes in image_data.Values) {
|
||||
bytes_to_process += bytes.Length;
|
||||
}
|
||||
bytes_to_process *= 2; // once to program, once to verify
|
||||
bytes_processed = 0;
|
||||
|
||||
// program the flash blocks
|
||||
log ("programming\n");
|
||||
foreach (KeyValuePair<UInt32, byte[]> kvp in image_data) {
|
||||
// move the program pointer to the base of this block
|
||||
cmdSetAddress (kvp.Key);
|
||||
log (string.Format ("prog 0x{0:X}/{1}\n", kvp.Key, kvp.Value.Length), 1);
|
||||
|
||||
upload_block_multi (kvp.Value);
|
||||
}
|
||||
|
||||
// and read them back to verify that they were programmed
|
||||
log ("verifying\n");
|
||||
foreach (KeyValuePair<UInt32, byte[]> kvp in image_data) {
|
||||
// move the program pointer to the base of this block
|
||||
cmdSetAddress (kvp.Key);
|
||||
log (string.Format ("verf 0x{0:X}/{1}\n", kvp.Key, kvp.Value.Length), 1);
|
||||
|
||||
verify_block_multi (kvp.Value);
|
||||
bytes_processed += kvp.Value.GetLength (0);
|
||||
progress ((double)bytes_processed / bytes_to_process);
|
||||
}
|
||||
log ("Success\n");
|
||||
}
|
||||
|
||||
private void upload_block (byte[] data)
|
||||
{
|
||||
foreach (byte b in data) {
|
||||
cmdProgram (b);
|
||||
progress ((double)(++bytes_processed) / bytes_to_process);
|
||||
}
|
||||
}
|
||||
|
||||
private void upload_block_multi (byte[] data)
|
||||
{
|
||||
int offset = 0;
|
||||
int to_send;
|
||||
int length = data.GetLength (0);
|
||||
|
||||
// Chunk the block in units of no more than what the bootloader
|
||||
// will program.
|
||||
while (offset < length) {
|
||||
to_send = length - offset;
|
||||
if (to_send > (int)Code.PROG_MULTI_MAX)
|
||||
to_send = (int)Code.PROG_MULTI_MAX;
|
||||
|
||||
log (string.Format ("multi {0}/{1}\n", offset, to_send), 1);
|
||||
cmdProgramMulti (data, offset, to_send);
|
||||
offset += to_send;
|
||||
|
||||
bytes_processed += to_send;
|
||||
progress ((double)bytes_processed / bytes_to_process);
|
||||
}
|
||||
}
|
||||
|
||||
private void verify_block_multi (byte[] data)
|
||||
{
|
||||
int offset = 0;
|
||||
int to_verf;
|
||||
int length = data.GetLength (0);
|
||||
|
||||
// Chunk the block in units of no more than what the bootloader
|
||||
// will read.
|
||||
while (offset < length) {
|
||||
to_verf = length - offset;
|
||||
if (to_verf > (int)Code.READ_MULTI_MAX)
|
||||
to_verf = (int)Code.READ_MULTI_MAX;
|
||||
|
||||
log (string.Format ("multi {0}/{1}\n", offset, to_verf), 1);
|
||||
cmdVerifyMulti (data, offset, to_verf);
|
||||
offset += to_verf;
|
||||
|
||||
bytes_processed += to_verf;
|
||||
progress ((double)bytes_processed / bytes_to_process);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Requests a sync reply.
|
||||
/// </summary>
|
||||
/// <returns>
|
||||
/// True if in sync, false otherwise.
|
||||
/// </returns>
|
||||
private bool cmdSync ()
|
||||
{
|
||||
port.DiscardInBuffer ();
|
||||
|
||||
send (Code.GET_SYNC);
|
||||
send (Code.EOC);
|
||||
|
||||
try {
|
||||
getSync ();
|
||||
} catch {
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Erases the device.
|
||||
/// </summary>
|
||||
private void cmdErase ()
|
||||
{
|
||||
send (Code.CHIP_ERASE);
|
||||
send (Code.EOC);
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Set the address for the next program or read operation.
|
||||
/// </summary>
|
||||
/// <param name='address'>
|
||||
/// Address to be set.
|
||||
/// </param>
|
||||
private void cmdSetAddress (UInt32 address)
|
||||
{
|
||||
send (Code.LOAD_ADDRESS);
|
||||
send ((UInt16)address);
|
||||
send (Code.EOC);
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Programs a byte and advances the program address by one.
|
||||
/// </summary>
|
||||
/// <param name='data'>
|
||||
/// Data to program.
|
||||
/// </param>
|
||||
private void cmdProgram (byte data)
|
||||
{
|
||||
send (Code.PROG_FLASH);
|
||||
send (data);
|
||||
send (Code.EOC);
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
private void cmdProgramMulti (byte[] data, int offset, int length)
|
||||
{
|
||||
send (Code.PROG_MULTI);
|
||||
send ((byte)length);
|
||||
for (int i = 0; i < length; i++)
|
||||
send (data [offset + i]);
|
||||
send (Code.EOC);
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Verifies the byte at the current program address.
|
||||
/// </summary>
|
||||
/// <param name='data'>
|
||||
/// Data expected to be found.
|
||||
/// </param>
|
||||
/// <exception cref='VerifyFail'>
|
||||
/// Is thrown when the verify fail.
|
||||
/// </exception>
|
||||
private void cmdVerify (byte data)
|
||||
{
|
||||
send (Code.READ_FLASH);
|
||||
send (Code.EOC);
|
||||
|
||||
if (recv () != data)
|
||||
throw new Exception ("flash verification failed");
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
private void cmdVerifyMulti (byte[] data, int offset, int length)
|
||||
{
|
||||
send (Code.READ_MULTI);
|
||||
send ((byte)length);
|
||||
send (Code.EOC);
|
||||
|
||||
for (int i = 0; i < length; i++) {
|
||||
if (recv () != data [offset + i]) {
|
||||
log ("flash verification failed\n");
|
||||
throw new Exception ("VERIFY FAIL");
|
||||
}
|
||||
}
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
private void cmdReboot ()
|
||||
{
|
||||
send (Code.REBOOT);
|
||||
}
|
||||
|
||||
private void checkDevice ()
|
||||
{
|
||||
Code id, freq;
|
||||
|
||||
send (Code.GET_DEVICE);
|
||||
send (Code.EOC);
|
||||
|
||||
id = (Code)recv ();
|
||||
freq = (Code)recv ();
|
||||
|
||||
// XXX should be getting valid board/frequency data from firmware file
|
||||
if ((id != Code.DEVICE_ID_HM_TRP) && (id != Code.DEVICE_ID_RF50))
|
||||
throw new Exception ("bootloader device ID mismatch");
|
||||
|
||||
getSync ();
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Expect the two-byte synchronisation codes within the read timeout.
|
||||
/// </summary>
|
||||
/// <exception cref='NoSync'>
|
||||
/// Is thrown if the wrong bytes are read.
|
||||
/// <exception cref='TimeoutException'>
|
||||
/// Is thrown if the read timeout expires.
|
||||
/// </exception>
|
||||
private void getSync ()
|
||||
{
|
||||
try {
|
||||
Code c;
|
||||
|
||||
c = (Code)recv ();
|
||||
if (c != Code.INSYNC) {
|
||||
log (string.Format ("got {0:X} when expecting {1:X}\n", (int)c, (int)Code.INSYNC), 2);
|
||||
throw new Exception ("BAD SYNC");
|
||||
}
|
||||
c = (Code)recv ();
|
||||
if (c != Code.OK) {
|
||||
log (string.Format ("got {0:X} when expecting {1:X}\n", (int)c, (int)Code.EOC), 2);
|
||||
throw new Exception ("BAD STATUS");
|
||||
}
|
||||
} catch {
|
||||
log ("FAIL: lost synchronisation with the bootloader\n");
|
||||
throw new Exception ("SYNC LOST");
|
||||
}
|
||||
log ("in sync\n", 5);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Send the specified code to the bootloader.
|
||||
/// </summary>
|
||||
/// <param name='code'>
|
||||
/// Code to send.
|
||||
/// </param>
|
||||
private void send (Code code)
|
||||
{
|
||||
byte[] b = new byte[] { (byte)code };
|
||||
|
||||
log ("send ", 5);
|
||||
foreach (byte x in b) {
|
||||
log (string.Format (" {0:X}", x), 5);
|
||||
}
|
||||
log ("\n", 5);
|
||||
|
||||
port.Write (b, 0, 1);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Send the specified byte to the bootloader.
|
||||
/// </summary>
|
||||
/// <param name='data'>
|
||||
/// Data byte to send.
|
||||
/// </param>
|
||||
private void send (byte data)
|
||||
{
|
||||
byte[] b = new byte[] { data };
|
||||
|
||||
log ("send ", 5);
|
||||
foreach (byte x in b) {
|
||||
log (string.Format (" {0:X}", x), 5);
|
||||
}
|
||||
log ("\n", 5);
|
||||
|
||||
port.Write (b, 0, 1);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Send the specified 16-bit value, LSB first.
|
||||
/// </summary>
|
||||
/// <param name='data'>
|
||||
/// Data value to send.
|
||||
/// </param>
|
||||
private void send (UInt16 data)
|
||||
{
|
||||
byte[] b = new byte[2] { (byte)(data & 0xff), (byte)(data >> 8) };
|
||||
|
||||
log ("send ", 5);
|
||||
foreach (byte x in b) {
|
||||
log (string.Format (" {0:X}", x), 5);
|
||||
}
|
||||
log ("\n", 5);
|
||||
|
||||
port.Write (b, 0, 2);
|
||||
}
|
||||
|
||||
/// <summary>
|
||||
/// Receive a byte.
|
||||
/// </summary>
|
||||
private byte recv ()
|
||||
{
|
||||
byte b;
|
||||
|
||||
DateTime Deadline = DateTime.Now.AddMilliseconds(port.ReadTimeout);
|
||||
|
||||
while (DateTime.Now < Deadline && port.BytesToRead == 0)
|
||||
{
|
||||
}
|
||||
if (port.BytesToRead == 0)
|
||||
throw new Exception("Timeout");
|
||||
|
||||
b = (byte)port.ReadByte ();
|
||||
|
||||
log (string.Format ("recv {0:X}\n", b), 5);
|
||||
|
||||
return b;
|
||||
}
|
||||
|
||||
private void log (string message, int level = 0)
|
||||
{
|
||||
if (LogEvent != null)
|
||||
LogEvent (message, level);
|
||||
}
|
||||
|
||||
private void progress (double completed)
|
||||
{
|
||||
if (ProgressEvent != null)
|
||||
ProgressEvent (completed);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -30,11 +30,8 @@ namespace ArdupilotMega
|
||||
scope.SetVariable("cs", MainV2.cs);
|
||||
scope.SetVariable("Script", this);
|
||||
|
||||
Console.WriteLine(DateTime.Now.Millisecond);
|
||||
engine.CreateScriptSourceFromString("print 'hello world from python'").Execute(scope);
|
||||
Console.WriteLine(DateTime.Now.Millisecond);
|
||||
engine.CreateScriptSourceFromString("print cs.roll").Execute(scope);
|
||||
Console.WriteLine(DateTime.Now.Millisecond);
|
||||
|
||||
|
||||
object thisBoxed = MainV2.cs;
|
||||
|
@ -85,11 +85,10 @@
|
||||
//
|
||||
// LBL_location
|
||||
//
|
||||
this.LBL_location.AutoSize = true;
|
||||
this.LBL_location.Font = new System.Drawing.Font("Microsoft Sans Serif", 14.25F, System.Drawing.FontStyle.Regular, System.Drawing.GraphicsUnit.Point, ((byte)(0)));
|
||||
this.LBL_location.Location = new System.Drawing.Point(9, 78);
|
||||
this.LBL_location.Location = new System.Drawing.Point(3, 64);
|
||||
this.LBL_location.Name = "LBL_location";
|
||||
this.LBL_location.Size = new System.Drawing.Size(50, 24);
|
||||
this.LBL_location.Size = new System.Drawing.Size(365, 59);
|
||||
this.LBL_location.TabIndex = 4;
|
||||
this.LBL_location.Text = "0,0,0";
|
||||
//
|
||||
|
@ -64,7 +64,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
alt = (100 * MainV2.cs.multiplierdist).ToString("0");
|
||||
}
|
||||
if (DialogResult.Cancel == Common.InputBox("Enter Alt", "Enter Alt", ref alt))
|
||||
if (DialogResult.Cancel == Common.InputBox("Enter Alt", "Enter Alt (relative to home alt)", ref alt))
|
||||
return;
|
||||
|
||||
intalt = (int)(100 * MainV2.cs.multiplierdist);
|
||||
@ -87,54 +87,56 @@ namespace ArdupilotMega
|
||||
|
||||
void mainloop()
|
||||
{
|
||||
|
||||
DateTime nextsend = DateTime.Now;
|
||||
|
||||
threadrun = true;
|
||||
int counter = 0;
|
||||
while (threadrun)
|
||||
{
|
||||
try
|
||||
{
|
||||
string line = comPort.ReadLine();
|
||||
|
||||
|
||||
//string line = string.Format("$GP{0},{1:HHmmss},{2},{3},{4},{5},{6},{7},{8},{9},{10},{11},{12},{13},", "GGA", DateTime.Now.ToUniversalTime(), Math.Abs(lat * 100), MainV2.cs.lat < 0 ? "S" : "N", Math.Abs(lng * 100), MainV2.cs.lng < 0 ? "W" : "E", MainV2.cs.gpsstatus, MainV2.cs.satcount, MainV2.cs.gpshdop, MainV2.cs.alt, "M", 0, "M", "");
|
||||
if (line.StartsWith("$GPGGA")) //
|
||||
{
|
||||
int c1 = line.IndexOf(',',0)+ 1;
|
||||
int c2 = line.IndexOf(',', c1) + 1;
|
||||
int c3 = line.IndexOf(',', c2) + 1;
|
||||
int c4 = line.IndexOf(',', c3 ) + 1;
|
||||
int c5 = line.IndexOf(',', c4 ) + 1;
|
||||
int c6 = line.IndexOf(',', c5 ) + 1;
|
||||
int c7 = line.IndexOf(',', c6 ) + 1;
|
||||
int c8 = line.IndexOf(',', c7 ) + 1;
|
||||
int c9 = line.IndexOf(',', c8 ) + 1;
|
||||
int c10 = line.IndexOf(',', c9 ) + 1;
|
||||
int c11 = line.IndexOf(',', c10 ) + 1;
|
||||
int c12 = line.IndexOf(',', c11) + 1;
|
||||
string[] items = line.Trim().Split(',','*');
|
||||
|
||||
gotolocation.Lat = double.Parse(line.Substring(c2, c3 - c2 - 1)) / 100.0;
|
||||
if (items[15] != GetChecksum(line.Trim()))
|
||||
{
|
||||
Console.WriteLine("Bad Nmea line " + items[15] + " vs " + GetChecksum(line.Trim()));
|
||||
continue;
|
||||
}
|
||||
|
||||
if (items[6] == "0")
|
||||
{
|
||||
Console.WriteLine("No Fix");
|
||||
continue;
|
||||
}
|
||||
|
||||
gotolocation.Lat = double.Parse(items[2]) / 100.0;
|
||||
|
||||
gotolocation.Lat = (int)gotolocation.Lat + ((gotolocation.Lat - (int)gotolocation.Lat) / 0.60);
|
||||
|
||||
if (line.Substring(c3, c4 - c3 - 1) == "S")
|
||||
if (items[3] == "S")
|
||||
gotolocation.Lat *= -1;
|
||||
|
||||
gotolocation.Lng = double.Parse(line.Substring(c4, c5 - c4 - 1)) / 100.0;
|
||||
gotolocation.Lng = double.Parse(items[4]) / 100.0;
|
||||
|
||||
gotolocation.Lng = (int)gotolocation.Lng + ((gotolocation.Lng - (int)gotolocation.Lng) / 0.60);
|
||||
|
||||
if (line.Substring(c5, c6 - c5 - 1) == "W")
|
||||
if (items[5] == "W")
|
||||
gotolocation.Lng *= -1;
|
||||
|
||||
gotolocation.Alt = intalt; // double.Parse(line.Substring(c9, c10 - c9 - 1)) +
|
||||
|
||||
gotolocation.Tag = "Sats "+ items[7] + " hdop " + items[8] ;
|
||||
|
||||
}
|
||||
|
||||
|
||||
if (counter % 10 == 0 && gotolocation.Lat != 0 && gotolocation.Lng != 0 && gotolocation.Alt != 0) // 200 * 10 = 2 sec /// lastgotolocation != gotolocation &&
|
||||
if (DateTime.Now > nextsend && gotolocation.Lat != 0 && gotolocation.Lng != 0 && gotolocation.Alt != 0) // 200 * 10 = 2 sec /// lastgotolocation != gotolocation &&
|
||||
{
|
||||
nextsend = DateTime.Now.AddSeconds(2);
|
||||
Console.WriteLine("Sending follow wp " +DateTime.Now.ToString("h:MM:ss")+" "+ gotolocation.Lat + " " + gotolocation.Lng + " " +gotolocation.Alt);
|
||||
lastgotolocation = new PointLatLngAlt(gotolocation);
|
||||
|
||||
@ -159,14 +161,13 @@ namespace ArdupilotMega
|
||||
|
||||
MainV2.comPort.setWP(gotohere, 0, MAVLink.MAV_FRAME.MAV_FRAME_GLOBAL_RELATIVE_ALT, (byte)2);
|
||||
|
||||
GCSViews.FlightData.GuidedModeWP = new PointLatLngAlt(gotohere);
|
||||
|
||||
MainV2.givecomport = false;
|
||||
}
|
||||
catch { MainV2.givecomport = false; }
|
||||
}
|
||||
}
|
||||
|
||||
System.Threading.Thread.Sleep(200);
|
||||
counter++;
|
||||
}
|
||||
catch { System.Threading.Thread.Sleep(2000); }
|
||||
}
|
||||
@ -176,7 +177,7 @@ namespace ArdupilotMega
|
||||
{
|
||||
this.BeginInvoke((MethodInvoker)delegate
|
||||
{
|
||||
LBL_location.Text = gotolocation.Lat + " " + gotolocation.Lng + " " + gotolocation.Alt;
|
||||
LBL_location.Text = gotolocation.Lat + " " + gotolocation.Lng + " " + gotolocation.Alt +" "+ gotolocation.Tag;
|
||||
}
|
||||
);
|
||||
|
||||
@ -200,7 +201,7 @@ namespace ArdupilotMega
|
||||
break;
|
||||
case '*':
|
||||
// Stop processing before the asterisk
|
||||
continue;
|
||||
return Checksum.ToString("X2");
|
||||
default:
|
||||
// Is this the first value for the checksum?
|
||||
if (Checksum == 0)
|
||||
|
83
Tools/ArdupilotMegaPlanner/Speech.cs
Normal file
83
Tools/ArdupilotMegaPlanner/Speech.cs
Normal file
@ -0,0 +1,83 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Speech.Synthesis;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
public class Speech
|
||||
{
|
||||
SpeechSynthesizer _speechwindows;
|
||||
System.Diagnostics.Process _speechlinux;
|
||||
|
||||
System.Speech.Synthesis.SynthesizerState _state = SynthesizerState.Ready;
|
||||
|
||||
bool MONO = false;
|
||||
|
||||
public SynthesizerState State {
|
||||
get {
|
||||
if (MONO)
|
||||
{
|
||||
return _state;
|
||||
}
|
||||
else
|
||||
{
|
||||
return _speechwindows.State;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public Speech()
|
||||
{
|
||||
var t = Type.GetType("Mono.Runtime");
|
||||
MONO = (t != null);
|
||||
|
||||
if (MONO)
|
||||
{
|
||||
_state = SynthesizerState.Ready;
|
||||
}
|
||||
else
|
||||
{
|
||||
_speechwindows = new SpeechSynthesizer();
|
||||
}
|
||||
}
|
||||
|
||||
public void SpeakAsync(string text)
|
||||
{
|
||||
if (MONO)
|
||||
{
|
||||
if (_speechlinux == null || _speechlinux.HasExited)
|
||||
{
|
||||
_state = SynthesizerState.Speaking;
|
||||
_speechlinux = new System.Diagnostics.Process();
|
||||
_speechlinux.StartInfo.FileName = "echo " + text + " | festival --tts";
|
||||
_speechlinux.Start();
|
||||
_speechlinux.Exited += new EventHandler(_speechlinux_Exited);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
_speechwindows.SpeakAsync(text);
|
||||
}
|
||||
}
|
||||
|
||||
void _speechlinux_Exited(object sender, EventArgs e)
|
||||
{
|
||||
_state = SynthesizerState.Ready;
|
||||
}
|
||||
|
||||
public void SpeakAsyncCancelAll()
|
||||
{
|
||||
if (MONO)
|
||||
{
|
||||
_speechlinux.Close();
|
||||
_state = SynthesizerState.Ready;
|
||||
}
|
||||
else
|
||||
{
|
||||
_speechwindows.SpeakAsyncCancelAll();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
64
Tools/ArdupilotMegaPlanner/Utility.cs
Normal file
64
Tools/ArdupilotMegaPlanner/Utility.cs
Normal file
@ -0,0 +1,64 @@
|
||||
//this file contains some simple extension methods
|
||||
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Globalization;
|
||||
using System.ComponentModel;
|
||||
using System.Windows.Forms;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
static class CultureInfoEx
|
||||
{
|
||||
public static CultureInfo GetCultureInfo(string name)
|
||||
{
|
||||
try { return new CultureInfo(name); }
|
||||
catch (Exception) { return null; }
|
||||
}
|
||||
|
||||
public static bool IsChildOf(this CultureInfo cX, CultureInfo cY)
|
||||
{
|
||||
|
||||
if (cX == null || cY == null)
|
||||
return false;
|
||||
|
||||
CultureInfo c = cX;
|
||||
while (!c.Equals(CultureInfo.InvariantCulture))
|
||||
{
|
||||
if (c.Equals(cY))
|
||||
return true;
|
||||
c = c.Parent;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
static class ComponentResourceManagerEx
|
||||
{
|
||||
public static void ApplyResource(this ComponentResourceManager rm, Control ctrl)
|
||||
{
|
||||
rm.ApplyResources(ctrl, ctrl.Name);
|
||||
foreach (Control subctrl in ctrl.Controls)
|
||||
ApplyResource(rm, subctrl);
|
||||
|
||||
if (ctrl.ContextMenu != null)
|
||||
ApplyResource(rm, ctrl.ContextMenu);
|
||||
|
||||
|
||||
if (ctrl is DataGridView)
|
||||
{
|
||||
foreach (DataGridViewColumn col in (ctrl as DataGridView).Columns)
|
||||
rm.ApplyResources(col, col.Name);
|
||||
}
|
||||
}
|
||||
|
||||
public static void ApplyResource(this ComponentResourceManager rm, Menu menu)
|
||||
{
|
||||
rm.ApplyResources(menu, menu.Name);
|
||||
foreach (MenuItem submenu in menu.MenuItems)
|
||||
ApplyResource(rm, submenu);
|
||||
}
|
||||
}
|
||||
}
|
@ -1,7 +1,34 @@
|
||||
<?xml version="1.0"?>
|
||||
<configuration>
|
||||
<configSections>
|
||||
<section name="log4net" type="log4net.Config.Log4NetConfigurationSectionHandler, log4net" />
|
||||
</configSections>
|
||||
<startup useLegacyV2RuntimeActivationPolicy="true">
|
||||
<supportedRuntime version="v2.0.50727"/></startup>
|
||||
<appSettings>
|
||||
<add key="UpdateLocation"
|
||||
value="http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/bin/Release/"/>
|
||||
</appSettings>
|
||||
<log4net>
|
||||
<appender name="Console" type="log4net.Appender.ConsoleAppender">
|
||||
<layout type="log4net.Layout.PatternLayout">
|
||||
<conversionPattern value="%level %logger - %message%newline" />
|
||||
</layout>
|
||||
<threshold value="INFO"/>
|
||||
</appender>
|
||||
<appender name="RollingFile" type="log4net.Appender.RollingFileAppender">
|
||||
<file value="ArdupilotPlanner.log" />
|
||||
<appendToFile value="true" />
|
||||
<maximumFileSize value="100KB" />
|
||||
<maxSizeRollBackups value="2" />
|
||||
<layout type="log4net.Layout.PatternLayout">
|
||||
<conversionPattern value="%date %5level %logger - %message (%file:%line) [%thread]%newline" />
|
||||
</layout>
|
||||
</appender>
|
||||
<root>
|
||||
<level value="DEBUG" />
|
||||
<appender-ref ref="RollingFile" />
|
||||
<appender-ref ref="Console" />
|
||||
</root>
|
||||
</log4net>
|
||||
</configuration>
|
||||
|
29
Tools/ArdupilotMegaPlanner/bin/Release/.gdbinit
Normal file
29
Tools/ArdupilotMegaPlanner/bin/Release/.gdbinit
Normal file
@ -0,0 +1,29 @@
|
||||
handle SIGXCPU SIG33 SIG35 SIGPWR nostop noprint
|
||||
|
||||
define mono_backtrace
|
||||
select-frame 0
|
||||
set $i = 0
|
||||
while ($i < $arg0)
|
||||
set $foo = (char*) mono_pmip ($pc)
|
||||
if ($foo)
|
||||
printf "#%d %p in %s\n", $i, $pc, $foo
|
||||
else
|
||||
frame
|
||||
end
|
||||
up-silently
|
||||
set $i = $i + 1
|
||||
end
|
||||
end
|
||||
|
||||
|
||||
define mono_stack
|
||||
set $mono_thread = mono_thread_current ()
|
||||
if ($mono_thread == 0x00)
|
||||
printf "No mono thread associated with this thread\n"
|
||||
else
|
||||
set $ucp = malloc (sizeof (ucontext_t))
|
||||
call (void) getcontext ($ucp)
|
||||
call (void) mono_print_thread_dump ($ucp)
|
||||
call (void) free ($ucp)
|
||||
end
|
||||
end
|
@ -1,7 +1,34 @@
|
||||
<?xml version="1.0"?>
|
||||
<configuration>
|
||||
<configSections>
|
||||
<section name="log4net" type="log4net.Config.Log4NetConfigurationSectionHandler, log4net" />
|
||||
</configSections>
|
||||
<startup useLegacyV2RuntimeActivationPolicy="true">
|
||||
<supportedRuntime version="v2.0.50727"/></startup>
|
||||
<appSettings>
|
||||
<add key="UpdateLocation"
|
||||
value="http://ardupilot-mega.googlecode.com/git/Tools/ArdupilotMegaPlanner/bin/Release/"/>
|
||||
</appSettings>
|
||||
<log4net>
|
||||
<appender name="Console" type="log4net.Appender.ConsoleAppender">
|
||||
<layout type="log4net.Layout.PatternLayout">
|
||||
<conversionPattern value="%level %logger - %message%newline" />
|
||||
</layout>
|
||||
<threshold value="INFO"/>
|
||||
</appender>
|
||||
<appender name="RollingFile" type="log4net.Appender.RollingFileAppender">
|
||||
<file value="ArdupilotPlanner.log" />
|
||||
<appendToFile value="true" />
|
||||
<maximumFileSize value="100KB" />
|
||||
<maxSizeRollBackups value="2" />
|
||||
<layout type="log4net.Layout.PatternLayout">
|
||||
<conversionPattern value="%date %5level %logger - %message (%file:%line) [%thread]%newline" />
|
||||
</layout>
|
||||
</appender>
|
||||
<root>
|
||||
<level value="DEBUG" />
|
||||
<appender-ref ref="RollingFile" />
|
||||
<appender-ref ref="Console" />
|
||||
</root>
|
||||
</log4net>
|
||||
</configuration>
|
||||
|
Binary file not shown.
@ -19,6 +19,7 @@
|
||||
<F4>Pitch</F4>
|
||||
<F5>Yaw IN</F5>
|
||||
<F6>Yaw</F6>
|
||||
<F7>Mag Heading</F7>
|
||||
</ATT>
|
||||
<NTUN>
|
||||
<F1>WP Dist</F1>
|
||||
|
@ -377,8 +377,8 @@
|
||||
</DO_JUMP>
|
||||
<DO_CHANGE_SPEED>
|
||||
<P1>Type (0=as 1=gs)</P1>
|
||||
<P2>Throttle(%)</P2>
|
||||
<P3>Speed (m/s)</P3>
|
||||
<P2>Speed (m/s)</P2>
|
||||
<P3>Throttle(%)</P3>
|
||||
<P4></P4>
|
||||
<X></X>
|
||||
<Y></Y>
|
||||
|
3
Tools/ArdupilotMegaPlanner/bin/Release/runme
Normal file
3
Tools/ArdupilotMegaPlanner/bin/Release/runme
Normal file
@ -0,0 +1,3 @@
|
||||
#!/bin/bash
|
||||
|
||||
gdb --args mono ArdupilotMegaPlanner.exe
|
@ -19,6 +19,7 @@
|
||||
<F4>Pitch</F4>
|
||||
<F5>Yaw IN</F5>
|
||||
<F6>Yaw</F6>
|
||||
<F7>Mag Heading</F7>
|
||||
</ATT>
|
||||
<NTUN>
|
||||
<F1>WP Dist</F1>
|
||||
|
@ -1,22 +1,19 @@
|
||||
using System;
|
||||
using System.Collections.Generic;
|
||||
using System.Linq;
|
||||
using System.Text;
|
||||
using System.Drawing;
|
||||
using System.Drawing.Imaging;
|
||||
using System.Reflection;
|
||||
using System.IO;
|
||||
using System.Windows.Forms;
|
||||
using com.drew.imaging.jpg;
|
||||
using com.drew.metadata;
|
||||
|
||||
using log4net;
|
||||
using SharpKml.Base;
|
||||
using SharpKml.Dom;
|
||||
using SharpKml.Dom.GX;
|
||||
|
||||
namespace ArdupilotMega
|
||||
{
|
||||
class georefimage : Form
|
||||
public class Georefimage : Form
|
||||
{
|
||||
private static readonly ILog log = LogManager.GetLogger(MethodBase.GetCurrentMethod().DeclaringType);
|
||||
private OpenFileDialog openFileDialog1;
|
||||
private MyButton BUT_browselog;
|
||||
private MyButton BUT_browsedir;
|
||||
@ -31,7 +28,7 @@ namespace ArdupilotMega
|
||||
|
||||
int latpos = 5, lngpos = 4, altpos = 7;
|
||||
|
||||
internal georefimage() {
|
||||
internal Georefimage() {
|
||||
InitializeComponent();
|
||||
}
|
||||
|
||||
@ -51,7 +48,7 @@ namespace ArdupilotMega
|
||||
}
|
||||
catch (JpegProcessingException e)
|
||||
{
|
||||
Console.WriteLine(e.Message);
|
||||
log.InfoFormat(e.Message);
|
||||
return dtaken;
|
||||
}
|
||||
|
||||
@ -61,7 +58,7 @@ namespace ArdupilotMega
|
||||
if (lcDirectory.ContainsTag(0x9003))
|
||||
{
|
||||
dtaken = lcDirectory.GetDate(0x9003);
|
||||
Console.WriteLine("does " + lcDirectory.GetTagName(0x9003) + " " + dtaken);
|
||||
log.InfoFormat("does " + lcDirectory.GetTagName(0x9003) + " " + dtaken);
|
||||
break;
|
||||
}
|
||||
|
||||
@ -96,6 +93,51 @@ namespace ArdupilotMega
|
||||
{
|
||||
List<string[]> list = new List<string[]>();
|
||||
|
||||
if (fn.ToLower().EndsWith("tlog"))
|
||||
{
|
||||
MAVLink mine = new MAVLink();
|
||||
mine.logplaybackfile = new BinaryReader(File.Open(fn, FileMode.Open, FileAccess.Read, FileShare.Read));
|
||||
mine.logreadmode = true;
|
||||
|
||||
mine.packets.Initialize(); // clear
|
||||
|
||||
CurrentState cs = new CurrentState();
|
||||
|
||||
string[] oldvalues = {""};
|
||||
|
||||
while (mine.logplaybackfile.BaseStream.Position < mine.logplaybackfile.BaseStream.Length)
|
||||
{
|
||||
|
||||
byte[] packet = mine.readPacket();
|
||||
|
||||
cs.datetime = mine.lastlogread;
|
||||
|
||||
cs.UpdateCurrentSettings(null, true, mine);
|
||||
|
||||
// line "GPS: 82686250, 1, 8, -34.1406480, 118.5441900, 0.0000, 309.1900, 315.9500, 0.0000, 279.1200" string
|
||||
|
||||
|
||||
string[] vals = new string[] { "GPS", (new DateTime(cs.datetime.Year,cs.datetime.Month,cs.datetime.Day,0,0,0) - cs.datetime).TotalMilliseconds.ToString(), "1",
|
||||
"8",cs.lat.ToString(),cs.lng.ToString(),"0.0",cs.alt.ToString(),cs.alt.ToString(),"0.0",cs.groundcourse.ToString()};
|
||||
|
||||
if (oldvalues.Length > 2 && oldvalues[latpos] == vals[latpos]
|
||||
&& oldvalues[lngpos] == vals[lngpos]
|
||||
&& oldvalues[altpos] == vals[altpos])
|
||||
continue;
|
||||
|
||||
oldvalues = vals;
|
||||
|
||||
list.Add(vals);
|
||||
// 4 5 7
|
||||
Console.Write((mine.logplaybackfile.BaseStream.Position * 100 / mine.logplaybackfile.BaseStream.Length) + " \r");
|
||||
|
||||
}
|
||||
|
||||
mine.logplaybackfile.Close();
|
||||
|
||||
return list;
|
||||
}
|
||||
|
||||
StreamReader sr = new StreamReader(fn);
|
||||
|
||||
string lasttime = "0";
|
||||
@ -172,7 +214,7 @@ namespace ArdupilotMega
|
||||
localmax = crap;
|
||||
}
|
||||
|
||||
Console.WriteLine("min " + localmin + " max " + localmax);
|
||||
log.InfoFormat("min " + localmin + " max " + localmax);
|
||||
TXT_outputlog.AppendText("Log min " + localmin + " max " + localmax + "\r\n");
|
||||
}
|
||||
|
||||
@ -220,7 +262,7 @@ namespace ArdupilotMega
|
||||
sw.WriteLine(Path.GetFileNameWithoutExtension(file) + "\t" + crap.ToString("yyyy:MM:dd HH:mm:ss") + "\t" + arr[lngpos] + "\t" + arr[latpos] + "\t" + arr[altpos]);
|
||||
sw.Flush();
|
||||
sw2.Flush();
|
||||
Console.WriteLine(Path.GetFileNameWithoutExtension(file) + " " + arr[lngpos] + " " + arr[latpos] + " " + arr[altpos] + " ");
|
||||
log.InfoFormat(Path.GetFileNameWithoutExtension(file) + " " + arr[lngpos] + " " + arr[latpos] + " " + arr[altpos] + " ");
|
||||
break;
|
||||
}
|
||||
//Console.WriteLine(crap);
|
||||
@ -359,7 +401,7 @@ namespace ArdupilotMega
|
||||
this.Controls.Add(this.TXT_logfile);
|
||||
this.Controls.Add(this.BUT_browsedir);
|
||||
this.Controls.Add(this.BUT_browselog);
|
||||
this.Name = "georefimage";
|
||||
this.Name = "Georefimage";
|
||||
this.ResumeLayout(false);
|
||||
this.PerformLayout();
|
||||
|
||||
@ -367,7 +409,7 @@ namespace ArdupilotMega
|
||||
|
||||
private void BUT_browselog_Click(object sender, EventArgs e)
|
||||
{
|
||||
openFileDialog1.Filter = "Logs|*.log";
|
||||
openFileDialog1.Filter = "Logs|*.log;*.tlog";
|
||||
openFileDialog1.ShowDialog();
|
||||
|
||||
if (File.Exists(openFileDialog1.FileName))
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user